From 541d589af92b04b648ea826824941fff10e8c104 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 12 Mar 2023 19:04:55 +0100 Subject: [PATCH 001/175] Filter setup via EzTune --- src/main/CMakeLists.txt | 2 + src/main/config/parameter_group_ids.h | 3 +- src/main/fc/fc_init.c | 5 ++ src/main/fc/fc_msp.c | 2 + src/main/fc/settings.c | 2 + src/main/fc/settings.h | 1 + src/main/fc/settings.yaml | 17 +++++ src/main/flight/ez_tune.c | 91 +++++++++++++++++++++++++++ src/main/flight/ez_tune.h | 36 +++++++++++ src/main/target/common.h | 2 + 10 files changed, 160 insertions(+), 1 deletion(-) create mode 100644 src/main/flight/ez_tune.c create mode 100644 src/main/flight/ez_tune.h diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 317da760b6..cdc01ac315 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -331,6 +331,8 @@ main_sources(COMMON_SRC flight/secondary_dynamic_gyro_notch.h flight/dynamic_lpf.c flight/dynamic_lpf.h + flight/ez_tune.c + flight/ez_tune.h io/beeper.c io/beeper.h diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index 46293524b1..329f42b219 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -119,7 +119,8 @@ #define PG_UNUSED_1 1029 #define PG_POWER_LIMITS_CONFIG 1030 #define PG_OSD_COMMON_CONFIG 1031 -#define PG_INAV_END 1031 +#define PG_EZ_TUNE 1032 +#define PG_INAV_END PG_EZ_TUNE // OSD configuration (subject to change) //#define PG_OSD_FONT_CONFIG 2047 diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index a8ab8146d2..64b421c583 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -96,6 +96,7 @@ #include "flight/power_limits.h" #include "flight/rpm_filter.h" #include "flight/servos.h" +#include "flight/ez_tune.h" #include "io/asyncfatfs/asyncfatfs.h" #include "io/beeper.h" @@ -509,6 +510,10 @@ void init(void) owInit(); #endif +#ifdef USE_EZ_TUNE + ezTuneUpdate(); +#endif + if (!sensorsAutodetect()) { // if gyro was not detected due to whatever reason, we give up now. failureMode(FAILURE_MISSING_ACC); diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index ee5c8f0397..7f8354deee 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -3164,6 +3164,8 @@ static bool mspSettingInfoCommand(sbuf_t *dst, sbuf_t *src) sbufWriteU8(dst, 0); sbufWriteU8(dst, 0); break; + case EZ_TUNE_VALUE: + FALLTHROUGH; case PROFILE_VALUE: FALLTHROUGH; case CONTROL_RATE_VALUE: diff --git a/src/main/fc/settings.c b/src/main/fc/settings.c index 8dc17edc63..bef0750e88 100644 --- a/src/main/fc/settings.c +++ b/src/main/fc/settings.c @@ -237,6 +237,8 @@ static uint16_t getValueOffset(const setting_t *value) return value->offset + sizeof(pidProfile_t) * getConfigProfile(); case CONTROL_RATE_VALUE: return value->offset + sizeof(controlRateConfig_t) * getConfigProfile(); + case EZ_TUNE_VALUE: + return value->offset + sizeof(ezTuneSettings_t) * getConfigProfile(); case BATTERY_CONFIG_VALUE: return value->offset + sizeof(batteryProfile_t) * getConfigBatteryProfile(); } diff --git a/src/main/fc/settings.h b/src/main/fc/settings.h index b14289ba27..a6cc403842 100644 --- a/src/main/fc/settings.h +++ b/src/main/fc/settings.h @@ -34,6 +34,7 @@ typedef enum { PROFILE_VALUE = (1 << SETTING_SECTION_OFFSET), CONTROL_RATE_VALUE = (2 << SETTING_SECTION_OFFSET), // 0x20 BATTERY_CONFIG_VALUE = (3 << SETTING_SECTION_OFFSET), + EZ_TUNE_VALUE = (4 << SETTING_SECTION_OFFSET) } setting_section_e; typedef enum { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index c0df0e204c..de52e9a7a5 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1477,6 +1477,23 @@ groups: min: 0 max: 99 + - name: PG_EZ_TUNE + headers: ["flight/ez_tune.h"] + type: ezTuneSettings_t + value_type: EZ_TUNE_VALUE + members: + - name: ez_tune_enabled + description: "Enables EzTune feature" + default_value: OFF + field: enabled + type: bool + - name: ez_tune_filter_hz + description: "EzTune filter cutoff frequency" + default_value: 110 + field: filterHz + min: 10 + max: 300 + - name: PG_RPM_FILTER_CONFIG headers: ["flight/rpm_filter.h"] condition: USE_RPM_FILTER diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c new file mode 100644 index 0000000000..a9656bd83f --- /dev/null +++ b/src/main/flight/ez_tune.c @@ -0,0 +1,91 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include "fc/config.h" +#include "config/config_reset.h" +#include "config/parameter_group.h" +#include "config/parameter_group_ids.h" + +#include "flight/ez_tune.h" + +#include "fc/settings.h" +#include "flight/pid.h" +#include "sensors/gyro.h" + +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(ezTuneSettings_t, ezTune, PG_EZ_TUNE, 0); + +PG_RESET_TEMPLATE(ezTuneSettings_t, ezTune, + .enabled = SETTING_EZ_TUNE_ENABLED_DEFAULT, + .filterHz = SETTING_EZ_TUNE_FILTER_HZ_DEFAULT, +); + +static float computePt1FilterDelayMs(uint8_t filterHz) { + return 1.0f / (2.0f * M_PIf * filterHz); +} + +/** + * Update INAV settings based on current EZTune settings + * This has to be called every time control profile is changed, or EZTune settings are changed + * FIXME call on profile change + * FIXME call on EZTune settings change + */ +void ezTuneUpdate(void) { + if (ezTune()->enabled) { + + // Setup filtering + + //Enable Smith predictor + pidProfileMutable()->smithPredictorDelay = computePt1FilterDelayMs(ezTune()->filterHz) + + computePt1FilterDelayMs(gyroConfig()->gyro_anti_aliasing_lpf_hz); + + //Set Dterm LPF + pidProfileMutable()->dterm_lpf_hz = MAX(ezTune()->filterHz - 5, 50); + pidProfileMutable()->dterm_lpf_type = FILTER_PT2; + + //Set main gyro filter + gyroConfigMutable()->gyro_main_lpf_hz = ezTune()->filterHz; + gyroConfigMutable()->gyro_main_lpf_type = FILTER_PT1; + + //Set anti-aliasing filter + gyroConfigMutable()->gyro_anti_aliasing_lpf_hz = MIN(ezTune()->filterHz * 2, 250); + gyroConfigMutable()->gyro_anti_aliasing_lpf_type = FILTER_PT1; + + //Enable dynamic notch + gyroConfigMutable()->dynamicGyroNotchEnabled = 1; + gyroConfigMutable()->dynamicGyroNotchQ = 250; + gyroConfigMutable()->dynamicGyroNotchMinHz = MAX(ezTune()->filterHz * 0.667f, SETTING_DYNAMIC_GYRO_NOTCH_MIN_HZ_DEFAULT); + gyroConfigMutable()->dynamicGyroNotchMode = DYNAMIC_NOTCH_MODE_3D; + + //Make sure Kalman filter is enabled + gyroConfigMutable()->kalmanEnabled = 1; + if (ezTune()->filterHz < 150) { + gyroConfigMutable()->kalman_q = 200; + } else { + gyroConfigMutable()->kalman_q = scaleRangef(ezTune()->filterHz, 150, 300, 200, 400); + } + + + + } +} \ No newline at end of file diff --git a/src/main/flight/ez_tune.h b/src/main/flight/ez_tune.h new file mode 100644 index 0000000000..a2ba6f0249 --- /dev/null +++ b/src/main/flight/ez_tune.h @@ -0,0 +1,36 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +#include "config/parameter_group.h" + +typedef struct ezTuneSettings_s { + uint8_t enabled; + uint16_t filterHz; +} ezTuneSettings_t; + +PG_DECLARE_PROFILE(ezTuneSettings_t, ezTune); + +void ezTuneUpdate(void); \ No newline at end of file diff --git a/src/main/target/common.h b/src/main/target/common.h index 2365be9671..26ec4ff012 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -192,3 +192,5 @@ #define USE_HOTT_TEXTMODE #endif + +#define USE_EZ_TUNE \ No newline at end of file From a2051c1371b7689ce3a97a5e5ed5b82ff2f4ae03 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 12 Mar 2023 19:06:29 +0100 Subject: [PATCH 002/175] Disable gyro dynamic LPF for EZ-Tune --- src/main/flight/ez_tune.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index a9656bd83f..240e64f921 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -85,7 +85,8 @@ void ezTuneUpdate(void) { gyroConfigMutable()->kalman_q = scaleRangef(ezTune()->filterHz, 150, 300, 200, 400); } - + //Disable dynamic LPF + gyroConfigMutable()->useDynamicLpf = 0; } } \ No newline at end of file From fb5210d0b952601f6ca9721321a4313414db065a Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 12 Mar 2023 19:52:22 +0100 Subject: [PATCH 003/175] Add EzTune to the settings.yaml --- src/main/fc/settings.yaml | 30 ++++++++++++++++++++++++++++++ src/main/flight/ez_tune.c | 10 ++++++++++ src/main/flight/ez_tune.h | 8 ++++++++ 3 files changed, 48 insertions(+) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index de52e9a7a5..7dbc1d8453 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1493,6 +1493,36 @@ groups: field: filterHz min: 10 max: 300 + - name: ez_tune_axis_ratio + description: "EzTune axis ratio" + default_value: 100 + field: axisRatio + min: 25 + max: 175 + - name: ez_tune_response + description: "EzTune response" + default_value: 100 + field: response + min: 0 + max: 200 + - name: ez_tune_damping + description: "EzTune damping" + default_value: 100 + field: damping + min: 0 + max: 200 + - name: ez_tune_stability + description: "EzTune stability" + default_value: 100 + field: stability + min: 0 + max: 200 + - name: ez_tune_aggressiveness + description: "EzTune aggressiveness" + default_value: 100 + field: aggressiveness + min: 0 + max: 200 - name: PG_RPM_FILTER_CONFIG headers: ["flight/rpm_filter.h"] diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index 240e64f921..35717ed828 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -38,6 +38,11 @@ PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(ezTuneSettings_t, ezTune, PG_EZ_TUNE, 0) PG_RESET_TEMPLATE(ezTuneSettings_t, ezTune, .enabled = SETTING_EZ_TUNE_ENABLED_DEFAULT, .filterHz = SETTING_EZ_TUNE_FILTER_HZ_DEFAULT, + .axisRatio = SETTING_EZ_TUNE_AXIS_RATIO_DEFAULT, + .response = SETTING_EZ_TUNE_RESPONSE_DEFAULT, + .damping = SETTING_EZ_TUNE_DAMPING_DEFAULT, + .stability = SETTING_EZ_TUNE_STABILITY_DEFAULT, + .aggressiveness = SETTING_EZ_TUNE_AGGRESSIVENESS_DEFAULT, ); static float computePt1FilterDelayMs(uint8_t filterHz) { @@ -88,5 +93,10 @@ void ezTuneUpdate(void) { //Disable dynamic LPF gyroConfigMutable()->useDynamicLpf = 0; + //Setup PID controller + + //Roll + + } } \ No newline at end of file diff --git a/src/main/flight/ez_tune.h b/src/main/flight/ez_tune.h index a2ba6f0249..98cb692636 100644 --- a/src/main/flight/ez_tune.h +++ b/src/main/flight/ez_tune.h @@ -29,8 +29,16 @@ typedef struct ezTuneSettings_s { uint8_t enabled; uint16_t filterHz; + uint8_t axisRatio; + uint8_t response; + uint8_t damping; + uint8_t stability; + uint8_t aggressiveness; } ezTuneSettings_t; +#define EZ_TUNE_PID_RP_DEFAULT {40, 75, 23, 100} +#define EZ_TUNE_PID_YAW_DEFAULT {45, 80, 0, 100} + PG_DECLARE_PROFILE(ezTuneSettings_t, ezTune); void ezTuneUpdate(void); \ No newline at end of file From de6c442a11028d72035ba191ab6bcaea2ed6bd96 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 13 Mar 2023 11:24:10 +0100 Subject: [PATCH 004/175] Adjust PIDs from EzTune --- src/main/fc/settings.yaml | 2 +- src/main/flight/ez_tune.c | 33 +++++++++++++++++++++++++++++++-- src/main/flight/ez_tune.h | 3 --- 3 files changed, 32 insertions(+), 6 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 7dbc1d8453..0d00044049 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1495,7 +1495,7 @@ groups: max: 300 - name: ez_tune_axis_ratio description: "EzTune axis ratio" - default_value: 100 + default_value: 110 field: axisRatio min: 25 max: 175 diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index 35717ed828..c337332e1f 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -45,10 +45,21 @@ PG_RESET_TEMPLATE(ezTuneSettings_t, ezTune, .aggressiveness = SETTING_EZ_TUNE_AGGRESSIVENESS_DEFAULT, ); +#define EZ_TUNE_PID_RP_DEFAULT { 40, 75, 23, 100 } +#define EZ_TUNE_PID_YAW_DEFAULT { 45, 80, 0, 100 } + +#define EZ_TUNE_YAW_SCALE 0.5f + static float computePt1FilterDelayMs(uint8_t filterHz) { return 1.0f / (2.0f * M_PIf * filterHz); } +static float getYawPidScale(float input) { + const float normalized = (input - 100) * 0.01f; + + return 1.0f + (normalized * 0.5f); +} + /** * Update INAV settings based on current EZTune settings * This has to be called every time control profile is changed, or EZTune settings are changed @@ -95,8 +106,26 @@ void ezTuneUpdate(void) { //Setup PID controller - //Roll - + const uint8_t pidDefaults[4] = EZ_TUNE_PID_RP_DEFAULT; + const uint8_t pidDefaultsYaw[4] = EZ_TUNE_PID_YAW_DEFAULT; + const float pitchRatio = ezTune()->axisRatio / 100.0f; + //Roll + pidProfileMutable()->bank_mc.pid[PID_ROLL].P = pidDefaults[0] * ezTune()->response / 100.0f; + pidProfileMutable()->bank_mc.pid[PID_ROLL].I = pidDefaults[1] * ezTune()->stability / 100.0f; + pidProfileMutable()->bank_mc.pid[PID_ROLL].D = pidDefaults[2] * ezTune()->damping / 100.0f; + pidProfileMutable()->bank_mc.pid[PID_ROLL].FF = pidDefaults[3] * ezTune()->aggressiveness / 100.0f; + + //Pitch + pidProfileMutable()->bank_mc.pid[PID_PITCH].P = pidDefaults[0] * ezTune()->response / 100.0f * pitchRatio; + pidProfileMutable()->bank_mc.pid[PID_PITCH].I = pidDefaults[1] * ezTune()->stability / 100.0f * pitchRatio; + pidProfileMutable()->bank_mc.pid[PID_PITCH].D = pidDefaults[2] * ezTune()->damping / 100.0f * pitchRatio; + pidProfileMutable()->bank_mc.pid[PID_PITCH].FF = pidDefaults[3] * ezTune()->aggressiveness / 100.0f * pitchRatio; + + //Yaw + pidProfileMutable()->bank_mc.pid[PID_YAW].P = pidDefaultsYaw[0] * getYawPidScale(ezTune()->response); + pidProfileMutable()->bank_mc.pid[PID_YAW].I = pidDefaultsYaw[1] * getYawPidScale(ezTune()->stability); + pidProfileMutable()->bank_mc.pid[PID_YAW].D = pidDefaultsYaw[2] * getYawPidScale(ezTune()->damping); + pidProfileMutable()->bank_mc.pid[PID_YAW].FF = pidDefaultsYaw[3] * getYawPidScale(ezTune()->aggressiveness); } } \ No newline at end of file diff --git a/src/main/flight/ez_tune.h b/src/main/flight/ez_tune.h index 98cb692636..aa0088fe7f 100644 --- a/src/main/flight/ez_tune.h +++ b/src/main/flight/ez_tune.h @@ -36,9 +36,6 @@ typedef struct ezTuneSettings_s { uint8_t aggressiveness; } ezTuneSettings_t; -#define EZ_TUNE_PID_RP_DEFAULT {40, 75, 23, 100} -#define EZ_TUNE_PID_YAW_DEFAULT {45, 80, 0, 100} - PG_DECLARE_PROFILE(ezTuneSettings_t, ezTune); void ezTuneUpdate(void); \ No newline at end of file From 554eaeaa0ea59cd584e300b6c4fc9e3ab6d662cc Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 13 Mar 2023 17:03:41 +0100 Subject: [PATCH 005/175] Add rate and expo to EZ-Tune --- src/main/fc/settings.yaml | 26 +++++++++++++++++++------- src/main/flight/ez_tune.c | 16 +++++++++------- src/main/flight/ez_tune.h | 2 ++ 3 files changed, 30 insertions(+), 14 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 0d00044049..188f1c9119 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1482,47 +1482,59 @@ groups: type: ezTuneSettings_t value_type: EZ_TUNE_VALUE members: - - name: ez_tune_enabled + - name: ez_enabled description: "Enables EzTune feature" default_value: OFF field: enabled type: bool - - name: ez_tune_filter_hz + - name: ez_filter_hz description: "EzTune filter cutoff frequency" default_value: 110 field: filterHz min: 10 max: 300 - - name: ez_tune_axis_ratio + - name: ez_axis_ratio description: "EzTune axis ratio" default_value: 110 field: axisRatio min: 25 max: 175 - - name: ez_tune_response + - name: ez_response description: "EzTune response" default_value: 100 field: response min: 0 max: 200 - - name: ez_tune_damping + - name: ez_damping description: "EzTune damping" default_value: 100 field: damping min: 0 max: 200 - - name: ez_tune_stability + - name: ez_stability description: "EzTune stability" default_value: 100 field: stability min: 0 max: 200 - - name: ez_tune_aggressiveness + - name: ez_aggressiveness description: "EzTune aggressiveness" default_value: 100 field: aggressiveness min: 0 max: 200 + - name: ez_rate + description: "EzTune rate" + default_value: 100 + field: rate + min: 0 + max: 200 + - name: ez_expo + description: "EzTune expo" + default_value: 100 + field: expo + min: 0 + max: 200 - name: PG_RPM_FILTER_CONFIG headers: ["flight/rpm_filter.h"] diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index c337332e1f..cc1c3dab5b 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -36,13 +36,15 @@ PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(ezTuneSettings_t, ezTune, PG_EZ_TUNE, 0); PG_RESET_TEMPLATE(ezTuneSettings_t, ezTune, - .enabled = SETTING_EZ_TUNE_ENABLED_DEFAULT, - .filterHz = SETTING_EZ_TUNE_FILTER_HZ_DEFAULT, - .axisRatio = SETTING_EZ_TUNE_AXIS_RATIO_DEFAULT, - .response = SETTING_EZ_TUNE_RESPONSE_DEFAULT, - .damping = SETTING_EZ_TUNE_DAMPING_DEFAULT, - .stability = SETTING_EZ_TUNE_STABILITY_DEFAULT, - .aggressiveness = SETTING_EZ_TUNE_AGGRESSIVENESS_DEFAULT, + .enabled = SETTING_EZ_ENABLED_DEFAULT, + .filterHz = SETTING_EZ_FILTER_HZ_DEFAULT, + .axisRatio = SETTING_EZ_AXIS_RATIO_DEFAULT, + .response = SETTING_EZ_RESPONSE_DEFAULT, + .damping = SETTING_EZ_DAMPING_DEFAULT, + .stability = SETTING_EZ_STABILITY_DEFAULT, + .aggressiveness = SETTING_EZ_AGGRESSIVENESS_DEFAULT, + .rate = SETTING_EZ_RATE_DEFAULT, + .expo = SETTING_EZ_EXPO_DEFAULT, ); #define EZ_TUNE_PID_RP_DEFAULT { 40, 75, 23, 100 } diff --git a/src/main/flight/ez_tune.h b/src/main/flight/ez_tune.h index aa0088fe7f..5fcc1ef6f7 100644 --- a/src/main/flight/ez_tune.h +++ b/src/main/flight/ez_tune.h @@ -34,6 +34,8 @@ typedef struct ezTuneSettings_s { uint8_t damping; uint8_t stability; uint8_t aggressiveness; + uint8_t rate; + uint8_t expo; } ezTuneSettings_t; PG_DECLARE_PROFILE(ezTuneSettings_t, ezTune); From 0589b5636e6c1f7ac371675bdb439cc761f74428 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Fri, 17 Mar 2023 23:10:37 +0000 Subject: [PATCH 006/175] Increase RC Channels to 24 Both FrSky and Jeti can use 24 channels. INAV doesn't handle the additional channels gracefully, certainly from Jeti. This PR increases the channel count to 24. But, does not apply to F411 or F722. --- src/main/navigation/navigation.c | 17 ++++++++--------- src/main/rx/jetiexbus.c | 7 ++++++- src/main/rx/rx.h | 6 +++++- src/main/rx/sbus_channels.h | 4 ++++ src/main/target/common.h | 1 + 5 files changed, 24 insertions(+), 11 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index e164b33ab5..4d88b1dbef 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -3808,8 +3808,7 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) if ((FLIGHT_MODE(NAV_ALTHOLD_MODE)) || (canActivateAltHold)) return NAV_FSM_EVENT_SWITCH_TO_ALTHOLD; } - } - else { + } else { canActivateWaypoint = false; // Launch mode can be activated if feature FW_LAUNCH is enabled or BOX is turned on prior to arming (avoid switching to LAUNCH in flight) @@ -3924,13 +3923,13 @@ navArmingBlocker_e navigationIsBlockingArming(bool *usedBypass) } } - /* - * Don't allow arming if any of JUMP waypoint has invalid settings - * First WP can't be JUMP - * Can't jump to immediately adjacent WPs (pointless) - * Can't jump beyond WP list - * Only jump to geo-referenced WP types - */ + /* + * Don't allow arming if any of JUMP waypoint has invalid settings + * First WP can't be JUMP + * Can't jump to immediately adjacent WPs (pointless) + * Can't jump beyond WP list + * Only jump to geo-referenced WP types + */ if (posControl.waypointCount) { for (uint8_t wp = posControl.startWpIndex; wp < posControl.waypointCount + posControl.startWpIndex; wp++){ if (posControl.waypointList[wp].action == NAV_WP_ACTION_JUMP){ diff --git a/src/main/rx/jetiexbus.c b/src/main/rx/jetiexbus.c index d9b009342e..ce6ebfe958 100644 --- a/src/main/rx/jetiexbus.c +++ b/src/main/rx/jetiexbus.c @@ -63,7 +63,12 @@ #define JETIEXBUS_BAUDRATE 125000 // EX Bus 125000; EX Bus HS 250000 not supported #define JETIEXBUS_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO) #define JETIEXBUS_MIN_FRAME_GAP 1000 -#define JETIEXBUS_CHANNEL_COUNT 16 // most Jeti TX transmit 16 channels + +#ifdef USE_24CHANNELS +#define JETIEXBUS_CHANNEL_COUNT 24 +#else +#define JETIEXBUS_CHANNEL_COUNT 16 +#endif #define EXBUS_START_CHANNEL_FRAME (0x3E) diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 4880c4c4fe..4655f23e8c 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -81,7 +81,11 @@ typedef enum { SERIALRX_MAVLINK, } rxSerialReceiverType_e; -#define MAX_SUPPORTED_RC_CHANNEL_COUNT 18 +#ifdef USE_24CHANNELS +#define MAX_SUPPORTED_RC_CHANNEL_COUNT 26 +#else +#define MAX_SUPPORTED_RC_CHANNEL_COUNT 18 +#endif #define NON_AUX_CHANNEL_COUNT 4 #define MAX_AUX_CHANNEL_COUNT (MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT) diff --git a/src/main/rx/sbus_channels.h b/src/main/rx/sbus_channels.h index 5e8a6a0268..e5ec0ff2c9 100644 --- a/src/main/rx/sbus_channels.h +++ b/src/main/rx/sbus_channels.h @@ -20,7 +20,11 @@ #include #include "rx/rx.h" +#ifdef USE_24CHANNELS +#define SBUS_MAX_CHANNEL 26 +#else #define SBUS_MAX_CHANNEL 18 +#endif #define SBUS_FLAG_SIGNAL_LOSS (1 << 2) #define SBUS_FLAG_FAILSAFE_ACTIVE (1 << 3) diff --git a/src/main/target/common.h b/src/main/target/common.h index 2365be9671..e07ac9704a 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -190,5 +190,6 @@ #define USE_SERIALRX_SUMD #define USE_TELEMETRY_HOTT #define USE_HOTT_TEXTMODE +#define USE_24CHANNELS #endif From a22c24f472d9f8f5b5056cea065e82b58ccfcfa6 Mon Sep 17 00:00:00 2001 From: Nick B Date: Thu, 6 Apr 2023 22:11:01 +0200 Subject: [PATCH 007/175] Support for ATOMRC Exceed F405 FC V2 Support for ATOMRC Exceed F405 FC V2 --- src/main/target/ATOMRCF405V2/CMakeLists.txt | 1 + src/main/target/ATOMRCF405V2/README.md | 151 +++++++++++++++ src/main/target/ATOMRCF405V2/target.c | 47 +++++ src/main/target/ATOMRCF405V2/target.h | 194 ++++++++++++++++++++ 4 files changed, 393 insertions(+) create mode 100644 src/main/target/ATOMRCF405V2/CMakeLists.txt create mode 100644 src/main/target/ATOMRCF405V2/README.md create mode 100644 src/main/target/ATOMRCF405V2/target.c create mode 100644 src/main/target/ATOMRCF405V2/target.h diff --git a/src/main/target/ATOMRCF405V2/CMakeLists.txt b/src/main/target/ATOMRCF405V2/CMakeLists.txt new file mode 100644 index 0000000000..e78fd04a1a --- /dev/null +++ b/src/main/target/ATOMRCF405V2/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(ATOMRCF405V2) diff --git a/src/main/target/ATOMRCF405V2/README.md b/src/main/target/ATOMRCF405V2/README.md new file mode 100644 index 0000000000..2b17e279b6 --- /dev/null +++ b/src/main/target/ATOMRCF405V2/README.md @@ -0,0 +1,151 @@ +# ATOMRC F405 config +Tested against a "ATOMRC Exceed F405 DJI Mini FC" + +## Betaflight config + +``` +# Betaflight / STM32F405 (S405) 4.1.0 May 22 2019 / 02:24:46 (1541466da) MSP API: 1.42 + +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + +board_name ATOMRCF405 +manufacturer_id SKZO + +# resources +resource BEEPER 1 C13 +resource MOTOR 1 B00 +resource MOTOR 2 B01 +resource MOTOR 3 C07 +resource MOTOR 4 B04 +resource MOTOR 5 C08 +resource MOTOR 6 C09 +resource PPM 1 B15 +resource LED_STRIP 1 B06 +resource SERIAL_TX 1 A09 +resource SERIAL_TX 2 A02 +resource SERIAL_TX 3 B10 +resource SERIAL_TX 4 A00 +resource SERIAL_TX 5 C12 +resource SERIAL_RX 1 A10 +resource SERIAL_RX 2 A03 +resource SERIAL_RX 3 B11 +resource SERIAL_RX 4 A01 +resource SERIAL_RX 5 D02 +resource I2C_SCL 1 B08 +resource I2C_SDA 1 B09 +resource LED 1 C14 +resource LED 2 B02 +resource SPI_SCK 1 A05 +resource SPI_SCK 2 B13 +resource SPI_SCK 3 C10 +resource SPI_MISO 1 A06 +resource SPI_MISO 2 B14 +resource SPI_MISO 3 C11 +resource SPI_MOSI 1 A07 +resource SPI_MOSI 2 C03 +resource SPI_MOSI 3 B05 +resource ESCSERIAL 1 A03 +resource CAMERA_CONTROL 1 B03 +resource ADC_BATT 1 C02 +resource ADC_RSSI 1 C00 +resource ADC_CURR 1 C01 +resource FLASH_CS 1 B12 +resource OSD_CS 1 A15 +resource GYRO_EXTI 1 C04 +resource GYRO_CS 1 A04 + +# timer +timer B15 AF9 +# pin B15: TIM12 CH2 (AF9) +timer B00 AF2 +# pin B00: TIM3 CH3 (AF2) +timer B01 AF2 +# pin B01: TIM3 CH4 (AF2) +timer C07 AF2 +# pin C07: TIM3 CH2 (AF2) +timer B04 AF2 +# pin B04: TIM3 CH1 (AF2) +timer C08 AF3 +# pin C08: TIM8 CH3 (AF3) +timer C09 AF3 +# pin C09: TIM8 CH4 (AF3) +timer B06 AF2 +# pin B06: TIM4 CH1 (AF2) +timer B03 AF1 +# pin B03: TIM2 CH2 (AF1) + +# dma +dma ADC 1 1 +# ADC 1: DMA2 Stream 4 Channel 0 +dma pin B00 0 +# pin B00: DMA1 Stream 7 Channel 5 +dma pin B01 0 +# pin B01: DMA1 Stream 2 Channel 5 +dma pin C07 0 +# pin C07: DMA1 Stream 5 Channel 5 +dma pin B04 0 +# pin B04: DMA1 Stream 4 Channel 5 +dma pin C08 0 +# pin C08: DMA2 Stream 2 Channel 0 +dma pin C09 0 +# pin C09: DMA2 Stream 7 Channel 7 +dma pin B06 0 +# pin B06: DMA1 Stream 0 Channel 2 +dma pin B03 0 +# pin B03: DMA1 Stream 6 Channel 3 + +# feature +feature OSD + +# master +set baro_bustype = I2C +set baro_i2c_device = 1 +set blackbox_device = SPIFLASH +set dshot_burst = ON +set current_meter = ADC +set battery_meter = ADC +set beeper_inversion = ON +set beeper_od = OFF +set system_hse_mhz = 8 +set max7456_spi_bus = 3 +set flash_spi_bus = 2 +set gyro_1_bustype = SPI +set gyro_1_spibus = 1 +set gyro_1_sensor_align = CW90 +set gyro_1_align_yaw = 900 +``` + +## Board timers +``` +# timer + +# pin B15: TIM12 CH2 (AF9) # PPM 1 +timer B15 AF9 + +# pin B00: TIM3 CH3 (AF2) # M1 +timer B00 AF2 + +# pin B01: TIM3 CH4 (AF2) # M2 +timer B01 AF2 + +# pin C07: TIM3 CH2 (AF2) # M3 +timer C07 AF2 + +# pin B04: TIM3 CH1 (AF2) # M4 +timer B04 AF2 + +# pin C08: TIM8 CH3 (AF3) # M5 +timer C08 AF3 + +# pin C09: TIM8 CH4 (AF3) # M6 +timer C09 AF3 + +# pin B06: TIM4 CH1 (AF2) # LED_STRIP 1 +timer B06 AF2 + +# pin B03: TIM2 CH2 (AF1) # CAMERA_CONTROL 1 +timer B03 AF1 +``` \ No newline at end of file diff --git a/src/main/target/ATOMRCF405V2/target.c b/src/main/target/ATOMRCF405V2/target.c new file mode 100644 index 0000000000..848bd0a80e --- /dev/null +++ b/src/main/target/ATOMRCF405V2/target.c @@ -0,0 +1,47 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S5 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S6 + + DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED_STRIP +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/ATOMRCF405V2/target.h b/src/main/target/ATOMRCF405V2/target.h new file mode 100644 index 0000000000..b831565389 --- /dev/null +++ b/src/main/target/ATOMRCF405V2/target.h @@ -0,0 +1,194 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once +#define TARGET_BOARD_IDENTIFIER "ARF4" + +#define USBD_PRODUCT_STRING "AtomRCF405V2" + +#define LED0 PC14 +#define LED1 PB2 + +#define BEEPER PC13 +#define BEEPER_INVERTED + +/* + * SPI defines + */ +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PC3 + +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PB5 + +/* + * I2C defines + */ +#define USE_I2C +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +//MPU6000 +//#define USE_IMU_MPU6000 +//#define IMU_MPU6000_ALIGN CW180_DEG +//#define MPU6000_SPI_BUS BUS_SPI1 +//#define MPU6000_CS_PIN PA4 + +//BMI270 +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW180_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PA4 + + +/* + * Magnetometer + */ +#define USE_MAG +#define MAG_I2C_BUS DEFAULT_I2C_BUS + +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +/* + * Barometer + */ +#define USE_BARO +#define BARO_I2C_BUS DEFAULT_I2C_BUS +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_BMP085 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 + +/* + * Serial ports + */ +#define USE_VCP +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 + +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define SERIAL_PORT_COUNT 6 + +/* + * ADC + */ +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream4 + +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC2 + +#define VBAT_ADC_CHANNEL ADC_CHN_3 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_1 + +#define CURRENT_METER_SCALE 320 + +/* + * OSD + */ +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI3 +#define MAX7456_CS_PIN PA15 + +/* + * Blackbox + */ +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI2 +#define M25P16_CS_PIN PB12 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +/* + * LED Strip + */ +#define USE_LED_STRIP +#define WS2811_PIN PB6 + +/* + * Other configs + */ +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT ) +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// #define USE_RANGEFINDER +// #define USE_RANGEFINDER_MSP +// #define USE_OPFLOW +// #define USE_OPFLOW_MSP + +// #define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS +// #define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS +// #define PITOT_I2C_BUS DEFAULT_I2C_BUS + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define MAX_PWM_OUTPUT_PORTS 6 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) From d4e941ba3e668508c608241ff4025db4f465ffcf Mon Sep 17 00:00:00 2001 From: Nick B Date: Thu, 6 Apr 2023 22:45:57 +0200 Subject: [PATCH 008/175] Removed files from pull request --- .../target/SPEEDYBEEF405WING/CMakeLists.txt | 1 - src/main/target/SPEEDYBEEF405WING/config.c | 38 ---- src/main/target/SPEEDYBEEF405WING/target.c | 43 ----- src/main/target/SPEEDYBEEF405WING/target.h | 178 ------------------ 4 files changed, 260 deletions(-) delete mode 100644 src/main/target/SPEEDYBEEF405WING/CMakeLists.txt delete mode 100644 src/main/target/SPEEDYBEEF405WING/config.c delete mode 100644 src/main/target/SPEEDYBEEF405WING/target.c delete mode 100644 src/main/target/SPEEDYBEEF405WING/target.h diff --git a/src/main/target/SPEEDYBEEF405WING/CMakeLists.txt b/src/main/target/SPEEDYBEEF405WING/CMakeLists.txt deleted file mode 100644 index dcdde1675a..0000000000 --- a/src/main/target/SPEEDYBEEF405WING/CMakeLists.txt +++ /dev/null @@ -1 +0,0 @@ -target_stm32f405xg(SPEEDYBEEF405WING) diff --git a/src/main/target/SPEEDYBEEF405WING/config.c b/src/main/target/SPEEDYBEEF405WING/config.c deleted file mode 100644 index 62f5216cbd..0000000000 --- a/src/main/target/SPEEDYBEEF405WING/config.c +++ /dev/null @@ -1,38 +0,0 @@ -/* - * This file is part of INAV Project. - * - * This Source Code Form is subject to the terms of the Mozilla Public - * License, v. 2.0. If a copy of the MPL was not distributed with this file, - * You can obtain one at http://mozilla.org/MPL/2.0/. - * - * Alternatively, the contents of this file may be used under the terms - * of the GNU General Public License Version 3, as described below: - * - * This file is free software: you may copy, redistribute and/or modify - * it under the terms of the GNU General Public License as published by the - * Free Software Foundation, either version 3 of the License, or (at your - * option) any later version. - * - * This file is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General - * Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see http://www.gnu.org/licenses/. - */ - -#include -#include - -#include "platform.h" - -#include "fc/fc_msp_box.h" -#include "io/serial.h" - -void targetConfiguration(void) -{ - serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_RX_SERIAL; - serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART3)].functionMask = FUNCTION_GPS; - serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_MSP; -} diff --git a/src/main/target/SPEEDYBEEF405WING/target.c b/src/main/target/SPEEDYBEEF405WING/target.c deleted file mode 100644 index 4892321064..0000000000 --- a/src/main/target/SPEEDYBEEF405WING/target.c +++ /dev/null @@ -1,43 +0,0 @@ -/* - * This file is part of INAV. - * - * INAV is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * INAV is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with INAV. If not, see . - */ - -#include -#include -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" -#include "drivers/timer.h" - -timerHardware_t timerHardware[] = { - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S1 D(1,3,2) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S2 D(1,0,2) - - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S3 D(1,7,5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S4 D(1,2,5) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S5 D(2,4,7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S6 D(2,7,7) - - DEF_TIM(TIM8, CH2N,PB14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S7 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S8 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S9 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S10 - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S11 - - DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) - -}; - -const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SPEEDYBEEF405WING/target.h b/src/main/target/SPEEDYBEEF405WING/target.h deleted file mode 100644 index ad58668268..0000000000 --- a/src/main/target/SPEEDYBEEF405WING/target.h +++ /dev/null @@ -1,178 +0,0 @@ -/* - * This file is part of INAV. - * - * INAV is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * INAV is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with INAV. If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "SP4W" -#define USBD_PRODUCT_STRING "SpeedyBee F405 Wing" - -// LEDs -#define LED0 PA14 //Blue -#define LED1 PA13 //Green - -// Beeper -#define BEEPER PC15 -#define BEEPER_INVERTED - -/* - * Buses - */ - -// SPI1 -#define USE_SPI -#define USE_SPI_DEVICE_1 -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - -// SPI2 -#define USE_SPI_DEVICE_2 -#define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PC2 -#define SPI2_MOSI_PIN PC3 - -// SPI3 -#define USE_SPI_DEVICE_3 -#define SPI3_SCK_PIN PB3 -#define SPI3_MISO_PIN PB4 -#define SPI3_MOSI_PIN PB5 - -// Serial ports -#define USE_VCP - -#define USE_UART1 -#define UART1_TX_PIN PA9 -#define UART1_RX_PIN PA10 - -#define USE_UART2 -#define UART2_TX_PIN PA2 -#define UART2_RX_PIN PA3 - -#define USE_UART3 -#define UART3_TX_PIN PC10 -#define UART3_RX_PIN PC11 - -#define USE_UART4 -#define UART4_TX_PIN PA0 -#define UART4_RX_PIN PA1 - -#define USE_UART5 -#define UART5_TX_PIN PC12 -#define UART5_RX_PIN PD2 - -#define USE_UART6 -#define UART6_TX_PIN PC6 -#define UART6_RX_PIN PC7 - -//Optional Softserial on UART2 TX Pin PA2 -#define USE_SOFTSERIAL1 -#define SOFTSERIAL_1_TX_PIN PA2 -#define SOFTSERIAL_1_RX_PIN PA2 - -#define SERIAL_PORT_COUNT 8 - -/* - * I2C - */ -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 - -/* - * Sensor drivers - */ - -// ICM42605/ICM42688P -#define USE_IMU_ICM42605 -#define IMU_ICM42605_ALIGN CW270_DEG -#define ICM42605_CS_PIN PA4 -#define ICM42605_SPI_BUS BUS_SPI1 - -// Baro -#define USE_BARO -#define BARO_I2C_BUS BUS_I2C1 -#define USE_BARO_BMP280 -#define USE_BARO_MS5611 -#define USE_BARO_BMP085 -#define USE_BARO_DPS310 -#define USE_BARO_SPL06 - -//Mag -#define USE_MAG -#define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_VCM5883 - -#define RANGEFINDER_I2C_BUS BUS_I2C1 -#define PITOT_I2C_BUS BUS_I2C1 -#define TEMPERATURE_I2C_BUS BUS_I2C1 - -// OSD -#define USE_MAX7456 -#define MAX7456_CS_PIN PB12 -#define MAX7456_SPI_BUS BUS_SPI2 - -// SD Card -#define USE_SDCARD -#define USE_SDCARD_SPI -#define SDCARD_SPI_BUS BUS_SPI3 -#define SDCARD_CS_PIN PC14 - -#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT - -#define DEFAULT_RX_TYPE RX_TYPE_SERIAL -#define SERIALRX_PROVIDER SERIALRX_CRSF -#define SERIALRX_UART SERIAL_PORT_USART1 - -// *************** ADC *************************** -#define USE_ADC -#define ADC_INSTANCE ADC1 -#define ADC1_DMA_STREAM DMA2_Stream0 -#define ADC_CHANNEL_1_PIN PC0 -#define ADC_CHANNEL_2_PIN PC1 -#define ADC_CHANNEL_3_PIN PC5 -#define ADC_CHANNEL_4_PIN PC4 -#define VBAT_ADC_CHANNEL ADC_CHN_1 -#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 -#define RSSI_ADC_CHANNEL ADC_CHN_4 -#define AIRSPEED_ADC_CHANNEL ADC_CHN_3 - -// *************** LED2812 ************************ -#define USE_LED_STRIP -#define WS2811_PIN PA8 - -// *************** OTHERS ************************* -#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_BLACKBOX | FEATURE_AIRMODE) -#define CURRENT_METER_SCALE 195 - -#define USE_DSHOT -#define USE_ESC_SENSOR -#define USE_SERIAL_4WAY_BLHELI_INTERFACE - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) - -#define MAX_PWM_OUTPUT_PORTS 11 \ No newline at end of file From 7ea039bb10a0c0ceb795821fcbe9608f1af144f7 Mon Sep 17 00:00:00 2001 From: Nick B Date: Thu, 6 Apr 2023 22:49:17 +0200 Subject: [PATCH 009/175] Delete README.md --- src/main/target/ATOMRCF405V2/README.md | 151 ------------------------- 1 file changed, 151 deletions(-) delete mode 100644 src/main/target/ATOMRCF405V2/README.md diff --git a/src/main/target/ATOMRCF405V2/README.md b/src/main/target/ATOMRCF405V2/README.md deleted file mode 100644 index 2b17e279b6..0000000000 --- a/src/main/target/ATOMRCF405V2/README.md +++ /dev/null @@ -1,151 +0,0 @@ -# ATOMRC F405 config -Tested against a "ATOMRC Exceed F405 DJI Mini FC" - -## Betaflight config - -``` -# Betaflight / STM32F405 (S405) 4.1.0 May 22 2019 / 02:24:46 (1541466da) MSP API: 1.42 - -#define USE_ACC_SPI_MPU6000 -#define USE_GYRO_SPI_MPU6000 -#define USE_FLASH_W25Q128FV -#define USE_MAX7456 - -board_name ATOMRCF405 -manufacturer_id SKZO - -# resources -resource BEEPER 1 C13 -resource MOTOR 1 B00 -resource MOTOR 2 B01 -resource MOTOR 3 C07 -resource MOTOR 4 B04 -resource MOTOR 5 C08 -resource MOTOR 6 C09 -resource PPM 1 B15 -resource LED_STRIP 1 B06 -resource SERIAL_TX 1 A09 -resource SERIAL_TX 2 A02 -resource SERIAL_TX 3 B10 -resource SERIAL_TX 4 A00 -resource SERIAL_TX 5 C12 -resource SERIAL_RX 1 A10 -resource SERIAL_RX 2 A03 -resource SERIAL_RX 3 B11 -resource SERIAL_RX 4 A01 -resource SERIAL_RX 5 D02 -resource I2C_SCL 1 B08 -resource I2C_SDA 1 B09 -resource LED 1 C14 -resource LED 2 B02 -resource SPI_SCK 1 A05 -resource SPI_SCK 2 B13 -resource SPI_SCK 3 C10 -resource SPI_MISO 1 A06 -resource SPI_MISO 2 B14 -resource SPI_MISO 3 C11 -resource SPI_MOSI 1 A07 -resource SPI_MOSI 2 C03 -resource SPI_MOSI 3 B05 -resource ESCSERIAL 1 A03 -resource CAMERA_CONTROL 1 B03 -resource ADC_BATT 1 C02 -resource ADC_RSSI 1 C00 -resource ADC_CURR 1 C01 -resource FLASH_CS 1 B12 -resource OSD_CS 1 A15 -resource GYRO_EXTI 1 C04 -resource GYRO_CS 1 A04 - -# timer -timer B15 AF9 -# pin B15: TIM12 CH2 (AF9) -timer B00 AF2 -# pin B00: TIM3 CH3 (AF2) -timer B01 AF2 -# pin B01: TIM3 CH4 (AF2) -timer C07 AF2 -# pin C07: TIM3 CH2 (AF2) -timer B04 AF2 -# pin B04: TIM3 CH1 (AF2) -timer C08 AF3 -# pin C08: TIM8 CH3 (AF3) -timer C09 AF3 -# pin C09: TIM8 CH4 (AF3) -timer B06 AF2 -# pin B06: TIM4 CH1 (AF2) -timer B03 AF1 -# pin B03: TIM2 CH2 (AF1) - -# dma -dma ADC 1 1 -# ADC 1: DMA2 Stream 4 Channel 0 -dma pin B00 0 -# pin B00: DMA1 Stream 7 Channel 5 -dma pin B01 0 -# pin B01: DMA1 Stream 2 Channel 5 -dma pin C07 0 -# pin C07: DMA1 Stream 5 Channel 5 -dma pin B04 0 -# pin B04: DMA1 Stream 4 Channel 5 -dma pin C08 0 -# pin C08: DMA2 Stream 2 Channel 0 -dma pin C09 0 -# pin C09: DMA2 Stream 7 Channel 7 -dma pin B06 0 -# pin B06: DMA1 Stream 0 Channel 2 -dma pin B03 0 -# pin B03: DMA1 Stream 6 Channel 3 - -# feature -feature OSD - -# master -set baro_bustype = I2C -set baro_i2c_device = 1 -set blackbox_device = SPIFLASH -set dshot_burst = ON -set current_meter = ADC -set battery_meter = ADC -set beeper_inversion = ON -set beeper_od = OFF -set system_hse_mhz = 8 -set max7456_spi_bus = 3 -set flash_spi_bus = 2 -set gyro_1_bustype = SPI -set gyro_1_spibus = 1 -set gyro_1_sensor_align = CW90 -set gyro_1_align_yaw = 900 -``` - -## Board timers -``` -# timer - -# pin B15: TIM12 CH2 (AF9) # PPM 1 -timer B15 AF9 - -# pin B00: TIM3 CH3 (AF2) # M1 -timer B00 AF2 - -# pin B01: TIM3 CH4 (AF2) # M2 -timer B01 AF2 - -# pin C07: TIM3 CH2 (AF2) # M3 -timer C07 AF2 - -# pin B04: TIM3 CH1 (AF2) # M4 -timer B04 AF2 - -# pin C08: TIM8 CH3 (AF3) # M5 -timer C08 AF3 - -# pin C09: TIM8 CH4 (AF3) # M6 -timer C09 AF3 - -# pin B06: TIM4 CH1 (AF2) # LED_STRIP 1 -timer B06 AF2 - -# pin B03: TIM2 CH2 (AF1) # CAMERA_CONTROL 1 -timer B03 AF1 -``` \ No newline at end of file From 91ee7cc45bda2a5138e2960fb45522fac1781a80 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 15 Apr 2023 22:09:15 +0100 Subject: [PATCH 010/175] Add Odometer to OSD First cut --- src/main/drivers/osd_symbols.h | 1 + src/main/io/osd.c | 30 ++++++++++++++++++++++++++++++ src/main/io/osd.h | 1 + 3 files changed, 32 insertions(+) diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index a127234579..8fa94456c8 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -225,6 +225,7 @@ #define SYM_HOME_DIST 0x165 // 357 DIST #define SYM_AH_CH_CENTER 0x166 // 358 Crossair center #define SYM_FLIGHT_DIST_REMAINING 0x167 // 359 Flight distance reminaing +#define SYM_ODOMETER 0x168 // 360 Odometer #define SYM_AH_CH_TYPE3 0x190 // 400 to 402, crosshair 3 #define SYM_AH_CH_TYPE4 0x193 // 403 to 405, crosshair 4 diff --git a/src/main/io/osd.c b/src/main/io/osd.c index d9621ccb65..e0c3359436 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1842,6 +1842,35 @@ static bool osdDrawSingleElement(uint8_t item) osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); break; + case OSD_ODOMETER: +#ifdef USE_STATS + { + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_ODOMETER); + int odometerDist = (int)statsConfig()->stats_total_dist + (getTotalTravelDistance() / 100); + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + tfp_sprintf(buff+1, "%7d", (int)(odometerDist / METERS_PER_MILE)); + buff[6] = SYM_MI; + break; + default: + case OSD_UNIT_GA: + tfp_sprintf(buff+1, "%7d", (int)(odometerDist / METERS_PER_NAUTICALMILE)); + buff[6] = SYM_NM; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + tfp_sprintf(buff+1, "%7d", (int)(odometerDist / METERS_PER_KILOMETER)); + buff[6] = SYM_KM; + break; + } + buff[7] = '\0'; + } +#endif + break; + case OSD_GROUND_COURSE: { buff[0] = SYM_GROUND_COURSE; @@ -3670,6 +3699,7 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) //line 2 osdLayoutsConfig->item_pos[0][OSD_HOME_DIST] = OSD_POS(1, 1); osdLayoutsConfig->item_pos[0][OSD_TRIP_DIST] = OSD_POS(1, 2); + osdLayoutsConfig->item_pos[0][OSD_ODOMETER] = OSD_POS(1, 3); osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_CELL_VOLTAGE] = OSD_POS(12, 1); osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1); osdLayoutsConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1); diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 4bae42847e..6a41a97dfe 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -273,6 +273,7 @@ typedef enum { OSD_CROSS_TRACK_ERROR, OSD_PILOT_NAME, OSD_PAN_SERVO_CENTRED, + OSD_ODOMETER, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; From 55e47a26d5b1eeb1617215d405446a5ce4ac0fe0 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 10 Jun 2023 17:57:14 -0500 Subject: [PATCH 011/175] New target: SDMODELH7V1 first draft --- src/main/target/SDMODELH7V1/CMakeLists.txt | 1 + src/main/target/SDMODELH7V1/config.c | 40 +++++ src/main/target/SDMODELH7V1/target.c | 44 +++++ src/main/target/SDMODELH7V1/target.h | 184 +++++++++++++++++++++ 4 files changed, 269 insertions(+) create mode 100644 src/main/target/SDMODELH7V1/CMakeLists.txt create mode 100644 src/main/target/SDMODELH7V1/config.c create mode 100644 src/main/target/SDMODELH7V1/target.c create mode 100644 src/main/target/SDMODELH7V1/target.h diff --git a/src/main/target/SDMODELH7V1/CMakeLists.txt b/src/main/target/SDMODELH7V1/CMakeLists.txt new file mode 100644 index 0000000000..d8e1f7c3ab --- /dev/null +++ b/src/main/target/SDMODELH7V1/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32h743xi(SDMODELH7V1) diff --git a/src/main/target/SDMODELH7V1/config.c b/src/main/target/SDMODELH7V1/config.c new file mode 100644 index 0000000000..54f980fd8b --- /dev/null +++ b/src/main/target/SDMODELH7V1/config.c @@ -0,0 +1,40 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "fc/config.h" + +#include "io/piniobox.h" +#include "drivers/serial.h" +#include "io/serial.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; + + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].msp_baudrateIndex = BAUD_115200; + + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].msp_baudrateIndex = BAUD_115200; + +} diff --git a/src/main/target/SDMODELH7V1/target.c b/src/main/target/SDMODELH7V1/target.c new file mode 100644 index 0000000000..086d941f1c --- /dev/null +++ b/src/main/target/SDMODELH7V1/target.c @@ -0,0 +1,44 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" + +timerHardware_t timerHardware[] = { + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4 + + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 4), // S5 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 5), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 6), // S7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 7), // S8 + + DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 9), // LED_2812 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SDMODELH7V1/target.h b/src/main/target/SDMODELH7V1/target.h new file mode 100644 index 0000000000..1c1deedb1e --- /dev/null +++ b/src/main/target/SDMODELH7V1/target.h @@ -0,0 +1,184 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "SMH71" +#define USBD_PRODUCT_STRING "SDMODELH7V1" + +#endif + +#define USE_TARGET_CONFIG + +#define LED0 PC2 + +#define BEEPER PC13 +#define BEEPER_INVERTED + +// *************** IMU generic *********************** + + + + +// *************** SPI1 **************** +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_FLASHFS +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI1 +#define W25N01G_CS_PIN PA4 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + + + +// *************** SPI2 *********************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +// *************** SPI4 *************** +#define USE_SPI_DEVICE_4 +#define SPI4_SCK_PIN PE2 +#define SPI4_MISO_PIN PE5 +#define SPI4_MOSI_PIN PE6 + +//MPU6000 +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW270_DEG +#define MPU6000_SPI_BUS BUS_SPI4 +#define MPU6000_CS_PIN PE4 + +//BMI270 +#define USE_IMU_BMI270 +#define BMI270_SPI_BUS BUS_SPI4 +#define BMI270_CS_PIN PE4 + +#define IMU_BMI270_ALIGN CW0_DEG + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** I2C /Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL +#define USE_MAG_VCM5883 + +#define TEMPERATURE_I2C_BUS BUS_I2C1 +#define PITOT_I2C_BUS BUS_I2C1 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PD5 +#define UART2_RX_PIN PD6 + +#define USE_UART3 +#define UART3_TX_PIN PD8 +#define UART3_RX_PIN PD9 + +#define USE_UART4 +#define UART4_TX_PIN PD1 +#define UART4_RX_PIN PD0 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_UART7 +#define UART7_RX_PIN PE7 + +#define SERIAL_PORT_COUNT 7 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART1 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 + +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC5 +#define ADC_CHANNEL_3_PIN PC1 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3 +#define RSSI_ADC_CHANNEL ADC_CHN_2 + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX + +#define PINIO1_PIN PE13 +#define PINIO2_PIN PB11 +#define PINIO1_FLAGS PINIO_FLAGS_INVERTED +#define PINIO2_FLAGS PINIO_FLAGS_INVERTED + + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PD12 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) +#define CURRENT_METER_SCALE 250 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 8 +#define USE_DSHOT +#define USE_ESC_SENSOR + From 3d1474131eab0bc55c5c5aba24eac4fc330134c1 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 10 Jun 2023 18:13:55 -0500 Subject: [PATCH 012/175] SDMODELH7V1: remove stray endif --- src/main/target/SDMODELH7V1/target.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/target/SDMODELH7V1/target.h b/src/main/target/SDMODELH7V1/target.h index 1c1deedb1e..cc4d39cf6c 100644 --- a/src/main/target/SDMODELH7V1/target.h +++ b/src/main/target/SDMODELH7V1/target.h @@ -21,8 +21,6 @@ #define TARGET_BOARD_IDENTIFIER "SMH71" #define USBD_PRODUCT_STRING "SDMODELH7V1" -#endif - #define USE_TARGET_CONFIG #define LED0 PC2 From 9799ae07882822c65ced1028accd1105bcee741c Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 15 Jun 2023 10:16:00 +0200 Subject: [PATCH 013/175] Cap gyro_anti_aliasing_lpf_hz and gyro nyquist frequency to 1/2 of gyro sampling rate --- src/main/flight/ez_tune.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index cc1c3dab5b..c4846d3989 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -86,7 +86,7 @@ void ezTuneUpdate(void) { gyroConfigMutable()->gyro_main_lpf_type = FILTER_PT1; //Set anti-aliasing filter - gyroConfigMutable()->gyro_anti_aliasing_lpf_hz = MIN(ezTune()->filterHz * 2, 250); + gyroConfigMutable()->gyro_anti_aliasing_lpf_hz = MIN(MIN(ezTune()->filterHz * 2, 250), getGyroLooptime() * 0.5f); gyroConfigMutable()->gyro_anti_aliasing_lpf_type = FILTER_PT1; //Enable dynamic notch From 8de1ceb638c8558c838492e1fa06bb5e3363ad4d Mon Sep 17 00:00:00 2001 From: MrD-RC Date: Tue, 20 Jun 2023 08:19:34 +0100 Subject: [PATCH 014/175] Added mAh precision to Battery Capacity Remaining --- docs/Settings.md | 4 +-- src/main/fc/settings.yaml | 6 ++--- src/main/io/osd.c | 53 +++++++++++++++++++++++++++------------ src/main/io/osd.h | 2 +- 4 files changed, 43 insertions(+), 22 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 62d1791d34..84529e4e65 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -4292,9 +4292,9 @@ LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50 --- -### osd_mah_used_precision +### osd_mah_precision -Number of digits used to display mAh used. +Number of digits used for mAh precision. Currently used by mAh Used and Battery Remaining Capacity | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 7b26fb5df9..5441c0268e 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3448,9 +3448,9 @@ groups: max: 6 default_value: 3 - - name: osd_mah_used_precision - description: Number of digits used to display mAh used. - field: mAh_used_precision + - name: osd_mah_precision + description: Number of digits used for mAh precision. Currently used by mAh Used and Battery Remaining Capacity + field: mAh_precision min: 4 max: 6 default_value: 4 diff --git a/src/main/io/osd.c b/src/main/io/osd.c index d7841823a2..9bf68685ba 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1710,21 +1710,17 @@ static bool osdDrawSingleElement(uint8_t item) } case OSD_MAH_DRAWN: { - uint8_t mah_digits = osdConfig()->mAh_used_precision; // Initialize to config value - bool bfcompat = false; // Assume BFCOMPAT is off + uint8_t mah_digits = osdConfig()->mAh_precision; // Initialize to config value #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it if (isBfCompatibleVideoSystem(osdConfig())) { - bfcompat = true; - } -#endif - - if (bfcompat) { //BFcompat is unable to work with scaled values and it only has mAh symbol to work with - tfp_sprintf(buff, "%5d", (int)getMAhDrawn()); // Use 5 digits to allow 10Ah+ packs + tfp_sprintf(buff, "%5d", (int)getMAhDrawn()); // Use 5 digits to allow packs below 100Ah buff[5] = SYM_MAH; buff[6] = '\0'; - } else { + } else +#endif + { if (osdFormatCentiNumber(buff, getMAhDrawn() * 100, 1000, 0, (mah_digits - 2), mah_digits)) { // Shown in Ah buff[mah_digits] = SYM_AH; @@ -1747,25 +1743,50 @@ static bool osdDrawSingleElement(uint8_t item) break; case OSD_BATTERY_REMAINING_CAPACITY: + { + bool unitsDrawn = false; if (currentBatteryProfile->capacity.value == 0) tfp_sprintf(buff, " NA"); else if (!batteryWasFullWhenPluggedIn()) tfp_sprintf(buff, " NF"); - else if (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH) - tfp_sprintf(buff, "%4lu", (unsigned long)getBatteryRemainingCapacity()); - else // currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH + else if (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH) { + uint8_t mah_digits = osdConfig()->mAh_precision; // Initialize to config value + +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it + if (isBfCompatibleVideoSystem(osdConfig())) { + //BFcompat is unable to work with scaled values and it only has mAh symbol to work with + tfp_sprintf(buff, "%5d", (int)getBatteryRemainingCapacity()); // Use 5 digits to allow packs below 100Ah + buff[5] = SYM_MAH; + buff[6] = '\0'; + unitsDrawn = true; + } else +#endif + { + if (osdFormatCentiNumber(buff, getBatteryRemainingCapacity() * 100, 1000, 0, (mah_digits - 2), mah_digits)) { + // Shown in Ah + buff[mah_digits] = SYM_AH; + } else { + // Shown in mAh + buff[mah_digits] = SYM_MAH; + } + buff[mah_digits + 1] = '\0'; + unitsDrawn = true; + } + } else // currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH osdFormatCentiNumber(buff + 1, getBatteryRemainingCapacity() / 10, 0, 2, 0, 3); - buff[4] = currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH ? SYM_MAH : SYM_WH; - buff[5] = '\0'; + if (!unitsDrawn) { + buff[4] = currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH ? SYM_MAH : SYM_WH; + buff[5] = '\0'; + } if (batteryUsesCapacityThresholds()) { osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); } break; - + } case OSD_BATTERY_REMAINING_PERCENT: osdFormatBatteryChargeSymbol(buff); tfp_sprintf(buff + 1, "%3d%%", calculateBatteryPercentage()); @@ -3660,7 +3681,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .pan_servo_offcentre_warning = SETTING_OSD_PAN_SERVO_OFFCENTRE_WARNING_DEFAULT, .pan_servo_indicator_show_degrees = SETTING_OSD_PAN_SERVO_INDICATOR_SHOW_DEGREES_DEFAULT, .esc_rpm_precision = SETTING_OSD_ESC_RPM_PRECISION_DEFAULT, - .mAh_used_precision = SETTING_OSD_MAH_USED_PRECISION_DEFAULT, + .mAh_precision = SETTING_OSD_MAH_PRECISION_DEFAULT, .osd_switch_indicator0_name = SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_DEFAULT, .osd_switch_indicator0_channel = SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_DEFAULT, .osd_switch_indicator1_name = SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_DEFAULT, diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 2dad5ceb81..50d3e658a1 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -436,7 +436,7 @@ typedef struct osdConfig_s { uint8_t telemetry; // use telemetry on displayed pixel line 0 uint8_t esc_rpm_precision; // Number of characters used for the RPM numbers. uint16_t system_msg_display_time; // system message display time for multiple messages (ms) - uint8_t mAh_used_precision; // Number of numbers used for mAh drawn. Plently of packs now are > 9999 mAh + uint8_t mAh_precision; // Number of numbers used for mAh elements. Plenty of packs now are > 9999 mAh uint8_t ahi_pitch_interval; // redraws AHI at set pitch interval (Not pixel OSD) char osd_switch_indicator0_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 0. uint8_t osd_switch_indicator0_channel; // RC Channel to use for switch indicator 0. From c1039a7b2f34a0d6ea3ace06a90765a153c7ad79 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Tue, 11 Jul 2023 17:37:05 +0200 Subject: [PATCH 015/175] added gravityF7 --- src/main/target/GRAVITYF7/CMakeLists.txt | 1 + src/main/target/GRAVITYF7/config.c | 28 ++++ src/main/target/GRAVITYF7/target.c | 59 ++++++++ src/main/target/GRAVITYF7/target.h | 182 +++++++++++++++++++++++ 4 files changed, 270 insertions(+) create mode 100644 src/main/target/GRAVITYF7/CMakeLists.txt create mode 100644 src/main/target/GRAVITYF7/config.c create mode 100644 src/main/target/GRAVITYF7/target.c create mode 100644 src/main/target/GRAVITYF7/target.h diff --git a/src/main/target/GRAVITYF7/CMakeLists.txt b/src/main/target/GRAVITYF7/CMakeLists.txt new file mode 100644 index 0000000000..c56916ca10 --- /dev/null +++ b/src/main/target/GRAVITYF7/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(GRAVITYF7) diff --git a/src/main/target/GRAVITYF7/config.c b/src/main/target/GRAVITYF7/config.c new file mode 100644 index 0000000000..9e9e36732a --- /dev/null +++ b/src/main/target/GRAVITYF7/config.c @@ -0,0 +1,28 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include "platform.h" +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; +} \ No newline at end of file diff --git a/src/main/target/GRAVITYF7/target.c b/src/main/target/GRAVITYF7/target.c new file mode 100644 index 0000000000..80ee99e395 --- /dev/null +++ b/src/main/target/GRAVITYF7/target.c @@ -0,0 +1,59 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include "platform.h" +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS + + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 (2,1) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 (2,1) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 (2,5) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 (2,5) + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED STRIP(1,5) + + //DEF_TIM(TIM3, CH4, PB1, TIM_USE_CAMERA_CONTROL, 0, 0), // FC CAM + +}; + + +/* +timerHardware_t timerHardware[] = { + DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS + + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 (2,1) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 (2,1) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 (2,5) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 (2,5) + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_FW_SERVO, 0, 0), // LED STRIP(1,5) + + //DEF_TIM(TIM3, CH4, PB1, TIM_USE_CAMERA_CONTROL, 0, 0), // FC CAM + +}; +*/ +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); \ No newline at end of file diff --git a/src/main/target/GRAVITYF7/target.h b/src/main/target/GRAVITYF7/target.h new file mode 100644 index 0000000000..a770fbc861 --- /dev/null +++ b/src/main/target/GRAVITYF7/target.h @@ -0,0 +1,182 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "FLMD" +#define USBD_PRODUCT_STRING "GRAVITYF7" + +//#define USE_HARDWARE_PREBOOT_SETUP + +// User pin +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC2 // VTX power switcher + +#define LED0 PC14 +#define BEEPER PC13 +#define BEEPER_INVERTED + +#define USE_PITOT_VIRTUAL + + +// MPU6000 +#define USE_IMU_MPU6000 +#define MPU6000_CS_PIN PB0 +#define MPU6000_SPI_BUS BUS_SPI1 +#define IMU_MPU6000_ALIGN CW0_DEG_FLIP + +#define USE_EXTI +#define GYRO_INT_EXTI PB10 +#define USE_MPU_DATA_READY_SIGNAL + +// USB +#define USE_VCP +#define VBUS_SENSING_PIN PA10 +#define VBUS_SENSING_ENABLED + +// UARTs +#define USE_UART1 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PC10 +#define UART3_RX_PIN PC11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define SERIAL_PORT_COUNT 7 + +// i2c +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +// baro +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define BMP280_I2C_ADDR (0x77) + +// mag +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +// temp +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +#define PITOT_I2C_BUS BUS_I2C1 + + +// SPIs +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + + +#define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN PB2 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + + +// OSD +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + + +// BLACKBOX +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define M25P16_CS_PIN SPI3_NSS_PIN +#define M25P16_SPI_BUS BUS_SPI3 +#define USE_FLASHFS +#define USE_FLASH_M25P16 + + + +// ADC +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 + +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define VBAT_SCALE_DEFAULT 1120 +#define CURRENT_METER_SCALE 182 + + +// LED Strip +#define USE_LED_STRIP +#define WS2811_PIN PA15 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST5_HANDLER +#define WS2811_DMA_STREAM DMA1_Stream5 +#define WS2811_DMA_CHANNEL DMA_CHANNEL_3 + + + +// FEATURES +#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_BLACKBOX ) +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART1 + + +#define USE_ESC_SENSOR +#define USE_SERIALSHOT +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define MAX_PWM_OUTPUT_PORTS 6 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) \ No newline at end of file From e273fbb54690f70650702fa6788312ee789fb9d3 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Tue, 18 Jul 2023 00:29:55 +0200 Subject: [PATCH 016/175] osd joystick poc implementation --- docs/LED pin PWM.md | 61 +++++++++++++++ docs/OSD Joystick.md | 67 ++++++++++++++++ docs/Runcam device.md | 1 + src/main/CMakeLists.txt | 2 + src/main/config/parameter_group_ids.h | 4 +- src/main/drivers/light_ws2811strip.c | 107 ++++++++++++++++++++++---- src/main/drivers/light_ws2811strip.h | 22 +++++- src/main/drivers/timer_impl_hal.c | 20 +++-- src/main/fc/cli.c | 16 ++++ src/main/fc/fc_tasks.c | 5 ++ src/main/fc/settings.yaml | 55 +++++++++++++ src/main/io/osd_joystick.c | 74 ++++++++++++++++++ src/main/io/osd_joystick.h | 26 +++++++ src/main/io/rcdevice_cam.c | 60 +++++++++++++-- 14 files changed, 488 insertions(+), 32 deletions(-) create mode 100644 docs/LED pin PWM.md create mode 100644 docs/OSD Joystick.md create mode 100644 docs/Runcam device.md create mode 100644 src/main/io/osd_joystick.c create mode 100644 src/main/io/osd_joystick.h diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md new file mode 100644 index 0000000000..676d31f12b --- /dev/null +++ b/docs/LED pin PWM.md @@ -0,0 +1,61 @@ +# LED pin PWM + +Normally LED pin is used to drive WS2812 led strip. LED pin is held low, and every 10ms a set of pulses is sent to change color of the 24 LEDs: + +As alternative function, it is possible to generate PWM signal with specified duty ratio on the LED pin. + +Feature can be used to drive external devices. It also is used to simulate OSD joystick to control cameras. + +PWN frequency is fixed to 24kHz with duty ratio between 0 and 100%. + +There are four modes of opearation: +- low +- high +- shared_low +- shared_high + +Mode is configured using led_pin_pwm_mode setting. + +## Low + LED Pin is initialized to output low level and can be used to generate PWM signal. + ws2812 strip can not be controlled. + +## High + LED Pin is initialized to output high level and can be used to generate PWM signal. + ws2812 strip can not be controlled. + +## Shared low ( default) + LED Pin is used to drive WS2812 strip. Pauses between pulses are low: + + + It is possible to generate PWM signal with duty ratio >0...100%. While PWM signal is generated, ws2811 strip is not updated. When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio < ~10%. + + + +## Shared high + LED Pin is used to drive WS2812 strip. Pauses between pulses are high. ws2812 pulses are prefixed with 300us low 'reset' pulse: + + It is possible to generate PWM signal with duty ratio 0...<100%. While PWM signal is generated, ws2811 strip is not updated. When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1.5ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio > ~85%. + After sending ws2812 pulses for 24 LEDS, we held line high for 9ms, then send 300us low 'reset' pulse. Datasheet for ws2812 protocol does not describe behavior for long high pulse, but in practice it works the same as 'reset' pulse. To be safe, we also send correct low 'reset' pulse before starting next LEDs update sequence. + This moude is used to simulate OSD joystick. It is Ok that effective PWM ratio is 85..100% while driving LEDs, because OSD joystick keyspress voltages are far below 85%. + See OSD Joystick.md for more information. + +# Generating PWM signal in programming framework + +*TODO* +0...100 - enable PWM generation with specified duty cicle +-1 - disable PWM generation ( disable to allow ws2812 LEDs updates in shared modes ) + +# Generating PWM signal from CLI + +led_pin_pwm - value=0...100 - enable PWM generation with specified duty cicle +led_pin_pwm - disable PWM generation ( disable to allow ws2812 LEDs updates in shared modes ) + +# Example of driving single color LED + +*TODO* + +# Example of driving powerfull white LED + +*TODO* + diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md new file mode 100644 index 0000000000..a7f37d5d1d --- /dev/null +++ b/docs/OSD Joystick.md @@ -0,0 +1,67 @@ +# OSD joystick + +LED pin can be used to emulate 5key OSD joystick for OSD camera pin, while still driving ws2812 LEDs (shared functionality). + +Note that for cameras which support RuncamDevice protocol, there is alternative functionality sing serial communication: Runcam device.md + +# OSD Joystick schematics + +* TODO * + +Camera internal resistance seems to be 47kOhm or 9kOhm depending on camera model. + +Each key effectively implements voltage divider. Voltage is sensed by the camera and is compared to the list of keys voltages with some threshold. + +Key voltage has to be held for at least 200ms. + +To simulate 5key joystick, it is sufficient to generate correct voltage on camera OSD pin. + +# Enabling OSD Joystick emulation + +set led_pin_pwm_mode = shared_high +set osd_joystick_enabled = on + +# Connection diagram + +We use LED pin PWM functionality with RC filter to generate voltage: + +*schematics TODO - shows FC LED pin, ws2812 strip, RC filter, camera OSD pin* + +470Ohm, 10uF + + +# Example PCB layout (SMD components) + +RC Filter can be soldered on small piece of PCB: + + +# Configutring keys voltages + +If default voltages does not work with your camera model, then you have to measure voltages and find out corresponding PWM duty ratios. + +1. Connect 5keys joystick to camera. +2. Measure voltages on OSD pin while each key is pressed. +3. Connect camera to FC throught RC filter as shown on schematix above. +4. Enable OSD Joystick emulation (see "Enabling OSD Joystick emulation" above) +4. use cli command led_pin_pwm , value = 0...100 to find out PWM values for each voltage. +5. Specify PWM values in configuration and save: + +set osd_joystick_down=0 +set osd_joystick_up=48 +set osd_joystick_left=63 +set osd_joystick_right=28 +set osd_joystick_enter=75 + +# Entering OSD Joysyick emulation mode + +OSD Joystick emulation mode is enabled using the following stick combinations: +RIGHT CENTER + +Mode is exited using stick combinations: +LEFT CENTER + +*Note that the same stick combination is used to enable 5keys joystick emulation with RuncamDevice protocol.* + +Emulation can be enabled in unarmed state only. + +When you press key combination, correct voltage should be generated on OSD pin. diff --git a/docs/Runcam device.md b/docs/Runcam device.md new file mode 100644 index 0000000000..caac19b5b3 --- /dev/null +++ b/docs/Runcam device.md @@ -0,0 +1 @@ +# Runcam device \ No newline at end of file diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index e67ea9629d..02285abeeb 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -518,6 +518,8 @@ main_sources(COMMON_SRC io/osd_grid.h io/osd_hud.c io/osd_hud.h + io/osd_joystick.c + io/osd_joystick.h io/smartport_master.c io/smartport_master.h io/vtx.c diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index 46293524b1..119f2cf514 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -119,7 +119,9 @@ #define PG_UNUSED_1 1029 #define PG_POWER_LIMITS_CONFIG 1030 #define PG_OSD_COMMON_CONFIG 1031 -#define PG_INAV_END 1031 +#define PG_LEDPIN_CONFIG 1032 +#define PG_OSD_JOYSTICK_CONFIG 1033 +#define PG_INAV_END 1033 // OSD configuration (subject to change) //#define PG_OSD_FONT_CONFIG 2047 diff --git a/src/main/drivers/light_ws2811strip.c b/src/main/drivers/light_ws2811strip.c index 718c96ca8a..dbb3f093cd 100644 --- a/src/main/drivers/light_ws2811strip.c +++ b/src/main/drivers/light_ws2811strip.c @@ -43,15 +43,26 @@ #include "drivers/timer.h" #include "drivers/light_ws2811strip.h" +#include "config/parameter_group_ids.h" +#include "fc/settings.h" +#include "fc/runtime_config.h" + #define WS2811_PERIOD (WS2811_TIMER_HZ / WS2811_CARRIER_HZ) #define WS2811_BIT_COMPARE_1 ((WS2811_PERIOD * 2) / 3) #define WS2811_BIT_COMPARE_0 (WS2811_PERIOD / 3) +PG_REGISTER_WITH_RESET_TEMPLATE(ledPinConfig_t, ledPinConfig, PG_LEDPIN_CONFIG, 0); + +PG_RESET_TEMPLATE(ledPinConfig_t, ledPinConfig, + .led_pin_pwm_mode = SETTING_LED_PIN_PWM_MODE_DEFAULT +); + static DMA_RAM timerDMASafeType_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE]; static IO_t ws2811IO = IO_NONE; static TCH_t * ws2811TCH = NULL; static bool ws2811Initialised = false; +static bool pwmMode = false; static hsvColor_t ledColorBuffer[WS2811_LED_STRIP_LENGTH]; @@ -91,6 +102,24 @@ void setStripColors(const hsvColor_t *colors) } } +bool ledConfigureDMA(void) { + /* Compute the prescaler value */ + uint8_t period = WS2811_TIMER_HZ / WS2811_CARRIER_HZ; + + timerConfigBase(ws2811TCH, period, WS2811_TIMER_HZ); + timerPWMConfigChannel(ws2811TCH, 0); + + return timerPWMConfigChannelDMA(ws2811TCH, ledStripDMABuffer, sizeof(ledStripDMABuffer[0]), WS2811_DMA_BUFFER_SIZE); +} + +void ledConfigurePWM(void) { + timerConfigBase(ws2811TCH, 100, WS2811_TIMER_HZ ); + timerPWMConfigChannel(ws2811TCH, 0); + timerPWMStart(ws2811TCH); + timerEnable(ws2811TCH); + pwmMode = true; +} + void ws2811LedStripInit(void) { const timerHardware_t * timHw = timerGetByTag(IO_TAG(WS2811_PIN), TIM_USE_ANY); @@ -104,27 +133,34 @@ void ws2811LedStripInit(void) return; } - /* Compute the prescaler value */ - uint8_t period = WS2811_TIMER_HZ / WS2811_CARRIER_HZ; - ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOConfigGPIOAF(ws2811IO, IOCFG_AF_PP_FAST, timHw->alternateFunction); - timerConfigBase(ws2811TCH, period, WS2811_TIMER_HZ); - timerPWMConfigChannel(ws2811TCH, 0); + if ( ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_LOW ) { + ledConfigurePWM(); + *timerCCR(ws2811TCH) = 0; + IOLo(ws2811IO); + } else if ( ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_HIGH ) { + ledConfigurePWM(); + *timerCCR(ws2811TCH) = 100; + IOHi(ws2811IO); + } else { + if (!ledConfigureDMA()) { + // If DMA failed - abort + ws2811Initialised = false; + return; + } - // If DMA failed - abort - if (!timerPWMConfigChannelDMA(ws2811TCH, ledStripDMABuffer, sizeof(ledStripDMABuffer[0]), WS2811_DMA_BUFFER_SIZE)) { - ws2811Initialised = false; - return; + // Zero out DMA buffer + memset(&ledStripDMABuffer, 0, sizeof(ledStripDMABuffer)); + if ( ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_SHARED_HIGH ) { + ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE-1] = 255; + } + ws2811Initialised = true; + + ws2811UpdateStrip(); } - - // Zero out DMA buffer - memset(&ledStripDMABuffer, 0, sizeof(ledStripDMABuffer)); - ws2811Initialised = true; - - ws2811UpdateStrip(); } bool isWS2811LedStripReady(void) @@ -140,7 +176,7 @@ STATIC_UNIT_TESTED void fastUpdateLEDDMABuffer(rgbColor24bpp_t *color) uint32_t grb = (color->rgb.g << 16) | (color->rgb.r << 8) | (color->rgb.b); for (int8_t index = 23; index >= 0; index--) { - ledStripDMABuffer[dmaBufferOffset++] = (grb & (1 << index)) ? WS2811_BIT_COMPARE_1 : WS2811_BIT_COMPARE_0; + ledStripDMABuffer[WS2811_DELAY_BUFFER_LENGTH + dmaBufferOffset++] = (grb & (1 << index)) ? WS2811_BIT_COMPARE_1 : WS2811_BIT_COMPARE_0; } } @@ -153,7 +189,7 @@ void ws2811UpdateStrip(void) static rgbColor24bpp_t *rgb24; // don't wait - risk of infinite block, just get an update next time round - if (timerPWMDMAInProgress(ws2811TCH)) { + if (pwmMode || timerPWMDMAInProgress(ws2811TCH)) { return; } @@ -178,4 +214,41 @@ void ws2811UpdateStrip(void) timerPWMStartDMA(ws2811TCH); } +//value +void ledPinStartPWM(uint16_t value) { + if (ws2811TCH == NULL) { + return; + } + + if ( !pwmMode ) { + timerPWMStopDMA(ws2811TCH); + //FIXME: implement method to release DMA + ws2811TCH->dma->owner = OWNER_FREE; + + ledConfigurePWM(); + } + *timerCCR(ws2811TCH) = value; +} + +void ledPinStopPWM(void) { + if (ws2811TCH == NULL || !pwmMode ) { + return; + } + pwmMode = false; + + if ( (ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_SHARED_HIGH) || + (ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_HIGH) ) { + *timerCCR(ws2811TCH) = 100; + IOHi(ws2811IO); + } else { + *timerCCR(ws2811TCH) = 0; + IOLo(ws2811IO); + } + + if (!ledConfigureDMA()) { + ws2811Initialised = false; + } +} + + #endif diff --git a/src/main/drivers/light_ws2811strip.h b/src/main/drivers/light_ws2811strip.h index d70a255d88..a673899146 100644 --- a/src/main/drivers/light_ws2811strip.h +++ b/src/main/drivers/light_ws2811strip.h @@ -17,23 +17,41 @@ #pragma once #include "common/color.h" +#include "config/parameter_group.h" #define WS2811_LED_STRIP_LENGTH 32 #define WS2811_BITS_PER_LED 24 -#define WS2811_DELAY_BUFFER_LENGTH 42 // for 50us delay +#define WS2811_DELAY_BUFFER_LENGTH 242 // for 300us delay ( new LEDS since 2017 require 300us delay, old LEDS were fine with 50us ) #define WS2811_DATA_BUFFER_SIZE (WS2811_BITS_PER_LED * WS2811_LED_STRIP_LENGTH) -#define WS2811_DMA_BUFFER_SIZE (WS2811_DATA_BUFFER_SIZE + WS2811_DELAY_BUFFER_LENGTH) // number of bytes needed is #LEDs * 24 bytes + 42 trailing bytes) +#define WS2811_DMA_BUFFER_SIZE (WS2811_DELAY_BUFFER_LENGTH + WS2811_DATA_BUFFER_SIZE + 1) // leading bytes (reset low 302us) + data bytes LEDS*3 + 1 byte(keep line high optionally) #define WS2811_TIMER_HZ 2400000 #define WS2811_CARRIER_HZ 800000 +typedef enum { + LED_PIN_PWM_MODE_SHARED_LOW = 0, + LED_PIN_PWM_MODE_SHARED_HIGH = 1, + LED_PIN_PWM_MODE_LOW = 2, + LED_PIN_PWM_MODE_HIGH = 3 +} led_pin_pwm_mode_e; + +typedef struct ledPinConfig_s { + uint8_t led_pin_pwm_mode; //led_pin_pwm_mode_e +} ledPinConfig_t; + +PG_DECLARE(ledPinConfig_t, ledPinConfig); + void ws2811LedStripInit(void); void ws2811LedStripHardwareInit(void); void ws2811LedStripDMAEnable(void); bool ws2811LedStripDMAInProgress(void); +//value 0...100 +void ledPinStartPWM(uint16_t value); +void ledPinStopPWM(void); + void ws2811UpdateStrip(void); void setLedHsv(uint16_t index, const hsvColor_t *color); diff --git a/src/main/drivers/timer_impl_hal.c b/src/main/drivers/timer_impl_hal.c index 0649513f21..e49382f87a 100644 --- a/src/main/drivers/timer_impl_hal.c +++ b/src/main/drivers/timer_impl_hal.c @@ -81,13 +81,16 @@ void impl_timerConfigBase(TCH_t * tch, uint16_t period, uint32_t hz) TIM_HandleTypeDef * timHandle = tch->timCtx->timHandle; TIM_TypeDef * timer = tch->timCtx->timDef->tim; - if (timHandle->Instance == timer) { + uint16_t period1 = (period - 1) & 0xffff; + uint16_t prescaler1 = lrintf((float)timerGetBaseClock(tch) / hz + 0.01f) - 1; + + if (timHandle->Instance == timer && timHandle->Init.Prescaler == prescaler1 && timHandle->Init.Period == period1) { return; } timHandle->Instance = timer; - timHandle->Init.Prescaler = lrintf((float)timerGetBaseClock(tch) / hz + 0.01f) - 1; - timHandle->Init.Period = (period - 1) & 0xffff; // AKA TIMx_ARR + timHandle->Init.Prescaler = prescaler1; + timHandle->Init.Period = period1; // AKA TIMx_ARR timHandle->Init.RepetitionCounter = 0; timHandle->Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; timHandle->Init.CounterMode = TIM_COUNTERMODE_UP; @@ -462,6 +465,13 @@ void impl_timerPWMStartDMA(TCH_t * tch) void impl_timerPWMStopDMA(TCH_t * tch) { - (void)tch; - // FIXME + const uint32_t streamLL = lookupDMALLStreamTable[DMATAG_GET_STREAM(tch->timHw->dmaTag)]; + DMA_TypeDef *dmaBase = tch->dma->dma; + + ATOMIC_BLOCK(NVIC_PRIO_MAX) { + LL_TIM_DisableDMAReq_CCx(tch->timHw->tim, lookupDMASourceTable[tch->timHw->channelIndex]); + LL_DMA_DisableStream(dmaBase, streamLL); + DMA_CLEAR_FLAG(tch->dma, DMA_IT_TCIF); + } + HAL_TIM_Base_Start(tch->timCtx->timHandle); } diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index a14aac38a2..b1302043ce 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -68,6 +68,7 @@ bool cliMode = false; #include "drivers/time.h" #include "drivers/usb_msc.h" #include "drivers/vtx_common.h" +#include "drivers/light_ws2811strip.h" #include "fc/fc_core.h" #include "fc/cli.h" @@ -1681,6 +1682,20 @@ static void cliModeColor(char *cmdline) cliPrintLinef("mode_color %u %u %u", modeIdx, funIdx, color); } } + +static void cliLedPinPWM(char *cmdline) +{ + int i; + + if (isEmpty(cmdline)) { + ledPinStopPWM(); + cliPrintLine("PWM stopped"); + } else { + i = fastA2I(cmdline); + ledPinStartPWM(i); + cliPrintLinef("PWM started: %d%%",i); + } +} #endif static void cliDelay(char* cmdLine) { @@ -3912,6 +3927,7 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("help", NULL, NULL, cliHelp), #ifdef USE_LED_STRIP CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed), + CLI_COMMAND_DEF("ledpinpwm", "start/stop PWM on LED pin, 0..100 duty ratio", "[]\r\n", cliLedPinPWM), #endif CLI_COMMAND_DEF("map", "configure rc channel order", "[]", cliMap), CLI_COMMAND_DEF("memory", "view memory usage", NULL, cliMemory), diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 7b2ba3b5d5..199f3cae4f 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -62,6 +62,7 @@ #include "io/osd.h" #include "io/serial.h" #include "io/rcdevice_cam.h" +#include "io/osd_joystick.h" #include "io/smartport_master.h" #include "io/vtx.h" #include "io/osd_dji_hd.h" @@ -389,8 +390,12 @@ void fcTasksInit(void) #endif #endif #ifdef USE_RCDEVICE +#ifdef USE_LED_STRIP + setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled() || osdJoystickEnabled()); +#else setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled()); #endif +#endif #ifdef USE_PROGRAMMING_FRAMEWORK setTaskEnabled(TASK_PROGRAMMING_FRAMEWORK, true); #endif diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a0904af6f3..e5db27089c 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -190,6 +190,9 @@ tables: - name: nav_fw_wp_turn_smoothing values: ["OFF", "ON", "ON-CUT"] enum: wpFwTurnSmoothing_e + - name: led_pin_pwm_mode + values: ["SHARED_LOW", "SHARED_HIGH", "LOW", "HIGH"] + enum: led_pin_pwm_mode_e constants: RPYL_PID_MIN: 0 @@ -3896,3 +3899,55 @@ groups: default_value: 1.2 field: attnFilterCutoff max: 100 + + - name: PG_LEDPIN_CONFIG + type: ledPinConfig_t + headers: ["drivers/light_ws2811strip.h"] + members: + - name: led_pin_pwm_mode + condition: USE_LED_STRIP + description: "PWM mode of LED pin." + default_value: "SHARED_LOW" + field: led_pin_pwm_mode + table: led_pin_pwm_mode + + - name: PG_OSD_JOYSTICK_CONFIG + type: osdJoystickConfig_t + headers: ["io/osd_joystick.h"] + condition: USE_RCDEVICE && USE_LED_STRIP + members: + - name: osd_joystick_enabled + description: "Enable OSD Joystick emulation" + default_value: OFF + field: osd_joystick_enabled + type: bool + - name: osd_joystick_down + description: "PWM value for DOWN key" + default_value: 0 + field: osd_joystick_down + min: 0 + max: 100 + - name: osd_joystick_up + description: "PWM value for UP key" + default_value: 48 + field: osd_joystick_up + min: 0 + max: 100 + - name: osd_joystick_left + description: "PWM value for LEFT key" + default_value: 63 + field: osd_joystick_left + min: 0 + max: 100 + - name: osd_joystick_right + description: "PWM value for RIGHT key" + default_value: 28 + field: osd_joystick_right + min: 0 + max: 100 + - name: osd_joystick_enter + description: "PWM value for ENTER key" + default_value: 75 + field: osd_joystick_enter + min: 0 + max: 100 diff --git a/src/main/io/osd_joystick.c b/src/main/io/osd_joystick.c new file mode 100644 index 0000000000..c1d9dee5a5 --- /dev/null +++ b/src/main/io/osd_joystick.c @@ -0,0 +1,74 @@ +#include +#include +#include + +#include "platform.h" + +#include "common/crc.h" +#include "common/maths.h" +#include "common/streambuf.h" +#include "common/utils.h" + +#include "build/build_config.h" + +#include "config/parameter_group.h" +#include "config/parameter_group_ids.h" +#include "fc/settings.h" +#include "fc/runtime_config.h" + +#include "drivers/time.h" +#include "drivers/light_ws2811strip.h" + +#include "io/serial.h" +#include "io/rcdevice.h" + +#include "osd_joystick.h" + +#ifdef USE_RCDEVICE +#ifdef USE_LED_STRIP + + +PG_REGISTER_WITH_RESET_TEMPLATE(osdJoystickConfig_t, osdJoystickConfig, PG_OSD_JOYSTICK_CONFIG, 0); + +PG_RESET_TEMPLATE(osdJoystickConfig_t, osdJoystickConfig, + .osd_joystick_enabled = SETTING_OSD_JOYSTICK_ENABLED_DEFAULT, + .osd_joystick_down = SETTING_OSD_JOYSTICK_DOWN_DEFAULT, + .osd_joystick_up = SETTING_OSD_JOYSTICK_UP_DEFAULT, + .osd_joystick_left = SETTING_OSD_JOYSTICK_LEFT_DEFAULT, + .osd_joystick_right = SETTING_OSD_JOYSTICK_RIGHT_DEFAULT, + .osd_joystick_enter = SETTING_OSD_JOYSTICK_ENTER_DEFAULT +); + +bool osdJoystickEnabled(void) { + return osdJoystickConfig()->osd_joystick_enabled; +} + + +void osdJoystickSimulate5KeyButtonPress(uint8_t operation) { + switch (operation) { + case RCDEVICE_CAM_KEY_ENTER: + ledPinStartPWM( osdJoystickConfig()->osd_joystick_enter ); + break; + case RCDEVICE_CAM_KEY_LEFT: + ledPinStartPWM( osdJoystickConfig()->osd_joystick_left ); + break; + case RCDEVICE_CAM_KEY_UP: + ledPinStartPWM( osdJoystickConfig()->osd_joystick_up ); + break; + case RCDEVICE_CAM_KEY_RIGHT: + ledPinStartPWM( osdJoystickConfig()->osd_joystick_right ); + break; + case RCDEVICE_CAM_KEY_DOWN: + ledPinStartPWM( osdJoystickConfig()->osd_joystick_down ); + break; + } +} + + +void osdJoystickSimulate5KeyButtonRelease(void) { + ledPinStopPWM(); +} + + +#endif +#endif diff --git a/src/main/io/osd_joystick.h b/src/main/io/osd_joystick.h new file mode 100644 index 0000000000..574b8e3b77 --- /dev/null +++ b/src/main/io/osd_joystick.h @@ -0,0 +1,26 @@ +#pragma once + +#include "config/parameter_group.h" + +#ifdef USE_RCDEVICE +#ifdef USE_LED_STRIP + +typedef struct osdJoystickConfig_s { + bool osd_joystick_enabled; + uint8_t osd_joystick_down; + uint8_t osd_joystick_up; + uint8_t osd_joystick_left; + uint8_t osd_joystick_right; + uint8_t osd_joystick_enter; +} osdJoystickConfig_t; + +PG_DECLARE(osdJoystickConfig_t, osdJoystickConfig); + +bool osdJoystickEnabled(void); + +// 5 key osd cable simulation +void osdJoystickSimulate5KeyButtonPress(uint8_t operation); +void osdJoystickSimulate5KeyButtonRelease(void); + +#endif +#endif \ No newline at end of file diff --git a/src/main/io/rcdevice_cam.c b/src/main/io/rcdevice_cam.c index 36a0f99869..a353d713f4 100644 --- a/src/main/io/rcdevice_cam.c +++ b/src/main/io/rcdevice_cam.c @@ -29,6 +29,7 @@ #include "io/beeper.h" #include "io/rcdevice_cam.h" +#include "io/osd_joystick.h" #include "rx/rx.h" @@ -100,10 +101,33 @@ static void rcdeviceCameraControlProcess(void) break; } if (behavior != RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION) { - runcamDeviceSimulateCameraButton(camDevice, behavior); + if ( rcdeviceIsEnabled() ) { + runcamDeviceSimulateCameraButton(camDevice, behavior); + } +#ifdef USE_LED_STRIP + else if (osdJoystickEnabled()) { + + switch (behavior) { + case RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN: + osdJoystickSimulate5KeyButtonPress(RCDEVICE_CAM_KEY_ENTER); + break; + case RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN: + osdJoystickSimulate5KeyButtonPress(RCDEVICE_CAM_KEY_UP); + break; + case RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE: + osdJoystickSimulate5KeyButtonPress(RCDEVICE_CAM_KEY_DOWN); + break; + } + } +#endif switchStates[switchIndex].isActivated = true; } } else { +#ifdef USE_LED_STRIP + if (osdJoystickEnabled() && switchStates[switchIndex].isActivated) { + osdJoystickSimulate5KeyButtonRelease(); + } +#endif switchStates[switchIndex].isActivated = false; } } @@ -225,14 +249,21 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs) } #endif - if (camDevice->serialPort == 0 || ARMING_FLAG(ARMED)) { + if (ARMING_FLAG(ARMED)) { return; } if (isButtonPressed) { if (IS_MID(YAW) && IS_MID(PITCH) && IS_MID(ROLL)) { - rcdeviceSend5KeyOSDCableSimualtionEvent(RCDEVICE_CAM_KEY_RELEASE); - waitingDeviceResponse = true; + if ( rcdeviceIsEnabled() ) { + rcdeviceSend5KeyOSDCableSimualtionEvent(RCDEVICE_CAM_KEY_RELEASE); + waitingDeviceResponse = true; + } +#ifdef USE_LED_STRIP + else if (osdJoystickEnabled()) { + osdJoystickSimulate5KeyButtonRelease(); + } +#endif } } else { if (waitingDeviceResponse) { @@ -266,16 +297,31 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs) } if (key != RCDEVICE_CAM_KEY_NONE) { - rcdeviceSend5KeyOSDCableSimualtionEvent(key); + if ( rcdeviceIsEnabled() ) { + rcdeviceSend5KeyOSDCableSimualtionEvent(key); + waitingDeviceResponse = true; + } +#ifdef USE_LED_STRIP + else if (osdJoystickEnabled()) { + if ( key == RCDEVICE_CAM_KEY_CONNECTION_OPEN ) { + rcdeviceInMenu = true; + } else if ( key == RCDEVICE_CAM_KEY_CONNECTION_CLOSE ) { + rcdeviceInMenu = false; + } else { + osdJoystickSimulate5KeyButtonPress(key); + } + } +#endif isButtonPressed = true; - waitingDeviceResponse = true; } } } void rcdeviceUpdate(timeUs_t currentTimeUs) { - rcdeviceReceive(currentTimeUs); + if ( rcdeviceIsEnabled() ) { + rcdeviceReceive(currentTimeUs); + } rcdeviceCameraControlProcess(); From 37b172aaf2d15067a8648cd66aa93e233fdd4cb1 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 20 Jul 2023 16:47:02 +0200 Subject: [PATCH 017/175] Update OSD Joystick.md --- docs/OSD Joystick.md | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md index a7f37d5d1d..794aac26d4 100644 --- a/docs/OSD Joystick.md +++ b/docs/OSD Joystick.md @@ -2,7 +2,7 @@ LED pin can be used to emulate 5key OSD joystick for OSD camera pin, while still driving ws2812 LEDs (shared functionality). -Note that for cameras which support RuncamDevice protocol, there is alternative functionality sing serial communication: Runcam device.md +Note that for cameras which support RuncamDevice protocol, there is alternative functionality using serial communication: Runcam device.md # OSD Joystick schematics @@ -10,7 +10,7 @@ Note that for cameras which support RuncamDevice protocol, there is alternative Camera internal resistance seems to be 47kOhm or 9kOhm depending on camera model. -Each key effectively implements voltage divider. Voltage is sensed by the camera and is compared to the list of keys voltages with some threshold. +Each key effectively turns on voltage divider. Voltage is sensed by the camera and is compared to the list of keys voltages with some threshold. Key voltage has to be held for at least 200ms. @@ -43,7 +43,7 @@ If default voltages does not work with your camera model, then you have to measu 2. Measure voltages on OSD pin while each key is pressed. 3. Connect camera to FC throught RC filter as shown on schematix above. 4. Enable OSD Joystick emulation (see "Enabling OSD Joystick emulation" above) -4. use cli command led_pin_pwm , value = 0...100 to find out PWM values for each voltage. +4. Use cli command led_pin_pwm , value = 0...100 to find out PWM values for each voltage. 5. Specify PWM values in configuration and save: set osd_joystick_down=0 @@ -52,12 +52,12 @@ set osd_joystick_left=63 set osd_joystick_right=28 set osd_joystick_enter=75 -# Entering OSD Joysyick emulation mode +# Entering OSD Joystick emulation mode -OSD Joystick emulation mode is enabled using the following stick combinations: +OSD Joystick emulation mode is enabled using the following stick combination: RIGHT CENTER -Mode is exited using stick combinations: +Mode is exited using stick combination: LEFT CENTER *Note that the same stick combination is used to enable 5keys joystick emulation with RuncamDevice protocol.* From ce1ec2aec17ff8a27af25744702eb4adf6514fe3 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 20 Jul 2023 16:56:12 +0200 Subject: [PATCH 018/175] Update LED pin PWM.md --- docs/LED pin PWM.md | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index 676d31f12b..fa9fb489d1 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -4,9 +4,9 @@ Normally LED pin is used to drive WS2812 led strip. LED pin is held low, and eve As alternative function, it is possible to generate PWM signal with specified duty ratio on the LED pin. -Feature can be used to drive external devices. It also is used to simulate OSD joystick to control cameras. +Feature can be used to drive external devices. It is also used to simulate OSD joystick to control cameras. -PWN frequency is fixed to 24kHz with duty ratio between 0 and 100%. +PWM frequency is fixed to 24kHz with duty ratio between 0 and 100%. There are four modes of opearation: - low @@ -17,14 +17,14 @@ There are four modes of opearation: Mode is configured using led_pin_pwm_mode setting. ## Low - LED Pin is initialized to output low level and can be used to generate PWM signal. + LED Pin is initialized to output low level by default and can be used to generate PWM signal. ws2812 strip can not be controlled. ## High - LED Pin is initialized to output high level and can be used to generate PWM signal. + LED Pin is initialized to output high level by default and can be used to generate PWM signal. ws2812 strip can not be controlled. -## Shared low ( default) +## Shared low (default) LED Pin is used to drive WS2812 strip. Pauses between pulses are low: From 9b77aa90563a70b9287cc23dfa407078eb87f2c7 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Fri, 21 Jul 2023 23:18:12 +0200 Subject: [PATCH 019/175] adjusted documentation --- docs/LED pin PWM.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index fa9fb489d1..4f43ce37d5 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -48,8 +48,8 @@ Mode is configured using led_pin_pwm_mode setting. # Generating PWM signal from CLI -led_pin_pwm - value=0...100 - enable PWM generation with specified duty cicle -led_pin_pwm - disable PWM generation ( disable to allow ws2812 LEDs updates in shared modes ) +ledpinpwm - value=0...100 - enable PWM generation with specified duty cicle +ledpinpwm - disable PWM generation ( disable to allow ws2812 LEDs updates in shared modes ) # Example of driving single color LED From 2105235e6eb981b0d7471d450e0fff0e398efe83 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Fri, 21 Jul 2023 23:18:42 +0200 Subject: [PATCH 020/175] fixed led_pin_pwm_mode=high --- src/main/drivers/light_ws2811strip.c | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/src/main/drivers/light_ws2811strip.c b/src/main/drivers/light_ws2811strip.c index dbb3f093cd..cb56a7fe79 100644 --- a/src/main/drivers/light_ws2811strip.c +++ b/src/main/drivers/light_ws2811strip.c @@ -140,11 +140,9 @@ void ws2811LedStripInit(void) if ( ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_LOW ) { ledConfigurePWM(); *timerCCR(ws2811TCH) = 0; - IOLo(ws2811IO); } else if ( ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_HIGH ) { ledConfigurePWM(); *timerCCR(ws2811TCH) = 100; - IOHi(ws2811IO); } else { if (!ledConfigureDMA()) { // If DMA failed - abort @@ -234,16 +232,15 @@ void ledPinStopPWM(void) { if (ws2811TCH == NULL || !pwmMode ) { return; } - pwmMode = false; - if ( (ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_SHARED_HIGH) || - (ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_HIGH) ) { + if ( ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_HIGH ) { *timerCCR(ws2811TCH) = 100; - IOHi(ws2811IO); - } else { + return; + } else if ( ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_LOW ) { *timerCCR(ws2811TCH) = 0; - IOLo(ws2811IO); + return; } + pwmMode = false; if (!ledConfigureDMA()) { ws2811Initialised = false; From 6ec0370cd2d3f23bdbc7e3325f8c69a8d7234ade Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Wed, 26 Jul 2023 00:51:09 +0200 Subject: [PATCH 021/175] added images for documentation --- docs/assets/images/ws2811_data.png | Bin 0 -> 4264 bytes docs/assets/images/ws2811_packets.png | Bin 0 -> 6555 bytes 2 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 docs/assets/images/ws2811_data.png create mode 100644 docs/assets/images/ws2811_packets.png diff --git a/docs/assets/images/ws2811_data.png b/docs/assets/images/ws2811_data.png new file mode 100644 index 0000000000000000000000000000000000000000..ce95ef947fc1423b0a5ccfe19ef0aec06625fdde GIT binary patch literal 4264 zcmcIndo)!2*PnWlav7lr6_sl)X=2=R&6II1Bn(k*Ni&0CCWHt-Oez$)R!C`@B9}7^ z%H5zy%wWb{Ga1H{J0twY^LyTBt@mB;`{%pXUgw;3&i;PR-uv^}`+H8(CEJU_0@4B? z5J(tqVQvos{Q>ZL6^X%wR#sNI#w6zl z=@HUgok16-r`hxK^O3oDGPzb#Qi{oB78c<-9FFE0XiiRUgsuGf^X68jhJ>QH#>Pe) z%-xun*w)sziHV7K1cI&rj1XgCZEaf=c3xRo_3`7>$jGSdqHq@wC?g}o$jDS*-ykUm zzxS}Zr{{IuLwrR!@qt$^!(bLpPR>~D9n%9^2!xxKmac}z8D3dL;odf<#c&Uk)znTq z%PB&kI=3{{H8mm1XI+k+ycC#*KVx-6N5}P`ChXuYP?F0D1qDSA$TPy%F3FW zn$y#tKp?V)@~Xy0$`FY1U~l&sIn%zrK0*;*M&`)WaQ6)m2wV?0H+8%-G|Naqh)qlH z4YW9O(M_O2O0dJ%Tz=y7Zbfj&5j^ynIbHi><#4cM@vu-Im9KkFui^I$E7C9FbR|{I zd+*!^+sugBDHUb7SbKlKagXUc2^s9JSm$9*-fsAaLKsZ6gq=aNO?Bl)uS*oqGz2M;O zJ4YiVOf?!gY=QI9vuk`V<9BbRq?FuBE?3gU#S?Ywl0bhd!a~)@Ro>j{t#Uf}7JA*o z(9>+$v$%OK-6g>7lw>KI8@qpN-ww)WWN-IP)Y)2t=M!LMGj^5Q;_T%oIZI`DBOLsS zplUKyTkmCt)$J6LVJUyG0(B%fKyXOJkl$dSa$j!*@bVrL>z6uwMTz2%PH}ic&$e_v z7N}C4JK*7hw5_dYGkgp`mR@A&cl>ruA_5G{`ncie4f(LgcwM^;!#?6!&+fMnvgC-Q zWgZFx_J~(VgDD-2Nha!AH6&+#h}+B+^Yapzp)n+^Ovy!Szi%I1-pQNDmS1rLQ(wLv zG#rtAN5s~+PZ2h1t!*E#78bmfh~K>P%d=B*iJuLRU%j)Y71}uvV5aAFT6Rw%f){kK zD5`&V5aD261w~lTY{^l_;Xw&m)xP8zy!Z$>-m~l2+rR`_^FKS(8Z|w+JyViToh*OytapGW^!(H zs%nR6cg@?3BMSOh+qU+)wHZZmMG5ti!5gPo*T3uDY?{u9GFx1A)A0CVcG>AG-){KR zs2l0m2=5oJklXevFgtf;+T#S0A3d_-`Tm5?4zTWw%CF1ju3BhUnUCzQrXpUnwrpDN zvb0{kKvX;&(O*1tB&I_eJanmsSW|7nxs<}!zWprf+I|`J-Hkf%J8g5_XnaIVAU)dXAX?t)hxH zk0F*~P)|bnr!ReySNgw{CMA0eiLb?FR@n*3>~o@m*DW>c1(cYbsfI+AL6X9)sW+KW{J1pDX_HB>3$*P(*sAeNZLW= zPmF(5H!2=^riTmcNf_pY9~M%}tc{D*oJE!EE(8h!f%wmy_?o)=a*6%D?*Q~Av}hlq zGf$~WeK){+x{uMwp?v|@D^kNngCd6+D0ksKrbdTIumhxc#GV+0_h$&i5DAhI@HS1@E_V6l@s(MqOS_oPKz6%J)c3%;;|LIWo#STFAm=dLAu(B{>iZrPE| z1;Um&EtdRR`&ulbnT@KH`7+X;@-W=$lz16*e(ILDx9_DMXspiy-#TEw)Xsl^u1BZ>PI@Fk=wgPvFqLjL$7 zT)P}HLCGyUEbxni-0T`#?w>A6nE%hKqxeWLHTr1U$2)Hk3u4odi^Uc`((cFHZ+_}d z(TSXzi+(Mw#7L8**hdc*JDfIrg&E%VeJJ5vh=occft0~dMqS#rHLn8l1IUqt(6m@LjpP%#wDbfTi6E`rTVYlhX-i=D>We6 zPTlGpDR(qLDhb9Q3ln;pLSTw*YdE%-YJ}sE)J}m)<(t z**aX^s>MZkTQHz)>3;fc>6v~K#m2vToE0}YSn?6fYU&TXB^}_**dCPW_-(`DcExrWetVExb*Z% zij~fYky0or;#}C?NlN<*QopUT!G}?H=B<+)!kY?qDsFwD5O?~RR$F>B_3aR(ZcWeh z+DWC})JYop__YB;kTa~$E3l1#d|i5E>{20!Dr*m?o8|AU9&Z%jos zk6x~K`5yJGjpk)~YNt3Qo+|DxIG2x=qM=2-o&Ny#@j4nW$FoFjhJK!37~3lLPjac} zuSiM7ZF1OA|3w0&$uJQA_dQvh!G~AdsHQ5)lX+!rf5B)Zun%H^VzF#?>D1+%2x7m) z;l6v|_}&0-fWU~$DEEo1NwaAD7B-P_p>XkQ2kQB7)a*Hz-w!^k^JYjqSz-T-_V@l{ znXw2GtZQy%%3&`Brl`SOkt#mncPAkZv3?u)iT*YU&OoqVjH3FvD*n~#d`Sr78C|gs zdw9l=;2vLR8*GtR73Mur2@~1!w7(lr?G6KllOU?M3#YM(QZqzX<4qNJKbx_M8*iQ+ zq^?5y4L59(&&dBaWUcThbhI(XAslpeY2`3?ep|Foa zK%jve>dU-dn_YF~cTsP}V*)=~bXD;bOF7y&)FJI*oIV$^1e|A5kF3Wba@1tY<{so= ztQYpbCUtU~!9dhXPv`RnBwD!vX*axrkr`jHYI|kQcIfJpO0dI+0b`tyoIZ`2f{}ue zM&dLhN{f>IoNU6QM*=nek737#Yrf7=d2u!o2UY$Hjd~Du8GRW&P7OzW8!h-0 zkKj%Fe{6|I)HwD4VAwe^4ZtjtHKtTLZW$?xE6 z6A>!4lllq<*ZoTw1)pHi1{NsH>yHY7nEOAfbe@b=y+&eLKj!?)fegSg;2$45fD?waE0F z2mh+j_>SHRK5_Es`YANjYIxmpJ?n`_OGx>0m=Aj$`$JE}#O|tZJW`7eKI2svsvlv9 zxLOB$m+G~QC3#%~#=D=L{GEj&a}mwbdeqTIKU=t6j+oAR`sEI z@ICsjz<}h#llFce;@_{34(`yl@}0Bp`&~19vmyH{wa{z5Dt7KPfhQ4a z5z5Ow+1+QC4D5iD@ta%+EukHv}8V$Lzo^0sFXg{FiOM!=N2%ZM~HIeYUGIU9fircO>7ilZgOwT zeUIGN%x~)Z`~Cje`}24|_IbZw$MgAoJs(@NxtYN^W*%lbI=XX4hIcLK=uV+&&k1Kv z(LT8Xi7#l&6>q(V-j>j(-o8&@E_6E1P)8R*Bk+@FE*36Noc%rVE*f-n|GY9cwbG+f zsR%?tPfw4Rmv>uR+sMdhS67#qxC9Vr*VObAhr>-wOgK6^Nk~X1B_*kN* znm*Xv+>DEhS5&-}o10fsf*cqagu~&Djg22ae!O?jvbeaox*8Q79UT-DY-| zSnKQSZ*6TUDXHx3?bX!OEG;bwT@y)9PX~h`b8~Y$J3A{Y?W@cPn-H1e@zrTM&Ljw@_(8$PGU0q8~PTt(y+{edH zTl==LvH9c2cB-nX2?>cZGO`K^Dw>*FAtA41Wp5f9-V+cIw6wH(^X6@1W0RYkyNkM5fL#qHda?xS5Q#+{rmT|wY7i${kOipzN4dKYHA8>WdJbLy?Il9 zq_5lF-T__w@9o<Z9vCv1+(bHohU%jG(2-#lP|KXJP3AiG=XQ2{FpWE_$%{7|DI8qcLF|dw9;IFFsDay?!Y11$(nW@E`O=zE)&Z@49{(Vqw*!JRl6D9BGc?Yg5K`any%RGeCsY zk_b0Vo{EY$`tKaheXd9X1@@cD8($Wg;L1ByQ$5cjnsBXZv1^uCt`9*9KbvD`XJw;h z@gzyA&<|Gu8b|&%ahly2W($xVU0xe3xVE@pVG1&9)VT6rb+S3w%hZ@Lk$zr6X^odD zBSifm#)xh9`pk8`@YQsSgoVQ`M|&Sj9Ob}#b5 z_LJfjf¨+ptt*dE8`zD5+5HVfaI-oF6jS^8Cf=b%0o2-j1K1lX<6^LxO1ceXs#} zPpa{Gw;p+~1<~nf=pc|L6zlP6?{2(HRqa4|U8fA+qv`!IdK+(0$Q736@C{4%kEIN* zAqc0PD&N}it0Mad9b(lrD7yy z6a-zmDK&VT?6pC+ovQNOjh#N&w>ojY7du*a+VnyY8mS-FUkF%GligG1kFZ7K8^a;~ zp>9&PgUzWKN}ET9XX8)31w}epD%k3V>iO=rN0o2bsc6>$%~XzB*{n8td&kWsqLK1_ zoaQotV2l(t*Bl+k>{xu&p-oIT9@#g4Q+9cbcu8I-sthFc#uDy3sid_a$OvR*k`0cfv zH`VU3fkYiwpRKc_j0-nr3_iI8Kwz0N0yh~d8G}(6ucQNAVD5b7_1UDSA3pzp->}K@ zJ^ZM`{o&LYV}1Unw@sqYBt?5EJ!6SyY{li>y^b)L1Pnb=av&~b`6kqyP!d;fXTE%y z;KUfkQt|W7eSFqilB+e)wKJ2Welh<%<7J&Zy0TV#wcs}QQVnpyMl2}tQ>cS+an7QfBg&G+>vf1uONHK#+#P`1%A?jOEez&l;h->qLCHdU*)cb zyhW8-Tt{zf+G*0*D9Z>>sqL~MmT!%On<=E=cue}y4Y-xE!|&z&oL8_Bd!w<%@=Dq( zS3O)j0B)zO?zRUt0@CLqDz04Gde7(lZ!8#|ok=u%6LfwfO+iD!$!1+#Z2m|88(dU& zbvhB1eU3!-U*ul=t*3YZ{j&Zl64q_*Ft8UvR;i_!RD@jo}8X5>XsBv&)(1O9xb9tO%`z*E|ccViOSTV{=IZ z`A~d0V30OeGz`|dW6h(-m9FU`R5I^1ms`bXUZ}FJek7!x{H7RYbjy6jWY{S>id6}7 z0xA{hEkkXM)aoZK0`1P${rucMV}&#kS^QE`CSC?$Udwm^5G_eN0Miee9O-yw5?l*0 zyPjsT?t{WbHnjjXQn+yv5oP0&u&H9LI;>2SK6og{(5C%Vv-p-B(eB09w%uz0>VP%e zv4-=@Mt*BKYc&v2hm<;oq_wFNW3J}Z6WYlnFkqj0?=wd`IJ2b!dzT`5tO=k;H^_J# zGS(akoH_Fr%_Tv?MFbHXan&Op07ulTAeMd9tiQZR>`$-;!8ZTJRSW~fKAS*wGd+dA z;K|$FqJb8!@kQptw#-l3KLbpC zHK(j%>gxMnw|c$P1dmO7CIwP9p+y_Y=p&7$qgsX>&=VWN>#Pu5V&fP|kf%n8=TPPI z^U9z=>g;3Q>308?IZ%iH#-KhpJ1&-7w5#JGMAF4!8^M&)`g6fsJ6;J4-O({r^)=$! z(H;ivH}-Q79(XST= z1=Li2J3Dkcd650|lr@Ty{srl+%zff;C33<c-3$j?@eW{Zwc;4D}DWXjuywN+Q*)DBQvw%ldV zYH9`Bazw7BrqXe=$h0WA4j!-0Qjii5tlb0RH8_wscPWANP%=Qo1@1kZTY}l7f32k~ zOzBf~tZI5}W5!HCcuO72S?YFrciftkPhjU4083uXFJP+CqguzAekaB3uN6^GuFVn- z@x8x^#vBbC$)Gwi+6p}a(b<&qZ|a{-rUtguKYTlt%FWOOP!9v~S?;8CXa#WiEIdC= zE_rk5cE21$xKfWR@M$~p{@`AL>v3MM=nROjw|YP9ChtQmcuqn`E$D*hp;bCJnYT-M z4LhW2YqupBNTGn;i92XG0i6at(hEO>Q5+)5&M8=@H>QdAP)1S==gv+!KYp;39(v?+LY3loBN87fGv&OxQ##Vpo7x^Z1vL$ilw3FKVGr zcaFb*XwfpK@}P6DeG>Quh=+7X3SYG?=N{-cTBgM7G$iK@D8SQM!;cJ=VasVijy%!x zUY#G~R1-E$VlYOi#cHcb)qE%4_=4;MbPmxdLuh-+&_J&ASSG!%iCXv#bTyyr&3dPg z3_B%|Ar3m#`u&^qQ~mjTjc6Wp=6Saq=YACopH_|G2ZJ!s1WFanzPm?=$fc?Ui3z9`o%LRECc?Mou`GG! zizyohJGGOiDHTQwm9z%so=PK%ad(-%>?u8xY2jNd>JORa+9ODZ#u6SU+=5R)bF+h> zn*OHp?!xd#@3*{&i5+bN6mpEn?N+xWZ+JT3DWkMrx;ma>P#%Ma!6B8Gr9bretG)n|# zwP1NENmED$2(9}k%le?ngZE4Plq^!{4EHSTSk|U!j1s<5TA!S1Q!~rpR(f^*n~@aS zt9me9A-&qzP_#(r&gHy zD1-}Q|3&xA_6$(=H!X8@(jW$q>MZr_=_9V$so8wh$YkmCW#GnHV%w~n%l4EY1m~{j zr(CLRQeu=JHf`L(`94C$(ESv8;HsTF6D<#!8PEfw{)07YB4x>Vsi;mDDT%ghCbw~-E&az1s98&G(w1)t82odllY&_*qEQ9I*F2ze zAizhpl)kN7XsqbG5}IiC&LYbOIz#v%!m#a3t1D+Wx%PYDlrox1`S5$e8V8<(lAV>l z?hI0pWdk=yhFX#2>*uzePx_fN0R_#aT1vmrsqXjvMN;;ty=KI+?OZ5h2L+0O8`%Uh zI4`8M#LtIKEhV!r;b{#G*r2UQFJ8rjglAd1Ln)D&_K9P}f*E-FXQWM#^ApO~;nq!_EJJ_0YfDwW zih9k&G_?4A)7bG`EC@ql=ugSbrUY!y+?+ynZ}jF>eAd$ai%oEU3Il|l3%;F&vdub~ zY2o$3>@Ow52p;{$7tZ%_Niw3>c3WlsK+Qf01n^dnyM@WMb^ie-vxKeMg#|MI3C10! zzHkJ<=h?e=Zh((i!b)O3m8}^0`!mH+e+r}#o1ZEC2$z`OWtenVt~DyUjD&JzT0X|b z*a4G&@EGl1P;!eJKTnZ4k)XVqYC{Avi|JdZjBh9Tylb0H@ovLyhi0Y@OOj|cbRf$j zu2|N77DHBDC;p+L`F+R?immi1kw9!_sv=qsaTW4iEbWPHduPVEs2XD-Il$fj>epRK zn%I9_hCJ%H{-_77(|k+a#sq^cd_0uaN!VD*BuYufWK{mG30Dr`aM0w7+4LQQqP;K7 zo|$dIzDupPIHdhj<2pThr)?h$DZb!tqpGv2IKHYYQx``ezr@97a#;RXKP?EtnRL6k zE_Ya$$P^GD41_fVwqnaOUea0!n%GIloRi9H_RnYN zHMTZ2UX?}1&qFg|>Z$g)xxt#mImkT0rGk42f8wyRh_EZOuQt5}8^= zsFY}(+6{JU50HlfeuVUBsH5TwxPQL6bGkQkUs>i0aV`~vXPJju zChxak0Cu55^fNTsO@xA`cajdvejNNEgnAE23r6z#0~z%s!a>)YwdqqdoRa1a_a+W# zEv9K;4{4m&qn?F-3D0LS5g8!=_n6R}AVL#q2TdUDoTxqvbtjq_vX06Gt#SW3EvNa! zZ|%Sc$LlBdF^o{S57OG|C6Kg22{fCwmwoaMO+cLpS)u+z&3mw}dIy?}+ALR@-w#1V zl+fn8tyry}g;?V~nGUrx=c(4-v?xYu15c^{vxNWZov8Dd zdouHc5RU&aV@XBT^U%8chubF$P6Dl;-|&YL6HroOJ<{v2sgJimC8xYrrHuVkHpQ4J zy#f5v{fns>-1vr|prD#IWFFK@^|7_8>^T(2d_;W-vIn|WP8K!2SQmlA_A@WHn}Yya zog|-9;|Z=bf*-0{f8-YJCR7+G+##=l+(>M$tmFZ>$6IAg-u+|GKM+R!1=r!Dh5clY z>1r$6d?^l8s_wA78|SZ+naO@FQ}t)O%YD$U-=i7+V@f9Nry`lAJ2dZ2z}$|?3W-X* z-*EmFrV$+carzS`T3Ue3*9!SH)=l|x04Myz<_yxe+FxE4wLCsIp`|PlF|~mlF6S5; zTM7UHaG|_Xg+IMODn=7ffeo~7Unk02g4J#a;i0fRKlj&t)1w`0ep>kduisw(f4@Ea zGC${Z%1#RFB&v^x`#|~vO`{TEhv%md`Am_i`{m?8gP#0zMP)|=E(=!*9n1MZx42^Q z8j|@YnoSnG*mt4Lj+L6br{hGLTe`AWa54Q>z? zRK2>3daVcEs)oE{0&PLrb{^SoEo*Ybk-Qnwc1LRb7{?zg2~}GSJ|+rhTEGq!Nk2Pha^&A4n;{NN+2BOi;N{K{n9&zQ z&50QP=Mgb966OYF`fvug+Afb`HA0KeUHnJp;|lYcl=&dCA_Qz!7a&X$duN+Pvr|XH zo8WlDtvv$w2JL=k3fW}uuL~lvp^w?7NXOzG{nTU9ak$^=UiYz<357|YZA!j@gsU?q zF7H`m^Gc^rg&r~;(k$Vf+uk7!`-Cpbv%9sgf@0fc`VranvIAmp^R$DAC5vND2ReF5 X{3j0if?(ReEp$eDW_L?<9m4+yA8e5# literal 0 HcmV?d00001 From 23aba76d5490d52473b6f48811e33a8e5e0f70cb Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Wed, 26 Jul 2023 02:04:27 +0300 Subject: [PATCH 022/175] Update LED pin PWM.md --- docs/LED pin PWM.md | 24 +++++++++++++++++------- 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index 4f43ce37d5..a3706cd7ea 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -2,11 +2,15 @@ Normally LED pin is used to drive WS2812 led strip. LED pin is held low, and every 10ms a set of pulses is sent to change color of the 24 LEDs: +![alt text](/docs/assets/images/ws2811_packets.png "ws2811 packets") +![alt text](/docs/assets/images/ws2811_data.png "ws2811 data") + As alternative function, it is possible to generate PWM signal with specified duty ratio on the LED pin. Feature can be used to drive external devices. It is also used to simulate OSD joystick to control cameras. -PWM frequency is fixed to 24kHz with duty ratio between 0 and 100%. +PWM frequency is fixed to 24kHz with duty ratio between 0 and 100%: +![alt text](/docs/assets/images/led_pin_pwm.png "led pin pwm") There are four modes of opearation: - low @@ -17,24 +21,30 @@ There are four modes of opearation: Mode is configured using led_pin_pwm_mode setting. ## Low - LED Pin is initialized to output low level by default and can be used to generate PWM signal. - ws2812 strip can not be controlled. +LED Pin is initialized to output low level by default and can be used to generate PWM signal. + +ws2812 strip can not be controlled. ## High - LED Pin is initialized to output high level by default and can be used to generate PWM signal. - ws2812 strip can not be controlled. +LED Pin is initialized to output high level by default and can be used to generate PWM signal. + +ws2812 strip can not be controlled. ## Shared low (default) - LED Pin is used to drive WS2812 strip. Pauses between pulses are low: +LED Pin is used to drive WS2812 strip. Pauses between pulses are low: +![alt text](/docs/assets/images/ws2811_packets.png "ws2811 packets") - It is possible to generate PWM signal with duty ratio >0...100%. While PWM signal is generated, ws2811 strip is not updated. When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio < ~10%. +It is possible to generate PWM signal with duty ratio >0...100%. While PWM signal is generated, ws2811 strip is not updated. When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio < ~10%. ## Shared high LED Pin is used to drive WS2812 strip. Pauses between pulses are high. ws2812 pulses are prefixed with 300us low 'reset' pulse: +![alt text](/docs/assets/images/ws2811_packets_high.png "ws2811 packets_high") +![alt text](/docs/assets/images/ws2811_data_high.png "ws2811 data_high") + It is possible to generate PWM signal with duty ratio 0...<100%. While PWM signal is generated, ws2811 strip is not updated. When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1.5ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio > ~85%. After sending ws2812 pulses for 24 LEDS, we held line high for 9ms, then send 300us low 'reset' pulse. Datasheet for ws2812 protocol does not describe behavior for long high pulse, but in practice it works the same as 'reset' pulse. To be safe, we also send correct low 'reset' pulse before starting next LEDs update sequence. This moude is used to simulate OSD joystick. It is Ok that effective PWM ratio is 85..100% while driving LEDs, because OSD joystick keyspress voltages are far below 85%. From dfb092470e28722174506cb6b0b74517e0f6c268 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Wed, 26 Jul 2023 01:04:43 +0200 Subject: [PATCH 023/175] added images for documentation --- docs/assets/images/led_pin_pwm.png | Bin 0 -> 5069 bytes docs/assets/images/ws2811_data_high.png | Bin 0 -> 6042 bytes docs/assets/images/ws2811_packets_high.png | Bin 0 -> 5114 bytes 3 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 docs/assets/images/led_pin_pwm.png create mode 100644 docs/assets/images/ws2811_data_high.png create mode 100644 docs/assets/images/ws2811_packets_high.png diff --git a/docs/assets/images/led_pin_pwm.png b/docs/assets/images/led_pin_pwm.png new file mode 100644 index 0000000000000000000000000000000000000000..93bab8d1df459c24a2f187222eedbefc5cda4f68 GIT binary patch literal 5069 zcmZXYc{o(>`^PIuQB-y+vSjRK&sO%3HA{>oYaePBd$N;cPqt)>u`?8L#yZ5<#uC}j zF!o6qME0fc@cI1y`d!a;o%5XMI_KQaxu5s_dfwNGG}PC+M9V>Y>eQ)A+7Hx?Po1Iy zDE)WmsVK){$zDOqiQQAHe~sgtpjoujW?my_bDQ>TLs zADUc+l=H%p>nwow6+WPRJVObg4-#>trm3?n-FEcX>3bm4# zSE#P8-rU@T!x52@QE6#uuU>^WH8o95O$i70^uemcH6+fP((y@cz7f*F!<3U6KChAuCC9rvp+^eL<|iLnVZ|(z9Z9->}z0P zrmLbPDJg4eYL%FnsH0;zJUl!&_`ScsKQ%QKkMHsG^A8JqRbO8}Iy!dejzoHTMr&(p zbaeF4(D3BsB+NvML?X@2%~e!XR8>`VbabFlC@dChW@cSjSY-M@Rs6ODP@1>4wl+T4 z4}zeIit5J3#;;$$N=r+LL?SaY3n%9_p~PXzf?b)@R#!23F|nMvYddlO3@!nBMFlRb zNzKHR!vwjpU>G@JY*eQOqZ@Q>@xr-|PI_rb?T*S`fP5U}3FV(@1)W_J^L0<~ro& z`Jb+E59$<<-*3#_0hObeg8`F;8=7ynsGRMG1wmr3)gTVl>f^#4dZlO%M`ht_36&xbaPo>iG< z3FXdluV0a6JNVVZg$T6_3)GMkkg1UULBa<`G0eheOxdo>uw6VO|JgNM1D)+ZU6W&y z1JT=$V_}IK%UX*(Di(u-#q z{JILQH@V4MKNoEm9%;B6= zzi^MW92eUsiB#*17cR@fF+E8m5Az*-_mqgjA_mLx@J56~_~e2&eyR6OMZCWje>^O4 z-oheMnmyO?J3d|{PWLX*eotQUhjT^Tv)> zl{Iew@(eZXS}~5NiDf5M)jS0KpZ^m_%z{`W(Vt<&ARqQ;4yq*ne|DA9AkE% z;6?a4xy`>a&>p$EoE+Qd7Z4*#W~B2r%Gyc7N_I6R+i`CX!1(alp-=VTPSkzmQnDe9bIN6P4>LJBJz;W7uNZ z3;gLio=FD8S;7q-eV3SJB#MQtYUEF{dR@d`)QvNvzZgO`$lhy&;-ynVqz~tYgi*Uz zc8t)L$d)U`U(<_bMxN_%iCDe%wXx&Uvdwf6mn=OANF_~>x8mElMCejQe;Ez#4YEUI>LcJ)A5 z)HEqlwXO)fK3v?UG3mGEO}u=KQNK!eV-dIBUP?X%;^(g}reeJROyfnu70O5*^ds}u8G`a_kd-oI69x@jLQJy|LZL{% z2oQV!a+|E_;TF|Fjaubn%ki_=aH7n2{d2(eg%l>Dh48HwQ4EX|aL8zeL2LPODveux zmS|lLNc_l3y2UWB z)c!es+Q~U@N5|zx^}m;a=n5ZYPeX+YaBUb&4&1Nzc9$G0*D9I*ikJaXkcj0OH@Ug^#6`{MbU;{_hE1m-~#-SmmiPe;_ELp~j<=j*ISmmU#iW0|96q0wNdnccXi+-CI;d1qFs%3!q_R4A>-mjhq$ z;N1`csui>z0OyQ?35*sCC>T=vee1`GYAjW8TC&cSi?!PlU6@>da@VKZ2q$WBNSlZm z7`x@C=ca6&i(1bxGB1cyt0Gt`8Sju$wP^P2ixj!nw2`B}+AgMSf^Us=)8cqH5+r=P zp1-TJ%!QQ3xY>JidU-MTlEmqy9rH64;hIfoqSQX-cUM&>&R?$GD|9+>E z?29Stbuy{B=RxjoT-1a`pHuCcxFn>2 zU8noc;>oA?5~+Q1a^GGDK2#gNf*iWX4I{5aaf$4Y}vLtZda+e1@1yI1U9u18# zpwt};froh9wm5*VMILrsQc+ZdQWpE9A?e^0yigzCTJu#@!A6H?K&DwA-OwZ# zZFDrW8JGdRLL}Yrx3fReVxO(4ORFX*Qo(J`RH-e{Qle7gM%0=<=B!^>A9U+UP#)|2 zz)NIub;emvu(I7PfTV7Dm)2AfXiVF$ygR2vU(dmt;VprPq^m2MFdqK# z_(#uZ?>Qwi1PT+|O&{Q)RXOVcAJr#}Mzj5?DK+^Op@1WYl`N%xeIa;^h86s=NJ60@ z$mri)l%Dr#U|>5?{AIvde^9=kND-J13bFwjSH^MWM{2Q7Q^|dyoou znBNcTyHKq`cSH|T7y_Y--X1#74&%G!nbj!YrO~vYfn~zOjR7;TMyV{uW8IRu=FM0I%ipBg4n!P`R7~5PcT5f+yJ=Dm z3OspbB}*`yy87j_r*)w0LNB?UDnmpef z1G*}tO?*h`JX1~hux0;H!NNF8O5G^ZUHzokz2AdxAKshgO0)mRwEWY?+KL;LEVboy zO(W3_)lCi^WGw9hIJ>XyB~nVBA|=5@JlnpDlu_(KO*eV?4!*GN7O_v9Y*x#!SI)MV zc)YIJ;b2(nH78}oC$)M)7=MKXZNf}V2BJ{1W$d#^No{1)#nQo;xfH0t_VbH>1h%JC zP;&CkWJDI77C*DG&IhAMz+uptOM$?-x(M)yFoTxN>8c=Y^ zBzZrl`FCwI2~BaHSzzb0<7Z$BwbloUBQEd`WpPT?(ZRtk(d!gj^NSB~Na!CB$mTyG z1NnMKz~S`U7;hKSCeP~9%M~S*+{2M8byWst?2jqR%f zGvJn=;U^0U=@yy-(k(g=grYo*drYTCjNP5db zpp63=F851!2r7yg_r+p=GNxg0)#^MqH}v@A19~v?*%w=iV#GTvi0e4c-&$+kWV&$&q@C zn|v<})P_8hlSD71ikp@zAIjOODX{OJ&@U&Tc9S09V%;N|4wkk1noN|WLE2^2BXAxzrDXdm)GfQT8`4zHZH44*N+9%ruxVEB9A!{W|phu769a zwkfsb&!B}$aI2&6aOO&;KUs#e}5ETm@&|1rT1mu09g&Af=E z29z=oK^3V!TDIIoS|Q?zKzG~7wibsQK|Bd>c2@8GrTwk(_sCCpPnI^WU$to=plM-K zQF$KvCGlpF`Kx`PVH;{g7f1*9`(hh4s(S2ZadKJ|4f%G8VyTZU#WB>6vECHUU9`U$ dbo$&W8Ufmvs1G}1l>c+5v^DhA%T=F*{ts&QSbhKi literal 0 HcmV?d00001 diff --git a/docs/assets/images/ws2811_data_high.png b/docs/assets/images/ws2811_data_high.png new file mode 100644 index 0000000000000000000000000000000000000000..a1a2d8512fc4d501d94bb7730504b194ef2201f3 GIT binary patch literal 6042 zcmZWtXEa=0xE@`M-bRm-5M2n-yO4-Z2txFP7&9U|VMG#4v=9ngy{d3M;1D?sKAy4RvX#IH&*s0L@)JZBqb%1VI=lP?8X? ze@f>r7TA4stbEM8Tz&i;yj=hq&R&i#ymvhv++0ju9GnB7KV6go0HQGC`{p`ALN}g2 z_c1rOSYBSXw6t4WTN@r8+1uNjnwoZWbW%`I?&|8w%gZ}EJCl`FXl`y!O-+rDPdGk4 z{`s@Fs_JV|QBg)l1|0tG^XJdo+uK}R+-+^`H*ScksHg`Aht$^AH8gySjC{?w)!T3T9+jEu9gvN}3Cf`WodN=i~v zQetA@AP~EhluS=g&!c+ytDs@w?Cpo~>)Jk7N<@fK=U%!6k=ND{j zY@kr6>gt-+)zyK4fy&CtiHXUaoZP;?J}ed+5%FqkYs=GI*FsNoetuq3Ql`EnS4~ZQ zXJ=<>WT?I#(b(8HIy%b9$;Hd5X8-`ORNmFrF!!Hc%ZRd>o*wTeNjl2i? zHz_1CH!d+JXGxF#vY2Vq#o)2Aj^C|bus=_fqGXNK)&xG<*r}lz{W1OX%w^rr#VvxK zm;MRnRVyDL9AHaNx%<17rU$z<*ZJm&G7lcmLphq4J#*>|QCm-m#J-1~Z5H-)+tyK2XijG=kQ@vOn|=A=@V# zZJ8)7zZRSjai?B5yJ$BgJRTA7LGoxLIyC+7ghQ8gC@70k zAF!8#ciM`)ml#QAJOin~{sY?d?6o%OjtHk<@q0*ii6mmB!6#~*tk>QqwT3=abzu;8 zn2AFceAK;XWjtT=`fteH-`1(TBXPtE9rz`|h5Q1cu6=o|9=5l_JDk*wXW4p7Q@qI< zM~4X6kn>@BGy%@rB@foZh23)CNt=q#ERXm{#_t3vQ*)rjOeA6;v`lwog#Gjgb z)Owv{jgu{W4-^-5=y0bVN|}j4sf>2_`QuH$cX={UMfV)=ltH9@_or)V{PZdLKgqLP z@hUQlJr?Q#QS&(juFc-_?%!Z8DuvXkXA!+lVC08BK6#vMlB*qldhO2yFv7LF`-bVa zDCbfkaIqV+ajlWq$J0Rm+Bf;%-%TlMe;N%=wr4iz|D>n05=HvJtI%nO`RSq{?fv@C zX>1?XpC$D?_|It`7-wmEHi(rw1lt@)4&GVn7>&Fpqgs(3IuD!UO0(4KPS*}TwtJsD z%|c}tO;@wDEXQFM`=_}H8+y~*Yf5Ogxc%_zEkp|@J>D-ie~zJHgo)tzistpA@IJAT z=%!gvzjTz(xOaHw{j4uI(SsB%@`Uj;y?(e2{kMuaudb@cKUA=+BI0lIXcJti574Mx z={Gg|JfJL(WQaV@jPfhw{C1rr8;pb9rmo_4x@&88(d{7J90xKH_* z*ftA(Ekpd(!d?dd7!}@cm%7FZ5G5D7iGw`3Q0jIJL@27`o)jRl02NGyQi4*z_ zw+aEBZ&9b}EV5LcCeKj%Sr+c&%BAi45%&kyii<)~4eTguiv6l994aMukZfqcl@2!Z{4yAtOdDeG{qu~JGJEs7oXQ@; z^u)K!uQr`XS-<~dfmDy@f1t&$&)DQ=p^uLLD-~LO<39=`oZL# zI@$z|J(so#Sk%2a+c+LYY2(PtpI(0<`R4$xk2fjd*q74jQ`6Ty|M+(m;9^Xj$P;7nwi~DV)7+F7N0cL;sT7It`$yx z+rCceYx>og%Gjj6STRu8Ve3ALT6OHLDK|(*sesE#lz^P?$<*YXZ=K(wxUlToWS)=?a#*9=zzE(ZQL{!=ZOBh`zo;4Wl?_;rpJDYk$`FNRc2@oYE$uV;O2sep~J5PUc&)Drnq+GqPG`VRsNXFn2PF z-r2G9e8})Im>8ri5%Jl(Z|kLBCm%w0BU@EIJ&@hjv?+jSSH#Mpdhm^C zj3(55DcY{N-xuz2mHCP6w03hfDqY&+XigLo6#l)D6Ani3F{e_ zwz*li_JpT(oddb=252RN1W}i3m`ol?hh}SxnOht&s0;y7%2c+aU&S-k*bdx)41g3G z#JV!LUG=sbT6nCDd+)EfmEyI}eZuYnz13Vc49>lvZ6l}A)n(&n+{zOENFm6CQ=#MO zXiSMor1~N%@dk6d?bwkB|7^gc+6dVk#$p9q6 zW@3bg022CfoNve5XjmOBW#zJhY!k;FGiHQID&nUUCtAFc2RcoGT>(mO-eU|kEshRM)mrfxU303qoE#tKEb6<& zZEjI-cSYJPq^^Plk^Py; zJh_1-ryxRaDJjupjc?A6*JR-1_b2Ma@0rURue=H@=P8m5xoQ2D{~N#Ri;qR04PYfE zI|T0Fo%jEQ{p0V9O!;z_FZ$K8bS=zdlmEBQ1a9lW%48F}6t6#C1BU9}Q6KCRBP+M4 z$y8Ff(v@F~aSa(-Ay@CoRbkhOtBZYkougdD&ZQwhrEJ{c=G_?yFaedoQ;7LeNuo zzn()LxpR{}dESlczpf`&(&upNLrdWe23=@%oz!awv@iqil+>4AR zLmWEa*bN&i>7`@NZ_-~;Ew^lWWPjYg61Q&Jm!me`f@zfsoKvoU5aiE&PWl&8=hnZ4!NK^t=NmID6w@3Qz7s7a@9?> z^YD;Bs!j(KFWaFSldZ*yx_dP~N4l2i_T85cf6-0T7G7c${}D5txWUAB6j$`9JA-A| zp4C}=b~J@_7_Ddoygl01CFZuf4Ke^aVRS@QHr&$!KiRdA^AN<`AITGBOBXjWu%2z% zI$+NO9x>ul7KaaCvHkVy3L#-D3WzA`jOSSqHlIeXmi3Is?Y_T)R-E0;Vvn{yM{au|<&j?KMhUQTR2sgt9mjR4N`ClnAx|q>v0ux-;aR zryfh{w+aO{Zd=IU3>@o@c_qjs@OVTLdX;v4{u*=!ByYiBzgh?<_7gK~;a04~tmcO9YY)ce!_vG>|i9{l7Q-7-|S zXg(>6wYxQj!rJBZifvgSQ*rMlwKt$~zC-(QyKarlh$g3Lf|OAVwU!0i4j4GfNJU}% zLma55vE=j94fg@YuQ|RCiUVNx<%Y;Ao);cKBy}4vTHiU6^(F3ZFKr zCj(h14mWA!PGT{rHBYYpSJD>XGY$a{QcI`_g~CZ5p)@Ka-_jBeJphSdo2!?IXeI}> zB=B5RQDX}s$x7isMokaAfSLwD5`pY~R?^^-9u$@yNg&Ln_onIASDsUX{mCv>O`;Xw zgy>;M1jS@sqG+84QO1)ZCI0$Ap2$zK$;yN70`C|o8VAkdJ|7a@Kn(Y~71Gj{WEc0B zefxn3kth0xA|XND7v1|GO{wqc68={kh^Av<= z2pE!R6(?I>e|)8Np58W+*npsR;0nT2h9XOI*@!~KbwG*$BnwPoP${dBb=LR6pKy>` zfL{5($H-@v%VcpgR1%cCt_G(79O>8&1J))oI4nZHCTm;1O|FFZS#<~FjM1&C0mL)i zroLx8sqp!w(oWxa7FVT0HV38Cn}$AIBK7lfP5p3Ww_C7lTF?Ef$4JjalRDIbnJ&a$ zTJ$0xU$+sX7D9TD%AXl^71do6wEQ?vNcsi5g%N5^8qkA3^d`3caD5{4s`#6;HzOS- zw3_Wv_b8cje{ny0by`4)X`#d^(HDAg@V$r*MYACC0?j`%-Mi1pFmQ(G)NZjyS^spd zei$WH#^U8xy(+Ly`X+%n47ehLXn4B();e80G@aYzW%@wYwyq{|^sfT(or(4zsq!{m zK9A`6&kJ=8zl*fsNDwp-heB#C7m3%slA{&H?RcQSNxYO{Op(U+XxEnM9)54-gO0LO z%?;zODZV3qzRmY9qnE!P|B_UG^_igkfCIPiRm-<3-HM3ZB9{E+`c<35+b4-obU}$W z_)}Xlm!SU!5wfm6!u|Fu!skGWJ|siNt-V7Lp}(BOTXUzmIca>@CSWU+1`=LERBm!^ zVlu7;U7>&+>~qYu_ZOv*$rRWfb>dpb@PB0ubCkBdr>(>a4r=xP@~b!s*271~t(Q2# zoz!TXw!Q5pGq-skAVTVSF^etzTLBZ~LuNV|xA~$BJ$0cPNtCvTVw3n|H z?Skl8{IPKWvWiu!G+B%bVb|{bcpC%JHU-)IM5Zz&J9lcP=@zKa8ylDV0ojKC-&%k0e+k{1f#6;s_3`J9T@$lzvPG zuXje~pCF9WVYAG)yNdQt+di4CMVo0eHIQEND}oeEHwd^K;)xE<$=CqxK`#cB=_mRK QKidI!bqux3H6O$N2hCsac>n+a literal 0 HcmV?d00001 diff --git a/docs/assets/images/ws2811_packets_high.png b/docs/assets/images/ws2811_packets_high.png new file mode 100644 index 0000000000000000000000000000000000000000..49c4711e417133c49a32f67aa0d1e7e4389d6411 GIT binary patch literal 5114 zcmc&&i8qw*-yRx5NF+tJnC!C4p0%}1InV@YETWf_%ivJS&{vS$r5 z7)I6%$-d1ye1Grzp7$?!&vnl8Jm-1NechkW^|?RSeV#ks$nZV`9XlNW0AP6dKFDSk9v-HqrX?jMA(7wYlo>A~8Nb zo`>g_goKoahK`Jk{O0E7%*+f9hXa9bFDxvGi%XQ2mPtv;>FPc*GqXKDJ{A!XGcYg_ z6%|iONijAy4hVp{y1IS%@PYRh9}0ysGc)Jp@&mRsP=fY9E@Mgy9xcRFmQ> zt!wj>x=22g@vT8Ozoij7k2L8ix)RkBIaJGK7lm~3Ya`Ly5Q54SFPKTAlnK?J0q-z3 zkc11p076uPmAuy%whyRW-d#dA{-G1JN25~(yff;Dj4PF7HW+NqOXZ3hIODGoz z>CFK)rHZ?m&Gf_bk5`Y>wSNSVl6uokW7XW5-?nb$`=o#5j(&qb^i*pMR!)!E>Jkr} zq(LanHPl44DI!}DM_#dus@M(c{fh!Koa-LUJ5i}uaB*StUoDI`ULL7I8#vmhiAuY( zNu(`27cMOQ@r|F%#-|Ze&CWMxv`%=QCG=UvrowPjGfa~=TN}&Ai%QI=9r`AGGW$IU zR>Z7XVeSH5rnvD74SzUr`H@fx$rwdVz|siVuLQiS6?&L5xFHT7kmp^3m=^jBRq)>4Wm2v=7SBZ}*I!3yOw6 ziGVW1BueNP7n(YKcX>Q7lR=HMz;u0%)X*GGld#zRRgJ#SEGP#8{v7XT!XisU3?F=a zF2$M)*DJ%ducl4W5{@4tYoN7)wOy4RSx9?&spi`Ud&myD!Wtd@Nu9!^ z4%gc2N!SZ7taCdu9v^ITPOPZUO@C%ou^xC6{H8lT^t4N{Hp`;dlOsuYi<4F(Un=@8 z+RG!Mq!GAB8@oI1)4C*E>st0#L~mZE@^*H^1Dp zzPnkfhr#a{ggu&_8R-?=Wid_U0zh}kCs*{Vd;O35MZHcn7k76mtdn{(w5ZMJ(Z%+pF{k<%Sn4} z0?2!kyz^(ezY(|tRkekq zZRE>HMwsv7Kl{zGuk##p^JU|PHrKSTLvDH+Jzw5?COtPeFWYAci6S@U!q56t zG}rH${-q;ii)K9rzZ^1+vR#}6_O@TCm!H@nTGS0Nj)Fc4NN`u@Zm44N#y%I{O&{`M zdn$A6b0xAA`)XLs4xJ87DGWhettx~CK9imqo2h1(OABYmO=(*oB1G&o{U3e1pEHwH z$(Z|Kvw$&uww2~>E2oU-Do-6N^K1}wUU^#3!fFlvm#7-lJQeydPHkWSK4o6t?5Ifc zAspD@`e6FDg91h~(Ox^z#7iq_o9Y|yGiQhL&_gM&dvryrr_jmC05 z4J1z5t^9`W=Lneqm&@ZIqyR~(GJir(rDAS*++wy??UpWjO8Ya!rI;UNhpu&P1UEBP z^YZe|`LddvHwBkDlI8<70?MG-2wee7i&}EZ!3qi)xxdl8jpQI4iSg=nh$=hzHhE~o zQ%~z%Y4Dd}*B8POm$%X}ZDxYevqg)1ij6n@n;f5f6)IQAjC}G~HT~ZHelngSe$(|< z$6A@SdgPFCg_6`@8Q5J}CAMMgkhg7hbxD*4^Z{}|(@mk3PrdV>{HN=)V`S;=E1!&S zzmKg;XDe|KQ|}X-c<_gvPE8T1Rb1HNp~U0QkgI!-!E@(U>dash1#`w_-SwoJDj{iNVBQSlwTi*4vb~Md?@HWBIRpoEC1Hgo_BzpU!OIshuunnW2Z&0OBYreERxk+Lm2m%oAvSrKBT(+U$b-uwuYT)Yzo+M*mg&#deRc#iIZf3=*n3z4Iy%ijp z^%*#+d6!C-TY=~+chl@oN=Cd^$FGAAtvP!9^}8eY-5o@#Liz1cCuCI@0%>sjm{ah)BO3Gm*BwtU^FYyK&4(iDI;^0IXl@Ae z>@rffBxHk7L};x{uHcHlh&;}U4gLwQNvkpKMP4~N+{hn`+ZH**W zlaMT;iK%*N1A{_VUYlg#3|h+cKaU!8!^d=T?!BG6%7E;ElrtjIYAR&r3WXcoPWqni zs3&vY*~Bif$dLdxp%pjP40L7R7a1ED&0Xzc4lM(k_d!;*N-{Pw?}s0KMX3-d`hC6$ zS6l9;I@~_eq(p|kPM8%}0|u(G$Smsv%*7!>0SkbJX_Wt$wQ|1uf(M4(&62d%1dnOs zxLIMZwb~}fjw5vje4h6O-8(4Q1)R{?8o>4wN(Ygs+B8WYOXqBBwnK!s6;xyY@w;bS zp0K(<;i|MLB2k!E>QT!2uuso2+{!Dj`EO)=fNfGH7}vY$V6-u;KfTAkPFK81zLat) zMWlyt*cqv}CNbwN`JNIv-!6No70E$`1hCvrlQiv->~ z7rFsP`z2YK2*gdO2+HB!s@;WLabe!YqU8=Jz&h?-q$8$!6oh3Xi*OxHO)X`oMj;JLv zOPHR?s!bN@3|$bq|H+<;91ogIRNsc_0_WJ5izX!un^L+?gY3)SBqx$_R)R|@iE~%~ zdkV5@lBTg_8jr9PvJmZHOLo?h3gB>~9twPelkE&-J;@+9{<*;Cp*=09C(~e0x&B`Z zGYG}8z_!Lj&TEPrXE*$mp^U6PudEmqg857pJuA=h%F*YYk^d%6Ua6on7a&*pd)%ij zJ&TS3l=!q;C! zatxU!ep7(-XO1mXqdY*6vU0qc=IxXw^}yp;@^00PDY-O57>?oRYT!C|dFNYVH`9#B zzd-Srl3^qE6um2SRl;n%}($$3o_v~6F zdX8VLvjx*1TT4AAdux@ZuX{8Yec;CmClUf&^9n1Xgr<_PYFYfFMmT49z*5J(+rmx$#uG42v!A;u`!OK5!$L zzhF9rF+357@>G|nd8pHFqItS z9R*U2%Eldrg;t2Vp#t0bS>#&9cXd5n{vH>9KzIF~z4ott)8WQX@5A5DY<=`h-z1TAM#!3zWFs z3t0|kqi_wE6FS5uIGNMs`V%AR#b5xUF+C~&HU;8+pke$iwm`#{TBWki==nC3)9@?l z#ACJ+;#+}jpRa1*3t7g7+|rj((}O?;#gSoU5EAK|Fh3xKQ;PW*Q86;MGmw&j<-4Pp!Kh=y2BR%0^vbQCj zUYs{i2|KC&zRy;BH1sDMV}K&tM#52DYe`VgleH)etGwy8Hd7rQCN+UgRdGc`=QL%0 zIPVD9QW<&OuBcj3j)TTYbpWsqJzvX`{cBj+!iHJr!=WG#{A+%oo-pg0nZ1mI@# Wq-j{%Q7HK^5AaaiPz#}9ANgNslmtQm literal 0 HcmV?d00001 From edde1b40a095acb38e2249b4ece74289db5b040d Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Wed, 26 Jul 2023 02:09:54 +0300 Subject: [PATCH 024/175] Update LED pin PWM.md --- docs/LED pin PWM.md | 36 +++++++++++++++++++++++++++++------- 1 file changed, 29 insertions(+), 7 deletions(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index a3706cd7ea..9bb445070b 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -1,6 +1,6 @@ # LED pin PWM -Normally LED pin is used to drive WS2812 led strip. LED pin is held low, and every 10ms a set of pulses is sent to change color of the 24 LEDs: +Normally LED pin is used to drive WS2812 led strip. LED pin is held low, and every 10ms or 20ms a set of pulses is sent to change color of the 24 LEDs: ![alt text](/docs/assets/images/ws2811_packets.png "ws2811 packets") ![alt text](/docs/assets/images/ws2811_data.png "ws2811 data") @@ -10,6 +10,7 @@ As alternative function, it is possible to generate PWM signal with specified du Feature can be used to drive external devices. It is also used to simulate OSD joystick to control cameras. PWM frequency is fixed to 24kHz with duty ratio between 0 and 100%: + ![alt text](/docs/assets/images/led_pin_pwm.png "led pin pwm") There are four modes of opearation: @@ -35,7 +36,13 @@ LED Pin is used to drive WS2812 strip. Pauses between pulses are low: ![alt text](/docs/assets/images/ws2811_packets.png "ws2811 packets") -It is possible to generate PWM signal with duty ratio >0...100%. While PWM signal is generated, ws2811 strip is not updated. When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio < ~10%. +It is possible to generate PWM signal with duty ratio >0...100%. + +While PWM signal is generated, ws2811 strip is not updated. + +When PWM generation is disabled, LED pin is used to drive ws2812 strip. + +Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio < ~10%. @@ -45,21 +52,36 @@ It is possible to generate PWM signal with duty ratio >0...100%. While PWM signa ![alt text](/docs/assets/images/ws2811_packets_high.png "ws2811 packets_high") ![alt text](/docs/assets/images/ws2811_data_high.png "ws2811 data_high") - It is possible to generate PWM signal with duty ratio 0...<100%. While PWM signal is generated, ws2811 strip is not updated. When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1.5ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio > ~85%. - After sending ws2812 pulses for 24 LEDS, we held line high for 9ms, then send 300us low 'reset' pulse. Datasheet for ws2812 protocol does not describe behavior for long high pulse, but in practice it works the same as 'reset' pulse. To be safe, we also send correct low 'reset' pulse before starting next LEDs update sequence. - This moude is used to simulate OSD joystick. It is Ok that effective PWM ratio is 85..100% while driving LEDs, because OSD joystick keyspress voltages are far below 85%. + It is possible to generate PWM signal with duty ratio 0...<100%. + + While PWM signal is generated, ws2811 strip is not updated. + + When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1.5ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio > ~85%. + + After sending ws2812 pulses for 24 LEDS, we held line high for 9ms, then send 300us low 'reset' pulse. + + Datasheet for ws2812 protocol does not describe behavior for long high pulse, but in practice it works the same as 'reset' pulse. + + To be safe, we also send correct low 'reset' pulse before starting next LEDs update sequence. + + This mode is used to simulate OSD joystick. It is Ok that effective PWM ratio is 85..100% while driving LEDs, because OSD joystick keyspress voltages are far below 85%. + See OSD Joystick.md for more information. # Generating PWM signal in programming framework *TODO* + 0...100 - enable PWM generation with specified duty cicle + -1 - disable PWM generation ( disable to allow ws2812 LEDs updates in shared modes ) # Generating PWM signal from CLI -ledpinpwm - value=0...100 - enable PWM generation with specified duty cicle -ledpinpwm - disable PWM generation ( disable to allow ws2812 LEDs updates in shared modes ) +```ledpinpwm ``` - value = 0...100 - enable PWM generation with specified duty cycle + +```ledpinpwm``` - disable PWM generation ( disable to allow ws2812 LEDs updates in shared modes ) + # Example of driving single color LED From e55dc7bdae1a2b66e8b6ce793d8795c417599e5e Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 27 Jul 2023 00:41:52 +0200 Subject: [PATCH 025/175] fixed bugs in osd_joystick implementation --- src/main/drivers/light_ws2811strip.h | 2 +- src/main/drivers/timer_impl_hal.c | 2 ++ src/main/drivers/timer_impl_stdperiph.c | 1 + src/main/drivers/timer_impl_stdperiph_at32.c | 2 +- src/main/io/rcdevice_cam.c | 7 +++++++ 5 files changed, 12 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/light_ws2811strip.h b/src/main/drivers/light_ws2811strip.h index a673899146..829ba93509 100644 --- a/src/main/drivers/light_ws2811strip.h +++ b/src/main/drivers/light_ws2811strip.h @@ -21,7 +21,7 @@ #define WS2811_LED_STRIP_LENGTH 32 #define WS2811_BITS_PER_LED 24 -#define WS2811_DELAY_BUFFER_LENGTH 242 // for 300us delay ( new LEDS since 2017 require 300us delay, old LEDS were fine with 50us ) +#define WS2811_DELAY_BUFFER_LENGTH 42 // for 50us delay #define WS2811_DATA_BUFFER_SIZE (WS2811_BITS_PER_LED * WS2811_LED_STRIP_LENGTH) diff --git a/src/main/drivers/timer_impl_hal.c b/src/main/drivers/timer_impl_hal.c index e49382f87a..2478c60168 100644 --- a/src/main/drivers/timer_impl_hal.c +++ b/src/main/drivers/timer_impl_hal.c @@ -473,5 +473,7 @@ void impl_timerPWMStopDMA(TCH_t * tch) LL_DMA_DisableStream(dmaBase, streamLL); DMA_CLEAR_FLAG(tch->dma, DMA_IT_TCIF); } + tch->dmaState = TCH_DMA_IDLE; + HAL_TIM_Base_Start(tch->timCtx->timHandle); } diff --git a/src/main/drivers/timer_impl_stdperiph.c b/src/main/drivers/timer_impl_stdperiph.c index 599b8b5cb3..fdd39fd78b 100644 --- a/src/main/drivers/timer_impl_stdperiph.c +++ b/src/main/drivers/timer_impl_stdperiph.c @@ -408,5 +408,6 @@ void impl_timerPWMStopDMA(TCH_t * tch) { DMA_Cmd(tch->dma->ref, DISABLE); TIM_DMACmd(tch->timHw->tim, lookupDMASourceTable[tch->timHw->channelIndex], DISABLE); + tch->dmaState = TCH_DMA_IDLE; TIM_Cmd(tch->timHw->tim, ENABLE); } diff --git a/src/main/drivers/timer_impl_stdperiph_at32.c b/src/main/drivers/timer_impl_stdperiph_at32.c index 4579db2bb7..0cc194897d 100644 --- a/src/main/drivers/timer_impl_stdperiph_at32.c +++ b/src/main/drivers/timer_impl_stdperiph_at32.c @@ -404,6 +404,6 @@ void impl_timerPWMStopDMA(TCH_t * tch) { dma_channel_enable(tch->dma->ref,FALSE); tmr_dma_request_enable(tch->timHw->tim, lookupDMASourceTable[tch->timHw->channelIndex], FALSE); + tch->dmaState = TCH_DMA_IDLE; tmr_counter_enable(tch->timHw->tim, TRUE); - } diff --git a/src/main/io/rcdevice_cam.c b/src/main/io/rcdevice_cam.c index a353d713f4..8fb5b637f0 100644 --- a/src/main/io/rcdevice_cam.c +++ b/src/main/io/rcdevice_cam.c @@ -48,6 +48,12 @@ bool waitingDeviceResponse = false; static bool isFeatureSupported(uint8_t feature) { +#ifdef USE_LED_STRIP + if (!rcdeviceIsEnabled() && osdJoystickEnabled() ) { + return true; + } +#endif + if (camDevice->info.features & feature) { return true; } @@ -262,6 +268,7 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs) #ifdef USE_LED_STRIP else if (osdJoystickEnabled()) { osdJoystickSimulate5KeyButtonRelease(); + isButtonPressed = false; } #endif } From 5c9b37e9518d0c49dd9dcd0298422af243db775e Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 27 Jul 2023 00:42:20 +0200 Subject: [PATCH 026/175] updated led pin pwm documentation --- docs/LED pin PWM.md | 8 ++++---- docs/assets/images/ws2811_data_high.png | Bin 6042 -> 4108 bytes 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index a3706cd7ea..2d2e9b2a31 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -1,6 +1,6 @@ # LED pin PWM -Normally LED pin is used to drive WS2812 led strip. LED pin is held low, and every 10ms a set of pulses is sent to change color of the 24 LEDs: +Normally LED pin is used to drive WS2812 led strip. LED pin is held low, and every 10ms a set of pulses is sent to change color of the 32 LEDs: ![alt text](/docs/assets/images/ws2811_packets.png "ws2811 packets") ![alt text](/docs/assets/images/ws2811_data.png "ws2811 data") @@ -35,7 +35,7 @@ LED Pin is used to drive WS2812 strip. Pauses between pulses are low: ![alt text](/docs/assets/images/ws2811_packets.png "ws2811 packets") -It is possible to generate PWM signal with duty ratio >0...100%. While PWM signal is generated, ws2811 strip is not updated. When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio < ~10%. +It is possible to generate PWM signal with duty ratio >0...100%. While PWM signal is generated, ws2811 strip is not updated. When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio < ~7%. @@ -45,8 +45,8 @@ It is possible to generate PWM signal with duty ratio >0...100%. While PWM signa ![alt text](/docs/assets/images/ws2811_packets_high.png "ws2811 packets_high") ![alt text](/docs/assets/images/ws2811_data_high.png "ws2811 data_high") - It is possible to generate PWM signal with duty ratio 0...<100%. While PWM signal is generated, ws2811 strip is not updated. When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1.5ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio > ~85%. - After sending ws2812 pulses for 24 LEDS, we held line high for 9ms, then send 300us low 'reset' pulse. Datasheet for ws2812 protocol does not describe behavior for long high pulse, but in practice it works the same as 'reset' pulse. To be safe, we also send correct low 'reset' pulse before starting next LEDs update sequence. + It is possible to generate PWM signal with duty ratio 0...<100%. While PWM signal is generated, ws2811 strip is not updated. When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio > ~93%. + After sending ws2812 pulses for 32 LEDS, we held line high for 9ms, then send 50us low 'reset' pulse. Datasheet for ws2812 protocol does not describe behavior for long high pulse, but in practice it works the same as 'reset' pulse. To be safe, we also send correct low 'reset' pulse before starting next LEDs update sequence. This moude is used to simulate OSD joystick. It is Ok that effective PWM ratio is 85..100% while driving LEDs, because OSD joystick keyspress voltages are far below 85%. See OSD Joystick.md for more information. diff --git a/docs/assets/images/ws2811_data_high.png b/docs/assets/images/ws2811_data_high.png index a1a2d8512fc4d501d94bb7730504b194ef2201f3..c77e89e5ece1c2a8cfc5d30b76bd20f555a5bbb7 100644 GIT binary patch literal 4108 zcmX|E2{=?=+&1>8sQg9Ak|N7wi6Ohmk|k?YCRB_Q%;sRhC zY%iOSk57F2HkO>6lAD{`+uOUfwbj+tWnyCP?G4S(&)3t_UtL{=!x0V+uIA^-vm+~e^2`~P#l^*%ni?Y`lj!IeI-SmDvzbh$va)J? z{FA!6y5Qi@si~>Cxw(~zkdOrO{{w1qDk>OBEFr)6>%~7r`SVqiSjzzkmPk?(T+Nwp?3VYiVhj zoSf|F=&Y`;CX^RGdi3by$B%=9gU63c1^u{a%*A!^q?MWJ<@;lcIX^BO>k@CfcGt4m zG~V=(V8TnS@-qp?c+J+D%`_aT2N01O{f{j=pqZIRm(Zw2QGo#AA+T^@@6ng0XNN-2 zR6T;tDJfo4tinD!0BM--p0GL%UlWjYmjooAw&1N0Ki z;(pp3>;ADZ*1u3+Y?rM_cLf?6dQCAZj=)O{!(=R_8DJ-$f$6*j1C8K%Re9%pR;rI1 zT)I=uJX_EA1%~nfClmf1TG$C&ZjQ@n%1K&_jL6Aizci-SDW{ZuL0Q$_pA*bI_-C&( zr0-`{is3wo0rFK}XwZZguv$nsF3tZqoI#0)LrOeHIGn{67~j5~v(Sm`TB5YPCgo5v zo~i+#igaF{dtX?SQcwg#w_`^U*MqV3^*%0?7u(32~Nyp@9y z1KuG)Po5Q*;rLlavVzndH#@~%z1TuuEx7wv-38IqVr43S#T!sy1Y6DvRaC|HN2+?Q zhY9a!-Ox7oH|8tC)PQIzPul-Ztskn|CwX(&JMDB16YwY5Kg$CE(5Y}$X_HCkZU?`? zq#E5oJQTSzE*ff`qBW&(DTRVCB#sl9JE0z@Pj7UX)}HH;%)~ zX2hNeFc{&}CeR@1h=`s`?1p3cY9$B_o$iSt?3P-$={eEmHFjwY=wg`>pssrD6G@=P|3894mNFO49lQ<~_Ni z;m%LL*cXO0mD=>ESi}`*KX6SCWde6aJ7scz!cd73*UF@dMMmEPFBRr80guu?fqu{- z|HlTVqSKYSjGJg#cGLNG?|$#w7uiL*%CP4itAX_HB_O3g=h<}o=dwFL>vE?LE0aco zh$6tF!TP=Rs{mqCt@(flN$HG8Cn^5Bkn_p{2FIRtb9KieLr=fC!2%n9@P*3G>8=e3 z46-G3m2Ck~6FYxt9d_au0WI~zeb=93Fz?)t>0KNUFdKNBr)3WB`!iy{N{}NITGqMU z-=5D7(;;Q7%~17Qu#C^@jkUN)hkGv&WP>9$(XZf;ysP4BuK~PeqYmTF!=14 zq&{3HA*?CP1oW{}5fw((Cy)waPnOOJZDI6#@V{9bLfcY-+xViJ|IZ>M^2>MUrE-!n zJ9n7v$QWCImP~6FFo%tmR46A7Cph&6yL~nk_s2Z<_?=iU<@p!GI@&0$;LH(1a%Dq| zdII^-^GO%UomOoz8v3@fyVuS+33;t)jo7x4W<(EH2x{g1ItUn=Es<%LJb`NN>9X^C z?tNfg>P7k1`Tyl`JwX4JP_L8(* zKeo4BIko5|zi8_Bp9=(L;6}UwUkuL%>5xACSFKEbGv-(g&O&}e>dAi&x`e-nB7|c3 zneUIBrz84|Z~shJJWp0>3ZpWQuqB3cf8J6$mu|>3D3#rr{X*$pJyH3 zxc7ml(d?kE#yXY9FGsg%XfoYL6-xE^dYa%}vzQaOZ&)nq+2C`x2SQNLwh-I;7 z4MVl6`p@3vX;yf>N6NlI^psq0e1dlp|QQ1Ws`NZ)Z& zUHWe}3>vDiR(*ugd^jkjYb-%vYy9Z1&A!s@gYG5{L00?G5x-u#{K=q15z?s_Pw#6Q z9`B>AN!IlbL^p($Joe2*gQV)au@#j^s7Ci%Xs#i-w)qK<@<>ympXbzKBmyH9n~&Y4 zUHwku5e7YUK`965g900(0^V@JpGQMV-A1DEo`?%$MLn_r4Lnq#EBb^h*+EaVL2#aG zLDPnhztQ-r*G*>TL6phAKVY14$6rZ@Vz0m$grNe;gWLxG)RawEzqzzWU!5q{*@kZx9N!sj`qX z=mA{YmvPXn16JYaF=tb=*yS*~W7RhH+U_A47LJCfxQyCYU7h^ka`HOa+*op(5njsi z9hd|=gQobSW5ZLZD})t-eM{xkA^L`LGL_>=BR+yCFZ_5P4J^urO|RqR1h>5hA%g4T z>*71&F=TU3Au5>DZ8tv9z$=6~#e%&3`FV*^nz7*t;lgO)7TPN{KDZo*@NP^Z7l@O&l4~z|G^(+9{KwdQE{?0!-V9|#EdSPe8KJD?s&LA%2n_Mh7 zAL{$G_P7TVC&$DcFU*sgA}$?J<@W}BJGl!&k=XYB0E3u-(2Ln3%$D5+9q7+ENqsoA zb{5-ip58+j=O$o3RH{nf`Fh6(>VXuFrdUk6p1XU^aZSf#6C$`%ufc}NihbDe7TjjE z&nw=(kcQ;QkUuf(Olpf#65J7INwolZ;d@c(u%`#5eT^gAg*n9$bK|V}dy@_bxj{-} zDPi-3D+liv8yNLlikont6Nqi*j69wM*_-Dq8&(<1Q8_AbX{)Q0AUeNvu9}lPQ8sYP ziIcH^lk5t@(WfD9Pi-*CoD@fnqa*q=xCx@1nzI}KhIH)_;G`}ZGPs8?j#A<*4uTXm zrSBy=Zr3nij%U1)oYffBPlT?->_Q#?L<uXgQl z{pdC$dk7*3CRHYd+e{*w8l_hWGkr!kTtIv;QfL$Vm=>=D*rc1>7G?(p(X7jyvPLM8 z&E?&#ibmOxbf|3|9h7C4=}jmx@v$z%aX!aD`m1>QRT->lO%L~sd2FbAycG8L$k_Rw z$1oS4>*`)E93%)3?%VFvzNGCQXd~X;t2CmfJ;RU{Z0rIK8Fdt1q3eZ>g>~o=x$nAn zaFe;^KXQ}d@1(e0bzVB(Y4$DY1enWA>SrL~Wk#|gp4LHM@pr6IWkRn{L@6Tw>_ZEq zSryx`OGMH=A#3XVwe%C#=J&Q2ZwT#`VJ?Eq0vKhMN?Kq4({}o~X-R50>*p6s!I;PM zk14SQY1E3Su|=HjVYZ=&{PJ4nhz>J~4C2_lw6#)jfgzM`;4PPfJXi6}qB-1kRWV^6p~3)#f6vOuMpacj2uUJV1^7FUcD&gYhtfnWB4QvY zc)Ym81C`ZpjL`_lR4BB2ndS!AJ8HUMmI8bYL*rZE%ma5&v5;JYDZS&?X$_Z7sq#}& zyS3$#A&VJ)Y|N;d3lLte@&QKn8|kRV*~3^0mJJEW?iX99E|dYMRd9as?_wUv&WRJo z$4@+eP+Wp1oNYU!k4OIMzBR1jxk9L*kqw`XC5sJnOj=6NElT=c58A1>_0CO19o?-q zdu(sFF3FgoVKu7V?7!8%N+)ax0P7(tAvLl+z@h&+|cCO1saRlM- zw&TD#h4Mm3MU(Z7sItbpNAlI;-e1oBUDV)D58OlLpGvpbYqU>uJj}W3&vG_|DK;O? bE5S8ehtlM~{{zqYz2~wrw==5(--!7iG8i}A literal 6042 zcmZWtXEa=0xE@`M-bRm-5M2n-yO4-Z2txFP7&9U|VMG#4v=9ngy{d3M;1D?sKAy4RvX#IH&*s0L@)JZBqb%1VI=lP?8X? ze@f>r7TA4stbEM8Tz&i;yj=hq&R&i#ymvhv++0ju9GnB7KV6go0HQGC`{p`ALN}g2 z_c1rOSYBSXw6t4WTN@r8+1uNjnwoZWbW%`I?&|8w%gZ}EJCl`FXl`y!O-+rDPdGk4 z{`s@Fs_JV|QBg)l1|0tG^XJdo+uK}R+-+^`H*ScksHg`Aht$^AH8gySjC{?w)!T3T9+jEu9gvN}3Cf`WodN=i~v zQetA@AP~EhluS=g&!c+ytDs@w?Cpo~>)Jk7N<@fK=U%!6k=ND{j zY@kr6>gt-+)zyK4fy&CtiHXUaoZP;?J}ed+5%FqkYs=GI*FsNoetuq3Ql`EnS4~ZQ zXJ=<>WT?I#(b(8HIy%b9$;Hd5X8-`ORNmFrF!!Hc%ZRd>o*wTeNjl2i? zHz_1CH!d+JXGxF#vY2Vq#o)2Aj^C|bus=_fqGXNK)&xG<*r}lz{W1OX%w^rr#VvxK zm;MRnRVyDL9AHaNx%<17rU$z<*ZJm&G7lcmLphq4J#*>|QCm-m#J-1~Z5H-)+tyK2XijG=kQ@vOn|=A=@V# zZJ8)7zZRSjai?B5yJ$BgJRTA7LGoxLIyC+7ghQ8gC@70k zAF!8#ciM`)ml#QAJOin~{sY?d?6o%OjtHk<@q0*ii6mmB!6#~*tk>QqwT3=abzu;8 zn2AFceAK;XWjtT=`fteH-`1(TBXPtE9rz`|h5Q1cu6=o|9=5l_JDk*wXW4p7Q@qI< zM~4X6kn>@BGy%@rB@foZh23)CNt=q#ERXm{#_t3vQ*)rjOeA6;v`lwog#Gjgb z)Owv{jgu{W4-^-5=y0bVN|}j4sf>2_`QuH$cX={UMfV)=ltH9@_or)V{PZdLKgqLP z@hUQlJr?Q#QS&(juFc-_?%!Z8DuvXkXA!+lVC08BK6#vMlB*qldhO2yFv7LF`-bVa zDCbfkaIqV+ajlWq$J0Rm+Bf;%-%TlMe;N%=wr4iz|D>n05=HvJtI%nO`RSq{?fv@C zX>1?XpC$D?_|It`7-wmEHi(rw1lt@)4&GVn7>&Fpqgs(3IuD!UO0(4KPS*}TwtJsD z%|c}tO;@wDEXQFM`=_}H8+y~*Yf5Ogxc%_zEkp|@J>D-ie~zJHgo)tzistpA@IJAT z=%!gvzjTz(xOaHw{j4uI(SsB%@`Uj;y?(e2{kMuaudb@cKUA=+BI0lIXcJti574Mx z={Gg|JfJL(WQaV@jPfhw{C1rr8;pb9rmo_4x@&88(d{7J90xKH_* z*ftA(Ekpd(!d?dd7!}@cm%7FZ5G5D7iGw`3Q0jIJL@27`o)jRl02NGyQi4*z_ zw+aEBZ&9b}EV5LcCeKj%Sr+c&%BAi45%&kyii<)~4eTguiv6l994aMukZfqcl@2!Z{4yAtOdDeG{qu~JGJEs7oXQ@; z^u)K!uQr`XS-<~dfmDy@f1t&$&)DQ=p^uLLD-~LO<39=`oZL# zI@$z|J(so#Sk%2a+c+LYY2(PtpI(0<`R4$xk2fjd*q74jQ`6Ty|M+(m;9^Xj$P;7nwi~DV)7+F7N0cL;sT7It`$yx z+rCceYx>og%Gjj6STRu8Ve3ALT6OHLDK|(*sesE#lz^P?$<*YXZ=K(wxUlToWS)=?a#*9=zzE(ZQL{!=ZOBh`zo;4Wl?_;rpJDYk$`FNRc2@oYE$uV;O2sep~J5PUc&)Drnq+GqPG`VRsNXFn2PF z-r2G9e8})Im>8ri5%Jl(Z|kLBCm%w0BU@EIJ&@hjv?+jSSH#Mpdhm^C zj3(55DcY{N-xuz2mHCP6w03hfDqY&+XigLo6#l)D6Ani3F{e_ zwz*li_JpT(oddb=252RN1W}i3m`ol?hh}SxnOht&s0;y7%2c+aU&S-k*bdx)41g3G z#JV!LUG=sbT6nCDd+)EfmEyI}eZuYnz13Vc49>lvZ6l}A)n(&n+{zOENFm6CQ=#MO zXiSMor1~N%@dk6d?bwkB|7^gc+6dVk#$p9q6 zW@3bg022CfoNve5XjmOBW#zJhY!k;FGiHQID&nUUCtAFc2RcoGT>(mO-eU|kEshRM)mrfxU303qoE#tKEb6<& zZEjI-cSYJPq^^Plk^Py; zJh_1-ryxRaDJjupjc?A6*JR-1_b2Ma@0rURue=H@=P8m5xoQ2D{~N#Ri;qR04PYfE zI|T0Fo%jEQ{p0V9O!;z_FZ$K8bS=zdlmEBQ1a9lW%48F}6t6#C1BU9}Q6KCRBP+M4 z$y8Ff(v@F~aSa(-Ay@CoRbkhOtBZYkougdD&ZQwhrEJ{c=G_?yFaedoQ;7LeNuo zzn()LxpR{}dESlczpf`&(&upNLrdWe23=@%oz!awv@iqil+>4AR zLmWEa*bN&i>7`@NZ_-~;Ew^lWWPjYg61Q&Jm!me`f@zfsoKvoU5aiE&PWl&8=hnZ4!NK^t=NmID6w@3Qz7s7a@9?> z^YD;Bs!j(KFWaFSldZ*yx_dP~N4l2i_T85cf6-0T7G7c${}D5txWUAB6j$`9JA-A| zp4C}=b~J@_7_Ddoygl01CFZuf4Ke^aVRS@QHr&$!KiRdA^AN<`AITGBOBXjWu%2z% zI$+NO9x>ul7KaaCvHkVy3L#-D3WzA`jOSSqHlIeXmi3Is?Y_T)R-E0;Vvn{yM{au|<&j?KMhUQTR2sgt9mjR4N`ClnAx|q>v0ux-;aR zryfh{w+aO{Zd=IU3>@o@c_qjs@OVTLdX;v4{u*=!ByYiBzgh?<_7gK~;a04~tmcO9YY)ce!_vG>|i9{l7Q-7-|S zXg(>6wYxQj!rJBZifvgSQ*rMlwKt$~zC-(QyKarlh$g3Lf|OAVwU!0i4j4GfNJU}% zLma55vE=j94fg@YuQ|RCiUVNx<%Y;Ao);cKBy}4vTHiU6^(F3ZFKr zCj(h14mWA!PGT{rHBYYpSJD>XGY$a{QcI`_g~CZ5p)@Ka-_jBeJphSdo2!?IXeI}> zB=B5RQDX}s$x7isMokaAfSLwD5`pY~R?^^-9u$@yNg&Ln_onIASDsUX{mCv>O`;Xw zgy>;M1jS@sqG+84QO1)ZCI0$Ap2$zK$;yN70`C|o8VAkdJ|7a@Kn(Y~71Gj{WEc0B zefxn3kth0xA|XND7v1|GO{wqc68={kh^Av<= z2pE!R6(?I>e|)8Np58W+*npsR;0nT2h9XOI*@!~KbwG*$BnwPoP${dBb=LR6pKy>` zfL{5($H-@v%VcpgR1%cCt_G(79O>8&1J))oI4nZHCTm;1O|FFZS#<~FjM1&C0mL)i zroLx8sqp!w(oWxa7FVT0HV38Cn}$AIBK7lfP5p3Ww_C7lTF?Ef$4JjalRDIbnJ&a$ zTJ$0xU$+sX7D9TD%AXl^71do6wEQ?vNcsi5g%N5^8qkA3^d`3caD5{4s`#6;HzOS- zw3_Wv_b8cje{ny0by`4)X`#d^(HDAg@V$r*MYACC0?j`%-Mi1pFmQ(G)NZjyS^spd zei$WH#^U8xy(+Ly`X+%n47ehLXn4B();e80G@aYzW%@wYwyq{|^sfT(or(4zsq!{m zK9A`6&kJ=8zl*fsNDwp-heB#C7m3%slA{&H?RcQSNxYO{Op(U+XxEnM9)54-gO0LO z%?;zODZV3qzRmY9qnE!P|B_UG^_igkfCIPiRm-<3-HM3ZB9{E+`c<35+b4-obU}$W z_)}Xlm!SU!5wfm6!u|Fu!skGWJ|siNt-V7Lp}(BOTXUzmIca>@CSWU+1`=LERBm!^ zVlu7;U7>&+>~qYu_ZOv*$rRWfb>dpb@PB0ubCkBdr>(>a4r=xP@~b!s*271~t(Q2# zoz!TXw!Q5pGq-skAVTVSF^etzTLBZ~LuNV|xA~$BJ$0cPNtCvTVw3n|H z?Skl8{IPKWvWiu!G+B%bVb|{bcpC%JHU-)IM5Zz&J9lcP=@zKa8ylDV0ojKC-&%k0e+k{1f#6;s_3`J9T@$lzvPG zuXje~pCF9WVYAG)yNdQt+di4CMVo0eHIQEND}oeEHwd^K;)xE<$=CqxK`#cB=_mRK QKidI!bqux3H6O$N2hCsac>n+a From 2cc0df92d18572534f05655ad2dc1440e94552f2 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 27 Jul 2023 01:46:35 +0300 Subject: [PATCH 027/175] Update LED pin PWM.md --- docs/LED pin PWM.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index 9bb445070b..aaa9226eda 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -1,6 +1,6 @@ # LED pin PWM -Normally LED pin is used to drive WS2812 led strip. LED pin is held low, and every 10ms or 20ms a set of pulses is sent to change color of the 24 LEDs: +Normally LED pin is used to drive WS2812 led strip. LED pin is held low, and every 10ms or 20ms a set of pulses is sent to change color of the 32 LEDs: ![alt text](/docs/assets/images/ws2811_packets.png "ws2811 packets") ![alt text](/docs/assets/images/ws2811_data.png "ws2811 data") @@ -56,15 +56,15 @@ Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device sho While PWM signal is generated, ws2811 strip is not updated. - When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1.5ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio > ~85%. + When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM signal with duty ratio > ~90%. - After sending ws2812 pulses for 24 LEDS, we held line high for 9ms, then send 300us low 'reset' pulse. + After sending ws2812 protocol pulses for 32 LEDS, we held line high for 9ms, then send 50us low 'reset' pulse. Datasheet for ws2812 protocol does not describe behavior for long high pulse, but in practice it works the same as 'reset' pulse. To be safe, we also send correct low 'reset' pulse before starting next LEDs update sequence. - This mode is used to simulate OSD joystick. It is Ok that effective PWM ratio is 85..100% while driving LEDs, because OSD joystick keyspress voltages are far below 85%. + This mode is used to simulate OSD joystick. It is Ok that effective PWM ratio is 90..100% while driving LEDs, because OSD joystick keypress voltages are below 90%. See OSD Joystick.md for more information. From 33cb1b499d7a6ea0f13f54c531eab0ac6eabf9ac Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 27 Jul 2023 01:54:26 +0300 Subject: [PATCH 028/175] Update LED pin PWM.md --- docs/LED pin PWM.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index aaa9226eda..4d113ca174 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -13,13 +13,13 @@ PWM frequency is fixed to 24kHz with duty ratio between 0 and 100%: ![alt text](/docs/assets/images/led_pin_pwm.png "led pin pwm") -There are four modes of opearation: +There are four modes of operation: - low - high - shared_low - shared_high -Mode is configured using led_pin_pwm_mode setting. +Mode is configured using ```led_pin_pwm_mode``` setting. ## Low LED Pin is initialized to output low level by default and can be used to generate PWM signal. @@ -64,7 +64,7 @@ Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device sho To be safe, we also send correct low 'reset' pulse before starting next LEDs update sequence. - This mode is used to simulate OSD joystick. It is Ok that effective PWM ratio is 90..100% while driving LEDs, because OSD joystick keypress voltages are below 90%. + This mode is used to simulate OSD joystick. It is Ok that effectively voltage level is held >90% while driving LEDs, because OSD joystick keypress voltages are below 90%. See OSD Joystick.md for more information. From d98f543b864b1352ebeaad4fb8200313a234d177 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 27 Jul 2023 11:16:07 +0200 Subject: [PATCH 029/175] updated documentation --- docs/assets/images/ledpinpwmfilter.png | Bin 0 -> 3352 bytes docs/assets/images/ledpinpwmled.png | Bin 0 -> 2109 bytes docs/assets/images/ledpinpwmpowerled.png | Bin 0 -> 3467 bytes docs/assets/images/osd_joystick.jpg | Bin 0 -> 26886 bytes docs/assets/images/osd_joystick_keys.png | Bin 0 -> 5761 bytes 5 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 docs/assets/images/ledpinpwmfilter.png create mode 100644 docs/assets/images/ledpinpwmled.png create mode 100644 docs/assets/images/ledpinpwmpowerled.png create mode 100644 docs/assets/images/osd_joystick.jpg create mode 100644 docs/assets/images/osd_joystick_keys.png diff --git a/docs/assets/images/ledpinpwmfilter.png b/docs/assets/images/ledpinpwmfilter.png new file mode 100644 index 0000000000000000000000000000000000000000..d27acea6bc6374ae7c00de6a0a6e67ebbdf7badd GIT binary patch literal 3352 zcmZ{ncUV(d7Qi1kf&;<|0;6<=plE`ku1a4OX+aqhgQ0~0M#>UUYEWr04pJ1Q1ZhDC ziP8xWkUmI>5Q-p0A{{~oq)3pCz74apW%m2_pZnc=?m6$A@7#NS@7$=LubWDU$%_F1 zAYpE1i~s;3wqU-zZ;xP1u<+X5IP8BF?T_@i?H}aqivup*@^Qhbn&X|_a0s09t>C+D zIDLUt_|KL%uC@}x0b~I{WM@)95)i?F!LqWlXmk*o4rQ@eSSQ84zCIFtXL)K$NJuDp z?_L-T78zs`8yk-RV%~Xq0RRzSgRk-OqM;&|YihFL@czQW`tWcBDlN~>ZfA4zArU<0 zBC|lJPqN;%JbSjWvGFD_5Rb>F8yIl8+zC(5&m7Kg(b3<(fA5i#%eFohYbXr>AQlU% zs)9Taq)mZ5I!I!H015<%f(XG@5CmCZD-i^zKm-7G000dIK2cM{GO?=3stCGZn}?ta zOuHyrS^$v6qdyxP18FD#WMzQ@>nSG4B7svhLEcCx8jUFU6wtcs1%V)f0Du7OQBH+; zfSA=v2ai05(pUmVU84>TBox@(3~r8(f8W@6c?Sa=ZQxCT4k;EvF{pzP68j&jsz)6z zx3JK8tV6h}$pc%H5)lvlEJ!F4Jo1c%g@sMfWk70-gaY)RW1n0)&trl47>pp+>oIf6 z03fbqZhYwmfipkyBM`^{msFLHEck#O(TfT+&v~*or1Y9d1%xOsV-$HGM)T`?&Qbsb8gq;6Fg6 zN=Oi4@;>xYY*aWzurl5i|8un~e*1@#K)kCI?YjB(wq1dwBO_Mcm(oDv(wQmJ12ZMo zbjnO;T1l)uU5-_Eq)Cx!5*Nn5;xklw(bI)-1oKJaX2Vnz%Kp?BEk+3H;=Mf!XFY8z z^Z2gw1(S!gI`&)W20J-)ELCnq+xZ(z3NM_>bHLykrpVeB2=@ad@|5%QYU|m@dsZ(S zn8`R6Zlc~;70ND78s~fa1P_gu9grYd`ATNy?r$KY31|sLoNNZtk1ZG0yuCwK%eYxH z%=w1Zs$U)8m?QXYdj3hUdgTV?a$`n$Gi0mcO{n!-%1I2~cWM%OD%HIB=h?@?e*MIs z$~+#&y|VJ1PV2OqwpLa-VVH3=WO8hlC4JVz!_PN}Ie&O%2>+CsKutWhRN02uIgqO+Gyl3i zUWel@$}07re_txawN>-XyVc9LK5=cUqWo6P#-#Ie+{f&^gK>^8OatZ%^D3t8vukj7 zmbQ)R2CrC}u@&4z6r4hJIdxMeKYcDn+_z0$pw>s!>Aph4F8)G0;eZ<&j%H%X-d*K1 z+-$0yeXD(~GXISAUFGM=Kf(h1Z z=FD!nG{|tAyBEwa3|#T@V+YKiP8cq^(o@>6G=jW8WVVKTb2-L-jwJT^<4YrWhF5+h zG&iIu7h`QQcFZ|fw=9KRhluuuI%5Anmot#X$t*J+ajr8OD5EOHQ%4W$cC|7RuQKq@H6_urY z@=nvh#V#31sn>h+x(cr(y`e@*60nWPrGQ-5?X3O8pfR>vfvPw%<3YZX+}FG&uCb$P zy^Dd(IQ!_z6lAcMOJfN+nEFH|DJIGJ+`0Aq#J)I|!!$ZVug{h6&3fi`%A=~N<&U@S z=3EU++_V+z==%VT#+}4{IlY>7uBO}aQR3RSrrTkOI(CwL{Wz_}zoB}gv==72*%2mB z$tEID=O5vM!X}qME4W6X;ZD}jhP2($scw(a?{X64-zxt#?f7d~L$kI4%*jcZ+D7JS zhH}P}S4z%t&fJ$E3n22}CRU@qL0%Lh=rP$v6o*q`Z9Yrh8OM3f9`%rK`Y*O0>?gOB z>}*XrqUC5$C9t-S>;D2?-iJ=jOx6=u6M~8(Sc^{su(pY7e8ZciB~T)_OE@4D>ro*9 z)vluzW{)}w&?EqIeqRrdZz$r-O@6{rMr*p_h3ZZRW|pJ^dV{>5%F z;Dp+QnGmcUg-&&=(z8h>B*v#F+%GxTS322loHHOzHnH{fG6gBqDmSq>khbZtuuyaMiaAHCnR5%2-jy|8Aq7Ak&EGFF17a^rzCV0$}c@^Upb$ zxGBSS!gMcCO_97nhetTfa-@nMwY-;ZSsPVl=@%pJ=1aBAn3Z1XO?6B8E0;mpPSa?l zL&i!u682WIUavjlD=$QDZ0Wn_|i!3{(ZHvtR08Oev;|1G$ zVzGR)@;lxgy>Z>@p9hY(RC8CwA3o{6jt^vdwLq(^ zklp3}(&P!pmjbmdZMMBV*-?wlTPopBzBF2=Fo&2=QCN(90Q&EabLfz4_2fO(j z!Xixx6iW{-BTvM2KQ zZsi);z;w6F$6_k(&n-KtKq~u!n~x}3x#wGpeAn|r&qPLP*X~U68h)s9riWZ}X*^T8 zu{bzvxP{@YtEW*-6}g|aZP07-$yy@2|Jnb&KmRIHeH}I!Aww=v)M6(kC2?aWMb$ei z9XK;@gxiGCMa4eDwoXow>YU%NU=EAg*Ml{2}g}uwptPB zw!n71j2aJe0{fG~7F^0;@obe0KDJd1t2520uaiQ(W@zg_FJLEJYNNUw!tKPgHxuT2 zTV>Jms3whpc-PM~EB0iFmG5cOLL9E%pUP+{(|%Bb~1<4G9g!%!)@z} zYol)mS6OVDIVHYVkv}_L^{cbTt^1lVM~dqqK}NZ!ZL^=kq9I&$t_D;bn@cfYTO0_I z6R?CPfAVF-+J};J1EtOXw|+Cj9tpSzUKDD`M$eoVmH7|jxCdG@!*-z=7OWI{mGQt; zB=mpk|6k{~ONA6y504< z1Mkd{Fsp_Gcg|I*Y`3#@vF_DeOLRjK&~t}zgB@PCX~P{Wrh&^(8dqO5%eG>#d=t{9;R}@*IVOP zoE0jE-5k;K)-COF2!Fqs&uYd8i~6Ug^q(#2pE}o<8x6o7APg6t4m_!23Z6QE`PJ*jMVGO}e*jcEn}+}Z literal 0 HcmV?d00001 diff --git a/docs/assets/images/ledpinpwmled.png b/docs/assets/images/ledpinpwmled.png new file mode 100644 index 0000000000000000000000000000000000000000..94fbdbe61385fc5bd9ef45fc04c072ebc327e052 GIT binary patch literal 2109 zcmYjSd0dj&8va}}8(Sw_FjF(jOs!PNav9gs$t4smDF-(w`@nL6Ynxw0PNPv;H?6ct zQ_Q6XHAoahCkGcqQ#QqSJyfQNc9PVqgI5}HUzp++ag1D8 z9)K;bsi`S3{W<^uR)?p8VfCV7Wdm3ay#*c>2&Uw6g#s1|;kN?82Zcfe!$JzBWC#Xm zu!sg@SSoXK7#=Ethd2OGsA9n-SQu`B)o;fD*;7+frKP1R76yh@O7-n((-5rqpa3od zbO45$Aq)!^DuocF_JTeD0G*{K&sM6*TId*>nyM26KpZ?C1Hg0uf?<(}26%aSshOBe zxQEH)pFGJYk<4>U>t)=B?5h|Wole6XPDdZc!KP?aW)G8&g_KGq9&!~8!6H~CYJp2w z@EsbQppT2RYkd*e;{HkewKTJDpb_j!Kb_YgRZaJ z-DY89>(!vxXm#Q9$Eg|qByZSeM~vmpU7DKg3kD$GyHOYQ73j&n0}b4+euTc$OYz6g z5}_@A>^dWJe1r6%T=29JaY?ek3%R9*OW`JuY?sA2l`ZF94)v02K-{60$nD$-E3}MrU~KtI2NCj{GM@tR}=o(qxF55~Xt2ld*Z4$fUJ0a;7EBdFkc& z5!~c^(69JpXsm^c^G8q|jLY-VGYw~Z^Aak4t>R#jU89{_t}s&A z^l`$ee(L#&RQKpU%BS^T+Pgd!A#wlQ;x4YU75F!2JTM^%Y=(ai;Zite4AQxn$ev}m&ZLML2dZ6Y-K!-fbXOZ)7DmFCkEahDSx$zw2lVL$eptF@ z#a=!M?eB|GXuLz`_a!z^)*D>D(xk_aIcPNRk-o{v`xlbK9=sM()`+^2rqA7d`?DFi zb9xMk&&o0VPe+2^%-_58zmSw&G|;wGx>qCLH1J)Ay=+)=JDBub=HWl>5|-~;AMhUQ zZc|d@Zz$VR{w9`LLQH4fTT*ZuCEMi$63itbzh6Opgdq)B4L+IAMPHtB>- z4IvMd2B#A33&DmYr1;j+n(jFzJi*UxOvRBaM^=LM(V$eujb$g}cJjc9%IBC_$wYe!is)d~t@Fmr6^HXUJ||Z7Yg%=K(#q9*H@q0feIhDcaC3X%ez{|_#x&G z$yv)usP+a8o_O3PS(?^S9?|ClXzG}~tmERNXMxNx@BX@lFhv~u-72@I{1}G-zV&+2 zXcOVl+X4a2{dVvOHZfrTGElvf_#{mA_PjVst6q^!voJYuth*oY{|<8>TW zc7>3x^9SzP8V%HKt-bn%ugkTc4mx9h;gPt2vg=o!{d2sOrZy*8P(a4*apus_kTKg= zLUnX>?8STEppD0k#8z`RpsRJyRp!iWDhbq031Av={Zp2vWI+Yv^}zIfeocH z%zB@F>Z#R0c}hunqgzWBylleGg2RO&8n}Jo(w<7JP2cOAocZc&j2HR3sHR2{Bg&TA zmL~5axM^@_&Eg*z8!xHEbcSi)S&-~Ple7>b268Yp<&ry=A*AUlQo~=wy%>?OS!Vr9 z`is9o(0H)3cqX2m%5q6awP^8MxQ=`JDPd`6O1(DbsMT@(R>ae>$lm_V$J`c)>@7Oq ta;g12sTt7s?5_T%_gcucxkSw$0PcM0mXO04r`2B~;O`sc^Vkbd`!}FY9-06E literal 0 HcmV?d00001 diff --git a/docs/assets/images/ledpinpwmpowerled.png b/docs/assets/images/ledpinpwmpowerled.png new file mode 100644 index 0000000000000000000000000000000000000000..2cc0d4bd1cfe8b485c0013574fedd146209f41a0 GIT binary patch literal 3467 zcmZ8kc{r5o`+sGtgd`-&WDXtcFp`8C*>W7ph+}tRh9Y4kjX^_-5M$p>DpR&(ZzxM) zUV9QUwlbI;+cA@6Z0~paeShbi>wErquJ^g_`}usX`~6(+d*7eu;bki`;r&PV0{|dw ze$f~W06ZA(`e`pOH-gA(28haIk59q+^ za}mVLzg{t6c6DXK;kdWB-JP8RE)syy0BLd(%E`$&k#VBXHUfz3MgvgHk5nXJThY`E zwM7s|Mn(by1EYY5n%{rl1pp!u8hY^}in4P*+m}M2C@3ggz949L0h03GlOZF6wk7BG z=W_8+PMxZBa9I5OnSw%b%WmW{*iu+577&^7kxXVV7|j5X#>dx_n)*IGoWo*u1qS{( zIa!ez^|h&~xuxZmjZG8{YKI^g3?jA?Kjh>vA*hf6K~V2VPR>h3MF?U-H110jpeam< zQ3Ej`CWRCQKoAWAY#}lk0%CXyZK3u^ZX7DK1<(`-h~&cCAx2?)Bzh76+9QENZiE&U z1r#tTXj)86^n>)oy2vP7Vic_x0MLar2x9cML%r=>a;QBy%(0zOvtMWmmT;6kJDV&j z%49$qT5TG)i0H`Ig|-FgR4zNyfv8hRt0^}%ZN7RnipJE}*SGVsD`arXhqT0;8UR43 zz}(pI${qT`c%0MdkhFlmzSD=#viIzquT?2tzNr6EWAA%-QiFryX#w7cJqr7Jl3#tV zeji10P%V>kM$O|m{PX&u4p=?P}4Kdr?R0T5+MJb;10Q3A+4 z7#OcK50VrS4@iT1Nf8GyeE(!|!HVZsdXA9b-Ed#}Nuw8`6<~N@f-o6Z4K`%Qm@n6T ztJr??5g%YSATlCMs42T{3a}0;n~f(s3A`QADO+5DFFD?J9nons)E_*3&yky>MRwmw z+$b0~%ug52_BdY|nG|iMD>8lEPA7ip7x{c|t=&b$J5sczE)L@um}qaUVSw1qvm+VU z71Yt@EVgDYV|*4GXv4{!g}xn&>eE(g*N@R_;Cy)2=-useSprYT1Z$~ae04GV zE0{um^lVr8?k#*0mR9F?8}6hR?T(R($$h+1Xgr~bIZsPn7abg~^^36%bkeJSM@l)> z7zN%yR-XK+j;3vC6F=Ik@?>7f)aug)x^}wd`C!LUHy%ur$!pA`GSLTs!%I)uP2mU6 z!%`OfHiP9T(e(;V5**$iYI4=(l?J)`{=E$ss#+m=rN=PdpCWmndP^&|y&~j>kf;QH z-D4Yj|L3ScW$2Z>&Z;AlO*+;*I8|`LxN+8#n(k{~b3+8II1%R*d(6d#OO2p7+mF>p z;KbZ$w7&T=Z2wBzQ1argI@$w9=;B9+TZ^a>7i?1It6jfY*LuK$;lq_VZYxu790ZV* zL6iUv#v1y$MC`0v^Q+=uWmLj(yicmc)TU?Fu8;Qe1b!UAeFA&7_ZbZZR@WS?icZLq z7^1anZSkW2tJFXG{v&k;e6ti(%1Y~xkkv*yNOpj59^5CT9?ywD1)GJC#4&4hUz`i4 zbt%;Sd6}#FfyR1me4cDWd`E}|&I+%(HdBISqt2Pds>H5nI#l*Xcl*_uE?e<%^!e|p z29wPD&mxecl&@XoC8%?5lffZlN|JU*kcbXlPG$}-b+~c)^K+PBEe5teyq*+^UA>}C z91EPx$f^lJO&rz!v9DWjQ@s%Fk6J2Q))UG7qoX6*Kw7hvkvlI1Ob4!pWx0=?pD8YX zSC*3Y*qvvZr^L9kV}I77{%aTIbfT=ar)1t?bLOsled;gNv=P^)prL_5_JhIY{80Pq zU<93z%5iOSdP>1+GjZv!1*Z*@#yj21-D-;+x^@XK<>{wLf~K>b^J|Z-7FN5~(n=dQ zhGho4*VcQEpwhv@1eR)msjRzO$HQL?XfJ|zLEaO=LkQ1{?OE3XG4w5M89RgD76S*o zVR~vK)`}{5Slt9?0=ucyT&3M@RvC4?RMBE4*~%^*Yf~G1ac6;l9(uV>Ekcs?j*$n_ zm8wcR_fU6t)^C(*dI9(^{rtABQshq(P^G&e+7Ev;#uoh|8QZ91U?Tl z!QT3O6cm#`59^AMO96C?aV-Lp{W@3}K{Dpnb7fxL_8OtETE6MbB#-~=T`*owXvb6;XPKS6v z6(s?yvLyJW@y5#!+?-KP0pcL4u@w|ck26We@q=p*KZh9I3ZNZOWJPh-mOP*)ELxcUKorjs zpNtP`3S?Zh|A-Rl{n5e0J7uzJzFxIizr_YK)Nxx>DJX?S`)ngO0TbNGjU5Wxa@;Ih{$jrrj-nGEv|+a$G8=6AS8n-xUeVYcjrTiCyW1VdQ2m zCYj}`yl|2Fa`cQKD`TW3H9&$bN(jgrjYTBlrzGjF+-SRQlt^LUn1wJ^D|=L=ZmHC|>MTbLSt6?~$w z90emdRtk;GY4amX6ue-UyeG?)wrX}>ABrz6|Jl!Zdp6qb1t;RXgZ(R`<>Vxj2hOUc zFOvoHgLLwq4U{~4CLd>{)sj7Sme&DaUgx~`j?4&McfVQwr<<(~DHay|c8ELF%kAO{ zmDyI$ZQSRrhE@hAQrkj;*n7@4G9`47_p6eg-#dFwr}Bt9pFH6akG`&XUl-gkFh2NgD+}TD{Xw!+FjF6Y*)cvx=536c? zNp+y4doo9>H#k>?!*_MxmM|B5_RFBwtt=5Ze00C z4j!K-U`)-ws!sP&j-E#PwH(OarIpTb_M(;=6txT{+?9$@>7(0~irtO@L7j)2_Va>a za2-6&>qELS2_I*hcWGL%uj?K zn6_7L50j2ppPC2q&;fE_#Y_hBT1UX_W=BVdpN8~9g6kpXt36-`KZr_zU%G1I76R8<+2!|L5GB7C+rTQuHKBZj;2Dhyoys z+iTK)Km=*fErU9)aVf^-V1A{65jpFPi3(V)#w6kk=)DN?*v&B$%Y+cV3^pt-B3G+^V~mg0 zEau@MLA|X}5TEi?uEnKIdQ#l|(xUw`EeEl<;Y!zPbe26Y<|Ad_0Q_x-#eUegf7{`| fv*oy5L^EKu`7BK75uSV70RVFoE8~|JevkYQBN40G literal 0 HcmV?d00001 diff --git a/docs/assets/images/osd_joystick.jpg b/docs/assets/images/osd_joystick.jpg new file mode 100644 index 0000000000000000000000000000000000000000..9b2ad0bac09f011cd745a965d6f6611db719988d GIT binary patch literal 26886 zcma%iWl$VJ*Y#qHdw|6W5Fl8P;1Jy1Wr5%XS$u)u?izwyaM!>t?ykWDixX^-1QH-Y zKc25%`TO3fsha7o?w(sUb?-Unc0YZ8+5v#%eI4uo0A*!%02bhX?dcRiEC;oA`UpS) zpg%W@0{~Cw00Ltm3kbx*#lykD#lgWN z!u$V5ghxO~L`Z-~O8VjjDJcy#H8l7;CMG@}K8T12L`6nSM)f}(|JR47J^(Qm zU>B7F4TTthN{oU=jPf)D$OiyWQPEIP{@0=BH*^375EBdKzwN*KP*4GA=+8Yw08|uI zbTr`eg^3D8!2qD35(Cg)@{*uSYhzftGxCuFLsN^I`em42V9x3A|Ju2*@*u+s`&2w2 ztNWI`*^~Jd1&H`RlLJuDQPBYZwK@th>VM`S)kc?ofniAolwo{Y1K^>dJbx=1F+dV< z`rS`Knn+F3j_jh)^g~r?=ju#~gS8U9-aNJbAIK?hr>T7Y$KzW_PJd{w@L{k-o zeOxI~Q%hi!0Npve^?iA&)Xj!@FxGE}yAS2Ei6h@CUNO2=%@dgt{g4vzklfM;j~rry zqCI9~Qq?)*Y<|F*P_q-({nB^j%9ocU7q^D%B+rdnt~OGlt4DpxwXQQ+r9qr9OgAcE zwP3bL(!|;@qD-EnK&=X z(bB_VSz|=3f9FXnrs6XI?%~oA?B-T{X)i~aHcXK_;l^g7c6{0NRF&v(N|i8Pe%9uE zCrow=JZaKQb}#18YJz~O8WMNN_U{+H4aW$T!nL(5o%Stk@rq#m7MZ5~Gbuh=3M#3o`Wtqmnh zQJ`|)DTI<01%1u6ArrU#*yNxJYpf&0X z`z^Jq7EM!W{`UpVeU%UQNoP+4I3 zwRis-ucvxU8S+XlhK`*#yk!BZB>eldcJVHQ*d0}oH{Zg_F_Ls=+ajDyyZQ|zb);0( z$O>dB@mp7|Qq>2wva>XpBiLFl!fyi`=4KvvmBpD1xsvP4K6q`(Ak)8?7i9DeIMntl zZD(vA#2dk9P4fgu# zHfPJLBjneCT8bhu0>&lMMPX#`ba}qJ4e(ZVwH(zLl7aAKJ=<%6!aL9L9Jr!Sg7EFttO0*;VsH zL?;7L4}j(4lFE0!iRIRv$^`6EnJ%oIRwXph*!7~3qRU@SY0x&B&jN>$16zOQ1s-x= znW*@(q+fUF&}92c{-7Bi#}+bByt}LL*_oMuVS%mD=f&4((@an)aCo1&#!Wcj1Is)7 zN)YN--qRXccQpD$1AN&k9YW9`tn}z!9%YAA50{N@6+d5@U_(7cuVs%F=2+~|S7S-} zLo$)!(=R1$REz6x*4!T$h%dz1*>}0#zkfNw;;YMn#kWs+v7<2*D~*aZP?a*JXG_~E zI>ykLnop&AKQNCzY-hXd8wC_|GDv{QWF49as1Kv7St`X%+onIreZ#luHMI4|1-lU1#DUpath%Yo|Qm1%@?N*71yj7?Q}s-!>AN=Ch*8&7;n`+s349y}KR8cTbPN zSDhLP-;fTafKJj=iZexns+RO8ExJDm*i-rL=!LvAvK`QG60zVA%<1{;z$$KI_ZrWz z<;Z}>B-p!bJeFUi(}l+pUVoljvqc+HqwFJo zfy8I|21twE?b|a>cQrON2$Lm_`XqP3uWR+i1_4JS>tj!%`CaR9Ei+hO#j!hNyBevZ zH5Mn{hPM(W-t*STD~xKKxn&LD08-*ltu&d=TrSG;!J^?Pl_w4xP6*>c|Dm9*f!^A! z^0E~)U;JSNrEN!M*OW$+a+||1oNIHDA(jy@kLT@)rGKQMDKn7`@nCcDWtFr;UO$`< zC^zC2kVLh@0_7aRlNz!H{}_<{7eT}#GPR_V%0AA{sKMfxl{-lvKfQAbEUwnZHJE&D zrQJNpG?2B3$S{_fm!^@cEb_axn5-Dh>n|hYD!obmZQ{gkM9~g`3 zKB-CIV0EITX{RT0&A_&KTl~!VcPVGy&V*^F4}F<^DPEOnl-W^G@iKKU*;bhtA5e+z z#wsfFqJx;@vJRwCmf;ot-C>%le!0HEs&G)-y0i+cNU$DltCpxnUeAfTNt$V^w=bAO zp%i9gsKgc*_T_-B5oJT$5nK7AtZhE?WI}}JSy@b|Cz*)7EX#Q}iLjNt9R}R0S?F3*A7i~m3XDO#wJ1Yd8fHz`UkLao#^Rso#2nX?tP7>DPsgQTAp>OIG zGBCyc#T<>Sj+N|x+Ym4leeA0phX?AVTiDoFkjfpuC+oD~A?X|I>x(-|u=JqA!YN6& zdt1rDkQc)%kJBN9$xzP65aQ_Wk%S;JhNgiUr)D7#M~_bdA69o|u?AAZ0rZ#aBw8^; z0g+5-$D)l{{P9=={v4#+c(_swKC|xS4DtO+91UvtDr#~`R;@hb8;kw?Az6DH+SNQ_ z9IDc$43x2_dvB5Mwr@?*U+0?=-YiLh!EFV6yxF)koh%u$e6>w<3{w0fc zn4l@*M2NGscq2QO`5naQ2(*04gU4~*u?F22CQ)r}2K8H( zvhKIcn(?HG3RR8^8B%UTfmw#ix-k^`DaiiI7Y1DQ$6@5sOxhD1Alt^&`qjQ{KHr@A z#*3FBBOY;eu^a=0&O~A(P(e^gRl@{cf;!Fu*Tl{r8jKHV*eMD|8gCb{71MV%+1S{y zF}{NCeV1QM`$yDws2>^CaO0E7Y><^Qo^G$PT zFdl(4Bx;nY+E!m^__!PShV;H$aJoQK7{*VF4H|vIiP^1$^-a(-K?xq^S`2BQ zskX@VyUI*=NJHzr*+CIUII9Wr;;owH6hr)!ag7nnEAMXeAY?dKZjRi@$v2{*+z94XY2xadHINM2$}xVq zj!#-tQFIww3FgJe)IXqRSs3V<6widdSWFGjT2VUGTJFQx22RqKxyFAmQc09?pK@cB zECcC4y10hjKt8_F5NAf!Bz^snj5JgpU?cy^=y14)Fb*_JmIRk*63C2K^WI=SjxS6q zK8=p1n&7L{0^v^K@Y=fx<&23`I`j3*y^C_aESWBAj=uzQOO{rzTW&!gqqE%7loZRt zfs~ZtvSjUGzonLOEA#>~a*&lMKtDMmVE7pw3}@n%;6Z&BzKG>_f?@%_pOYjmkR?$& z>AJ^E9qMCnyn=ndF#IuA#(eV5^9I*IznA3!*#z~vmcn>CNN_w)UU;$J{VSRgK zYPhuqbbNhradW_cJvssQev^(V!Wa$r$>w@*P9pCiIuWWhN+h>J{9G9LLt6qqaaAe{ zPuxjNI))T4nQ%W-*tTP9e1ek8Z-Ln|8OlF`pLjxvb*uZimZEmlj*K#g#erC)kp^KS zJNetc_DsA6*$KSDTucTH*>iEp$_RAWL=R<64MQ}{NrbPZtCDKS^LKqyvkJ?21qA;v z`9`#hEPsQv&P(Zto1(=2TcAopIJ6h<^o?WU=$6Rj#LUakxQ*SjSrvb`E-Gf#u^uU} zrghG>Ve(aV-=m@Jig?YSX}Nu`)M48lkdz+D!iXs zM@{NMgz>tL05>IRP?}h)Js&`1Lx-C6Ih)xOQ(N3EZfekDH*7*y1CKR&poPtb^X1eR z(!ZgPAbnVi)>C{o-dtQdVro0-*&qK<458M zTLY4x&c2$IeVRC7kvMWupdp9b<=1VnKgX|(G^(7@mq#ed>jADLQ#;oNBUsWO@M(Wx zrvZc3hB&;ai%@Wx20rHPM)j`?UeWSNsEv`J{GF3CH0*-M&3qZ9;URi=8*|i32nZu< zzU`qUj3ESc*DFfn8HBdIFmV~bD2lt7KUnv^B@ zWXle38ZnNn+(2NGvej)-=0Z4oqOYZTI4)YAA^eHU2OBzCO=9USN5)bZbX{x>SnVrw{qmQX+vjK_J}xWsDy(+mlY=ciI_wFjn%RELk8)VucBy|YO%m<)%w2P`?}Gp z)LL{3fZZT3tD?jY6nH>1(Jpm-gfB^ZUU~eaigCL;=}_CX-W{7a93@7JcTaOHK<D}Cc_#GXBa;(p`5Dw;h!R9i#a45u65Lc^H+rg-2#I*1PXg2k!{dOZ<|$_ zh5k`_DmhZT)yQ^Gi;3=(y&9kfSgX*?VdAXTC$1kiQ{LeSWhSvIPhD+y`GeZGP9Nu% zoX*!8%^m?|$dV-HSHTO#XQkvNl~h?gdQ(zY?A1?6LcqVFt6#|hJp;m2I)Z4hSW`=k zGwPX47X7nO0CWP{Rm(U0Wn@a}k$Exus8yUTf%+Im4$QlRoChBwxoNFri3ms|u6Oih zRCOVltB9tl>B>!8Y2O3fq0@9 zOk_-DL+X|RD1yD0y(3pcQCcde0o#iKsS7Q&3fA7Lb)d7yBv|*v@*HP!kt7yHT>P~j zsR5=;dYMjTprJO}(A~y;OKTG}XK?}ckpLLnh$C{=YE9l$l26_jV@s;os#EM5z<0j^ z-*Z-3Ym|suzvd)#wKZT>?seQ#NJ9(RAH>NeV~cE)Di>h=OnUWKuaRyc*KdzT?_PLE zJ}z9*4$d4Rg?@8UH%(51TF6ht@1m=3{gO-OQ#tlvpp%1N4)7gFVH?2Qh{ zx=3N)SE1FucrSWw&=l$^`zBYJQi1ljw%+82ghLI0STC+Y;-0M)2`zmfT_Xz-|lrqpV|XX1YqFDZfRNoEWg5 zAVBqJ{K|Q@r5F-ZfTuRiSHAP@iFt7R*v!a$ z*8N14Wx*RL3uwkCqwFkF^hfUwmfJpUS`z;a^TMJ1PBCqSudHXV8%uXV@aCS0@;8F3=m%e zIx^Kb3f{^PnZc->jgH4kRXJt9$4lqTx?}u_JCDVRuSBZ#<;5|2I7T%0ZBdz7t7V2v z)ef_UuO5_wz1kcM4t1u*X9n2ejAGaO)rzS4{ow3p5}$rAAjtJ#V zITTucpfa?LQk$m)P04QLk6td4W?=s;TtV=0yiTRlm~91%4~~^Od7`b44|j{?3mC!P z7Q@%8v#gZEO4J5Y%9*xY=j>ZEihE_M}p>4#{cES;#i{%Qt_N{*M*J zg*FQSBa>(@PTPv(5o{C{OIswa(AKqhsWYX`hfctw2m`YIjud}1wRTEAjjKR=;wy(s zU58L*1%d1{_pMMchS~xd3d_Xj)b!hhhXNfd<(Dj^m6_eXG!+gA(=o<f zbzh2}G89rLZ}G~Yzd}hK(re0)hA}Gm21hb`pKk*4a1z`nqWEMf7wZR!!g;SMJ}i~4 zXXIMQax)k18M3?8Ac|jokCJEL$6^ks?9jU5YGktzp$bp$3!Nm^jmsFpUoh5B@tleQ ziYfCNN1m+V;YIO>rJ)CWt^U@IOxEn*O%@bhmdeha2ZdC;8d0~dK1YoV11K->UrJJu z;k7(A;yh9$P5EOm=DlzL$P%X|xD`yeGd7-p}aHwBUxj! zqElM)3Evo%Vo4EM0xZDqi=#tO%>gknw!tXs0)A1ga#4G{-xFCpcZQV0NN`rIM}-2t z{Q{%bAaMx)Rdq;B1EY=fsB%?HMr}Q-avF~t+8(gthueuzd=yX#pbYroMn_epKxkxv z8iI!w)3-N>qSxPsVrEVG8+1PVS?~MDFEG^Rqj&Gbqxs(|In<5~s5*$NjiBu)^{=&c zC`J#X(eyu(X<32D9o$nz6_{ua*lMZmbsaxhSr;xxvRqDNU8e2|6Q(^PW7^Cdj%Hq<=`5M&>{7$9- zqtT?mKPunJiH7_85>U>nm-}(8kh``+Q#K!(LTz>Su+pK^ZbNa|6UkJqJeY_1CJxml zT9zSkl{nqb@0is-@`fjBs=xGh;Vvwq?c&I*Y5d{u$C^4*CrrLvF*wR^+$ghcWI#vf zwMKTj0fXb=ft1o_Vj~U-9 z!MNKuhI2f@Mvkbl-c5*RuceyIw6jsf$+1*Je&MaszK&}lQedoRY!;|eaVGgxxwH2x z?t7^i29FH^R3PPNLcJmrLbn#zKMZS$$Fn+LkTXL8J+2O>b?c@|BTI01M_IyYZg- z&$B)5&)>ncyYw}G|MTd*m1Nz<{mI?+wbaeqMp6n{Rt1h4&m|3l2x^D3~B0v@PwXM$HW zJXsy1%!7ucvRKKSy#0F{Ty*!S(J}4E_>SSoc(*?9WWT9+rd!PEQ7^n*Q#-vtn)7| zbEB|hUd<~ej}_gad9_eVrP97SM71!ia*jEl#REXtQMy#x6`_GLc7f7&|2mx&>{c&s ze4X~Y=G$-&G(U)#5^ZYR(Maa@$imQoHz6>~+9-Wnw?w-yB{Cs^S#RGU%Y2QE0%y&s zht~N!-I?C~hh;F;G z=T~`)fh|6lb3Ze=7EfB9x_Vp;++CKF$WEG3dLU-Wb4gTrDQuiI=5)`nieZaT@WQq| zsTN2&%FbSjA79Oa5G;9RlOVMpsW@)bV&rFOH2N<__+|;|j&qMn2TGFYrQ$h?9GEXwMG3(?FK*$QdysR$LErU|G>Ly<*Eu210FcAu zxz#ViGs`slTDC%tZa-zv2k9PZ*5TWBOnTws#2F{ftYn9-r=zmbV}(G$vEUtWwAG5r zXT%~9XD^98uU;l=)mcj+vT>w`@aO6-rEJZucdTj4Lnj0$ zJVQRZTjZ3Boa^N0GBE~Ic@#UQMQRO_iROYe9S90lj=xFF1v2fM`W#$l@+so7Ap*^? z0=RttJKc$D6)s$5T_)_lID!EeqQ*WnG*DH=oYmkq%7_NKzDh1;?duDTdQv^$bd*2~ z88n z5aOo95pl`5;;!E@gU%8ouC<0YwE8U5L0(jrw#}4!=KAbS@Yqp)cDBETDf2t|;=VcZ zO&A%<{Htn?;eJ@V*#8U&3#H{77A4ac(CXgBHodF9e6e^h_vYnaTiv>gs;iI@pg6{d zEppsn(rCo#j$1T_NJG*;1S{SMvm@YIP^K?o`P!D!khJbt+~wow{*C15`9stn^#+B_ z^BX~D=V&#g8KI{`owK3)?a3<|d_(S6ODId4`0sIkL8pQy&)SpqkAfbN5Bl&x(NUNn zb>b61)!p9zaWl={>%3#|Ri?f_h9S>zlrYt?aN_jG(Vx%;_rw*o8fz@j;0gW=_YcfpSvP1tQQByez<8zMxW>VoT2aDK3H;=(#qCz4RY zz8Bze_vUBU9o*mv;KxZ)a)o$B*APPsJ5q1I=d2#EeoaQdQgyfF)7ud!bH0-_xt=RV z?cFYzddg1*1JE%YBZjg?y!ACP@88@JzkdRp_0$`mt)FxYo|UBv3EuT;uY~*p|9Na} zI4L|Gye&M3{jN0o+IYQud|f$(KY8;fECeIoaiXq48&7~NXFaH^V6Q>oWVPoy_?*H_ z%wYX0-C#|u*||aFezMH1ts_*`UU^qb4?0vZdGH9vKkW3`P_^}}HbSx%pE|#2k1RB8 z7tK`tWUoph;1QQSQsb^L+ue~g-P(P(@<-N1#gto1lsEsmtPsMRW!}ern1pLa_yq7q zb_R9`G=1%C_Z7<>FG|eykwZY6Jhcq0(M=gb0(cYkF8VJyoaPp4OCX#*%XhEsuC5b? z>f^2U%WavDZQYajsNDIZmG{CA7VdU8dNSub;srjhuD4AdRa3*xjSyge%Ywet-L@Zj zcFFaulN*0e?a%BxMXT44Frmx_C@!@jteTsLWofdkoHCYYE@mh4W7nnh?ef+6Pj3HC z4?%1f9>4(PAlm(A)#IyA0kAAb?0~(SA6rLqkd)Ubjgkxxujt^_v2qXH}a$OfE#6-8wnYTEd9N2nMPqkUea5~+hC8doDG10Gb`#&8o#pjO;sgoIQX zpW;Mv1b_8lGn}|o-ZjECovR~gJ!Za1{$lWVoyKn$@4I5y6QFcJYMVfR@ACIWPqHHU zf(nz#yt1%bPTn6U6v$#dD<{Ja8Ru*Cs>GL?@pMq_^oAl5!+iC9owz|}SqpzB6;2Tu zw5hz4(t5AlU1KXbw~|WRSEr2@vX;V&Y(cL^Y5b9`jgr;+J1+vF@LlVs&_XpTaD+5o z*R*{rvs;f>-*Yeyv8JL-?18y6W8E9;tM~T(tdcl+-*dyNxP}mVb3TWN@H1vWeb!|QjyvN?swL|DfMaI`#VG}H{P+?h*^{hleD6HPjF^7I&6 z)|URW)WtdEEfA=BN7E}d`Y-V6p8efIO^L$;?I;?HG{fQ(z$ta*-#g>L2tf(=%T?2V z)eoS!mFqUit9S1Qf)Tf4fczrTD9*3C!LH#?0PX#Ikf`GOdC-}g_;>g79Le_a!o81@ z7>R`jD_@G4Jh-%j{WFyxDL!R(A8qIytSq!~H5{0=DBC#O;OONiWD?HM+g+Y|-R|U0@!(0@x#uAG zaBUXtX)R7aS=U*K9vXy@t#i`ulPZa%A|VvM#prBBQwKt*Ehz<%-{_{ ze~!+RPWvYECjc|h>q>yKZ`&#gxL0=8;VOGfYqhbzWxUb7AXVEslow;5thaOV`U{zXZSnVqX#cauOY&2}X zX)Jj_UeBYR;70qp&}j9F`f(o#jt{g3gI8UA9N!Amq>bh)pXpU+!|AMcd z0CyS)=psyvgDThhcx}r?v#9)P=X;Bljqu8=^?Jo=wOAjf7t+&Esv zrcWewHlL1@&S1j_!66myM%pKLXg>ZiS$x5;<`kV!-{!p)pr)9l#tiwn7xlle}b zHW=B>w`x@%uIp%puFRBR=aAojQTF~ua2z`~u3Ry)6cw-kR&R@wf7IamLDi`ZB{j4_ zPTo*rB6ox{)OIwd`hr8FvEn<}_2ujD1i=uGlR=7W6qrvGyDZI@zi#^>B6@*1cW9oj z0SF7NCUNP)9o+!EnccS5HmP9t?d$;peTq@T-=Q9|CvJMlJX!(0#M)#&r> zK#ecOnj1>y0xxorpGmd4OvXhGa(3F<$)?j}hKRmHZX(ZXTxdA>#zx8dR)T#vs1+6- zBK2cG!2Qp&U7;RJlOd*h@6=thuYY${{IjHgIW#s?{P*=87NQ0qdk!0q?WpMY_6M&20XXRD?v1Ijz zDOBW(sNoNexzQ8P$%BuQbC*6pmCf@o4+K+19EBgsJ7?+NP?-A%KBzrVMa{1cz22d{ z>fxO|t?$^}93;cvwF}Q%Iq1NR`5{d`u1o2hRtLd9}&*&;`((gYThCY5jPdK;GOt|GCk8jcG2nF`bkdY!8<#I=)+K z>W;n|@blp&!!(G=bRASNX>d6{ew;bkcrSL>P0Q*+AZ32B>3T>0P9QX2UFC7*kIazo zZN{&1R4HtTuXo&(VdL%BKkvG&s~Gu9OuDM$a~m~TBo9WC4vYT=V&D1SC3fHR%AI)o zfOB&_;cNMu|C~Q1yVb<25=KYQtI2zu|L{4e{1X&=M%#MOY46ZR5ywAUKg_L!UyHaz zT90&PY}Rzu^(sF{Ex6x)O|A{X>}!#fUAtFF7@w`Fq6=Bjw3GH(!I#d!tfTlgY5{m> z8^Ps0u3;dD$Al82wG52cOt?N!sNYXg^J~lM>DqW(1B}`du7h)4&#P)kr+REaLHU^k z#W?P`_-$`@&nA*qw&XifLeVk0=4@T8d(z2Ga3lP+oGnTT(Z3O>SWIsw@16AmOx>s2 zNHyk8%m-qo+G%wHDFa0^?4h)zI8ENss6tn+0&@O<{mmL5F#&saqSAeds|A?{u~0DV_cU5$O&k{p-CSf)b{37fJYAV%YC)Bn)S zbJlMcZ>@c=%3wX9$j)2No{Na5Ae&2nQApK~FY+eFax2ndDe8inHq&GSRXeJ=+-S;j z)vW!u@YOEF`RWY7QNtlEsv#V}0e|;l|EhlNq|+{#Cyz&%s<)ZtSF>n()F@8Fr=YjP zTdTYp@X8Tn|J3py*K~@imXG-?A49=R0Z4)^t4F5~-)Bd66bI<@rH>w1e&&pYAB1g< zB-hh7$NC9L!=C_ODhjHY&dPn;DLR;%j+{6(n_zcy9wTLK2_;=;R|zfBmDZ&u=*Nndv7EDo@&UVh z3(H1V-0Qz+3euMt)6tr3z1giT8%GuA6)#t^p%NMMhi01uh297A`!!|IB3uX-De;YA zZm&;JU_s`*Y*5&obyZ8O3;GBYk!(+w={TThSvwRW&>P5AcK!z3h-L<1cSD0kIru!7 zKOCvYVQSfC@$vT!-g-71Yy0Vitv%;RF5HY8wpzJ>mkJpya&td2_TL_4d%u)*%4!JVv3`ehIgJ_V?P4E2A(M`oy9VZg+gX}$n_Nt~hniKq4IyF}g z-brTO+?{Mzvn&F$p2dD%;roM*8Rm~-mx%kEi~$~q)`YFnp?+cXn{-uEcsvh@+OXZE zl#js`hK^ZV1W8c3gb!^%aLrcGoYi!}my_2mlY*Vwp)&-MDtiyvbWZ?^fA2KXg~aOW zx7;14A0Em!HlV5oq{EyeFN9u-th_nxUVj3_d#-FC4Fs37v87AHm@PxeE+pvT#b&L| zgK|L7Cx#iCntYB7SYHS;zZ-t^MRmB2cU`rM1CAuRJ(ybF$<;A{N0$d1$RS0$ydgod zJ&-2Ri_>kFS!JUC4JV7A;S=F1*kUy4asN~l0foM6sA}qb0*n%u1u&3c1Ewfr8w}$s zfB*9vrH1%qtX-8ZxE#;#EFND1>0_)#Pv%5Fy1I8=XLiB!X@An5FZp!Z$%DN^U~#n# zHNy-RcDcxU|J3(e;JfZ%_eSKn%kq|k$Lbp7l*7?h%tIhIHEi4+w6FF@)6k@#>a4!% z+YMc^HgwGeh38AgDv~ufduXyV%vn?(BrZbxnyaZ_?p*XOqb-EyIyz zpHQ5!^RRxo2aP!__$|A6k*%4cJ|kvo}S( z5xo7lzB5q@^qnVh{uyuT&!kXydc?Z zm(%FPO#UY0T7A)#wQ|i2atxCRO-|vwcMS3_jPN-5sXhz4t;&{7z>_ zp7&W0P*GZ}z>@;$2;XGB-gti#zX5T1+&q|cY6b7RY#30OMGl80m?*sdD-BZDOY)g0 zJ5ToUpR6(s%3l&%p||uN_zFqatDB^1bz+XmHXZ*w=KWbI`{LW7juGNXm;ybXz;Os-%E2jWSKx6fTx?2&YKR{!89MiW8T4>;8vz`a83h+Y(nx5&AM5UMudBCMeuWY&w;AkvTj(*hHYp;Kv1fMgKG}wh zAx$)s&D-$LdE7kvw!!axeby9T$<@f<4iJA}hwzcXZwi)gF{$x?>Hh6ihlV}@noKJ8 z$u7j6v6xq+F0$?}_^~X0BKU%#!eSKVtC?AFrFm0ZZ-<1;ojJ84LZDZTO#iV8!izg( zNG)L|G>6;}P&ws9We8#IVZ!-2 zcGU0Z+*m;gGG8#e;h8(BT0a4l>I+>ZCl5Vu1Fz1=>%1P@+Zjw&P4z7gyX2cBMu-2@ zO9ZX(o?biwQhyvf`-6j05E~nvSi#pL4fpD(ZC7_&(euBa0O7&6)rjfYrVb-k|IP>X z;aGz}yWnp*h6fz80S{NFx2D0FJBJ(7S8p~XB14vM6^8WyGTr_3@{a;Nw1ySQ6f}2= z9E;ui=RxI4kil17Vc=g_`)HESD%xR3eXCRJdXrH0xcjc|h=M>+I9=0RaImOl#4~3) zD}Ms4Bbqm8e?4a3u4Ftm>>MA?oQWFtb{8(m)K6BMQ0(0b^}ZhZHH!ATp4L}1>HeQB z^jYvk!GSd@FcZnUH;-z5rhS-TGXUxxk`OM#vI-ZC1rI0EVrg5m)z3-YCwPs~Y0;ji%9eIkrsqE96`5*-~8J>KNlTYB?ct zHI?I5X2A6u!;_9h%{P?Dwl2n4e^pS@fiP-OTbFCgJSV-chPA$wywW)lWj>Wu?`-o1 z*TqG)1yTqRZ>cE&qIUio>9VJf3|hgxl8PKDCaU4C^aPmZk;GTkd>~PcMFd441c9*o z_J(C1l0oyT;Uzs;*?S_hRWC6gb@=8v$z`6wS-P}%JaF*PxPt4Z#d{ofqw1o{m00t= z1AucBXZ$u&!420zxb@?+ODoYeSBFo43d4E0p^xC3b)lk-p^lKgV=7?U)Jk}P6T+DZ z;?8+B*4E&%(Woaej%uBaT0H@sxw`YWxzV`2bIuKhG~8BCdKL4)D$SJSJrqFwWak%K ziW9#tkfkf42G3yj$Lcz;Hk~ytV*`ITarHF0G}DfrdUFkkpXQl|ar@(;?FN3QI(+`RLP?ae@skbZq51na zHCwlyOr0>;cYsmlqIx+9oaJTl%`tDxJs) zw-E*M89}!_!6vK?5>E6th@01Ej&k46u9PS+Qe$-o7yZL=8cr??d#awn*u$j7GQz)A zMoBcX#+q(?@L2QeA3fASbE9{CDfRIuq(r3EO7d6n+#k=suAN_c&nwQI(w+dnmAZl} zEE4=_jdaDuAF0od`tOQ}!k zfZ*z{JrXoC5zd^jH)6GuhWgmSt}p{0S?p#y#Y$59LpF0k{3HmGPxV6V(S* z&o-lVS2)GR__=97CuMaHFZC1P)p{pv7DoLa)VJ+bc9;O(Dl3zd{#@iEX#5%+PCXgiZp5|Hry*E?|NEe2`$8QsBoD&JGg z2_-jVk6s}EUIcheWDU$7Ojo~{694GZlXFdVPFe zt-`C-)+fN{SCT|Ki1mU?#1#egbY$J;Fzx4cL=(lch|nO-nqg#!d)~W)G?Qp`u5Fx z;2ce6S(mHj~^4pA()D7s`<-gfj{&6|I`P6`gZ8$IuyN-V1Z8;@0T z&TTH~_EY^6`s)dP>^)DaoW7ktLxlf>67imr&AU%&PRn~^iY2JOZ+2cvM?mU0`wAdY zW>-Sxsj#ER?>Cr+3|=$2{%&>Y^F8@J56%EdoZR(-le`uGg(rYj;G|Faxe)bp#_`Yf zHa|ev+9){{Vaxj`hG2XFkxe`fttfBz{G=i0 zZ>xKHRuOnN1Z<+z^$@$CKdYr+b69QufzfV-S6!di>!$?BU&6e)obCq~-a5DYzCRUbRH0 z>03@L4WpW&$dpjEy-Ig4tvuD)q<=xyjr!y@oH?ER4@qBc1wdF2%F>W)3h(Sr??CpP zo=DhRwo1=8P?KLz#Pn0nuYz+JNl;|-p<9ZQNlOyh*M@3atuyd%-iYqr(&Fn?t|KT2 z>2J3z$4R6}#R@eXB|e{CIjuYf2hO%e{kRh9sLYi#`(8sC=!4Nmkn+-vzq+8Uo?HQL z`?GHLYwf0l5X8yfwX)Gaa(W)7f{K^zD(F5??ptAgSnx<(kL>MuyhTPGY`ONpo1~O2 zTi#2>h@3bC-zhzFg8m_=Lu7mY!CnoNy1}O!Dwewt)#P!q&WuL7E8Jh-thqCD<=Roy z)N1Szfye@SaSk0C`3agaeYw&o^Iq_B$q%kXkLt+a>SPH2@dhyz_s00#UhqzoL$Z~= z4W1LcIvwH4+7L9KK4Jk-ePDl+o7KLHOboVp0=T(|3nE;KJ;go~OGM#oUJJ(+Hq0I0 z;opV2dm&c=gz0cRsk|9%(9QDWDC^O&_sYG`&BtWJ;6^y33bJEJlZ$;x=-P(=>iFQ8LaWB_N;%<-hO3ctvi!80y?h`cW>%8_ZNSmvWUyHa{l&`a@(u#p)lJIg!dUeLXcY)_6n&`wIv4QRCFXiZf9G=m zf$jXd?7p6Dv^ISf%jTZ|4da=?Ho>mUgx^Fp=@-rErIsqryth{NHEvENo4BjU>&{Q% zZ+m&S>P)JGwv>D8Ci9S67rz}#-m4&I^4_`-n+GG+(F1BKB;h?ry>)**17)w@Zs(s@vf|0lpn|-*(ObwrYDb9&(2*;EaKT#cqNZP+Lx(1UPw{NGuIx!EPU4r+Pab_Kvjq3GeW{zT%!GG zqjv!{YfyX+HezsF32?Q8jvNy zkv#qJK;Yu9AzfFuq4Hkpit{x&q*4w>rU>9DtSLsGjeKIln)vz-$F?o8s9#6ey`iol zSN+O`J?c~Mgn!iwYhNX*K9~CwoBod|Sc! z?DeWmq>D4VB!2=3K-aSO(%1ZjHVa!f=v@Qoq9A-KYa0l-)y$6DB|O%sKzJG=H2hZ^ z@m#?C4%YO30`#5>-7GkJXTsuP?#TECFA!vi{kY8o-IAr(ED zwn%=ySMfeyVU4@4ghH!_kl>Rt8rDoUGM8uNm|SDawHI-IO#wGknJ|Mp=trIy)^j%) zza=x{Q5k_Qi!9vQ8}}{&0lwiQ~t<=_+6?gqVsx6CKg}u4HjL^5X?Qz^%xaCxSoCyKX^!SS9d32S% z=~udN-J{*HYVPk~o}I0}n~bNwW8s#4m0`U%4P)bvYq_=>oX*=IZ|dE|bM0r`pU9?Uo#wJ7)jxkK7kgPCL5auw9J88FD*;?-2+NmL6WI~Ki z5m9+msz+6l$l&RXNM}CCu6UttF5DL6U~?xati&b6YmmS)oZ~T7J;iiMv|ZEN+c5&r z0J@b8s|+S<-Q$lvuA8S>UAT2Y;Z;zeVSt+TN$BH6y6PKSAD3~8vkAZ$`HC%R9KHUV z?Tdt)mTZ!H3X}4R=WeP)HvZJ;*RA@NEC8n>w{DNIt4>=^KGWH0DzADD1s41L57Tahd#e}rEDx!b~$O`4wx=FsxhSJlr#+ag3_Fc8MZwMwat3uc56v#gU zDZ{2)+A3ry#?&>eM}0|o9{1Y)BdG&#sBG-tj0dQS&G0$ZPbG%<<#By;_IKL%*_&)` zY_6QWGpg9_(%;6qPuj81uh!+o^`LL+g3o6k z)H)Yg>8w+Iv%R)pb95jR-XvFUdX>uaVwiFV$2zS|T1IlEK`?SSM?N%GkkkVGzfVXr zFa!)^J{7OA{$87A$4~bQ^nHlx18KNxE93O8v!&lo94jg^ff&xEHRh5^^-oyzE}yku zW^|Lk-1Rp11*KDGd$JZ4%caAoUEfizUGNS@tK|kYwtdz6Z@b#rUGB?xyQc(MArjTA z#th^MQ>TM9Yht}!2e3)sAt8Cl7xVJi;ZKxvS&P8(0a;o-2#&_P->U&L^S?EYo&C3?sW7D*o+o81# zmmRLKWhmEfTMViUm667@={J`*)h+dHr&HSPc6U4*gZW#XwY%fe*LU+5aF?y?kkKbT zGs~yR9~$XwZ0xS@eQ`ZY;@erV`qDI!a^Pi4Eu=GG*9$W$m;y~t$#Oa!lJtG5-(A+* zb9<9+bzjoaPO`yz15qIV*Q%| zksi{j**5|WVFMDQ5JMG;#j^MHjo-OnX8SvvQMa+R^|vi`N3IQlr%kyxZo{B_1;Q|s zjZQ^PaemqAPqo;uOt)pWmhInd#jE!aJ6zo`^wj!34^4%UsZ9N~tZlDn=tXLt#bXFo*A-ZRDl?in8u+_ci#OQa@Km5#>Y-eyGxq~Jv)3ZA>57UgnA2X zsWEW`mt5n8Z##U?1=JIQPw>NIP zw6x)sG&Z6Mbq4?k7B%O!?j7y02S^Y{myn(Xs&S<|XeQ0IZxgW6NCFj*af207irQG( zlBEEa$P7es#CBDuMz%a)!PSAnah`H02R79dYhNi0NihR6IQLS;TG`t-31d07KpaOQ zQmt6GW)6^~9D(3R#;!y%?!}-L(ibLU!iyCZuA#KbVp=ohk7Y$yy48&fbco0K_!4WU zH5Mhdj7+J*W;hyb)ae&3dT(x53Bciy{xuk=c(Q=WFtac+9kj~88(_h_LAeehc-1nl z_oubO6zK~P2pHqqDmsQ$LAFF@vO#D#1DL2*ka}#e!$!9npvDq7)6Dg2T{hKp?pkET z1t3?ui|F#!;>E;GO>u$(1}t>_wb$&4_|}uGbprd+yHbyBR0eGPTtFhZb=s#YNVhK& zsZ@M0sh3q_q1Yw0*x5iMO2Ofb*Q1!_PSUd@I zbNy$j^$R=pv$eShp>+rZN$syUlg*Xio>hO`dby2PP|x{mo%2)hfd2q@>iV=w9AnG< z)P2Iv&R(fN850hCTPubQ;rlnr?5F^R@G*FDwYqQO%Y zurlSLqyv=YQCBJy1v4HYoK!cu!d+YpPB`~f^F`$OF{yB?`3y+7O7_;!0Hl)BAY(z- zDY)3HT-Av&2g@HpT<)$`yK~ZQ99U`tC>eLuTIo89DbrbA3XNEmz?mNmD3tX9y6OI+ zn|G8orV!TL0uOi~)y}MQ&&!nRU$uVG>W2-F=jOzaY zu^ZcNU#0K8Krsor1z>X4n!d{IKW=|6f7iz=)c*i)z2DO=>b=wMJ*Xqq+mUkEo;Y~E zYh9?L0C=rH9~lB>x7km?TTX}iYshVC+l2(9DU5kY z7|m4j)L$EAb78vNDjmk+`1GNXRmy_L3{((4bl)`-#|ppg&9&uqbZsyBjuoye>dR3! z$YY0XN845P#97C%{WA41z%;3VT+KHN{h z^y@o-AwZ5%^rm^!d}AG3dVloB7~*RF^!;o-UwEtoS^{wd*8AJ*Jvx@@fjSgp9Ac_@ zwXYap-)^{sKQL+gQ}KyCLvX5FO7@!Hbu)&rS!!zU$s_I}x7}{G{T@ZZ7k2;>Y zUo?$35XOZ|A9r z1a}%OFq<0?w?HZ3Y+E=7vI(g^=dRr`2*fNxkpN-9c2;A*MPR_XH9!~w58Nv;H~M{m z%KCuOoQ!eHjcsi+{k=`U0Sf0VU{BVT9gdzfNkhuuCyzf6s)C#PEi3Agp`-m%I01!g zMv!(JZ&n7AbDlXK7-dnaluy(4?4Tear!+X2Cj&H%O6`(0TL(gts$dz8Q$F#HArTBB;&?og%&iXZ1%3F zLlq`q6^vJmkA)D`#M;^lyv*|^57~uub6HhDns@<;IrIA~8d`unNQt4LgJCBbHLPIY zuy+R4+in%n!)SR5(jbP@$iWr40Nj4JZHC~s>dnCn%DCCOMqyS-wsPV@<_;S2sZLvI zqy%3byd$0!F{;Mj(=(A=##nYmT&c!ux2^#NhA^jx_}0c5W?~~DIFlm}<5N{BJ7jc~ zFa{+EBMf*=5vs~Mun^Ex@a8bbvbsu>9@4SYav0!#bkM5JZ%}kApx{P%VO*=EI9(cW zGar6gQ}PxiHw3IWhg>_&ROvU9Ob|7F+0{U=cH6Dta@de_;}tkypHcvz9Ry;yW0hvX8%%L*K*WPg0l8sa0175&hu=-$LZ4}^ zLo&nu9?z9W#}}bC+y@|P9J@sr+GVhW={OAgsgN@Dy+it#P6vbzbQ7#y!Mp?jaWS1& zG<6n$Bw!?Ej&;-B0R1}#A@VroMj1*}drWz9ikw!A5X*_gV-njsKe=iyfa0081EXgD&M9BXSrv=I1-nwq7RQ>RD~ zRVrw$rjrvjQ7O6v$;+J`DiVlhCP!^@#ae4^$rwbAb$=11qB@y5aH2IdF`T$n40E=f zWXne>oU5L$#I@9w020ULTUtO|3PS=sLNKW6DneZ?t7&MK$Pvb%;#SznOq`_72C6Xq zGVDW{VUnD%%Ip;uG?Xygk{Deum#OF z@A$yb_+!Fx&W04Y7cPJl#*7R`Inu`=DzW}vCOAye1z|&L2T5{C1c3k^7*i4}XpCn> z5sblrMg}o8Y?qSfP(C3nal$?o4HdTm1;Kk(rcvUL;T1J=)cbcsS@jgcw+NUcJdQO} zp?Mkb9B`8pjZi%eqim=!Ajmw&DHT(#6@uD;2n2$0eZQ?Z&z3 z!i%+*@U8-N898S-(N!VKeG4emq>+YLaWh(0!)@HKK@h4*)Wtv(-_EO3M6wiVG7d+u zc2!t47S#hXtayx`-ppz+#xlV04Fr%$!xKvxZ&)&OK43V-TumnZrqa=gVthPEHP5KN zYAmtVWhH>bW?*rO=M*o^cSdCH5nUjs7M}sYkDXjWs#J|95P0WR6H$K9Yg##RjH`9a zN=>^=s5EfkYnR1xfmxRHum(@d=}r({+gooKBx5`)V-L_cIUi^=g6=a}VC2QN!<-t{ zvm09=VTy*vr%7natjc5<#svnMZ$qgdO*)naV<2G}NW<${dLqSELdeLG&Wa4TdoaMq z^HoZUX=zb7fsr}Yj00$Z#z~l|rU9)csayf$QlqS)DiE2fg2d_;E029ns-oTJ5E}!Ktti9R z;fw}6YowyYi?e|p^{p5e(xyj!PMk>GDZ+c}PMhL2Bj;2SbjX^_mobA0}l zNi5$e-Xp0<#DE4=97;Oe8o+^=2MS{#dWhtKA;3D13d|v@;3d?EI7o;e5Nm4;Dmufg z10X!(MXWSL2m*ir&4i4&lT{-zr&6Gj7~;x&MCZnwO{H#6tKnc9(<4zN7&FLJ(*VnQ z-J}{hS1QG+3IiEA>Yf!`(b8DkCVa<`5@c0T0=FQ7qev$a*)fGo>9Flm zJkYt7Cxvw1M9_h7yWk-I08btt3X4@CcM-G(AQCYZBrBLX7S3derH3~c!cHR*-C3Az zD;-aa<_|GUgGSboL;-=$oNZOy?FbsJh~z=~RCNrgwgCag1PplN+eB4PmlE1Y=6F?9 z={{r zWe`L%m_4*gPVke7fNJ$P#$5_Dw4PO%tBB1GMj#Q}Q(@59xYpZ4NgU{&hWf0R3PBue zw61m!QpRH%LKe#E&)_IJRn$OZjYWo3qHu{6^45**@fZlowP{PztO$xQ>Y-0f#GK|T zFQT<((~<=INUD@revo`ql~P>2l2rJZ5IaX2^T%3oKn|@r*Gx{OZKwtS6T=Zl#OW_+ zgdjqU!J3;DIwU|kg9*rS#->9~20+b-&5XrTP|A&SLwEt~&*MQd-GGasMjTkfRm2y% zW=o1x5L8J1U!@gLYQfY7oN>S!AVup#JT(IXWJn#AtSQ#SY8kc+tOpP6#@W1pGa$R>8BuJwQ}skoofWC8*M%invmg%6P*~jRTwpkxG@&45(pzKdpXo< z*FuNJL2=|c;g`oMsZ(I=%iD+^9}Y zb)*Re(d3L9yAScJ(T5Q#OGL+qF~YZA%@r)Y!2bZ4K@p@3K>F7xwUkw4I!rO+g>+2! zCvKMw;>BQo0612|)mdPq5J>>wBCX7{w)%9o8ThI!R0>@-t^sfiaKwrfz=qw!i!hl2 zvm};z2Ldq!_EDn}jRR3RXZ?*au-kVvn8+Hf775yL4pcIo1UmL7GR3aiYVf3t@&i)kM^)<~h;;8^x!U z3WB(rmmU-l+F_R(!kp568Pc5&k;CI#4v}`$XApVR*r`~UEH4V2I>B+|gG)KpU24rg zJpRF4rCo!x#fB4{V^t`pV!5g90DbjZl&m%e0OecIk$=-EE9M=7FsPwQ23=-P%A%?WZY~k6QyAc25!+SBu(SOF#zf3R}n-mIMStjBuF!e{{R}yVye1vjB+@M&*@bnY8|bpI)|9d2+KdR zj*KZ$90mb+K@lVjY9uAtzS{IQYDkPpgXOKQi@Hf^J{27PaTU@;&@*VbQXytnEWgCo zz-_>8vjsXp&M}ejtysHi!J(VPGB~eyIj0Ri;S4~CCyy$@DpaOm{vH(2Rs0m(5rKjJ zo^{TwTW1>15s=b(_EmF5hUy~-&k}H|Lp7vgB1|8JQN$AAfeou1M+yKgn`Oc>;lP}6 z`BYk=+_vv*s$+3LJ@HtA+17NpkvWcihOnkELc3L=n(K0TF$ATuX~ z{0(L>T_YIF5l9*~HJDGN#PFf94dNaWC$_1u2!J%?YEBK9hM&Wcq+kR|gDP@0wXjza zSYz<5OfEv021QD-3;|&n0BbXyw5_8~pQ(!Dj+!8>OtxQzYjYD;9eau^Uhsgz;N+FE2rLqCDW zn$R|P7YS``sB_^bEGtUZ4&v%kbeu*EGoPOdz`efVoy?GUFcLKIgEgB36=z5VXT(^X zXW}_gVU(L`Y%?%jO*rz5rVR&0cGu;GPXNHMQ3t!_PJ^sGY1DJ@w`6npRZ1A@&8egg zJ|0|na-zX1ZL;czO!*A|0M+oOQ%+kcs1fDKfDt@?f~sP4EOjZkC1WqcA2G_cjEfib zOsFzolYleZS{f!)3|Ih1D8~%zQ7W$D-Men22@XIiFqX>?zPVpVN$R_1>Zmq}@h(F+ zn!ai}hK5qG1_vn;OmnM9R4EaLkkcL9Fg2Qn^C3X54I>gh+T9o%LfQgL6B+T2+^QnV zwuLT|ggOxqIh=5ch-&?^P6Qd}UAeAx9$wYV592jd1Ow|9LNEinxK?AXD-sw1t0j@g z_*S)$71?kak7g7>Sh|)c%6|?AzlAlltJWN`2-AismIk@lxl2bDBG@FHhN&dct%tqq zt0azCQ#&6MMdWdS#AjVJ7^DT5iKG_bvDAbJ;CpDXPz|czi1<+ECZpJd;NYPLSjV_> zsn%Gu(qXZRxSJCgkTN+_@nI_IAn`dqssKTvvZd$rLF*q{}u&J>} zF(q|*fX*`&Q7N|SL~89A(m`=<2P7ODI-0|_%nY)eay3v`aUi7RG6eIg)ZkJG(WoB7 zMv|`DDrN)&1P*o2sZ}dB>{MY@!&tD6tfo#Ug>=+nSrCcL)&N*mk|%^36p)J8sfgiO zgcrhRI!2ULmAfd?JAsG>JL@rJ;A#3%t%*WO(taJ4m`qByW>ixOxt^eAr%EJER);b! zHor0O5LjbeT^B9f4T;N{tBL6AR}?7|EyAywj2JqEm4)a1jZ+fntU*}TduBd$%caB> zCJy|i{0AhQOWpk^L+Z%>!Z6mN?Cjn2$ zUQM;SM{**6n}#D3BCd3t3njI1@gVXhG2<1KXgP!8Q946m#!S+XU$be_7Y!K!pKz(L z!1`-;(y5&R{X_Yh{qB8@eC;;R1j5}&= zR1#a#SwzGYAe!#sOW>d#Jn}WMSAa$W=tsy#9X9e@f^A zEuCfOIMOE}l>p0z7A`I)lwb{NVJUoD5*&e!9~>|ge2tpBg~cpS<*I6*Vgi_4(M2==7 zmQ{wb`sx7Tpb;SbwKf?^-Jt*#iIbKe3XYe`EL<=qhAqoqb$Hp+i*l@f|1v^3x_?W)0{odnJxQDK!R0P`7N zRB0X4LEktof^9X z1Y=BOUAW)~6NMVgwRLz1HMEac{io?wiB6%Wvn1RR2C;;e94b0g6|gZT0PUxmIvvPm zirooGD}+>H^q4aT4g$8bPk(N#B@Uc?M*|{@45PPV5*fi90TJ6(C!o?CU$F8NHL`IF zJbO)Z(-s!)rV7LciBNdPCb~+S5^S*~sR}q4tz$|O8q*9gI2IyJO^OZ2AZjwi;}OG| zsblTmEU@Hdh>jmRtz~wyg^mSIan3txX$8S`Zpdv`&JoMLv^8T>I)yM;#|$U7t5TO9 z4>XlHh2`Bt0BT`38%m~2#waoodeacc)FiKqPYN|yv$ZbhtZ+DHG0JMCML0#aBw(i* z;o3)iP$iPX2?}*gj&eK2O*&P?wwHrC%M*-bXAFC4Y*B{88;Wr7nNqpnd+CuTXt+r# zV21G#%B$3fTO~A>gPej)nWZ(B$pnH7#3=et&bBd5cNSbJNijOI%;Coxn+}h2w-=jk z%W;s~eNwTJ8cMYAHG%3D+W|0FAbeO%RY5}5JY|LgbpQbQ*7%(`T4pk3a3(T13S&^& zO(oQ}EG7))MU4xv6*mPY0|N`paH2I?Wx{llIn|{qj>;#FbA|?%);^38#~%EtuxU4} zDN^W|4kI()T<A-q)0W=peIn32MB>D38Ip1dWz&Z zlbAumqg1sTvjl%U@~)bcBSRZ;KNQdS}FBNS^wO4yEll8kL}M!m31` zw*#k(<5wzh3htL1mkKJOZtAyYU`+ffHCVNVokJSy9O-u@gor1$iwr?h6FQtxYTh`@ zm++`mF)n@_xdT`7PBJ_dn-DR>jb;tS{#+_+0tOnf10raK!>zYE=rM({z+pvg0Z>T( zU~;L$tuvIF`)I7oM^i&Aft4C?SI8J?COFK|S}HAp`jp%~!dXEIgUjOQhIOM=(q~AV zJ1e3=aY;IcDU=z`j53vUzL=j6HRJKFbx^xy+2m?b$*}s=%BvO{(RDIpk1044-B*dy zkX%*t;uz#{sl{lL^j?M-L;;RtjWIOahY&&W9_nyt0yKpSt4QJV&V!{ri-ZuT7|h`n zHZD^3_im-aU8W&i^X{TGjf&p1>Hx-YgPnDV16#HiTIy3iY){g)8Wj>sF(xryedeIb zJ2z4aKw=33bNJ0%qQSM}8bFD}ebm|{0y#3vCrAXx-BYAtrsf$yCUW>wI%M7+ssO-F zN;^1DDsA*=t76T_&>S-?hQRUrtCUg8Cfcc$Ad#mLj{}Lys!@hnxZn)&F&t{;PBQh! zw|NT^B*zHHx{9bFxJgE3fg~Bvv{s!98F|%#Wd(?j2sqJ9ffv9kxdfB-%8eE*+q?LN z0DxF>n&~=E#LH|N7)p#x9K}@VU`5M?0KjKG^j5`jDR3zy+ag9&F;Q3Uv?mBNIO^r{ zuAKWOzy|ds5OnaF6_^eHwjMEDJ!THV;ygA2B$NAR0y?$PWNu zGj7V-(B&m@3otM>aWs_{t(Gb@j7ek0XYZ+`Z=r?+XMy-oU@hD@D=-VlW#2^UtT}Yt zw!;8V0m`f0Iu)`PEICC~<&r>b&U`zltX2KEU>hSi5!q3BRHI9(qf3d3XQNrCX<5`b z#dMS*?dtNH)-yaoOyU&fKw^?k9#fq#Fp2RD#uckV?poG>$<#8bv3kol85p7d>Y329 zP7XO$?zEVdW%7}QGKy8pYXq-4j-sFdEr;^s+glq>K+zF2;4a{GGnEDo+Xv2;pehT) zWx}PkIu8n{DTtUs`PE`eDHj2p>TtAIJg3e5xz{@AT6xpF<(&+1%=z*e_f}w!DbAS3 z+sJou`>K;t-cd^tZ^}L%TIbTBANq^m`17b)>-|BOmyg|DBbaSw-RCUpDkA6N{{T>; z3UU6A48A-vt4KE4wp=sIDuR*tviNt^M38@@{{UCQrmh^H{IT3}@_*A>HD$l+pFfo4 zoRX`%DHAc^QN(H{VSj9}uv<5en{4>tFCXs*eecpeCbLo7pZT|qJ{Bz5V zUn%J?{Uhb$mR|~_6L0zro_uP0_Eb`D=v&LoKHe40Yt}rRGCBSAQJ6oXz5f8(XrXj} zO!o}4_*YI*NPqq+=jA`u^L%S`VOG3@%jDzTP^Mes-ZHHi-M95$&6mQo_Y~pgIb~f? zP0z#kRMIPd(>dmI%i&CF7R-J1&!x{}N0jHCUnytKs(?TBhJV;l!mI=<7JeEjC2}7c zByquDuQ_b0BNGJ3H?U!QgDz* z(4{M=8}uNUV8(4XXD{1{iHX~9Z$rGBmqtf#-@YAy2%u2-eGtfJV%-yOY$}!S0m+6y zunq3+kh>5*|Gkiq5T9C+3Q6tZ^EcMkdQy@-yh~QTf8V0=pLp|IgMz+=hO&Bl??NC< zCg0N15}VBbMxn5(J@C@fdu|DLVKB9a4@0mYC=`lHOjb1? z;?0L(`TS{q50;+_5qQeyQ&aiVRZuAZH5M{SCNqj3RCz-fBVDOjoENsc3d`?^jI5ge zkfQ-@(yhjF9QTeIZirK8Jp6Qll8ZD=h0`a^L!B$kZjwZfN ztis~5va;Ajq6e0LJ()?B66f>zlchQ)5Xk-_2OBG|_%A;mW+x5x9O*GQ^GI?BrDC$# zB{_9OJm2Fl|Izh4YuU_}+T-yk#pE~FLPpo0`@Cov>!)-k3}*%weTAOtJlD9jzTa-Aj8c>#sJ{S3T)L(Fw*M_yG-UME*HMdEnM|4G&aH|xuVqaq)BcVVB=SW88D`c5(9U%vKQKY&z@%t zSvLAdoIDPGQ&VThsFF?(l=)MJ+#oLIFS@ zEmt1?rMoT>t->s?v3fWr7P+kjpqmxg1jItEPUVt@`iT}Cb!CKP%gagAuW#_>I2Xeu zPze#i%eJgN0dttJUGWnK$K|`!Q7sm2>$mH=Nn5>yn4+D2r{?*QpW_A83srbGemIg;RljZP1l)EoCc&U)ptEm7u zSp^hXPMifzJ~7UBYzXZ8bd-3}Wq(cV2qC`^m0vQ)Us zBF?_=9=j=;dag0hbrHw(#XI+%tT_lGL>==YFXqVO!Ng#x@J8oGM*^=O?W$J>|G}Z(%>0;oweNO`aDxRP3{yJj&jj z9^JBxxy>8yW5rcIb`O674uwm2!)57IT`W2jq>$}b=mP@dCm0sl@?5&K`=+8sbOJIh zH6o{QLjECZG#H^`i(a#vZ7R1iH$&;@v@1S5hoUBy^uLu|8@2J-1MbLM(|dRU#d@z{ zF3hcc<#b9^;vO!NDiUXzIi@g}&|67+m95{hsJ?WuJzpeU>*1AW`gzi#+e zxDUIUwXtFRxjF*KE{X(or#rqXwRiu>3$2{f^8~g|n=h9wLQqb0=Hun={V4{q$uCt* z)-L8Ot*wzZpix?=y7XL`jt#M8-C2vPRXq493%5ZjMoPOfMNSAIa3CpXWHVaHcy6w% z=`Qc>yv4!k@iP^!r8iz{52m+=*o$oj@CqR)EgJO~8aY=j9WwuG?Bc7z9}HtFjK1wB zMuW4NkCp+bJZ7)odToTmoMq3LSG2zbx?wIubSkzrNb=tjw2* zPErXHMx{>>{&i_S`U&QUe(FXo-AT04t8q*E95l-PP<)PZkx88E$)NsY^#?O;H7!khUk+rY5GyiZ@! zrPqgRn+oV9?H`s~%3v!*&lj^AH0iqn$>~5s4v}RRz-Zbh0=!owou>Uk#qW7FN9voI zg$a%tNF8Amp6;n2{LS83p|K#3rxR!z)^mrb>6qYpr$m&vOpLJ+%aM3%_yBEHbsv^! zL?m6; zsEbfqPz?AK$#AhII#nuq3iKGK%Xr?rWq=lH(cPggUOr0DEeftznz(G^HkbGr;M=cK z$bD0&7Q3=ow9G zg}AXF@XX`03#O@vUTnJug`7&%mFC7S@dl>76g1UHpGdlMb-lKjX912|Mum5%%p*5T z3?1{DQl8Amm4pi& zqFCsq7o3He_cc%5O|$yEehlp;yLq&{@EOt!Thz+dOZ+|6UDSyILpSI5HJHeP`94>4 zgzN~9m4OsSilnx#LZ6MO?vPMK7CLFmK`#lsu2Y(UPCcwdu{@)OuOXrLDk&i>q6;L# zwsWWO{KkO<4Q`k+%K(goiwB*^L(gr_t7@{3fQOazitw5FtFe2PRNzTu_A=m-cs6)9 zcl7>c@bxo}Itm*fOJI5Kn}OOnc6@khyhkM}7ct&^7|)t1ad!tx)iBPQ?6&7;Nj{ws zd$*>p9>cdUy(@reb*9s#KHpnu*Q&1OE?US=eBar)s7I5=p<_p(4g_FE8EnqFxIxS| zl`n0!Hn!@#3lOs(-BY9EpQB%<*=NK~yxO%8dfB2fDr?npX0!8cvzyAeT$pcNw zdL^?3ysOfTo4f4HFWjq;&CG1cEpIer)NIwnD8X4k@Z`lOFC`>^0{{wfzVtSlOM`c; z@1jYUpv}Y(=W)i(&1;sO+JF)U87*@VrzeSWfBg#s$N9MWJVf}Hd^T<9C*3dm+wbiQ zGugD)_UGSyeo~sE_G)W|J%_LU*U`OP%ZpUWJQ!e)guAvVUdKmg;z=h6Je7?WD}(DN z&d4S#xZUq)9Ty?&H8is+p$$)Kt3>s^tKsG`FI-d#Mos4*;Mt$}8qgZ7h%#S&8c-Xr zqQvMaHD3?C_PKW9XV!-RdM{e9M!Da~eEnoyLr<%=y1hrXGwn8S7KL27X=qaGa}eA{ zvS5gYDQKSO>swF!nog0)KB{L|+5pSmW6EYEl))52oM^0(bvlit>+-|we!IntBNxek2u>BPB)q30G-N#><7?A0n6tY)iTxZp0^AgXA7MFtL zx2f8;)zKE*Ms#4$;=^}wC-1q`Eq#ZQ9=4B34LsER^c&$I!TB8l-9VCOBM%(P=W!E)213% zdZV)XQ(~YBdGIak*Sz_oz|P;f>G}EXYz$J7tNe3D8R1MJQ#wy#c<-J7Qm>2h(1IW7 z4EEW)tPj#Bog6xG7^F1mClM37aqRrVK+0C`?un$INbnQbza0Ek1{A=_oe1_v5ggyXpz)_#cyWE6`9idp_Ok3hDeK?-Mj*N z!=$hN`i+(LC=D)leRz}A{dSUCp{Ih{@b48*mIrjy%J0epm9h0pL|JQ#dG~P>S~|e~ zmja$ULQ79f7+D|AzIArZPSG^%?59|qaexTh>%B9Svk?;pMYw_*!9K|_TFSp4-u8@! z$FNO9Go0QDZlsDd82fgw?4S#E%aF8@*>0hB;$1>f&d$7aUGTVF+cMJfW(2=@YYHKI zH*mIb!WAz+-)~^g`1F_=wPYj}H+oSe`hnDi56Bz3@G>vmhL;JST*2WUYjL2J6O-?f z_qTFdT;@i|r=JDcdIdbI0@&VtkP^u9_Nq_UAla zE3r?PV$K)~DO@?Zx3yE08H04(x!&{q_+x*_p?mjDf zqf{i_H6Xj#1rzfPE`wW>xPr33(xs}=eoDdB-27ugu+~lWQWiC1;jC{~Z&ruXuTZyR z_@!?{c-%6cVQXJ_)f{yTo`lLo4W@$^Xz4JcdfLm|L_x4y5C1j z#~|Nn>%19;8)UE~)Cb?R={6pDoF>PHrsrw@N<1fgO#@x+XU$rTv@{SNbFDxf)fHb(HEa zE-_9sC-_Ju$lA+yv`Xc#hFs>L>6J{(`oVzGVq|UTH<5a~$W2euby8sG_f!5}uc9BE zps0fNE5ag4yK2q+zM}~Bi4QbaUDfRmadpiSjIRq#lhS?NWl`oSgM?cKRT&*pU&Qla zIg7I{BH;I2X}ey>U+u~Y4UcvUv|tRflQ3w0MY~Ty3mUZ@b!6B1>^xYIu2~P=lY|rP^269DUY?@ZxaS(}sqo z=GL>fHrS`P>oR_3(1y+`ap;nrzUH)28}lz^(w7d!958w$D-9S4GQZ@H?}ryi93@7o+q~3VKJC8DsjHM*}m2e84s`&31{X6(Yt60!rP%h>2rP z^^Z>;DkhHJw*zCFpIp1vG)QP+FE~2iYf`fC>>0DRg^MTTE#~GSR)M=}Cv6pTCj7eI zx!_t0+K&rRzFY&9BA|Gf$A--`0bNsbJe~PR)dz2`4;Q5C^5&1}E1i3>F^s%wiOJ8H z^C`MMJmX;kcK?en;VfWW>-FJrOb=;&9}N!wgQ?6V;+8z%$>L(U!<%nO>+1h$cM#M$ zQqAnl|Cpfm6Xf2n?_T2hCd1a*YN}D$f;<7Yn~)c9#B%jLI-np`EQegnvy}fsD4gs9 z;4lFxCSE6&1-nd~7r>%)D*9zcbnCu`H^N}hQO+ukCBSc|E#Nm3SEAtFzp>=^<75g@5AG!XEZkcAlX5*%RzQWapEPF6My$CRZdq zaaNzAjBCw@C0!np8jB4Xf1j38l&}N-a*feEAohY$ZzxwTDEaLaGVz#zvPn93e<_M6> z9Zp7f0&0c&f4Ki(&AD8kdBM04dRPo*=#NxOUx>yGEeNDJx&YNepLCHHdEJspv-@c^ zN(xIv&q`bU>&wknWTzG%~IB0X+ha?SXuT~%h=L0lT3FcR9LB&!hhBbWJc|4XtLalBp8Wbw$8 zl6rvXR8Y;~Fdy~&vtfL4E(j#Y4F$&8R^5wj%0u&y#|W*h!QHkfS6i)8+bKS#&y!P| za(U0S8UBu2VT3g$U^Cs=Ot~x@2)wvPQAM>MQKR(DV`wM9P3p6Fj>Xk_Q)@!*{XC|y z;1a;;pJihe_+g|th}M|rPVD8*55AXhV~oKG*H@Y-_ShL?(`l4smpx7DOK!Zp z)x&xqB$;8laLphmcsVG2b=tk+X>0L+ukrsZ_WwutU;ESji7#>pf?U24ewCi2D!5aI NIM}+{G+1B6{ukCN%~JpX literal 0 HcmV?d00001 From 8f5ccd40d77154c47bc6af15a757ccb2c4d4e168 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 27 Jul 2023 12:49:38 +0300 Subject: [PATCH 030/175] Update LED pin PWM.md --- docs/LED pin PWM.md | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index 4d113ca174..0e5f6f52bb 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -83,11 +83,15 @@ Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device sho ```ledpinpwm``` - disable PWM generation ( disable to allow ws2812 LEDs updates in shared modes ) -# Example of driving single color LED +# Example of driving LED -*TODO* +It is possible to drive single color LED with brightness control. Current consumption should not be greater then 1-2ma, thus LED can be used for indication only. + +![alt text](/docs/assets/images/ledpinpwmled.png "led pin pwm led") # Example of driving powerfull white LED -*TODO* +To drive power LED with brightness control, Mosfet should be used: + +![alt text](/docs/assets/images/ledpinpwmpowerled.png "led pin pwm power_led") From fd096f18ec47029b60b6ca4e6bfe57e0224018c7 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 27 Jul 2023 11:55:30 +0200 Subject: [PATCH 031/175] updated documentation --- docs/assets/images/ledpinpwmled.png | Bin 2109 -> 2142 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/docs/assets/images/ledpinpwmled.png b/docs/assets/images/ledpinpwmled.png index 94fbdbe61385fc5bd9ef45fc04c072ebc327e052..3286e51ae30f5b35604ff705b5fbb8a8e3993346 100644 GIT binary patch literal 2142 zcmZWqdpOj27yr5Be%Vk;h-g^FSW{9asaztV!AvOSmX(A?{1k6v%*bVJE+JuLGb0)7 zFr#QNZ(}ahDU5L$5~y$0OpxB27GEL!%;5k)aVO z39lk$3^|;ym%poFxC-Oar7}V|fg-&S1~qp>Su#GpH2x=_S|qX;0N8k3$(Ak4%gb!e z&;uAuDwSffSOCDuvKVMIolY;%)1%1Cm+sot)zyUx$b!LOqhxX?7MqusH$FbDm9B+G zqa7R^1Ofp=#sMI*5P|@}!~_yS5P<_V!eISaEDi@jLIwelnIQ-gp@4igktpHu*s==+ zGAT6y0w7!u?hTPxtEUIxArwUf1TY|uj0FLBHaP%C4gd%MgaRN6g~G1_H>ke)4#-0;?ZB zgan%f=d;F8<(8J!c6M=;OCpHvTi_d- z?i7_7wZ6DWNs0t^_Z}f)J+FFVoeT;1{L0EoU5^K>sHmW08W02px{g)?fKsA|%W;2j zVtzUsqw5YR#XmlBLMNtN53ldKH@cg8IVWvpY(KlisNN#1F8 z1JUw6Pbah*cd*`GTQQd0R7YAf1*Y%90qwU4zNsq9@!`USlq4PSNKznQ4C`3emn5z< zN}XqnD!%0SuP{<{mYluf(`(a{r3c0i?&ET2J^0a>;2+K^khUA&RwThl45~8HYZ!N@ zB7}+Ey#ZTJ6IK!Snt}>Mxhj|6^L(b%hFnmR)G}kYxjdhb9Z7q@M_aZYQGF0%ski7| zMGGmb9bWz<&U_X|HP>Fe$vac^c;rsYyusUwnWYs@?zXz{TN#A zWvX2+GY)SD#l$^-C1VU<-{r>zYVS{Zb8|3@r-el2!OUBeuSd)U? zI+^<9_o*PY5v|UhRX@aSDQtKgGRNMB4m_jXoBKM(9y#G=G*S{v)yuMYfZP>F_f32Q ze_gxR7`h*iToD{gyJ*?QTU-96Xwgg3B#}F7!~7$P7kd!y-TYzj4nM_{r0&xm1X8`- z`3qmxHcCB1Iyxye2*oAdPd8_qnwBh65;n{ynRzP6Sypgt11Up5Yeg8w)yA(``%gMr z|O*$DN@A6fw#a8ldW zO#RUJ=fOuqk4x`@(+xXsCv+RQ_h+1}N^Uv6EMTTu*G#yL9}H$39TErD7)caK7xye! z`o8?7Pt2+B3o=+s*0R2KYn?sxTiHg_X`8uPLX)JmwjS#FqEJmd6Yj`?{_|P_1Yb6Ggs%WQ2E`KRh zMq;W8mJSU5`NUd6b$Z0>8c`A$&2LMO`n>abx?gU7wVK4GYAceFpAj}5iZs|N`g|3d zo~XB~Hy0uptkwPI@8{!ej+xeQoKmExW9#LaS?6zbwx_z>Tl%5A*y0HZ>r;`4Hq16K zynTxvVV&8&T2UTT(|ZN?qqwhy_F1R3kUDo58>k;*R6b-8yOSgy9jOLC9n$eu3+a91 zxF>9k>OV<6_o^szs9BMOjNeXfEKL1Zzu0!H_35Ilb~yJ*gS%bgyR(SVTQd(Q+~_GK zA>_&k6!YWZ^_~RbtH}?5kJxs;*7pyPZq!AmduT|#}qbQ=&<#DhC06IFmNPW3DbKq?u0b?eee%O1I@5(nS@MrPxIQ?vlN0C=&fh#;zT_O7Ur~-*S zWv_{hWo9aU8@V^;$ONvo5;Jzs?byX>EhfyY}$KQ<3Zp3#I)@aT`n(CM%0pnS&usqS+~VhIMqVMtIrF zI>p})f(eg|*qs%j0|(Zi7gO86b@{u$|Mj5Cw#QqSJyfQNc9PVqgI5}HUzp++ag1D8 z9)K;bsi`S3{W<^uR)?p8VfCV7Wdm3ay#*c>2&Uw6g#s1|;kN?82Zcfe!$JzBWC#Xm zu!sg@SSoXK7#=Ethd2OGsA9n-SQu`B)o;fD*;7+frKP1R76yh@O7-n((-5rqpa3od zbO45$Aq)!^DuocF_JTeD0G*{K&sM6*TId*>nyM26KpZ?C1Hg0uf?<(}26%aSshOBe zxQEH)pFGJYk<4>U>t)=B?5h|Wole6XPDdZc!KP?aW)G8&g_KGq9&!~8!6H~CYJp2w z@EsbQppT2RYkd*e;{HkewKTJDpb_j!Kb_YgRZaJ z-DY89>(!vxXm#Q9$Eg|qByZSeM~vmpU7DKg3kD$GyHOYQ73j&n0}b4+euTc$OYz6g z5}_@A>^dWJe1r6%T=29JaY?ek3%R9*OW`JuY?sA2l`ZF94)v02K-{60$nD$-E3}MrU~KtI2NCj{GM@tR}=o(qxF55~Xt2ld*Z4$fUJ0a;7EBdFkc& z5!~c^(69JpXsm^c^G8q|jLY-VGYw~Z^Aak4t>R#jU89{_t}s&A z^l`$ee(L#&RQKpU%BS^T+Pgd!A#wlQ;x4YU75F!2JTM^%Y=(ai;Zite4AQxn$ev}m&ZLML2dZ6Y-K!-fbXOZ)7DmFCkEahDSx$zw2lVL$eptF@ z#a=!M?eB|GXuLz`_a!z^)*D>D(xk_aIcPNRk-o{v`xlbK9=sM()`+^2rqA7d`?DFi zb9xMk&&o0VPe+2^%-_58zmSw&G|;wGx>qCLH1J)Ay=+)=JDBub=HWl>5|-~;AMhUQ zZc|d@Zz$VR{w9`LLQH4fTT*ZuCEMi$63itbzh6Opgdq)B4L+IAMPHtB>- z4IvMd2B#A33&DmYr1;j+n(jFzJi*UxOvRBaM^=LM(V$eujb$g}cJjc9%IBC_$wYe!is)d~t@Fmr6^HXUJ||Z7Yg%=K(#q9*H@q0feIhDcaC3X%ez{|_#x&G z$yv)usP+a8o_O3PS(?^S9?|ClXzG}~tmERNXMxNx@BX@lFhv~u-72@I{1}G-zV&+2 zXcOVl+X4a2{dVvOHZfrTGElvf_#{mA_PjVst6q^!voJYuth*oY{|<8>TW zc7>3x^9SzP8V%HKt-bn%ugkTc4mx9h;gPt2vg=o!{d2sOrZy*8P(a4*apus_kTKg= zLUnX>?8STEppD0k#8z`RpsRJyRp!iWDhbq031Av={Zp2vWI+Yv^}zIfeocH z%zB@F>Z#R0c}hunqgzWBylleGg2RO&8n}Jo(w<7JP2cOAocZc&j2HR3sHR2{Bg&TA zmL~5axM^@_&Eg*z8!xHEbcSi)S&-~Ple7>b268Yp<&ry=A*AUlQo~=wy%>?OS!Vr9 z`is9o(0H)3cqX2m%5q6awP^8MxQ=`JDPd`6O1(DbsMT@(R>ae>$lm_V$J`c)>@7Oq ta;g12sTt7s?5_T%_gcucxkSw$0PcM0mXO04r`2B~;O`sc^Vkbd`!}FY9-06E From 227398fa7d12bbf1639170bc74cd0136834f2f3d Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 27 Jul 2023 13:02:29 +0300 Subject: [PATCH 032/175] Update OSD Joystick.md --- docs/OSD Joystick.md | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md index 794aac26d4..54c6b4430f 100644 --- a/docs/OSD Joystick.md +++ b/docs/OSD Joystick.md @@ -2,11 +2,11 @@ LED pin can be used to emulate 5key OSD joystick for OSD camera pin, while still driving ws2812 LEDs (shared functionality). -Note that for cameras which support RuncamDevice protocol, there is alternative functionality using serial communication: Runcam device.md +Note that for cameras which support RuncamDevice protocol, there is alternative functionality using serial communication: [Runcam device](Runcam%20device.md) # OSD Joystick schematics -* TODO * +![alt text](/docs/assets/images/osd_joystick_keys.png "osd jystick keys") Camera internal resistance seems to be 47kOhm or 9kOhm depending on camera model. @@ -25,15 +25,14 @@ set osd_joystick_enabled = on We use LED pin PWM functionality with RC filter to generate voltage: -*schematics TODO - shows FC LED pin, ws2812 strip, RC filter, camera OSD pin* - -470Ohm, 10uF +![alt text](/docs/assets/images/ledpinpwmfilter.png "led pin pwm filter") # Example PCB layout (SMD components) -RC Filter can be soldered on small piece of PCB: +RC Filter can be soldered on a small piece of PCB: +![alt text](/docs/assets/images/osd_joystick.jpg "osd joystick") # Configutring keys voltages @@ -64,4 +63,4 @@ LEFT CENTER Emulation can be enabled in unarmed state only. -When you press key combination, correct voltage should be generated on OSD pin. +See [Controls](Controls.md) From 68a603000d561b54c0bb9a00dd70292d32819b8c Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 27 Jul 2023 13:08:15 +0300 Subject: [PATCH 033/175] Update OSD Joystick.md --- docs/OSD Joystick.md | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md index 54c6b4430f..12e0c618f8 100644 --- a/docs/OSD Joystick.md +++ b/docs/OSD Joystick.md @@ -2,8 +2,12 @@ LED pin can be used to emulate 5key OSD joystick for OSD camera pin, while still driving ws2812 LEDs (shared functionality). +See [LED pin PWM](LED%20pin%20PWM.md) for more details. + Note that for cameras which support RuncamDevice protocol, there is alternative functionality using serial communication: [Runcam device](Runcam%20device.md) +Alao special adapters exist to convert RuncamDevice protocol to OSD Joystick: [Runcam control adapter](https://www.runcam.com/download/runcam_control_adapter_manual.pdf) + # OSD Joystick schematics ![alt text](/docs/assets/images/osd_joystick_keys.png "osd jystick keys") @@ -18,8 +22,9 @@ To simulate 5key joystick, it is sufficient to generate correct voltage on camer # Enabling OSD Joystick emulation -set led_pin_pwm_mode = shared_high -set osd_joystick_enabled = on +```set led_pin_pwm_mode=shared_high``` + +```set osd_joystick_enabled=on``` # Connection diagram @@ -34,7 +39,7 @@ RC Filter can be soldered on a small piece of PCB: ![alt text](/docs/assets/images/osd_joystick.jpg "osd joystick") -# Configutring keys voltages +# Configuring keys voltages If default voltages does not work with your camera model, then you have to measure voltages and find out corresponding PWM duty ratios. From 04c03bf76d59c87f66e785abda87d63c09eeb8f2 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 27 Jul 2023 13:14:37 +0300 Subject: [PATCH 034/175] Update LED pin PWM.md --- docs/LED pin PWM.md | 26 +++++++++++++------------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index 0e5f6f52bb..5e6396ec40 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -7,7 +7,7 @@ Normally LED pin is used to drive WS2812 led strip. LED pin is held low, and eve As alternative function, it is possible to generate PWM signal with specified duty ratio on the LED pin. -Feature can be used to drive external devices. It is also used to simulate OSD joystick to control cameras. +Feature can be used to drive external devices. It is also used to simulate [OSD joystick](OSD%20Joystick.md) to control cameras. PWM frequency is fixed to 24kHz with duty ratio between 0 and 100%: @@ -19,19 +19,21 @@ There are four modes of operation: - shared_low - shared_high -Mode is configured using ```led_pin_pwm_mode``` setting. +Mode is configured using ```led_pin_pwm_mode``` setting: ```LOW```, ```HIGH```, ```SHARED_LOW```, ```SHARED_HIGH``` -## Low +*Note that in any mode, there will be ~1 second LOW pulse on boot.* + +## LOW LED Pin is initialized to output low level by default and can be used to generate PWM signal. ws2812 strip can not be controlled. -## High +## HIGH LED Pin is initialized to output high level by default and can be used to generate PWM signal. ws2812 strip can not be controlled. -## Shared low (default) +## SHARED_LOW (default) LED Pin is used to drive WS2812 strip. Pauses between pulses are low: ![alt text](/docs/assets/images/ws2811_packets.png "ws2811 packets") @@ -44,10 +46,8 @@ When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio < ~10%. - - -## Shared high - LED Pin is used to drive WS2812 strip. Pauses between pulses are high. ws2812 pulses are prefixed with 300us low 'reset' pulse: +## SHARED_HIGH +LED Pin is used to drive WS2812 strip. Pauses between pulses are high. ws2812 pulses are prefixed with 300us low 'reset' pulse: ![alt text](/docs/assets/images/ws2811_packets_high.png "ws2811 packets_high") ![alt text](/docs/assets/images/ws2811_data_high.png "ws2811 data_high") @@ -66,15 +66,15 @@ Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device sho This mode is used to simulate OSD joystick. It is Ok that effectively voltage level is held >90% while driving LEDs, because OSD joystick keypress voltages are below 90%. - See OSD Joystick.md for more information. + See [OSD Joystick](OSD%20Joystick.md) for more information. -# Generating PWM signal in programming framework +# Generating PWM signal with programming framework *TODO* -0...100 - enable PWM generation with specified duty cicle +0...100 - start PWM generation with specified duty cicle --1 - disable PWM generation ( disable to allow ws2812 LEDs updates in shared modes ) +-1 - stop PWM generation ( stop to allow ws2812 LEDs updates in shared modes ) # Generating PWM signal from CLI From 4f5765b7810e794ea506a44982bb4251bb60620d Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 27 Jul 2023 13:19:38 +0300 Subject: [PATCH 035/175] Update OSD Joystick.md --- docs/OSD Joystick.md | 27 +++++++++++++++++++-------- 1 file changed, 19 insertions(+), 8 deletions(-) diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md index 12e0c618f8..b8500e5eee 100644 --- a/docs/OSD Joystick.md +++ b/docs/OSD Joystick.md @@ -32,6 +32,7 @@ We use LED pin PWM functionality with RC filter to generate voltage: ![alt text](/docs/assets/images/ledpinpwmfilter.png "led pin pwm filter") +*Note that there is ~1 second LOW pulse on FC boot, which can be sensed by some cameras as ENTER key*. # Example PCB layout (SMD components) @@ -47,22 +48,32 @@ If default voltages does not work with your camera model, then you have to measu 2. Measure voltages on OSD pin while each key is pressed. 3. Connect camera to FC throught RC filter as shown on schematix above. 4. Enable OSD Joystick emulation (see "Enabling OSD Joystick emulation" above) -4. Use cli command led_pin_pwm , value = 0...100 to find out PWM values for each voltage. +4. Use cli ```command led_pin_pwm ```, value = 0...100 to find out PWM values for each voltage. 5. Specify PWM values in configuration and save: -set osd_joystick_down=0 -set osd_joystick_up=48 -set osd_joystick_left=63 -set osd_joystick_right=28 -set osd_joystick_enter=75 +```set osd_joystick_down=0``` + +```set osd_joystick_up=48``` + +```set osd_joystick_left=63``` + +```set osd_joystick_right=28``` + +```set osd_joystick_enter=75``` + +```save``` # Entering OSD Joystick emulation mode OSD Joystick emulation mode is enabled using the following stick combination: -RIGHT CENTER + +```RIGHT CENTER``` + Mode is exited using stick combination: -LEFT CENTER + +```LEFT CENTER``` + *Note that the same stick combination is used to enable 5keys joystick emulation with RuncamDevice protocol.* From 7d024242c5775885bdc29df3d90183cf4b7929e7 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 27 Jul 2023 13:27:27 +0300 Subject: [PATCH 036/175] Update OSD Joystick.md --- docs/OSD Joystick.md | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md index b8500e5eee..46875307db 100644 --- a/docs/OSD Joystick.md +++ b/docs/OSD Joystick.md @@ -65,18 +65,26 @@ If default voltages does not work with your camera model, then you have to measu # Entering OSD Joystick emulation mode +Emulation can be enabled in unarmed state only. + OSD Joystick emulation mode is enabled using the following stick combination: ```RIGHT CENTER``` +Than camera OSD can be navigated using right stick. See [Controls](Controls.md) for all stick combinations. + +*Note that the same stick combination is used to enable 5keys joystick emulation with RuncamDevice protocol.* + Mode is exited using stick combination: ```LEFT CENTER``` +# RC Box -*Note that the same stick combination is used to enable 5keys joystick emulation with RuncamDevice protocol.* +There are 3 RC Boxes which can be used armed and unarmed state: +- Camera 1 - Enter +- Camera 2 - Up +- Camera 3 - Down -Emulation can be enabled in unarmed state only. - -See [Controls](Controls.md) +Other keys can be emulated using Programming framework ( see [LED pin PWM](LED%20pin%20PWM.md) for more details ). From 839709d6f083ee6aa18c2aec9d6aac4fe8831b64 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 01:36:13 +0300 Subject: [PATCH 037/175] Update OSD Joystick.md --- docs/OSD Joystick.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md index 46875307db..2ce1de458b 100644 --- a/docs/OSD Joystick.md +++ b/docs/OSD Joystick.md @@ -26,6 +26,8 @@ To simulate 5key joystick, it is sufficient to generate correct voltage on camer ```set osd_joystick_enabled=on``` +Also enable "Multi-color RGB LED Strinp support" in Configuration tab. + # Connection diagram We use LED pin PWM functionality with RC filter to generate voltage: From 9580c39d2754bd416392c632bcae119e444d6d73 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 02:19:56 +0300 Subject: [PATCH 038/175] Update Programming Framework.md --- docs/Programming Framework.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index c2ef089afc..8b15917ca7 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -86,6 +86,7 @@ IPF can be edited using INAV Configurator user interface, or via CLI | 49 | TIMER | A simple on - off timer. `true` for the duration of `Operand A` [ms]. Then `false` for the duration of `Operand B` [ms]. | | 50 | DELTA | This returns `true` when the value of `Operand A` has changed by the value of `Operand B` or greater within 100ms. | | 51 | APPROX_EQUAL | `true` if `Operand B` is within 1% of `Operand A`. | +| 52 | LED_PIN_PWM | Value 0...100 starts PWM generation on LED pin. See [LED pin PWM](LED%20pin%20PWM.md) Any other value stops PWM generation.| ### Operands From 9f486885ca50049164d5c19b3daf7a63da49acd6 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 02:22:32 +0300 Subject: [PATCH 039/175] Update LED pin PWM.md --- docs/LED pin PWM.md | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index 5e6396ec40..edb2bc4242 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -70,11 +70,8 @@ LED Pin is used to drive WS2812 strip. Pauses between pulses are high. ws2812 pu # Generating PWM signal with programming framework -*TODO* +See "LED Pin PWM" operation in [Programming Framework](Programming%20Framework.md) -0...100 - start PWM generation with specified duty cicle - --1 - stop PWM generation ( stop to allow ws2812 LEDs updates in shared modes ) # Generating PWM signal from CLI From d664aefe3f1287862c5d33075a7ce0d649cf6202 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 02:24:35 +0300 Subject: [PATCH 040/175] Update Programming Framework.md --- docs/Programming Framework.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index 8b15917ca7..1501c5c942 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -86,7 +86,7 @@ IPF can be edited using INAV Configurator user interface, or via CLI | 49 | TIMER | A simple on - off timer. `true` for the duration of `Operand A` [ms]. Then `false` for the duration of `Operand B` [ms]. | | 50 | DELTA | This returns `true` when the value of `Operand A` has changed by the value of `Operand B` or greater within 100ms. | | 51 | APPROX_EQUAL | `true` if `Operand B` is within 1% of `Operand A`. | -| 52 | LED_PIN_PWM | Value 0...100 starts PWM generation on LED pin. See [LED pin PWM](LED%20pin%20PWM.md) Any other value stops PWM generation.| +| 52 | LED_PIN_PWM | Value `Operand A` from [`0` : `100`] starts PWM generation on LED Pin. See [LED pin PWM](LED%20pin%20PWM.md). Any other value stops PWM generation (stop to allow ws2812 LEDs updates in shared modes)| ### Operands From a72a8f3543210b3d2752059606873aaa4380c427 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 02:43:32 +0300 Subject: [PATCH 041/175] Update Runcam device.md --- docs/Runcam device.md | 33 ++++++++++++++++++++++++++++++++- 1 file changed, 32 insertions(+), 1 deletion(-) diff --git a/docs/Runcam device.md b/docs/Runcam device.md index caac19b5b3..b8c6ef80fd 100644 --- a/docs/Runcam device.md +++ b/docs/Runcam device.md @@ -1 +1,32 @@ -# Runcam device \ No newline at end of file +# Runcam device + +Cameras which support [Runcam device protocol](https://support.runcam.com/hc/en-us/articles/360014537794-RunCam-Device-Protocol), can be configured using sticks. + +Note that for cameras which has OSD pin, there is alternative functionality: [OSD Joystick](OSD%20Joystick.md). + +Camera's RX/TX should be connected to FC's UART, which has "Runcam device" option selected. + +# Entering Joystick emulation mode + +Emulation can be enabled in unarmed state only. + +Joystick emulation mode is enabled using the following stick combination: + +```RIGHT CENTER``` + + +Than camera OSD can be navigated using right stick. See [Controls](Controls.md) for all stick combinations. + +*Note that the same stick combination is used to enable [OSD Joystick](OSD%20Joystick.md).* + +Mode is exited using stick combination: + +```LEFT CENTER``` + +# RC Box + +There are 3 RC Boxes which can be used in armed and unarmed state: +- Camera 1 - Simulate Wifi button +- Camera 2 - Simulate POWER button +- Camera 3 - Simulate Change Mode button. + From 52fd6d0c1d1fb0c02e5b460971c0cc0834dd6d73 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 02:45:11 +0300 Subject: [PATCH 042/175] Update LED pin PWM.md --- docs/LED pin PWM.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index edb2bc4242..48ee2a1ef1 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -21,7 +21,7 @@ There are four modes of operation: Mode is configured using ```led_pin_pwm_mode``` setting: ```LOW```, ```HIGH```, ```SHARED_LOW```, ```SHARED_HIGH``` -*Note that in any mode, there will be ~1 second LOW pulse on boot.* +*Note that in any mode, there will be ~2 seconds LOW pulse on boot.* ## LOW LED Pin is initialized to output low level by default and can be used to generate PWM signal. From a55bea82b8f56c3edbe0b78363609058961a0507 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 02:47:50 +0300 Subject: [PATCH 043/175] Update OSD Joystick.md --- docs/OSD Joystick.md | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md index 2ce1de458b..2e4f022452 100644 --- a/docs/OSD Joystick.md +++ b/docs/OSD Joystick.md @@ -84,9 +84,13 @@ Mode is exited using stick combination: # RC Box -There are 3 RC Boxes which can be used armed and unarmed state: +There are 3 RC Boxes which can be used in armed and unarmed state: - Camera 1 - Enter - Camera 2 - Up - Camera 3 - Down Other keys can be emulated using Programming framework ( see [LED pin PWM](LED%20pin%20PWM.md) for more details ). + +# Behavior on boot + +There is ~2 seconds LOW pulse during boot sequence, which corresponds to DOWN key. Fortunately, cameras seem to ignore any key events few seconds after statup. From 3c9895d8b1cee0772992d225adce43d963c61697 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 03:01:18 +0300 Subject: [PATCH 044/175] Update OSD Joystick.md --- docs/OSD Joystick.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md index 2e4f022452..f6c3f0be9d 100644 --- a/docs/OSD Joystick.md +++ b/docs/OSD Joystick.md @@ -6,7 +6,7 @@ See [LED pin PWM](LED%20pin%20PWM.md) for more details. Note that for cameras which support RuncamDevice protocol, there is alternative functionality using serial communication: [Runcam device](Runcam%20device.md) -Alao special adapters exist to convert RuncamDevice protocol to OSD Joystick: [Runcam control adapter](https://www.runcam.com/download/runcam_control_adapter_manual.pdf) +Also special adapters exist to convert RuncamDevice protocol to OSD Joystick: [Runcam control adapter](https://www.runcam.com/download/runcam_control_adapter_manual.pdf) # OSD Joystick schematics From 817b52903afe1a4c137548824545a46a69623b33 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 03:03:15 +0300 Subject: [PATCH 045/175] Update OSD Joystick.md --- docs/OSD Joystick.md | 2 -- 1 file changed, 2 deletions(-) diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md index f6c3f0be9d..d5ee6a2335 100644 --- a/docs/OSD Joystick.md +++ b/docs/OSD Joystick.md @@ -34,8 +34,6 @@ We use LED pin PWM functionality with RC filter to generate voltage: ![alt text](/docs/assets/images/ledpinpwmfilter.png "led pin pwm filter") -*Note that there is ~1 second LOW pulse on FC boot, which can be sensed by some cameras as ENTER key*. - # Example PCB layout (SMD components) RC Filter can be soldered on a small piece of PCB: From 6cfaa227cbc7d752c21658a1a78363fdae4bbcfe Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 02:10:55 +0200 Subject: [PATCH 046/175] implemented LED Pin PWM programming function --- src/main/programming/logic_condition.c | 12 ++++++++++++ src/main/programming/logic_condition.h | 3 ++- 2 files changed, 14 insertions(+), 1 deletion(-) diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index f07e487f9c..9588aec9ad 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -55,6 +55,7 @@ #include "io/vtx.h" #include "drivers/vtx_common.h" +#include "drivers/light_ws2811strip.h" PG_REGISTER_ARRAY_WITH_RESET_FN(logicCondition_t, MAX_LOGIC_CONDITIONS, logicConditions, PG_LOGIC_CONDITIONS, 4); @@ -472,6 +473,17 @@ static int logicConditionCompute( return false; } break; + +#ifdef LED_PIN + case LOGIC_CONDITION_LED_PIN_PWM: + if (operandA >=0 && operandA <= 100) { + ledPinStartPWM((uint8_t)operandA); + } else { + ledPinStopPWM(); + } + return operandA; + break; +#endif default: return false; diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 779dbb1b98..a652a371ca 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -81,7 +81,8 @@ typedef enum { LOGIC_CONDITION_TIMER = 49, LOGIC_CONDITION_DELTA = 50, LOGIC_CONDITION_APPROX_EQUAL = 51, - LOGIC_CONDITION_LAST = 52, + LOGIC_CONDITION_LED_PIN_PWM = 52, + LOGIC_CONDITION_LAST = 53, } logicOperation_e; typedef enum logicOperandType_s { From 988c9d40fe8a92aaa0b39407c4ff7df5d2e96ed7 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 02:11:50 +0200 Subject: [PATCH 047/175] removed GRAVITYF7 --- src/main/target/GRAVITYF7/CMakeLists.txt | 1 - src/main/target/GRAVITYF7/config.c | 28 ---- src/main/target/GRAVITYF7/target.c | 59 -------- src/main/target/GRAVITYF7/target.h | 182 ----------------------- 4 files changed, 270 deletions(-) delete mode 100644 src/main/target/GRAVITYF7/CMakeLists.txt delete mode 100644 src/main/target/GRAVITYF7/config.c delete mode 100644 src/main/target/GRAVITYF7/target.c delete mode 100644 src/main/target/GRAVITYF7/target.h diff --git a/src/main/target/GRAVITYF7/CMakeLists.txt b/src/main/target/GRAVITYF7/CMakeLists.txt deleted file mode 100644 index c56916ca10..0000000000 --- a/src/main/target/GRAVITYF7/CMakeLists.txt +++ /dev/null @@ -1 +0,0 @@ -target_stm32f722xe(GRAVITYF7) diff --git a/src/main/target/GRAVITYF7/config.c b/src/main/target/GRAVITYF7/config.c deleted file mode 100644 index 9e9e36732a..0000000000 --- a/src/main/target/GRAVITYF7/config.c +++ /dev/null @@ -1,28 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include -#include "platform.h" -#include "io/piniobox.h" - -void targetConfiguration(void) -{ - pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; -} \ No newline at end of file diff --git a/src/main/target/GRAVITYF7/target.c b/src/main/target/GRAVITYF7/target.c deleted file mode 100644 index 80ee99e395..0000000000 --- a/src/main/target/GRAVITYF7/target.c +++ /dev/null @@ -1,59 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include -#include "platform.h" -#include "drivers/bus.h" -#include "drivers/io.h" -#include "drivers/pwm_mapping.h" -#include "drivers/timer.h" - - -timerHardware_t timerHardware[] = { - DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS - - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 (2,1) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 (2,1) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 (2,5) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 (2,5) - - DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED STRIP(1,5) - - //DEF_TIM(TIM3, CH4, PB1, TIM_USE_CAMERA_CONTROL, 0, 0), // FC CAM - -}; - - -/* -timerHardware_t timerHardware[] = { - DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS - - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 (2,1) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 (2,1) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 (2,5) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 (2,5) - - DEF_TIM(TIM2, CH1, PA15, TIM_USE_FW_SERVO, 0, 0), // LED STRIP(1,5) - - //DEF_TIM(TIM3, CH4, PB1, TIM_USE_CAMERA_CONTROL, 0, 0), // FC CAM - -}; -*/ -const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); \ No newline at end of file diff --git a/src/main/target/GRAVITYF7/target.h b/src/main/target/GRAVITYF7/target.h deleted file mode 100644 index a770fbc861..0000000000 --- a/src/main/target/GRAVITYF7/target.h +++ /dev/null @@ -1,182 +0,0 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Cleanflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Cleanflight. If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "FLMD" -#define USBD_PRODUCT_STRING "GRAVITYF7" - -//#define USE_HARDWARE_PREBOOT_SETUP - -// User pin -#define USE_PINIO -#define USE_PINIOBOX -#define PINIO1_PIN PC2 // VTX power switcher - -#define LED0 PC14 -#define BEEPER PC13 -#define BEEPER_INVERTED - -#define USE_PITOT_VIRTUAL - - -// MPU6000 -#define USE_IMU_MPU6000 -#define MPU6000_CS_PIN PB0 -#define MPU6000_SPI_BUS BUS_SPI1 -#define IMU_MPU6000_ALIGN CW0_DEG_FLIP - -#define USE_EXTI -#define GYRO_INT_EXTI PB10 -#define USE_MPU_DATA_READY_SIGNAL - -// USB -#define USE_VCP -#define VBUS_SENSING_PIN PA10 -#define VBUS_SENSING_ENABLED - -// UARTs -#define USE_UART1 -#define UART1_TX_PIN PB6 -#define UART1_RX_PIN PB7 - -#define USE_UART2 -#define UART2_TX_PIN PA2 -#define UART2_RX_PIN PA3 - -#define USE_UART3 -#define UART3_TX_PIN PC10 -#define UART3_RX_PIN PC11 - -#define USE_UART4 -#define UART4_TX_PIN PA0 -#define UART4_RX_PIN PA1 - -#define USE_UART5 -#define UART5_TX_PIN PC12 -#define UART5_RX_PIN PD2 - -#define USE_UART6 -#define UART6_TX_PIN PC6 -#define UART6_RX_PIN PC7 - -#define SERIAL_PORT_COUNT 7 - -// i2c -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 - -// baro -#define USE_BARO -#define BARO_I2C_BUS BUS_I2C1 -#define USE_BARO_BMP280 -#define BMP280_I2C_ADDR (0x77) - -// mag -#define USE_MAG -#define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL - -// temp -#define TEMPERATURE_I2C_BUS BUS_I2C1 - -#define PITOT_I2C_BUS BUS_I2C1 - - -// SPIs -#define USE_SPI -#define USE_SPI_DEVICE_1 -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - - -#define USE_SPI_DEVICE_2 -#define SPI2_NSS_PIN PB12 -#define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PB14 -#define SPI2_MOSI_PIN PB15 - -#define USE_SPI_DEVICE_3 -#define SPI3_NSS_PIN PB2 -#define SPI3_SCK_PIN PB3 -#define SPI3_MISO_PIN PB4 -#define SPI3_MOSI_PIN PB5 - - -// OSD -#define USE_OSD -#define USE_MAX7456 -#define MAX7456_SPI_BUS BUS_SPI2 -#define MAX7456_CS_PIN SPI2_NSS_PIN - - -// BLACKBOX -#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT -#define M25P16_CS_PIN SPI3_NSS_PIN -#define M25P16_SPI_BUS BUS_SPI3 -#define USE_FLASHFS -#define USE_FLASH_M25P16 - - - -// ADC -#define USE_ADC -#define ADC_INSTANCE ADC1 -#define ADC1_DMA_STREAM DMA2_Stream0 -#define ADC_CHANNEL_1_PIN PC0 -#define ADC_CHANNEL_2_PIN PC1 - -#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 -#define VBAT_ADC_CHANNEL ADC_CHN_2 -#define VBAT_SCALE_DEFAULT 1120 -#define CURRENT_METER_SCALE 182 - - -// LED Strip -#define USE_LED_STRIP -#define WS2811_PIN PA15 -#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST5_HANDLER -#define WS2811_DMA_STREAM DMA1_Stream5 -#define WS2811_DMA_CHANNEL DMA_CHANNEL_3 - - - -// FEATURES -#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_BLACKBOX ) -#define DEFAULT_RX_TYPE RX_TYPE_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS -#define SERIALRX_UART SERIAL_PORT_USART1 - - -#define USE_ESC_SENSOR -#define USE_SERIALSHOT -#define USE_SERIAL_4WAY_BLHELI_INTERFACE - -#define MAX_PWM_OUTPUT_PORTS 6 - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) \ No newline at end of file From 0c9bec1efc1aaeaaf3b9d1469a29ef319a239edc Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 02:21:56 +0200 Subject: [PATCH 048/175] updated settings.md --- docs/Settings.md | 70 ++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 70 insertions(+) diff --git a/docs/Settings.md b/docs/Settings.md index dda075cee6..d4ddd33b85 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1922,6 +1922,16 @@ Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened w --- +### led_pin_pwm_mode + +PWM mode of LED pin. + +| Default | Min | Max | +| --- | --- | --- | +| SHARED_LOW | | | + +--- + ### ledstrip_visual_beeper _// TODO_ @@ -4292,6 +4302,66 @@ Temperature under which the IMU temperature OSD element will start blinking (dec --- +### osd_joystick_down + +PWM value for DOWN key + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 100 | + +--- + +### osd_joystick_enabled + +Enable OSD Joystick emulation + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + +### osd_joystick_enter + +PWM value for ENTER key + +| Default | Min | Max | +| --- | --- | --- | +| 75 | 0 | 100 | + +--- + +### osd_joystick_left + +PWM value for LEFT key + +| Default | Min | Max | +| --- | --- | --- | +| 63 | 0 | 100 | + +--- + +### osd_joystick_right + +PWM value for RIGHT key + +| Default | Min | Max | +| --- | --- | --- | +| 28 | 0 | 100 | + +--- + +### osd_joystick_up + +PWM value for UP key + +| Default | Min | Max | +| --- | --- | --- | +| 48 | 0 | 100 | + +--- + ### osd_left_sidebar_scroll _// TODO_ From 7309ac5cb17781dbb870a9e0ec1da7a5c967175e Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 08:50:41 +0200 Subject: [PATCH 049/175] attempts to fix unit test compilation error --- src/test/unit/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt index ebfd3b78d4..36c4f2482a 100644 --- a/src/test/unit/CMakeLists.txt +++ b/src/test/unit/CMakeLists.txt @@ -21,7 +21,7 @@ set_property(SOURCE olc_unittest.cc PROPERTY depends "common/olc.c") set_property(SOURCE rcdevice_unittest.cc PROPERTY definitions USE_RCDEVICE) set_property(SOURCE rcdevice_unittest.cc PROPERTY depends "common/bitarray.c" "common/crc.c" "io/rcdevice.c" "io/rcdevice_cam.c" - "fc/rc_modes.c" "common/maths.c") + "fc/rc_modes.c" "common/maths.c" "drivers/osd_joystick.c") set_property(SOURCE sensor_gyro_unittest.cc PROPERTY depends "build/debug.c" "common/maths.c" "common/calibration.c" "common/filter.c" From a0fc552f16a89c14961c97989a2b927e53c57809 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 09:19:41 +0200 Subject: [PATCH 050/175] attempts to fix unit test compilation error --- src/test/unit/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt index 36c4f2482a..071ca0f586 100644 --- a/src/test/unit/CMakeLists.txt +++ b/src/test/unit/CMakeLists.txt @@ -21,7 +21,7 @@ set_property(SOURCE olc_unittest.cc PROPERTY depends "common/olc.c") set_property(SOURCE rcdevice_unittest.cc PROPERTY definitions USE_RCDEVICE) set_property(SOURCE rcdevice_unittest.cc PROPERTY depends "common/bitarray.c" "common/crc.c" "io/rcdevice.c" "io/rcdevice_cam.c" - "fc/rc_modes.c" "common/maths.c" "drivers/osd_joystick.c") + "fc/rc_modes.c" "common/maths.c" "io/osd_joystick.c") set_property(SOURCE sensor_gyro_unittest.cc PROPERTY depends "build/debug.c" "common/maths.c" "common/calibration.c" "common/filter.c" From 9d4d22ce0fed449b026fbb7ab74684367d14f52d Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 10:12:40 +0200 Subject: [PATCH 051/175] attempts to fix unit test compilation error --- src/test/unit/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt index 071ca0f586..59ec9d2705 100644 --- a/src/test/unit/CMakeLists.txt +++ b/src/test/unit/CMakeLists.txt @@ -21,7 +21,7 @@ set_property(SOURCE olc_unittest.cc PROPERTY depends "common/olc.c") set_property(SOURCE rcdevice_unittest.cc PROPERTY definitions USE_RCDEVICE) set_property(SOURCE rcdevice_unittest.cc PROPERTY depends "common/bitarray.c" "common/crc.c" "io/rcdevice.c" "io/rcdevice_cam.c" - "fc/rc_modes.c" "common/maths.c" "io/osd_joystick.c") + "fc/rc_modes.c" "common/maths.c" "drivers/light_ws2811strip.c" "io/osd_joystick.c") set_property(SOURCE sensor_gyro_unittest.cc PROPERTY depends "build/debug.c" "common/maths.c" "common/calibration.c" "common/filter.c" From 0e82c7e2da8e31880bd2a67de9c9f198b60cfd9b Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 10:52:34 +0200 Subject: [PATCH 052/175] attempts to fix unit test compilation error --- src/main/io/rcdevice_cam.c | 10 ++++++++++ src/test/unit/CMakeLists.txt | 2 +- 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/src/main/io/rcdevice_cam.c b/src/main/io/rcdevice_cam.c index 8fb5b637f0..c5c54c1aa3 100644 --- a/src/main/io/rcdevice_cam.c +++ b/src/main/io/rcdevice_cam.c @@ -48,10 +48,12 @@ bool waitingDeviceResponse = false; static bool isFeatureSupported(uint8_t feature) { +#ifndef UNIT_TEST #ifdef USE_LED_STRIP if (!rcdeviceIsEnabled() && osdJoystickEnabled() ) { return true; } +#endif #endif if (camDevice->info.features & feature) { @@ -110,6 +112,7 @@ static void rcdeviceCameraControlProcess(void) if ( rcdeviceIsEnabled() ) { runcamDeviceSimulateCameraButton(camDevice, behavior); } +#ifndef UNIT_TEST #ifdef USE_LED_STRIP else if (osdJoystickEnabled()) { @@ -125,14 +128,17 @@ static void rcdeviceCameraControlProcess(void) break; } } +#endif #endif switchStates[switchIndex].isActivated = true; } } else { +#ifndef UNIT_TEST #ifdef USE_LED_STRIP if (osdJoystickEnabled() && switchStates[switchIndex].isActivated) { osdJoystickSimulate5KeyButtonRelease(); } +#endif #endif switchStates[switchIndex].isActivated = false; } @@ -265,11 +271,13 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs) rcdeviceSend5KeyOSDCableSimualtionEvent(RCDEVICE_CAM_KEY_RELEASE); waitingDeviceResponse = true; } +#ifndef UNIT_TEST #ifdef USE_LED_STRIP else if (osdJoystickEnabled()) { osdJoystickSimulate5KeyButtonRelease(); isButtonPressed = false; } +#endif #endif } } else { @@ -308,6 +316,7 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs) rcdeviceSend5KeyOSDCableSimualtionEvent(key); waitingDeviceResponse = true; } +#ifndef UNIT_TEST #ifdef USE_LED_STRIP else if (osdJoystickEnabled()) { if ( key == RCDEVICE_CAM_KEY_CONNECTION_OPEN ) { @@ -318,6 +327,7 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs) osdJoystickSimulate5KeyButtonPress(key); } } +#endif #endif isButtonPressed = true; } diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt index 59ec9d2705..ebfd3b78d4 100644 --- a/src/test/unit/CMakeLists.txt +++ b/src/test/unit/CMakeLists.txt @@ -21,7 +21,7 @@ set_property(SOURCE olc_unittest.cc PROPERTY depends "common/olc.c") set_property(SOURCE rcdevice_unittest.cc PROPERTY definitions USE_RCDEVICE) set_property(SOURCE rcdevice_unittest.cc PROPERTY depends "common/bitarray.c" "common/crc.c" "io/rcdevice.c" "io/rcdevice_cam.c" - "fc/rc_modes.c" "common/maths.c" "drivers/light_ws2811strip.c" "io/osd_joystick.c") + "fc/rc_modes.c" "common/maths.c") set_property(SOURCE sensor_gyro_unittest.cc PROPERTY depends "build/debug.c" "common/maths.c" "common/calibration.c" "common/filter.c" From 95c005d611ea8f44e8b06671712c3ee420e5f9ca Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 13:01:11 +0300 Subject: [PATCH 053/175] Update LED pin PWM.md --- docs/LED pin PWM.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index 48ee2a1ef1..818e1768a7 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -44,7 +44,7 @@ While PWM signal is generated, ws2811 strip is not updated. When PWM generation is disabled, LED pin is used to drive ws2812 strip. -Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM singal with duty ratio < ~10%. +Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM signal with duty ratio < ~10%. ## SHARED_HIGH LED Pin is used to drive WS2812 strip. Pauses between pulses are high. ws2812 pulses are prefixed with 300us low 'reset' pulse: From 3e01df1e256b79078d13cfdfcefdc3b690f7e852 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 13:01:41 +0300 Subject: [PATCH 054/175] Update LED pin PWM.md --- docs/LED pin PWM.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index 818e1768a7..853042b44f 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -47,7 +47,7 @@ When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM signal with duty ratio < ~10%. ## SHARED_HIGH -LED Pin is used to drive WS2812 strip. Pauses between pulses are high. ws2812 pulses are prefixed with 300us low 'reset' pulse: +LED Pin is used to drive WS2812 strip. Pauses between pulses are high. ws2812 pulses are prefixed with 50us low 'reset' pulse: ![alt text](/docs/assets/images/ws2811_packets_high.png "ws2811 packets_high") ![alt text](/docs/assets/images/ws2811_data_high.png "ws2811 data_high") From 093f3f9a8d483a28ef1157ed05cb5b7463b15ee1 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 29 Jul 2023 13:02:45 +0300 Subject: [PATCH 055/175] Update LED pin PWM.md --- docs/LED pin PWM.md | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/docs/LED pin PWM.md b/docs/LED pin PWM.md index 853042b44f..2aead4cd7a 100644 --- a/docs/LED pin PWM.md +++ b/docs/LED pin PWM.md @@ -58,11 +58,7 @@ LED Pin is used to drive WS2812 strip. Pauses between pulses are high. ws2812 pu When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM signal with duty ratio > ~90%. - After sending ws2812 protocol pulses for 32 LEDS, we held line high for 9ms, then send 50us low 'reset' pulse. - - Datasheet for ws2812 protocol does not describe behavior for long high pulse, but in practice it works the same as 'reset' pulse. - - To be safe, we also send correct low 'reset' pulse before starting next LEDs update sequence. + After sending ws2812 protocol pulses for 32 LEDS, we held line high for 9ms, then send 50us low 'reset' pulse. Datasheet for ws2812 protocol does not describe behavior for long high pulse, but in practice it works the same as 'reset' pulse. To be safe, we also send correct low 'reset' pulse before starting next LEDs update sequence. This mode is used to simulate OSD joystick. It is Ok that effectively voltage level is held >90% while driving LEDs, because OSD joystick keypress voltages are below 90%. From 3ecc2fa119682339865f8818d3074deeba70fa65 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 3 Aug 2023 22:11:14 +0200 Subject: [PATCH 056/175] simulate battery voltage with any sensor --- src/main/fc/fc_msp.c | 8 ++------ src/main/fc/runtime_config.c | 5 +++-- src/main/fc/runtime_config.h | 2 +- src/main/sensors/battery.c | 10 +++++++++- 4 files changed, 15 insertions(+), 10 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index dd28ae6166..df3046ddc7 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -3607,15 +3607,11 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu sbufAdvance(src, sizeof(uint16_t) * XYZ_AXIS_COUNT); } -#if defined(USE_FAKE_BATT_SENSOR) if (SIMULATOR_HAS_OPTION(HITL_EXT_BATTERY_VOLTAGE)) { - fakeBattSensorSetVbat(sbufReadU8(src) * 10); + simulatorData.vbat = sbufReadU8(src); } else { -#endif - fakeBattSensorSetVbat((uint16_t)(SIMULATOR_FULL_BATTERY * 10.0f)); -#if defined(USE_FAKE_BATT_SENSOR) + simulatorData.vbat = SIMULATOR_FULL_BATTERY; } -#endif if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { simulatorData.airSpeed = sbufReadU16(src); diff --git a/src/main/fc/runtime_config.c b/src/main/fc/runtime_config.c index 15dadd1c59..175de20c48 100644 --- a/src/main/fc/runtime_config.c +++ b/src/main/fc/runtime_config.c @@ -179,7 +179,8 @@ flightModeForTelemetry_e getFlightModeForTelemetry(void) #ifdef USE_SIMULATOR simulatorData_t simulatorData = { - .flags = 0, - .debugIndex = 0 + .flags = 0, + .debugIndex = 0, + .vbat = 0 }; #endif diff --git a/src/main/fc/runtime_config.h b/src/main/fc/runtime_config.h index 16d1b411df..b7cddf1095 100644 --- a/src/main/fc/runtime_config.h +++ b/src/main/fc/runtime_config.h @@ -170,7 +170,7 @@ flightModeForTelemetry_e getFlightModeForTelemetry(void); #define SIMULATOR_MSP_VERSION 2 // Simulator MSP version #define SIMULATOR_BARO_TEMP 25 // °C -#define SIMULATOR_FULL_BATTERY 12.6f // Volts +#define SIMULATOR_FULL_BATTERY 126 // Volts*10 #define SIMULATOR_HAS_OPTION(flag) ((simulatorData.flags & flag) != 0) typedef enum { diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 0afc15b5be..056a8e013b 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -84,7 +84,7 @@ static bool batteryUseCapacityThresholds = false; static bool batteryFullWhenPluggedIn = false; static bool profileAutoswitchDisable = false; -static uint16_t vbat = 0; // battery voltage in 0.1V steps (filtered) +static uint16_t vbat = 0; // battery voltage in 0.01V steps (filtered) static uint16_t powerSupplyImpedance = 0; // calculated impedance in milliohm static uint16_t sagCompensatedVBat = 0; // calculated no load vbat static bool powerSupplyImpedanceIsValid = false; @@ -297,6 +297,14 @@ static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected) vbat = 0; break; } + +#ifdef USE_SIMULATOR + if (ARMING_FLAG(SIMULATOR_MODE_HITL) && SIMULATOR_HAS_OPTION(HITL_SIMULATE_BATTERY)) { + vbat = ((uint16_t)simulatorData.vbat)*10; + return; + } +#endif + if (justConnected) { pt1FilterReset(&vbatFilterState, vbat); } else { From 67890ed3ec392c98f259470e4a4d69f68aa26618 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 14 Aug 2023 10:56:45 +0200 Subject: [PATCH 057/175] Add files --- .vscode/c_cpp_properties.json | 66 +++++++++++++++++++++++++++++++++++ .vscode/tasks.json | 41 ++++++++++++++++++++++ 2 files changed, 107 insertions(+) create mode 100755 .vscode/c_cpp_properties.json create mode 100755 .vscode/tasks.json diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json new file mode 100755 index 0000000000..6e7d914b25 --- /dev/null +++ b/.vscode/c_cpp_properties.json @@ -0,0 +1,66 @@ +{ + "configurations": [ + { + "name": "Linux", + "includePath": [ + "${workspaceRoot}/src/main/**", + "${workspaceRoot}/lib/main/**", + "/usr/include/**" + ], + "browse": { + "limitSymbolsToIncludedHeaders": false, + "path": [ + "${workspaceRoot}/src/main/**", + "${workspaceRoot}/lib/main/**" + ] + }, + "intelliSenseMode": "linux-gcc-arm", + "cStandard": "c11", + "cppStandard": "c++17", + "defines": [ + "MCU_FLASH_SIZE 512", + "USE_NAV", + "NAV_FIXED_WING_LANDING", + "USE_OSD", + "USE_GYRO_NOTCH_1", + "USE_GYRO_NOTCH_2", + "USE_DTERM_NOTCH", + "USE_ACC_NOTCH", + "USE_GYRO_BIQUAD_RC_FIR2", + "USE_D_BOOST", + "USE_SERIALSHOT", + "USE_ANTIGRAVITY", + "USE_ASYNC_GYRO_PROCESSING", + "USE_RPM_FILTER", + "USE_GLOBAL_FUNCTIONS", + "USE_DYNAMIC_FILTERS", + "USE_IMU_BNO055", + "USE_SECONDARY_IMU", + "USE_DSHOT", + "FLASH_SIZE 480", + "USE_I2C_IO_EXPANDER", + "USE_PCF8574", + "USE_ESC_SENSOR", + "USE_PROGRAMMING_FRAMEWORK", + "USE_SERIALRX_GHST", + "USE_TELEMETRY_GHST", + "USE_CMS", + "USE_DJI_HD_OSD", + "USE_GYRO_KALMAN", + "USE_RANGEFINDER", + "USE_RATE_DYNAMICS", + "USE_SMITH_PREDICTOR", + "USE_ALPHA_BETA_GAMMA_FILTER", + "USE_MAG_VCM5883", + "USE_TELEMETRY_JETIEXBUS", + "USE_NAV", + "USE_SDCARD_SDIO", + "USE_SDCARD", + "USE_Q_TUNE", + "USE_GYRO_FFT_FILTER" + ], + "configurationProvider": "ms-vscode.cmake-tools" + } + ], + "version": 4 +} \ No newline at end of file diff --git a/.vscode/tasks.json b/.vscode/tasks.json new file mode 100755 index 0000000000..3ca90b787d --- /dev/null +++ b/.vscode/tasks.json @@ -0,0 +1,41 @@ +{ + // See https://go.microsoft.com/fwlink/?LinkId=733558 + // for the documentation about the tasks.json format + "version": "2.0.0", + "tasks": [ + { + "label": "Build Matek F722-SE", + "type": "shell", + "command": "make MATEKF722SE", + "group": "build", + "problemMatcher": [], + "options": { + "cwd": "${workspaceFolder}/build" + } + }, + { + "label": "Build Matek F722", + "type": "shell", + "command": "make MATEKF722", + "group": { + "kind": "build", + "isDefault": true + }, + "problemMatcher": [], + "options": { + "cwd": "${workspaceFolder}/build" + } + } + , + { + "label": "CMAKE Update", + "type": "shell", + "command": "cmake ..", + "group": "build", + "problemMatcher": [], + "options": { + "cwd": "${workspaceFolder}/build" + } + } + ] +} \ No newline at end of file From 3a851e08bf426f006cede4e91cd9b089f098fb0d Mon Sep 17 00:00:00 2001 From: mateksys Date: Wed, 16 Aug 2023 15:09:10 +0800 Subject: [PATCH 058/175] Add more power options for 1G3 group --- src/main/io/vtx_tramp.c | 19 +++++++++++++++---- 1 file changed, 15 insertions(+), 4 deletions(-) diff --git a/src/main/io/vtx_tramp.c b/src/main/io/vtx_tramp.c index 2791ada294..540c9c9f22 100644 --- a/src/main/io/vtx_tramp.c +++ b/src/main/io/vtx_tramp.c @@ -575,16 +575,27 @@ const char * const trampPowerNames_5G8_800[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = const uint16_t trampPowerTable_1G3_800[VTX_TRAMP_1G3_MAX_POWER_COUNT] = { 25, 200, 800 }; const char * const trampPowerNames_1G3_800[VTX_TRAMP_1G3_MAX_POWER_COUNT + 1] = { "---", "25 ", "200", "800" }; +const uint16_t trampPowerTable_1G3_2000[VTX_TRAMP_1G3_MAX_POWER_COUNT] = { 25, 200, 2000 }; +const char * const trampPowerNames_1G3_2000[VTX_TRAMP_1G3_MAX_POWER_COUNT + 1] = { "---", "25 ", "200", "2000" }; + static void vtxProtoUpdatePowerMetadata(uint16_t maxPower) { switch (vtxSettingsConfig()->frequencyGroup) { case FREQUENCYGROUP_1G3: - vtxState.metadata.powerTablePtr = trampPowerTable_1G3_800; - vtxState.metadata.powerTableCount = VTX_TRAMP_1G3_MAX_POWER_COUNT; + if (maxPower >= 2000) { + vtxState.metadata.powerTablePtr = trampPowerTable_1G3_2000; + vtxState.metadata.powerTableCount = VTX_TRAMP_1G3_MAX_POWER_COUNT; - impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_1G3_800; - impl_vtxDevice.capability.powerCount = VTX_TRAMP_1G3_MAX_POWER_COUNT; + impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_1G3_2000; + impl_vtxDevice.capability.powerCount = VTX_TRAMP_1G3_MAX_POWER_COUNT; + } + else { + vtxState.metadata.powerTablePtr = trampPowerTable_1G3_800; + vtxState.metadata.powerTableCount = VTX_TRAMP_1G3_MAX_POWER_COUNT; + impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_1G3_800; + impl_vtxDevice.capability.powerCount = VTX_TRAMP_1G3_MAX_POWER_COUNT; + } impl_vtxDevice.capability.bandCount = VTX_TRAMP_1G3_BAND_COUNT; impl_vtxDevice.capability.channelCount = VTX_TRAMP_1G3_CHANNEL_COUNT; impl_vtxDevice.capability.bandNames = (char **)vtx1G3BandNames; From 5bf8e7254ec39af77ea6bf3f142578d6237de84d Mon Sep 17 00:00:00 2001 From: mateksys Date: Wed, 16 Aug 2023 16:08:47 +0800 Subject: [PATCH 059/175] Add MatekH743HD variant --- src/main/target/MATEKH743/CMakeLists.txt | 1 + src/main/target/MATEKH743/target.h | 25 +++++++++++++++--------- 2 files changed, 17 insertions(+), 9 deletions(-) diff --git a/src/main/target/MATEKH743/CMakeLists.txt b/src/main/target/MATEKH743/CMakeLists.txt index 96a65ca5a4..dcc5019a9d 100644 --- a/src/main/target/MATEKH743/CMakeLists.txt +++ b/src/main/target/MATEKH743/CMakeLists.txt @@ -1 +1,2 @@ target_stm32h743xi(MATEKH743) +target_stm32h743xi(MATEKH743HD) diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index 37742a88fc..25e0217bb0 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -19,7 +19,12 @@ #pragma once #define TARGET_BOARD_IDENTIFIER "H743" -#define USBD_PRODUCT_STRING "MATEKH743" + +#if defined(MATEKH743HD) + #define USBD_PRODUCT_STRING "MATEKH743HD" +#else + #define USBD_PRODUCT_STRING "MATEKH743" +#endif #define USE_TARGET_CONFIG @@ -69,14 +74,16 @@ #define ICM42605_CS_PIN PC13 // *************** SPI2 OSD *********************** -#define USE_SPI_DEVICE_2 -#define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PB14 -#define SPI2_MOSI_PIN PB15 + #define USE_SPI_DEVICE_2 + #define SPI2_SCK_PIN PB13 + #define SPI2_MISO_PIN PB14 + #define SPI2_MOSI_PIN PB15 -#define USE_MAX7456 -#define MAX7456_SPI_BUS BUS_SPI2 -#define MAX7456_CS_PIN PB12 +#if defined(MATEKH743) + #define USE_MAX7456 + #define MAX7456_SPI_BUS BUS_SPI2 + #define MAX7456_CS_PIN PB12 +#endif // *************** SPI3 SPARE for external RM3100 *********** #define USE_SPI_DEVICE_3 @@ -159,7 +166,7 @@ #define SERIAL_PORT_COUNT 9 #define DEFAULT_RX_TYPE RX_TYPE_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_PROVIDER SERIALRX_CRSF #define SERIALRX_UART SERIAL_PORT_USART6 // *************** SDIO SD BLACKBOX******************* From 26deae54bbdf08085e85cace5d5d203ba7fb7fa1 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Mon, 21 Aug 2023 23:28:11 +0100 Subject: [PATCH 060/175] first build --- src/main/fc/fc_core.c | 20 ++++++++++++++------ src/main/fc/fc_core.h | 1 + src/main/navigation/navigation.c | 20 +++++++++++++++----- src/main/navigation/navigation.h | 1 + src/main/navigation/navigation_fixedwing.c | 2 +- 5 files changed, 32 insertions(+), 12 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index af8d1202b1..46ef140f84 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -118,6 +118,7 @@ uint8_t motorControlEnable = false; static bool isRXDataNew; static disarmReason_t lastDisarmReason = DISARM_NONE; timeUs_t lastDisarmTimeUs = 0; +timeMs_t emergInflightRearmTimeout = 0; static bool prearmWasReset = false; // Prearm must be reset (RC Mode not active) before arming is possible static timeMs_t prearmActivationTime = 0; @@ -176,7 +177,7 @@ int16_t getAxisRcCommand(int16_t rawData, int16_t rate, int16_t deadband) { int16_t stickDeflection = 0; -#if defined(SITL_BUILD) // Workaround due to strange bug in GCC > 10.2 https://gcc.gnu.org/bugzilla/show_bug.cgi?id=108914 +#if defined(SITL_BUILD) // Workaround due to strange bug in GCC > 10.2 https://gcc.gnu.org/bugzilla/show_bug.cgi?id=108914 const int16_t value = rawData - PWM_RANGE_MIDDLE; if (value < -500) { stickDeflection = -500; @@ -186,9 +187,9 @@ int16_t getAxisRcCommand(int16_t rawData, int16_t rate, int16_t deadband) stickDeflection = value; } #else - stickDeflection = constrain(rawData - PWM_RANGE_MIDDLE, -500, 500); + stickDeflection = constrain(rawData - PWM_RANGE_MIDDLE, -500, 500); #endif - + stickDeflection = applyDeadbandRescaled(stickDeflection, deadband, -500, 500); return rcLookup(stickDeflection, rate); } @@ -432,6 +433,7 @@ void disarm(disarmReason_t disarmReason) if (ARMING_FLAG(ARMED)) { lastDisarmReason = disarmReason; lastDisarmTimeUs = micros(); + emergInflightRearmTimeout = US2MS(lastDisarmTimeUs) + (isProbablyStillFlying() ? 5000 : 0); DISABLE_ARMING_FLAG(ARMED); #ifdef USE_BLACKBOX @@ -509,6 +511,11 @@ void releaseSharedTelemetryPorts(void) { } } +bool emergInflightRearmEnabled(void) +{ + return millis() < emergInflightRearmTimeout; +} + void tryArm(void) { updateArmingStatus(); @@ -529,9 +536,10 @@ void tryArm(void) #endif #ifdef USE_PROGRAMMING_FRAMEWORK - if (!isArmingDisabled() || emergencyArmingIsEnabled() || LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY)) { + if (!isArmingDisabled() || emergencyArmingIsEnabled() || emergInflightRearmEnabled() || + LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY)) { #else - if (!isArmingDisabled() || emergencyArmingIsEnabled()) { + if (!isArmingDisabled() || emergencyArmingIsEnabled() || emergInflightRearmEnabled()) { #endif // If nav_extra_arming_safety was bypassed we always // allow bypassing it even without the sticks set @@ -837,7 +845,7 @@ static float calculateThrottleTiltCompensationFactor(uint8_t throttleTiltCompens void taskMainPidLoop(timeUs_t currentTimeUs) { - + cycleTime = getTaskDeltaTime(TASK_SELF); dT = (float)cycleTime * 0.000001f; diff --git a/src/main/fc/fc_core.h b/src/main/fc/fc_core.h index 37d0bbda79..1d34e31742 100644 --- a/src/main/fc/fc_core.h +++ b/src/main/fc/fc_core.h @@ -43,6 +43,7 @@ void tryArm(void); disarmReason_t getDisarmReason(void); bool emergencyArmingUpdate(bool armingSwitchIsOn); +bool emergInflightRearmEnabled(void); bool areSensorsCalibrating(void); float getFlightTime(void); diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index d8bc20554c..04c910aa63 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -228,6 +228,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, static navWapointHeading_t wpHeadingControl; navigationPosControl_t posControl; navSystemStatus_t NAV_Status; +static bool landingDetectorIsActive; EXTENDED_FASTRAM multicopterPosXyCoefficients_t multicopterPosXyCoefficients; @@ -2803,14 +2804,14 @@ void updateLandingStatus(timeMs_t currentTimeMs) } lastUpdateTimeMs = currentTimeMs; - static bool landingDetectorIsActive; - DEBUG_SET(DEBUG_LANDING, 0, landingDetectorIsActive); DEBUG_SET(DEBUG_LANDING, 1, STATE(LANDING_DETECTED)); if (!ARMING_FLAG(ARMED)) { - resetLandingDetector(); - landingDetectorIsActive = false; + if (!emergInflightRearmEnabled()) { + resetLandingDetector(); + landingDetectorIsActive = false; + } if (!IS_RC_MODE_ACTIVE(BOXARM)) { DISABLE_ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED); } @@ -2852,6 +2853,15 @@ bool isFlightDetected(void) return STATE(AIRPLANE) ? isFixedWingFlying() : isMulticopterFlying(); } +bool isProbablyStillFlying(void) +{ + bool inFlightSanityCheck = false; + if (STATE(AIRPLANE)) { + inFlightSanityCheck = isGPSHeadingValid(); + } + return landingDetectorIsActive && !STATE(LANDING_DETECTED) && inFlightSanityCheck; +} + /*----------------------------------------------------------- * Z-position controller *-----------------------------------------------------------*/ @@ -3801,7 +3811,7 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) canActivateWaypoint = false; // Launch mode can be activated if feature FW_LAUNCH is enabled or BOX is turned on prior to arming (avoid switching to LAUNCH in flight) - canActivateLaunchMode = isNavLaunchEnabled(); + canActivateLaunchMode = isNavLaunchEnabled() && (!sensors(SENSOR_GPS) || (sensors(SENSOR_GPS) && !isGPSHeadingValid())); } return NAV_FSM_EVENT_SWITCH_TO_IDLE; diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index cf4289e14a..9ffe532e6c 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -610,6 +610,7 @@ const char * fixedWingLaunchStateMessage(void); float calculateAverageSpeed(void); void updateLandingStatus(timeMs_t currentTimeMs); +bool isProbablyStillFlying(void); const navigationPIDControllers_t* getNavigationPIDControllers(void); diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 91354d97ae..7b55a48e6a 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -692,7 +692,7 @@ bool isFixedWingFlying(void) bool velCondition = posControl.actualState.velXY > 250.0f || airspeed > 250.0f; bool launchCondition = isNavLaunchEnabled() && fixedWingLaunchStatus() == FW_LAUNCH_FLYING; - return (isImuHeadingValid() && throttleCondition && velCondition) || launchCondition; + return (isGPSHeadingValid() && throttleCondition && velCondition) || launchCondition; } /*----------------------------------------------------------- From 8f5d78376649e18b9be92c61807cbd8fd4ee8bea Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Tue, 22 Aug 2023 17:31:23 +0100 Subject: [PATCH 061/175] Initial cut - Separated HD and SD arming screen - Added symbol for pilot logo - Switched space indents to tabs in osd_symbols.h --- src/main/drivers/osd_symbols.h | 416 +++++++++++++++++---------------- src/main/io/osd.c | 27 ++- 2 files changed, 234 insertions(+), 209 deletions(-) diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index a127234579..8dfaa10186 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -23,243 +23,247 @@ #if defined(USE_OSD) || defined(OSD_UNIT_TEST) -#define SYM_RSSI 0x01 // 001 Icon RSSI -#define SYM_LQ 0x02 // 002 LQ -#define SYM_LAT 0x03 // 003 GPS LAT -#define SYM_LON 0x04 // 004 GPS LON -#define SYM_AZIMUTH 0x05 // 005 Azimuth -#define SYM_TELEMETRY_0 0x06 // 006 Antenna tracking telemetry -#define SYM_TELEMETRY_1 0x07 // 007 Antenna tracking telemetry -#define SYM_SAT_L 0x08 // 008 Sats left -#define SYM_SAT_R 0x09 // 009 Sats right -#define SYM_HOME_NEAR 0x0A // 010 Home, near -#define SYM_DEGREES 0x0B // 011 ° heading angle -#define SYM_HEADING 0x0C // 012 Compass Heading symbol -#define SYM_SCALE 0x0D // 013 Map scale -#define SYM_HDP_L 0x0E // 014 HDOP left -#define SYM_HDP_R 0x0F // 015 HDOP right -#define SYM_HOME 0x10 // 016 Home icon -#define SYM_2RSS 0x11 // 017 RSSI 2 -#define SYM_DB 0x12 // 018 dB -#define SYM_DBM 0x13 // 019 dBm -#define SYM_SNR 0x14 // 020 SNR +#define SYM_RSSI 0x01 // 001 Icon RSSI +#define SYM_LQ 0x02 // 002 LQ +#define SYM_LAT 0x03 // 003 GPS LAT +#define SYM_LON 0x04 // 004 GPS LON +#define SYM_AZIMUTH 0x05 // 005 Azimuth +#define SYM_TELEMETRY_0 0x06 // 006 Antenna tracking telemetry +#define SYM_TELEMETRY_1 0x07 // 007 Antenna tracking telemetry +#define SYM_SAT_L 0x08 // 008 Sats left +#define SYM_SAT_R 0x09 // 009 Sats right +#define SYM_HOME_NEAR 0x0A // 010 Home, near +#define SYM_DEGREES 0x0B // 011 ° heading angle +#define SYM_HEADING 0x0C // 012 Compass Heading symbol +#define SYM_SCALE 0x0D // 013 Map scale +#define SYM_HDP_L 0x0E // 014 HDOP left +#define SYM_HDP_R 0x0F // 015 HDOP right +#define SYM_HOME 0x10 // 016 Home icon +#define SYM_2RSS 0x11 // 017 RSSI 2 +#define SYM_DB 0x12 // 018 dB +#define SYM_DBM 0x13 // 019 dBm +#define SYM_SNR 0x14 // 020 SNR -#define SYM_AH_DIRECTION_UP 0x15 // 021 Arrow up AHI -#define SYM_AH_DIRECTION_DOWN 0x16 // 022 Arrow down AHI -#define SYM_DIRECTION 0x17 // 023 to 030, directional little arrows +#define SYM_AH_DIRECTION_UP 0x15 // 021 Arrow up AHI +#define SYM_AH_DIRECTION_DOWN 0x16 // 022 Arrow down AHI +#define SYM_DIRECTION 0x17 // 023 to 030, directional little arrows -#define SYM_VOLT 0x1F // 031 VOLTS -#define SYM_MAH 0x99 // 153 mAh -// 0x21 // 033 ASCII ! -#define SYM_AH_KM 0x22 // 034 Ah/km -// 0x23 // 035 ASCII # -#define SYM_AH_MI 0x24 // 036 Ah/mi -// 0x25 // 037 ASCII % -// 0x26 // 038 ASCII & -#define SYM_VTX_POWER 0x27 // 039 VTx Power -// 0x28 // 040 to 062 ASCII -#define SYM_AH_NM 0x3F // 063 Ah/NM -// 0x40 // 064 to 095 ASCII -#define SYM_MAH_NM_0 0x60 // 096 mAh/NM left -#define SYM_MAH_NM_1 0x61 // 097 mAh/NM right -#define SYM_MAH_KM_0 0x6B // 107 MAH/KM left -#define SYM_MAH_KM_1 0x6C // 108 MAH/KM right -#define SYM_MILLIOHM 0x62 // 098 battery impedance Mohm +#define SYM_VOLT 0x1F // 031 VOLTS +#define SYM_MAH 0x99 // 153 mAh +// 0x21 // 033 ASCII ! +#define SYM_AH_KM 0x22 // 034 Ah/km +// 0x23 // 035 ASCII # +#define SYM_AH_MI 0x24 // 036 Ah/mi +// 0x25 // 037 ASCII % +// 0x26 // 038 ASCII & +#define SYM_VTX_POWER 0x27 // 039 VTx Power +// 0x28 // 040 to 062 ASCII +#define SYM_AH_NM 0x3F // 063 Ah/NM +// 0x40 // 064 to 095 ASCII +#define SYM_MAH_NM_0 0x60 // 096 mAh/NM left +#define SYM_MAH_NM_1 0x61 // 097 mAh/NM right +#define SYM_MAH_KM_0 0x6B // 107 MAH/KM left +#define SYM_MAH_KM_1 0x6C // 108 MAH/KM right +#define SYM_MILLIOHM 0x62 // 098 battery impedance Mohm -#define SYM_BATT_FULL 0x63 // 099 Battery full -#define SYM_BATT_5 0x64 // 100 Battery -#define SYM_BATT_4 0x65 // 101 Battery -#define SYM_BATT_3 0x66 // 102 Battery -#define SYM_BATT_2 0x67 // 103 Battery -#define SYM_BATT_1 0x68 // 104 Battery -#define SYM_BATT_EMPTY 0x69 // 105 Battery empty +#define SYM_BATT_FULL 0x63 // 099 Battery full +#define SYM_BATT_5 0x64 // 100 Battery +#define SYM_BATT_4 0x65 // 101 Battery +#define SYM_BATT_3 0x66 // 102 Battery +#define SYM_BATT_2 0x67 // 103 Battery +#define SYM_BATT_1 0x68 // 104 Battery +#define SYM_BATT_EMPTY 0x69 // 105 Battery empty -#define SYM_AMP 0x6A // 106 AMPS -#define SYM_WH 0x6D // 109 WH -#define SYM_WH_KM 0x6E // 110 WH/KM -#define SYM_WH_MI 0x6F // 111 WH/MI -#define SYM_WH_NM 0x70 // 112 Wh/NM -#define SYM_WATT 0x71 // 113 WATTS -#define SYM_MW 0x72 // 114 mW -#define SYM_KILOWATT 0x73 // 115 kW +#define SYM_AMP 0x6A // 106 AMPS +#define SYM_WH 0x6D // 109 WH +#define SYM_WH_KM 0x6E // 110 WH/KM +#define SYM_WH_MI 0x6F // 111 WH/MI +#define SYM_WH_NM 0x70 // 112 Wh/NM +#define SYM_WATT 0x71 // 113 WATTS +#define SYM_MW 0x72 // 114 mW +#define SYM_KILOWATT 0x73 // 115 kW -#define SYM_FT 0x74 // 116 FEET -#define SYM_TRIP_DIST 0x75 // 117 Trip distance -#define SYM_TOTAL 0x75 // 117 Total -#define SYM_ALT_M 0x76 // 118 ALT M -#define SYM_ALT_KM 0x77 // 119 ALT KM -#define SYM_ALT_FT 0x78 // 120 ALT FT -#define SYM_ALT_KFT 0x79 // 121 Alt KFT -#define SYM_DIST_M 0x7A // 122 DIS M -// 0x7B // 123 to 125 ASCII -#define SYM_DIST_KM 0x7E // 126 DIST KM -#define SYM_DIST_FT 0x7F // 127 DIST FT -#define SYM_DIST_MI 0x80 // 128 DIST MI -#define SYM_DIST_NM 0x81 // 129 DIST NM -#define SYM_M 0x82 // 130 M -#define SYM_KM 0x83 // 131 KM -#define SYM_MI 0x84 // 132 MI -#define SYM_NM 0x85 // 133 NM +#define SYM_FT 0x74 // 116 FEET +#define SYM_TRIP_DIST 0x75 // 117 Trip distance +#define SYM_TOTAL 0x75 // 117 Total +#define SYM_ALT_M 0x76 // 118 ALT M +#define SYM_ALT_KM 0x77 // 119 ALT KM +#define SYM_ALT_FT 0x78 // 120 ALT FT +#define SYM_ALT_KFT 0x79 // 121 Alt KFT +#define SYM_DIST_M 0x7A // 122 DIS M +// 0x7B // 123 to 125 ASCII +#define SYM_DIST_KM 0x7E // 126 DIST KM +#define SYM_DIST_FT 0x7F // 127 DIST FT +#define SYM_DIST_MI 0x80 // 128 DIST MI +#define SYM_DIST_NM 0x81 // 129 DIST NM +#define SYM_M 0x82 // 130 M +#define SYM_KM 0x83 // 131 KM +#define SYM_MI 0x84 // 132 MI +#define SYM_NM 0x85 // 133 NM -#define SYM_WIND_HORIZONTAL 0x86 // 134 Air speed horizontal -#define SYM_WIND_VERTICAL 0x87 // 135 Air speed vertical -#define SYM_3D_KMH 0x88 // 136 KM/H 3D -#define SYM_3D_MPH 0x89 // 137 MPH 3D -#define SYM_3D_KT 0x8A // 138 Knots 3D -#define SYM_RPM 0x8B // 139 RPM -#define SYM_AIR 0x8C // 140 Air speed -#define SYM_FTS 0x8D // 141 FT/S -#define SYM_100FTM 0x8E // 142 100 Feet per Min -#define SYM_MS 0x8F // 143 M/S -#define SYM_KMH 0x90 // 144 KM/H -#define SYM_MPH 0x91 // 145 MPH -#define SYM_KT 0x92 // 146 Knots +#define SYM_WIND_HORIZONTAL 0x86 // 134 Air speed horizontal +#define SYM_WIND_VERTICAL 0x87 // 135 Air speed vertical +#define SYM_3D_KMH 0x88 // 136 KM/H 3D +#define SYM_3D_MPH 0x89 // 137 MPH 3D +#define SYM_3D_KT 0x8A // 138 Knots 3D +#define SYM_RPM 0x8B // 139 RPM +#define SYM_AIR 0x8C // 140 Air speed +#define SYM_FTS 0x8D // 141 FT/S +#define SYM_100FTM 0x8E // 142 100 Feet per Min +#define SYM_MS 0x8F // 143 M/S +#define SYM_KMH 0x90 // 144 KM/H +#define SYM_MPH 0x91 // 145 MPH +#define SYM_KT 0x92 // 146 Knots -#define SYM_MAH_MI_0 0x93 // 147 mAh/mi left -#define SYM_MAH_MI_1 0x94 // 148 mAh/mi right -#define SYM_THR 0x95 // 149 Throttle -#define SYM_TEMP_F 0x96 // 150 °F -#define SYM_TEMP_C 0x97 // 151 °C -// 0x98 // 152 Home point map -#define SYM_BLANK 0x20 // 32 blank (space) -#define SYM_ON_H 0x9A // 154 ON HR -#define SYM_FLY_H 0x9B // 155 FLY HR -#define SYM_ON_M 0x9E // 158 On MIN -#define SYM_FLY_M 0x9F // 159 FL MIN -#define SYM_GLIDESLOPE 0x9C // 156 Glideslope -#define SYM_WAYPOINT 0x9D // 157 Waypoint -#define SYM_CLOCK 0xA0 // 160 Clock +#define SYM_MAH_MI_0 0x93 // 147 mAh/mi left +#define SYM_MAH_MI_1 0x94 // 148 mAh/mi right +#define SYM_THR 0x95 // 149 Throttle +#define SYM_TEMP_F 0x96 // 150 °F +#define SYM_TEMP_C 0x97 // 151 °C +// 0x98 // 152 Home point map +#define SYM_BLANK 0x20 // 32 blank (space) +#define SYM_ON_H 0x9A // 154 ON HR +#define SYM_FLY_H 0x9B // 155 FLY HR +#define SYM_ON_M 0x9E // 158 On MIN +#define SYM_FLY_M 0x9F // 159 FL MIN +#define SYM_GLIDESLOPE 0x9C // 156 Glideslope +#define SYM_WAYPOINT 0x9D // 157 Waypoint +#define SYM_CLOCK 0xA0 // 160 Clock -#define SYM_ZERO_HALF_TRAILING_DOT 0xA1 // 161 to 170 Numbers with trailing dot -#define SYM_ZERO_HALF_LEADING_DOT 0xB1 // 177 to 186 Numbers with leading dot +#define SYM_ZERO_HALF_TRAILING_DOT 0xA1 // 161 to 170 Numbers with trailing dot +#define SYM_ZERO_HALF_LEADING_DOT 0xB1 // 177 to 186 Numbers with leading dot -#define SYM_AUTO_THR0 0xAB // 171 Auto-throttle left -#define SYM_AUTO_THR1 0xAC // 172 Auto-throttle right -#define SYM_ROLL_LEFT 0xAD // 173 Sym roll left -#define SYM_ROLL_LEVEL 0xAE // 174 Sym roll horizontal -#define SYM_ROLL_RIGHT 0xAF // 175 Sym roll right -#define SYM_PITCH_UP 0xB0 // 176 Pitch up -#define SYM_PITCH_DOWN 0xBB // 187 Pitch down -#define SYM_GFORCE 0xBC // 188 Gforce (all axis) -#define SYM_GFORCE_X 0xBD // 189 Gforce X -#define SYM_GFORCE_Y 0xBE // 190 Gforce Y -#define SYM_GFORCE_Z 0xBF // 191 Gforce Z +#define SYM_AUTO_THR0 0xAB // 171 Auto-throttle left +#define SYM_AUTO_THR1 0xAC // 172 Auto-throttle right +#define SYM_ROLL_LEFT 0xAD // 173 Sym roll left +#define SYM_ROLL_LEVEL 0xAE // 174 Sym roll horizontal +#define SYM_ROLL_RIGHT 0xAF // 175 Sym roll right +#define SYM_PITCH_UP 0xB0 // 176 Pitch up +#define SYM_PITCH_DOWN 0xBB // 187 Pitch down +#define SYM_GFORCE 0xBC // 188 Gforce (all axis) +#define SYM_GFORCE_X 0xBD // 189 Gforce X +#define SYM_GFORCE_Y 0xBE // 190 Gforce Y +#define SYM_GFORCE_Z 0xBF // 191 Gforce Z -#define SYM_BARO_TEMP 0xC0 // 192 -#define SYM_IMU_TEMP 0xC1 // 193 -#define SYM_TEMP 0xC2 // 194 Thermometer icon -#define SYM_TEMP_SENSOR_FIRST 0xC2 // 194 -#define SYM_ESC_TEMP 0xC3 // 195 -#define SYM_TEMP_SENSOR_LAST 0xC7 // 199 +#define SYM_BARO_TEMP 0xC0 // 192 +#define SYM_IMU_TEMP 0xC1 // 193 +#define SYM_TEMP 0xC2 // 194 Thermometer icon +#define SYM_TEMP_SENSOR_FIRST 0xC2 // 194 +#define SYM_ESC_TEMP 0xC3 // 195 +#define SYM_TEMP_SENSOR_LAST 0xC7 // 199 #define TEMP_SENSOR_SYM_COUNT (SYM_TEMP_SENSOR_LAST - SYM_TEMP_SENSOR_FIRST + 1) -#define SYM_HEADING_N 0xC8 // 200 Heading Graphic north -#define SYM_HEADING_S 0xC9 // 201 Heading Graphic south -#define SYM_HEADING_E 0xCA // 202 Heading Graphic east -#define SYM_HEADING_W 0xCB // 203 Heading Graphic west -#define SYM_HEADING_DIVIDED_LINE 0xCC // 204 Heading Graphic -#define SYM_HEADING_LINE 0xCD // 205 Heading Graphic -#define SYM_MAX 0xCE // 206 MAX symbol -#define SYM_PROFILE 0xCF // 207 Profile symbol -#define SYM_SWITCH_INDICATOR_LOW 0xD0 // 208 Switch High -#define SYM_SWITCH_INDICATOR_MID 0xD1 // 209 Switch Mid -#define SYM_SWITCH_INDICATOR_HIGH 0xD2 // 210 Switch Low -#define SYM_AH 0xD3 // 211 Amphours symbol -#define SYM_GLIDE_DIST 0xD4 // 212 Glide Distance -#define SYM_GLIDE_MINS 0xD5 // 213 Glide Minutes -#define SYM_AH_V_FT_0 0xD6 // 214 mAh/v-ft left -#define SYM_AH_V_FT_1 0xD7 // 215 mAh/v-ft right -#define SYM_AH_V_M_0 0xD8 // 216 mAh/v-m left -#define SYM_AH_V_M_1 0xD9 // 217 mAh/v-m right -#define SYM_FLIGHT_MINS_REMAINING 0xDA // 218 Flight time (mins) remaining -#define SYM_FLIGHT_HOURS_REMAINING 0xDB // 219 Flight time (hours) remaining -#define SYM_GROUND_COURSE 0xDC // 220 Ground course -#define SYM_CROSS_TRACK_ERROR 0xFC // 252 Cross track error +#define SYM_HEADING_N 0xC8 // 200 Heading Graphic north +#define SYM_HEADING_S 0xC9 // 201 Heading Graphic south +#define SYM_HEADING_E 0xCA // 202 Heading Graphic east +#define SYM_HEADING_W 0xCB // 203 Heading Graphic west +#define SYM_HEADING_DIVIDED_LINE 0xCC // 204 Heading Graphic +#define SYM_HEADING_LINE 0xCD // 205 Heading Graphic +#define SYM_MAX 0xCE // 206 MAX symbol +#define SYM_PROFILE 0xCF // 207 Profile symbol +#define SYM_SWITCH_INDICATOR_LOW 0xD0 // 208 Switch High +#define SYM_SWITCH_INDICATOR_MID 0xD1 // 209 Switch Mid +#define SYM_SWITCH_INDICATOR_HIGH 0xD2 // 210 Switch Low +#define SYM_AH 0xD3 // 211 Amphours symbol +#define SYM_GLIDE_DIST 0xD4 // 212 Glide Distance +#define SYM_GLIDE_MINS 0xD5 // 213 Glide Minutes +#define SYM_AH_V_FT_0 0xD6 // 214 mAh/v-ft left +#define SYM_AH_V_FT_1 0xD7 // 215 mAh/v-ft right +#define SYM_AH_V_M_0 0xD8 // 216 mAh/v-m left +#define SYM_AH_V_M_1 0xD9 // 217 mAh/v-m right +#define SYM_FLIGHT_MINS_REMAINING 0xDA // 218 Flight time (mins) remaining +#define SYM_FLIGHT_HOURS_REMAINING 0xDB // 219 Flight time (hours) remaining +#define SYM_GROUND_COURSE 0xDC // 220 Ground course +#define SYM_CROSS_TRACK_ERROR 0xFC // 252 Cross track error -#define SYM_LOGO_START 0x101 // 257 to 297, INAV logo -#define SYM_LOGO_WIDTH 10 -#define SYM_LOGO_HEIGHT 4 +#define SYM_LOGO_START 0x101 // 257 to 297, INAV logo +#define SYM_LOGO_WIDTH 10 +#define SYM_LOGO_HEIGHT 4 -#define SYM_AH_LEFT 0x12C // 300 Arrow left -#define SYM_AH_RIGHT 0x12D // 301 Arrow right -#define SYM_AH_DECORATION_MIN 0x12E // 302 to 307 Scrolling -#define SYM_AH_DECORATION 0x131 // 305 Scrolling -#define SYM_AH_DECORATION_MAX 0x133 // 307 Scrolling +#define SYM_AH_LEFT 0x12C // 300 Arrow left +#define SYM_AH_RIGHT 0x12D // 301 Arrow right +#define SYM_AH_DECORATION_MIN 0x12E // 302 to 307 Scrolling +#define SYM_AH_DECORATION 0x131 // 305 Scrolling +#define SYM_AH_DECORATION_MAX 0x133 // 307 Scrolling #define SYM_AH_DECORATION_COUNT (SYM_AH_DECORATION_MAX - SYM_AH_DECORATION_MIN + 1) // Scrolling -#define SYM_AH_CH_LEFT 0x13A // 314 Crossair left -#define SYM_AH_CH_RIGHT 0x13B // 315 Crossair right +#define SYM_AH_CH_LEFT 0x13A // 314 Crossair left +#define SYM_AH_CH_RIGHT 0x13B // 315 Crossair right -#define SYM_ARROW_UP 0x13C // 316 Direction arrow 0° -#define SYM_ARROW_2 0x13D // 317 Direction arrow 22.5° -#define SYM_ARROW_3 0x13E // 318 Direction arrow 45° -#define SYM_ARROW_4 0x13F // 319 Direction arrow 67.5° -#define SYM_ARROW_RIGHT 0x140 // 320 Direction arrow 90° -#define SYM_ARROW_6 0x141 // 321 Direction arrow 112.5° -#define SYM_ARROW_7 0x142 // 322 Direction arrow 135° -#define SYM_ARROW_8 0x143 // 323 Direction arrow 157.5° -#define SYM_ARROW_DOWN 0x144 // 324 Direction arrow 180° -#define SYM_ARROW_10 0x145 // 325 Direction arrow 202.5° -#define SYM_ARROW_11 0x146 // 326 Direction arrow 225° -#define SYM_ARROW_12 0x147 // 327 Direction arrow 247.5° -#define SYM_ARROW_LEFT 0x148 // 328 Direction arrow 270° -#define SYM_ARROW_14 0x149 // 329 Direction arrow 292.5° -#define SYM_ARROW_15 0x14A // 330 Direction arrow 315° -#define SYM_ARROW_16 0x14B // 331 Direction arrow 337.5° +#define SYM_ARROW_UP 0x13C // 316 Direction arrow 0° +#define SYM_ARROW_2 0x13D // 317 Direction arrow 22.5° +#define SYM_ARROW_3 0x13E // 318 Direction arrow 45° +#define SYM_ARROW_4 0x13F // 319 Direction arrow 67.5° +#define SYM_ARROW_RIGHT 0x140 // 320 Direction arrow 90° +#define SYM_ARROW_6 0x141 // 321 Direction arrow 112.5° +#define SYM_ARROW_7 0x142 // 322 Direction arrow 135° +#define SYM_ARROW_8 0x143 // 323 Direction arrow 157.5° +#define SYM_ARROW_DOWN 0x144 // 324 Direction arrow 180° +#define SYM_ARROW_10 0x145 // 325 Direction arrow 202.5° +#define SYM_ARROW_11 0x146 // 326 Direction arrow 225° +#define SYM_ARROW_12 0x147 // 327 Direction arrow 247.5° +#define SYM_ARROW_LEFT 0x148 // 328 Direction arrow 270° +#define SYM_ARROW_14 0x149 // 329 Direction arrow 292.5° +#define SYM_ARROW_15 0x14A // 330 Direction arrow 315° +#define SYM_ARROW_16 0x14B // 331 Direction arrow 337.5° -#define SYM_AH_H_START 0x14C // 332 to 340 Horizontal AHI -#define SYM_AH_V_START 0x15A // 346 to 351 Vertical AHI +#define SYM_AH_H_START 0x14C // 332 to 340 Horizontal AHI +#define SYM_AH_V_START 0x15A // 346 to 351 Vertical AHI -#define SYM_VARIO_UP_2A 0x155 // 341 Vario up up -#define SYM_VARIO_UP_1A 0x156 // 342 Vario up -#define SYM_VARIO_DOWN_1A 0x157 // 343 Vario down -#define SYM_VARIO_DOWN_2A 0x158 // 344 Vario down down -#define SYM_ALT 0x159 // 345 ALT +#define SYM_VARIO_UP_2A 0x155 // 341 Vario up up +#define SYM_VARIO_UP_1A 0x156 // 342 Vario up +#define SYM_VARIO_DOWN_1A 0x157 // 343 Vario down +#define SYM_VARIO_DOWN_2A 0x158 // 344 Vario down down +#define SYM_ALT 0x159 // 345 ALT -#define SYM_HUD_SIGNAL_0 0x160 // 352 Hud signal icon Lost -#define SYM_HUD_SIGNAL_1 0x161 // 353 Hud signal icon 25% -#define SYM_HUD_SIGNAL_2 0x162 // 354 Hud signal icon 50% -#define SYM_HUD_SIGNAL_3 0x163 // 355 Hud signal icon 75% -#define SYM_HUD_SIGNAL_4 0x164 // 356 Hud signal icon 100% +#define SYM_HUD_SIGNAL_0 0x160 // 352 Hud signal icon Lost +#define SYM_HUD_SIGNAL_1 0x161 // 353 Hud signal icon 25% +#define SYM_HUD_SIGNAL_2 0x162 // 354 Hud signal icon 50% +#define SYM_HUD_SIGNAL_3 0x163 // 355 Hud signal icon 75% +#define SYM_HUD_SIGNAL_4 0x164 // 356 Hud signal icon 100% -#define SYM_HOME_DIST 0x165 // 357 DIST -#define SYM_AH_CH_CENTER 0x166 // 358 Crossair center -#define SYM_FLIGHT_DIST_REMAINING 0x167 // 359 Flight distance reminaing +#define SYM_HOME_DIST 0x165 // 357 DIST +#define SYM_AH_CH_CENTER 0x166 // 358 Crossair center +#define SYM_FLIGHT_DIST_REMAINING 0x167 // 359 Flight distance reminaing -#define SYM_AH_CH_TYPE3 0x190 // 400 to 402, crosshair 3 -#define SYM_AH_CH_TYPE4 0x193 // 403 to 405, crosshair 4 -#define SYM_AH_CH_TYPE5 0x196 // 406 to 408, crosshair 5 -#define SYM_AH_CH_TYPE6 0x199 // 409 to 411, crosshair 6 -#define SYM_AH_CH_TYPE7 0x19C // 412 to 414, crosshair 7 -#define SYM_AH_CH_TYPE8 0x19F // 415 to 417, crosshair 8 +#define SYM_AH_CH_TYPE3 0x190 // 400 to 402, crosshair 3 +#define SYM_AH_CH_TYPE4 0x193 // 403 to 405, crosshair 4 +#define SYM_AH_CH_TYPE5 0x196 // 406 to 408, crosshair 5 +#define SYM_AH_CH_TYPE6 0x199 // 409 to 411, crosshair 6 +#define SYM_AH_CH_TYPE7 0x19C // 412 to 414, crosshair 7 +#define SYM_AH_CH_TYPE8 0x19F // 415 to 417, crosshair 8 -#define SYM_AH_CH_AIRCRAFT0 0x1A2 // 418 Crossair aircraft left -#define SYM_AH_CH_AIRCRAFT1 0x1A3 // 419 Crossair aircraft -#define SYM_AH_CH_AIRCRAFT2 0x1A4 // 420 Crossair aircraft center -#define SYM_AH_CH_AIRCRAFT3 0x1A5 // 421 Crossair aircraft -#define SYM_AH_CH_AIRCRAFT4 0x1A6 // 422 Crossair aircraft RIGHT +#define SYM_AH_CH_AIRCRAFT0 0x1A2 // 418 Crossair aircraft left +#define SYM_AH_CH_AIRCRAFT1 0x1A3 // 419 Crossair aircraft +#define SYM_AH_CH_AIRCRAFT2 0x1A4 // 420 Crossair aircraft center +#define SYM_AH_CH_AIRCRAFT3 0x1A5 // 421 Crossair aircraft +#define SYM_AH_CH_AIRCRAFT4 0x1A6 // 422 Crossair aircraft RIGHT -#define SYM_HUD_ARROWS_L1 0x1AE // 430 1 arrow left -#define SYM_HUD_ARROWS_L2 0x1AF // 431 2 arrows left -#define SYM_HUD_ARROWS_L3 0x1B0 // 432 3 arrows left -#define SYM_HUD_ARROWS_R1 0x1B1 // 433 1 arrow right -#define SYM_HUD_ARROWS_R2 0x1B2 // 434 2 arrows right -#define SYM_HUD_ARROWS_R3 0x1B3 // 435 3 arrows right -#define SYM_HUD_ARROWS_U1 0x1B4 // 436 1 arrow up -#define SYM_HUD_ARROWS_U2 0x1B5 // 437 2 arrows up -#define SYM_HUD_ARROWS_U3 0x1B6 // 438 3 arrows up -#define SYM_HUD_ARROWS_D1 0x1B7 // 439 1 arrow down -#define SYM_HUD_ARROWS_D2 0x1B8 // 440 2 arrows down -#define SYM_HUD_ARROWS_D3 0x1B9 // 441 3 arrows down +#define SYM_HUD_ARROWS_L1 0x1AE // 430 1 arrow left +#define SYM_HUD_ARROWS_L2 0x1AF // 431 2 arrows left +#define SYM_HUD_ARROWS_L3 0x1B0 // 432 3 arrows left +#define SYM_HUD_ARROWS_R1 0x1B1 // 433 1 arrow right +#define SYM_HUD_ARROWS_R2 0x1B2 // 434 2 arrows right +#define SYM_HUD_ARROWS_R3 0x1B3 // 435 3 arrows right +#define SYM_HUD_ARROWS_U1 0x1B4 // 436 1 arrow up +#define SYM_HUD_ARROWS_U2 0x1B5 // 437 2 arrows up +#define SYM_HUD_ARROWS_U3 0x1B6 // 438 3 arrows up +#define SYM_HUD_ARROWS_D1 0x1B7 // 439 1 arrow down +#define SYM_HUD_ARROWS_D2 0x1B8 // 440 2 arrows down +#define SYM_HUD_ARROWS_D3 0x1B9 // 441 3 arrows down -#define SYM_HUD_CARDINAL 0x1BA // 442-453 Cardinal direction in 30 degree segments +#define SYM_HUD_CARDINAL 0x1BA // 442-453 Cardinal direction in 30 degree segments #define SYM_SERVO_PAN_IS_CENTRED 0x1C6 // 454 Pan servo is centred #define SYM_SERVO_PAN_IS_OFFSET_L 0x1C7 // 455 Pan servo is offset left #define SYM_SERVO_PAN_IS_OFFSET_R 0x1C8 // 456 Pan servo is offset right +#define SYM_PILOT_LOGO_SML_L 0x1D7 // 471 small Pilot logo L +#define SYM_PILOT_LOGO_SML_R 0x1D8 // 471 small Pilot logo R +#define SYM_PILOT_LOGO_LRG_START 0x1D9 // 473 to 511, Pilot logo + #else -#define TEMP_SENSOR_SYM_COUNT 0 +#define TEMP_SENSOR_SYM_COUNT 0 #endif // USE_OSD diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 947c03845d..b3edc03f05 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -4355,8 +4355,18 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) displayCommitTransaction(osdDisplayPort); } -// called when motors armed -static void osdShowArmed(void) +// HD arming screen. based on the minimum HD OSD grid size of 50 x 18 +static void osdShowHDArmScreen(void) +{ + dateTime_t dt; + char buf[MAX(32, FORMATTED_DATE_TIME_BUFSIZE)]; + char craftNameBuf[MAX_NAME_LENGTH]; + char versionBuf[30]; + char *date; + char *time; +} + +static void osdShowSDArmScreen(void) { dateTime_t dt; char buf[MAX(32, FORMATTED_DATE_TIME_BUFSIZE)]; @@ -4367,7 +4377,6 @@ static void osdShowArmed(void) // We need 12 visible rows, start row never < first fully visible row 1 uint8_t y = osdDisplayPort->rows > 13 ? (osdDisplayPort->rows - 12) / 2 : 1; - displayClearScreen(osdDisplayPort); strcpy(buf, "ARMED"); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); y += 2; @@ -4436,6 +4445,18 @@ static void osdShowArmed(void) displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, y, versionBuf); } +// called when motors armed +static void osdShowArmed(void) +{ + displayClearScreen(osdDisplayPort); + + if (osdDisplayPort->rows >= OSD_STATS_SINGLE_PAGE_MIN_ROWS) { + osdShowHDArmScreen(); + } else { + osdShowSDArmScreen(); + } +} + static void osdFilterData(timeUs_t currentTimeUs) { static timeUs_t lastRefresh = 0; float refresh_dT = US2S(cmpTimeUs(currentTimeUs, lastRefresh)); From 3b9e2a24ff26e697af412c000741bf3998466989 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Wed, 23 Aug 2023 15:07:20 +0100 Subject: [PATCH 062/175] add MR flight sanity and forced Angle --- src/main/fc/fc_core.c | 67 +++++++++++++++++++------------- src/main/navigation/navigation.c | 7 ++-- 2 files changed, 44 insertions(+), 30 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 46ef140f84..187613a9ee 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -104,6 +104,7 @@ enum { #define EMERGENCY_ARMING_TIME_WINDOW_MS 10000 #define EMERGENCY_ARMING_COUNTER_STEP_MS 1000 #define EMERGENCY_ARMING_MIN_ARM_COUNT 10 +#define EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS 5000 timeDelta_t cycleTime = 0; // this is the number in micro second to achieve a full loop, it can differ a little and is taken into account in the PID loop static timeUs_t flightTime = 0; @@ -119,6 +120,7 @@ static bool isRXDataNew; static disarmReason_t lastDisarmReason = DISARM_NONE; timeUs_t lastDisarmTimeUs = 0; timeMs_t emergInflightRearmTimeout = 0; +timeMs_t mcEmergRearmStabiliseTimeout = 0; static bool prearmWasReset = false; // Prearm must be reset (RC Mode not active) before arming is possible static timeMs_t prearmActivationTime = 0; @@ -314,11 +316,11 @@ static void updateArmingStatus(void) /* CHECK: Do not allow arming if Servo AutoTrim is enabled */ if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) { - ENABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM); - } + ENABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM); + } else { - DISABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM); - } + DISABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM); + } #ifdef USE_DSHOT /* CHECK: Don't arm if the DShot beeper was used recently, as there is a minimum delay before sending the next DShot command */ @@ -433,7 +435,7 @@ void disarm(disarmReason_t disarmReason) if (ARMING_FLAG(ARMED)) { lastDisarmReason = disarmReason; lastDisarmTimeUs = micros(); - emergInflightRearmTimeout = US2MS(lastDisarmTimeUs) + (isProbablyStillFlying() ? 5000 : 0); + emergInflightRearmTimeout = US2MS(lastDisarmTimeUs) + (isProbablyStillFlying() ? EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS : 0); DISABLE_ARMING_FLAG(ARMED); #ifdef USE_BLACKBOX @@ -501,19 +503,20 @@ bool emergencyArmingUpdate(bool armingSwitchIsOn) return counter >= EMERGENCY_ARMING_MIN_ARM_COUNT; } -#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK | FUNCTION_TELEMETRY_IBUS) - -void releaseSharedTelemetryPorts(void) { - serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP); - while (sharedPort) { - mspSerialReleasePortIfAllocated(sharedPort); - sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP); - } -} - bool emergInflightRearmEnabled(void) { - return millis() < emergInflightRearmTimeout; + /* Emergency rearm allowed within emergInflightRearmTimeout window. + * On MR emergency rearm only allowed after 1.5s if MR dropping after disarm, i.e. still in flight */ + timeMs_t currentTimeMs = millis(); + if (STATE(MULTIROTOR)) { + uint16_t mcFlightSanityCheckTime = EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS - 1500; // check MR vertical speed at least 2 sec after disarm + if (getEstimatedActualVelocity(Z) > -100.0f && (emergInflightRearmTimeout - currentTimeMs < mcFlightSanityCheckTime)) { + emergInflightRearmTimeout = currentTimeMs; // MR doesn't appear to be flying so don't allow emergency rearm + } else { + mcEmergRearmStabiliseTimeout = currentTimeMs + 5000; // activate Angle mode for 5s after rearm to help stabilise MR + } + } + return currentTimeMs < emergInflightRearmTimeout; } void tryArm(void) @@ -594,6 +597,16 @@ void tryArm(void) } } +#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK | FUNCTION_TELEMETRY_IBUS) + +void releaseSharedTelemetryPorts(void) { + serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP); + while (sharedPort) { + mspSerialReleasePortIfAllocated(sharedPort); + sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP); + } +} + void processRx(timeUs_t currentTimeUs) { // Calculate RPY channel data @@ -644,9 +657,12 @@ void processRx(timeUs_t currentTimeUs) processRcAdjustments(CONST_CAST(controlRateConfig_t*, currentControlRateProfile), canUseRxData); } + // Angle mode forced on briefly after multirotor emergency in flight rearm to help stabilise attitude + bool mcEmergRearmAngleEnforce = STATE(MULTIROTOR) && mcEmergRearmStabiliseTimeout > millis(); + bool autoEnableAngle = failsafeRequiresAngleMode() || navigationRequiresAngleMode() || mcEmergRearmAngleEnforce; bool canUseHorizonMode = true; - if ((IS_RC_MODE_ACTIVE(BOXANGLE) || failsafeRequiresAngleMode() || navigationRequiresAngleMode()) && sensors(SENSOR_ACC)) { + if (sensors(SENSOR_ACC) && (IS_RC_MODE_ACTIVE(BOXANGLE) || autoEnableAngle)) { // bumpless transfer to Level mode canUseHorizonMode = false; @@ -813,7 +829,6 @@ void processRx(timeUs_t currentTimeUs) } } #endif - } // Function for loop trigger @@ -929,15 +944,15 @@ void taskMainPidLoop(timeUs_t currentTimeUs) //Servos should be filtered or written only when mixer is using servos or special feaures are enabled #ifdef USE_SIMULATOR - if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) { - if (isServoOutputEnabled()) { - writeServos(); - } + if (!ARMING_FLAG(SIMULATOR_MODE_HITL)) { + if (isServoOutputEnabled()) { + writeServos(); + } - if (motorControlEnable) { - writeMotors(); - } - } + if (motorControlEnable) { + writeMotors(); + } + } #else if (isServoOutputEnabled()) { writeServos(); diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 04c910aa63..96d99ebf3b 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2855,10 +2855,9 @@ bool isFlightDetected(void) bool isProbablyStillFlying(void) { - bool inFlightSanityCheck = false; - if (STATE(AIRPLANE)) { - inFlightSanityCheck = isGPSHeadingValid(); - } + // Multirotor flight sanity checked after disarm so always true here + bool inFlightSanityCheck = STATE(MULTIROTOR) || (STATE(AIRPLANE) && isGPSHeadingValid()); + return landingDetectorIsActive && !STATE(LANDING_DETECTED) && inFlightSanityCheck; } From 7bb9b69a5f5b89e5d75534248b0931929d0b990f Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Wed, 23 Aug 2023 22:16:45 +0100 Subject: [PATCH 063/175] Fix logic --- src/main/fc/fc_core.c | 24 +++++++++++++++++------- src/main/navigation/navigation.c | 7 +++---- 2 files changed, 20 insertions(+), 11 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 187613a9ee..60c658809e 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -435,7 +435,10 @@ void disarm(disarmReason_t disarmReason) if (ARMING_FLAG(ARMED)) { lastDisarmReason = disarmReason; lastDisarmTimeUs = micros(); - emergInflightRearmTimeout = US2MS(lastDisarmTimeUs) + (isProbablyStillFlying() ? EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS : 0); + if (disarmReason == DISARM_SWITCH || disarmReason == DISARM_KILLSWITCH) { + emergInflightRearmTimeout = isProbablyStillFlying() ? US2MS(lastDisarmTimeUs) + EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS : 0; + } + DISABLE_ARMING_FLAG(ARMED); #ifdef USE_BLACKBOX @@ -506,17 +509,23 @@ bool emergencyArmingUpdate(bool armingSwitchIsOn) bool emergInflightRearmEnabled(void) { /* Emergency rearm allowed within emergInflightRearmTimeout window. - * On MR emergency rearm only allowed after 1.5s if MR dropping after disarm, i.e. still in flight */ + * On MR emergency rearm only allowed after 1.5s if MR dropping or climbing after disarm, i.e. still in flight */ + timeMs_t currentTimeMs = millis(); + if (!emergInflightRearmTimeout || currentTimeMs > emergInflightRearmTimeout) { + return false; + } + if (STATE(MULTIROTOR)) { - uint16_t mcFlightSanityCheckTime = EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS - 1500; // check MR vertical speed at least 2 sec after disarm - if (getEstimatedActualVelocity(Z) > -100.0f && (emergInflightRearmTimeout - currentTimeMs < mcFlightSanityCheckTime)) { - emergInflightRearmTimeout = currentTimeMs; // MR doesn't appear to be flying so don't allow emergency rearm + uint16_t mcFlightSanityCheckTime = EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS - 1500; // check MR vertical speed at least 1.5 sec after disarm + if (fabsf(getEstimatedActualVelocity(Z)) < 100.0f && (emergInflightRearmTimeout - currentTimeMs < mcFlightSanityCheckTime)) { + return false; // MR doesn't appear to be flying so don't allow emergency rearm } else { mcEmergRearmStabiliseTimeout = currentTimeMs + 5000; // activate Angle mode for 5s after rearm to help stabilise MR } } - return currentTimeMs < emergInflightRearmTimeout; + + return true; } void tryArm(void) @@ -555,6 +564,7 @@ void tryArm(void) } lastDisarmReason = DISARM_NONE; + emergInflightRearmTimeout = 0; ENABLE_ARMING_FLAG(ARMED); ENABLE_ARMING_FLAG(WAS_EVER_ARMED); @@ -657,7 +667,7 @@ void processRx(timeUs_t currentTimeUs) processRcAdjustments(CONST_CAST(controlRateConfig_t*, currentControlRateProfile), canUseRxData); } - // Angle mode forced on briefly after multirotor emergency in flight rearm to help stabilise attitude + // Angle mode forced on briefly after multirotor emergency inflight rearm to help stabilise attitude bool mcEmergRearmAngleEnforce = STATE(MULTIROTOR) && mcEmergRearmStabiliseTimeout > millis(); bool autoEnableAngle = failsafeRequiresAngleMode() || navigationRequiresAngleMode() || mcEmergRearmAngleEnforce; bool canUseHorizonMode = true; diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 96d99ebf3b..759ddd42f3 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2808,10 +2808,9 @@ void updateLandingStatus(timeMs_t currentTimeMs) DEBUG_SET(DEBUG_LANDING, 1, STATE(LANDING_DETECTED)); if (!ARMING_FLAG(ARMED)) { - if (!emergInflightRearmEnabled()) { - resetLandingDetector(); - landingDetectorIsActive = false; - } + resetLandingDetector(); + landingDetectorIsActive = false; + if (!IS_RC_MODE_ACTIVE(BOXARM)) { DISABLE_ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED); } From ce44da742cd4839cc8a35c0c3118fbd6e0e678af Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Thu, 24 Aug 2023 15:44:22 +0100 Subject: [PATCH 064/175] Initial code update - Switch small pilot logo to 3 characters - Added base code for arm screen --- src/main/drivers/osd_symbols.h | 5 +- src/main/io/osd.c | 7670 ++++++++++++++++---------------- 2 files changed, 3887 insertions(+), 3788 deletions(-) diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index 8dfaa10186..a1b84d52b1 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -258,8 +258,9 @@ #define SYM_SERVO_PAN_IS_OFFSET_L 0x1C7 // 455 Pan servo is offset left #define SYM_SERVO_PAN_IS_OFFSET_R 0x1C8 // 456 Pan servo is offset right -#define SYM_PILOT_LOGO_SML_L 0x1D7 // 471 small Pilot logo L -#define SYM_PILOT_LOGO_SML_R 0x1D8 // 471 small Pilot logo R +#define SYM_PILOT_LOGO_SML_L 0x1D6 // 470 small Pilot logo Left +#define SYM_PILOT_LOGO_SML_C 0x1D7 // 471 small Pilot logo Centre +#define SYM_PILOT_LOGO_SML_R 0x1D8 // 472 small Pilot logo Right #define SYM_PILOT_LOGO_LRG_START 0x1D9 // 473 to 511, Pilot logo #else diff --git a/src/main/io/osd.c b/src/main/io/osd.c index b3edc03f05..f6289520bc 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -142,8 +142,8 @@ // Wrap all string constants intenteded for display as messages with // this macro to ensure compile time length validation. #define OSD_MESSAGE_STR(x) ({ \ - STATIC_ASSERT(_CONST_STR_SIZE(x) <= OSD_MESSAGE_LENGTH, message_string_ ## __COUNTER__ ## _too_long); \ - x; \ + STATIC_ASSERT(_CONST_STR_SIZE(x) <= OSD_MESSAGE_LENGTH, message_string_ ## __COUNTER__ ## _too_long); \ + x; \ }) #define OSD_CHR_IS_NUM(c) (c >= '0' && c <= '9') @@ -164,17 +164,17 @@ static pt1Filter_t GForceFilter, GForceFilterAxis[XYZ_AXIS_COUNT]; static float GForce, GForceAxis[XYZ_AXIS_COUNT]; typedef struct statistic_s { - uint16_t max_speed; - uint16_t max_3D_speed; - uint16_t max_air_speed; - uint16_t min_voltage; // /100 - int16_t max_current; - int32_t max_power; - int16_t min_rssi; - int16_t min_lq; // for CRSF - int16_t min_rssi_dbm; // for CRSF - int32_t max_altitude; - uint32_t max_distance; + uint16_t max_speed; + uint16_t max_3D_speed; + uint16_t max_air_speed; + uint16_t min_voltage; // /100 + int16_t max_current; + int32_t max_power; + int16_t min_rssi; + int16_t min_lq; // for CRSF + int16_t min_rssi_dbm; // for CRSF + int32_t max_altitude; + uint32_t max_distance; } statistic_t; static statistic_t stats; @@ -187,8 +187,8 @@ static bool fullRedraw = false; static uint8_t armState; typedef struct osdMapData_s { - uint32_t scale; - char referenceSymbol; + uint32_t scale; + char referenceSymbol; } osdMapData_t; static osdMapData_t osdMapData; @@ -208,28 +208,28 @@ PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 8); PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 1); void osdStartedSaveProcess(void) { - savingSettings = true; + savingSettings = true; } void osdShowEEPROMSavedNotification(void) { - savingSettings = false; - notify_settings_saved = millis() + 5000; + savingSettings = false; + notify_settings_saved = millis() + 5000; } bool osdDisplayIsPAL(void) { - return displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL; + return displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL; } bool osdDisplayIsHD(void) { - if (displayScreenSize(osdDisplayPort) >= VIDEO_BUFFER_CHARS_HDZERO) - { - return true; - } - return false; + if (displayScreenSize(osdDisplayPort) >= VIDEO_BUFFER_CHARS_HDZERO) + { + return true; + } + return false; } @@ -239,11 +239,11 @@ bool osdDisplayIsHD(void) */ static void osdLeftAlignString(char *buff) { - uint8_t sp = 0, ch = 0; - uint8_t len = strlen(buff); - while (buff[sp] == ' ') sp++; - for (ch = 0; ch < (len - sp); ch++) buff[ch] = buff[ch + sp]; - for (sp = ch; sp < len; sp++) buff[sp] = ' '; + uint8_t sp = 0, ch = 0; + uint8_t len = strlen(buff); + while (buff[sp] == ' ') sp++; + for (ch = 0; ch < (len - sp); ch++) buff[ch] = buff[ch + sp]; + for (sp = ch; sp < len; sp++) buff[sp] = ' '; } /* @@ -253,29 +253,29 @@ static void osdLeftAlignString(char *buff) */ /* void osdSimpleDistanceSymbol(char *buff, int32_t dist) { - int32_t convertedDistance; - char suffix; + int32_t convertedDistance; + char suffix; - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_GA: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - convertedDistance = CENTIMETERS_TO_FEET(dist); - suffix = SYM_ALT_FT; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - convertedDistance = CENTIMETERS_TO_METERS(dist); - suffix = SYM_ALT_M; // Intentionally use the altitude symbol, as the distance symbol is not defined in BFCOMPAT mode - break; - } + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + convertedDistance = CENTIMETERS_TO_FEET(dist); + suffix = SYM_ALT_FT; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + convertedDistance = CENTIMETERS_TO_METERS(dist); + suffix = SYM_ALT_M; // Intentionally use the altitude symbol, as the distance symbol is not defined in BFCOMPAT mode + break; + } - tfp_sprintf(buff, "%5d", (int) convertedDistance); // 5 digits, allowing up to 99999 meters/feet, which should be plenty for 99.9% of use cases - buff[5] = suffix; - buff[6] = '\0'; + tfp_sprintf(buff, "%5d", (int) convertedDistance); // 5 digits, allowing up to 99999 meters/feet, which should be plenty for 99.9% of use cases + buff[5] = suffix; + buff[6] = '\0'; } */ /** @@ -285,58 +285,58 @@ static void osdLeftAlignString(char *buff) */ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) { - uint8_t digits = 3U; // Total number of digits (including decimal point) - uint8_t sym_index = 3U; // Position (index) at buffer of units symbol - uint8_t symbol_m = SYM_DIST_M; - uint8_t symbol_km = SYM_DIST_KM; - uint8_t symbol_ft = SYM_DIST_FT; - uint8_t symbol_mi = SYM_DIST_MI; - uint8_t symbol_nm = SYM_DIST_NM; + uint8_t digits = 3U; // Total number of digits (including decimal point) + uint8_t sym_index = 3U; // Position (index) at buffer of units symbol + uint8_t symbol_m = SYM_DIST_M; + uint8_t symbol_km = SYM_DIST_KM; + uint8_t symbol_ft = SYM_DIST_FT; + uint8_t symbol_mi = SYM_DIST_MI; + uint8_t symbol_nm = SYM_DIST_NM; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values - if (isBfCompatibleVideoSystem(osdConfig())) { - // Add one digit so up no switch to scaled decimal occurs above 99 - digits = 4U; - sym_index = 4U; - // Use altitude symbols on purpose, as it seems distance symbols are not defined in BFCOMPAT mode - symbol_m = SYM_ALT_M; - symbol_km = SYM_ALT_KM; - symbol_ft = SYM_ALT_FT; - symbol_mi = SYM_MI; - symbol_nm = SYM_MI; - } + if (isBfCompatibleVideoSystem(osdConfig())) { + // Add one digit so up no switch to scaled decimal occurs above 99 + digits = 4U; + sym_index = 4U; + // Use altitude symbols on purpose, as it seems distance symbols are not defined in BFCOMPAT mode + symbol_m = SYM_ALT_M; + symbol_km = SYM_ALT_KM; + symbol_ft = SYM_ALT_FT; + symbol_mi = SYM_MI; + symbol_nm = SYM_MI; + } #endif - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_MILE, decimals, 3, digits)) { - buff[sym_index] = symbol_mi; - } else { - buff[sym_index] = symbol_ft; - } - buff[sym_index + 1] = '\0'; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - if (osdFormatCentiNumber(buff, dist, METERS_PER_KILOMETER, decimals, 3, digits)) { - buff[sym_index] = symbol_km; - } else { - buff[sym_index] = symbol_m; - } - buff[sym_index + 1] = '\0'; - break; - case OSD_UNIT_GA: - if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), (uint32_t)FEET_PER_NAUTICALMILE, decimals, 3, digits)) { - buff[sym_index] = symbol_nm; - } else { - buff[sym_index] = symbol_ft; - } - buff[sym_index + 1] = '\0'; - break; - } + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_MILE, decimals, 3, digits)) { + buff[sym_index] = symbol_mi; + } else { + buff[sym_index] = symbol_ft; + } + buff[sym_index + 1] = '\0'; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + if (osdFormatCentiNumber(buff, dist, METERS_PER_KILOMETER, decimals, 3, digits)) { + buff[sym_index] = symbol_km; + } else { + buff[sym_index] = symbol_m; + } + buff[sym_index + 1] = '\0'; + break; + case OSD_UNIT_GA: + if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), (uint32_t)FEET_PER_NAUTICALMILE, decimals, 3, digits)) { + buff[sym_index] = symbol_nm; + } else { + buff[sym_index] = symbol_ft; + } + buff[sym_index + 1] = '\0'; + break; + } } /** @@ -345,45 +345,45 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) */ static void osdFormatDistanceStr(char *buff, int32_t dist) { - int32_t centifeet; - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - centifeet = CENTIMETERS_TO_CENTIFEET(dist); - if (abs(centifeet) < FEET_PER_MILE * 100 / 2) { - // Show feet when dist < 0.5mi - tfp_sprintf(buff, "%d%c", (int)(centifeet / 100), SYM_FT); - } else { - // Show miles when dist >= 0.5mi - tfp_sprintf(buff, "%d.%02d%c", (int)(centifeet / (100*FEET_PER_MILE)), - (abs(centifeet) % (100 * FEET_PER_MILE)) / FEET_PER_MILE, SYM_MI); - } - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - if (abs(dist) < METERS_PER_KILOMETER * 100) { - // Show meters when dist < 1km - tfp_sprintf(buff, "%d%c", (int)(dist / 100), SYM_M); - } else { - // Show kilometers when dist >= 1km - tfp_sprintf(buff, "%d.%02d%c", (int)(dist / (100*METERS_PER_KILOMETER)), - (abs(dist) % (100 * METERS_PER_KILOMETER)) / METERS_PER_KILOMETER, SYM_KM); - } - break; - case OSD_UNIT_GA: - centifeet = CENTIMETERS_TO_CENTIFEET(dist); - if (abs(centifeet) < 100000) { - // Show feet when dist < 1000ft - tfp_sprintf(buff, "%d%c", (int)(centifeet / 100), SYM_FT); - } else { - // Show nautical miles when dist >= 1000ft - tfp_sprintf(buff, "%d.%02d%c", (int)(centifeet / (100 * FEET_PER_NAUTICALMILE)), - (int)((abs(centifeet) % (int)(100 * FEET_PER_NAUTICALMILE)) / FEET_PER_NAUTICALMILE), SYM_NM); - } - break; - } + int32_t centifeet; + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + centifeet = CENTIMETERS_TO_CENTIFEET(dist); + if (abs(centifeet) < FEET_PER_MILE * 100 / 2) { + // Show feet when dist < 0.5mi + tfp_sprintf(buff, "%d%c", (int)(centifeet / 100), SYM_FT); + } else { + // Show miles when dist >= 0.5mi + tfp_sprintf(buff, "%d.%02d%c", (int)(centifeet / (100*FEET_PER_MILE)), + (abs(centifeet) % (100 * FEET_PER_MILE)) / FEET_PER_MILE, SYM_MI); + } + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + if (abs(dist) < METERS_PER_KILOMETER * 100) { + // Show meters when dist < 1km + tfp_sprintf(buff, "%d%c", (int)(dist / 100), SYM_M); + } else { + // Show kilometers when dist >= 1km + tfp_sprintf(buff, "%d.%02d%c", (int)(dist / (100*METERS_PER_KILOMETER)), + (abs(dist) % (100 * METERS_PER_KILOMETER)) / METERS_PER_KILOMETER, SYM_KM); + } + break; + case OSD_UNIT_GA: + centifeet = CENTIMETERS_TO_CENTIFEET(dist); + if (abs(centifeet) < 100000) { + // Show feet when dist < 1000ft + tfp_sprintf(buff, "%d%c", (int)(centifeet / 100), SYM_FT); + } else { + // Show nautical miles when dist >= 1000ft + tfp_sprintf(buff, "%d.%02d%c", (int)(centifeet / (100 * FEET_PER_NAUTICALMILE)), + (int)((abs(centifeet) % (int)(100 * FEET_PER_NAUTICALMILE)) / FEET_PER_NAUTICALMILE), SYM_NM); + } + break; + } } /** @@ -392,20 +392,20 @@ static void osdFormatDistanceStr(char *buff, int32_t dist) */ static int32_t osdConvertVelocityToUnit(int32_t vel) { - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - return CMSEC_TO_CENTIMPH(vel) / 100; // Convert to mph - case OSD_UNIT_METRIC: - return CMSEC_TO_CENTIKPH(vel) / 100; // Convert to kmh - case OSD_UNIT_GA: - return CMSEC_TO_CENTIKNOTS(vel) / 100; // Convert to Knots - } - // Unreachable - return -1; + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + return CMSEC_TO_CENTIMPH(vel) / 100; // Convert to mph + case OSD_UNIT_METRIC: + return CMSEC_TO_CENTIKPH(vel) / 100; // Convert to kmh + case OSD_UNIT_GA: + return CMSEC_TO_CENTIKNOTS(vel) / 100; // Convert to Knots + } + // Unreachable + return -1; } /** @@ -416,41 +416,41 @@ static int32_t osdConvertVelocityToUnit(int32_t vel) */ void osdFormatVelocityStr(char* buff, int32_t vel, bool _3D, bool _max) { - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - if (_max) { - tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_MPH : SYM_MPH)); - } else { - tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_MPH : SYM_MPH)); - } - break; - case OSD_UNIT_METRIC: - if (_max) { - tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KMH : SYM_KMH)); - } else { - tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KMH : SYM_KMH)); - } - break; - case OSD_UNIT_GA: - if (_max) { - tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KT : SYM_KT)); - } else { - tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KT : SYM_KT)); - } - break; - } + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + if (_max) { + tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_MPH : SYM_MPH)); + } else { + tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_MPH : SYM_MPH)); + } + break; + case OSD_UNIT_METRIC: + if (_max) { + tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KMH : SYM_KMH)); + } else { + tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KMH : SYM_KMH)); + } + break; + case OSD_UNIT_GA: + if (_max) { + tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KT : SYM_KT)); + } else { + tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KT : SYM_KT)); + } + break; + } } /** * Returns the average velocity. This always uses stats, so can be called as an OSD element later if wanted, to show a real time average */ static void osdGenerateAverageVelocityStr(char* buff) { - uint32_t cmPerSec = getTotalTravelDistance() / getFlightTime(); - osdFormatVelocityStr(buff, cmPerSec, false, false); + uint32_t cmPerSec = getTotalTravelDistance() / getFlightTime(); + osdFormatVelocityStr(buff, cmPerSec, false, false); } /** @@ -462,35 +462,35 @@ static void osdGenerateAverageVelocityStr(char* buff) { #ifdef USE_WIND_ESTIMATOR static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) { - int32_t centivalue; - char suffix; - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - centivalue = CMSEC_TO_CENTIMPH(ws); - suffix = SYM_MPH; - break; - case OSD_UNIT_GA: - centivalue = CMSEC_TO_CENTIKNOTS(ws); - suffix = SYM_KT; - break; - default: - case OSD_UNIT_METRIC: - centivalue = CMSEC_TO_CENTIKPH(ws); - suffix = SYM_KMH; - break; - } + int32_t centivalue; + char suffix; + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + centivalue = CMSEC_TO_CENTIMPH(ws); + suffix = SYM_MPH; + break; + case OSD_UNIT_GA: + centivalue = CMSEC_TO_CENTIKNOTS(ws); + suffix = SYM_KT; + break; + default: + case OSD_UNIT_METRIC: + centivalue = CMSEC_TO_CENTIKPH(ws); + suffix = SYM_KMH; + break; + } - osdFormatCentiNumber(buff, centivalue, 0, 2, 0, 3); + osdFormatCentiNumber(buff, centivalue, 0, 2, 0, 3); - if (!isValid && ((millis() / 1000) % 4 < 2)) - suffix = '*'; + if (!isValid && ((millis() / 1000) % 4 < 2)) + suffix = '*'; - buff[3] = suffix; - buff[4] = '\0'; + buff[3] = suffix; + buff[4] = '\0'; } #endif @@ -500,29 +500,29 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) */ /* void osdSimpleAltitudeSymbol(char *buff, int32_t alt) { - int32_t convertedAltutude = 0; - char suffix = '\0'; + int32_t convertedAltutude = 0; + char suffix = '\0'; - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_GA: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - convertedAltutude = CENTIMETERS_TO_FEET(alt); - suffix = SYM_ALT_FT; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - convertedAltutude = CENTIMETERS_TO_METERS(alt); - suffix = SYM_ALT_M; - break; - } + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + convertedAltutude = CENTIMETERS_TO_FEET(alt); + suffix = SYM_ALT_FT; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + convertedAltutude = CENTIMETERS_TO_METERS(alt); + suffix = SYM_ALT_M; + break; + } - tfp_sprintf(buff, "%4d", (int) convertedAltutude); - buff[4] = suffix; - buff[5] = '\0'; + tfp_sprintf(buff, "%4d", (int) convertedAltutude); + buff[4] = suffix; + buff[5] = '\0'; } */ /** @@ -532,54 +532,54 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) */ void osdFormatAltitudeSymbol(char *buff, int32_t alt) { - uint8_t totalDigits = 4U; - uint8_t digits = 4U; - uint8_t symbolIndex = 4U; - uint8_t symbolKFt = SYM_ALT_KFT; + uint8_t totalDigits = 4U; + uint8_t digits = 4U; + uint8_t symbolIndex = 4U; + uint8_t symbolKFt = SYM_ALT_KFT; - if (alt >= 0) { - digits = 3U; - buff[0] = ' '; - } + if (alt >= 0) { + digits = 3U; + buff[0] = ' '; + } #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values - if (isBfCompatibleVideoSystem(osdConfig())) { - totalDigits++; - digits++; - symbolIndex++; - symbolKFt = SYM_ALT_FT; - } + if (isBfCompatibleVideoSystem(osdConfig())) { + totalDigits++; + digits++; + symbolIndex++; + symbolKFt = SYM_ALT_FT; + } #endif - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_GA: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - if (osdFormatCentiNumber(buff + totalDigits - digits, CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, digits)) { - // Scaled to kft - buff[symbolIndex++] = symbolKFt; - } else { - // Formatted in feet - buff[symbolIndex++] = SYM_ALT_FT; - } - buff[symbolIndex] = '\0'; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - // alt is alredy in cm - if (osdFormatCentiNumber(buff + totalDigits - digits, alt, 1000, 0, 2, digits)) { - // Scaled to km - buff[symbolIndex++] = SYM_ALT_KM; - } else { - // Formatted in m - buff[symbolIndex++] = SYM_ALT_M; - } - buff[symbolIndex] = '\0'; - break; - } + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + if (osdFormatCentiNumber(buff + totalDigits - digits, CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, digits)) { + // Scaled to kft + buff[symbolIndex++] = symbolKFt; + } else { + // Formatted in feet + buff[symbolIndex++] = SYM_ALT_FT; + } + buff[symbolIndex] = '\0'; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + // alt is alredy in cm + if (osdFormatCentiNumber(buff + totalDigits - digits, alt, 1000, 0, 2, digits)) { + // Scaled to km + buff[symbolIndex++] = SYM_ALT_KM; + } else { + // Formatted in m + buff[symbolIndex++] = SYM_ALT_M; + } + buff[symbolIndex] = '\0'; + break; + } } /** @@ -588,52 +588,52 @@ void osdFormatAltitudeSymbol(char *buff, int32_t alt) */ static void osdFormatAltitudeStr(char *buff, int32_t alt) { - int32_t value; - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_GA: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - value = CENTIMETERS_TO_FEET(alt); - tfp_sprintf(buff, "%d%c", (int)value, SYM_FT); - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - value = CENTIMETERS_TO_METERS(alt); - tfp_sprintf(buff, "%d%c", (int)value, SYM_M); - break; - } + int32_t value; + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + value = CENTIMETERS_TO_FEET(alt); + tfp_sprintf(buff, "%d%c", (int)value, SYM_FT); + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + value = CENTIMETERS_TO_METERS(alt); + tfp_sprintf(buff, "%d%c", (int)value, SYM_M); + break; + } } static void osdFormatTime(char *buff, uint32_t seconds, char sym_m, char sym_h) { - uint32_t value = seconds; - char sym = sym_m; - // Maximum value we can show in minutes is 99 minutes and 59 seconds - if (seconds > (99 * 60) + 59) { - sym = sym_h; - value = seconds / 60; - } - buff[0] = sym; - tfp_sprintf(buff + 1, "%02d:%02d", (int)(value / 60), (int)(value % 60)); + uint32_t value = seconds; + char sym = sym_m; + // Maximum value we can show in minutes is 99 minutes and 59 seconds + if (seconds > (99 * 60) + 59) { + sym = sym_h; + value = seconds / 60; + } + buff[0] = sym; + tfp_sprintf(buff + 1, "%02d:%02d", (int)(value / 60), (int)(value % 60)); } static inline void osdFormatOnTime(char *buff) { - osdFormatTime(buff, micros() / 1000000, SYM_ON_M, SYM_ON_H); + osdFormatTime(buff, micros() / 1000000, SYM_ON_M, SYM_ON_H); } static inline void osdFormatFlyTime(char *buff, textAttributes_t *attr) { - uint32_t seconds = getFlightTime(); - osdFormatTime(buff, seconds, SYM_FLY_M, SYM_FLY_H); - if (attr && osdConfig()->time_alarm > 0) { - if (seconds / 60 >= osdConfig()->time_alarm && ARMING_FLAG(ARMED)) { - TEXT_ATTRIBUTES_ADD_BLINK(*attr); - } - } + uint32_t seconds = getFlightTime(); + osdFormatTime(buff, seconds, SYM_FLY_M, SYM_FLY_H); + if (attr && osdConfig()->time_alarm > 0) { + if (seconds / 60 >= osdConfig()->time_alarm && ARMING_FLAG(ARMED)) { + TEXT_ATTRIBUTES_ADD_BLINK(*attr); + } + } } /** @@ -642,23 +642,23 @@ static inline void osdFormatFlyTime(char *buff, textAttributes_t *attr) */ char *osdFormatTrimWhiteSpace(char *buff) { - char *end; + char *end; - // Trim leading spaces - while(isspace((unsigned char)*buff)) buff++; + // Trim leading spaces + while(isspace((unsigned char)*buff)) buff++; - // All spaces? - if(*buff == 0) - return buff; + // All spaces? + if(*buff == 0) + return buff; - // Trim trailing spaces - end = buff + strlen(buff) - 1; - while(end > buff && isspace((unsigned char)*end)) end--; + // Trim trailing spaces + end = buff + strlen(buff) - 1; + while(end > buff && isspace((unsigned char)*end)) end--; - // Write new null terminator character - end[1] = '\0'; + // Write new null terminator character + end[1] = '\0'; - return buff; + return buff; } /** @@ -666,32 +666,32 @@ char *osdFormatTrimWhiteSpace(char *buff) */ static uint16_t osdConvertRSSI(void) { - // change range to [0, 99] - return constrain(getRSSI() * 100 / RSSI_MAX_VALUE, 0, 99); + // change range to [0, 99] + return constrain(getRSSI() * 100 / RSSI_MAX_VALUE, 0, 99); } static uint16_t osdGetCrsfLQ(void) { - int16_t statsLQ = rxLinkStatistics.uplinkLQ; - int16_t scaledLQ = scaleRange(constrain(statsLQ, 0, 100), 0, 100, 170, 300); - int16_t displayedLQ = 0; - switch (osdConfig()->crsf_lq_format) { - case OSD_CRSF_LQ_TYPE1: - displayedLQ = statsLQ; - break; - case OSD_CRSF_LQ_TYPE2: - displayedLQ = statsLQ; - break; - case OSD_CRSF_LQ_TYPE3: - displayedLQ = rxLinkStatistics.rfMode >= 2 ? scaledLQ : statsLQ; - break; - } - return displayedLQ; + int16_t statsLQ = rxLinkStatistics.uplinkLQ; + int16_t scaledLQ = scaleRange(constrain(statsLQ, 0, 100), 0, 100, 170, 300); + int16_t displayedLQ = 0; + switch (osdConfig()->crsf_lq_format) { + case OSD_CRSF_LQ_TYPE1: + displayedLQ = statsLQ; + break; + case OSD_CRSF_LQ_TYPE2: + displayedLQ = statsLQ; + break; + case OSD_CRSF_LQ_TYPE3: + displayedLQ = rxLinkStatistics.rfMode >= 2 ? scaledLQ : statsLQ; + break; + } + return displayedLQ; } static int16_t osdGetCrsfdBm(void) { - return rxLinkStatistics.uplinkRSSI; + return rxLinkStatistics.uplinkRSSI; } /** * Displays a temperature postfixed with a symbol depending on the current unit system @@ -701,293 +701,293 @@ static int16_t osdGetCrsfdBm(void) */ static void osdDisplayTemperature(uint8_t elemPosX, uint8_t elemPosY, uint16_t symbol, const char *label, bool valid, int16_t temperature, int16_t alarm_min, int16_t alarm_max) { - char buff[TEMPERATURE_LABEL_LEN + 2 < 6 ? 6 : TEMPERATURE_LABEL_LEN + 2]; - textAttributes_t elemAttr = valid ? TEXT_ATTRIBUTES_NONE : _TEXT_ATTRIBUTES_BLINK_BIT; - uint8_t valueXOffset = 0; + char buff[TEMPERATURE_LABEL_LEN + 2 < 6 ? 6 : TEMPERATURE_LABEL_LEN + 2]; + textAttributes_t elemAttr = valid ? TEXT_ATTRIBUTES_NONE : _TEXT_ATTRIBUTES_BLINK_BIT; + uint8_t valueXOffset = 0; - if (symbol) { - buff[0] = symbol; - buff[1] = '\0'; - displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); - valueXOffset = 1; - } + if (symbol) { + buff[0] = symbol; + buff[1] = '\0'; + displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); + valueXOffset = 1; + } #ifdef USE_TEMPERATURE_SENSOR - else if (label[0] != '\0') { - uint8_t label_len = strnlen(label, TEMPERATURE_LABEL_LEN); - memcpy(buff, label, label_len); - memset(buff + label_len, ' ', TEMPERATURE_LABEL_LEN + 1 - label_len); - buff[5] = '\0'; - displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); - valueXOffset = osdConfig()->temp_label_align == OSD_ALIGN_LEFT ? 5 : label_len + 1; - } + else if (label[0] != '\0') { + uint8_t label_len = strnlen(label, TEMPERATURE_LABEL_LEN); + memcpy(buff, label, label_len); + memset(buff + label_len, ' ', TEMPERATURE_LABEL_LEN + 1 - label_len); + buff[5] = '\0'; + displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); + valueXOffset = osdConfig()->temp_label_align == OSD_ALIGN_LEFT ? 5 : label_len + 1; + } #else - UNUSED(label); + UNUSED(label); #endif - if (valid) { + if (valid) { - if ((temperature <= alarm_min) || (temperature >= alarm_max)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - if (osdConfig()->units == OSD_UNIT_IMPERIAL) temperature = temperature * 9 / 5.0f + 320; - tfp_sprintf(buff, "%3d", temperature / 10); + if ((temperature <= alarm_min) || (temperature >= alarm_max)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + if (osdConfig()->units == OSD_UNIT_IMPERIAL) temperature = temperature * 9 / 5.0f + 320; + tfp_sprintf(buff, "%3d", temperature / 10); - } else - strcpy(buff, "---"); + } else + strcpy(buff, "---"); - buff[3] = osdConfig()->units == OSD_UNIT_IMPERIAL ? SYM_TEMP_F : SYM_TEMP_C; - buff[4] = '\0'; + buff[3] = osdConfig()->units == OSD_UNIT_IMPERIAL ? SYM_TEMP_F : SYM_TEMP_C; + buff[4] = '\0'; - displayWriteWithAttr(osdDisplayPort, elemPosX + valueXOffset, elemPosY, buff, elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + valueXOffset, elemPosY, buff, elemAttr); } #ifdef USE_TEMPERATURE_SENSOR static void osdDisplayTemperatureSensor(uint8_t elemPosX, uint8_t elemPosY, uint8_t sensorIndex) { - int16_t temperature; - const bool valid = getSensorTemperature(sensorIndex, &temperature); - const tempSensorConfig_t *sensorConfig = tempSensorConfig(sensorIndex); - uint16_t symbol = sensorConfig->osdSymbol ? SYM_TEMP_SENSOR_FIRST + sensorConfig->osdSymbol - 1 : 0; - osdDisplayTemperature(elemPosX, elemPosY, symbol, sensorConfig->label, valid, temperature, sensorConfig->alarm_min, sensorConfig->alarm_max); + int16_t temperature; + const bool valid = getSensorTemperature(sensorIndex, &temperature); + const tempSensorConfig_t *sensorConfig = tempSensorConfig(sensorIndex); + uint16_t symbol = sensorConfig->osdSymbol ? SYM_TEMP_SENSOR_FIRST + sensorConfig->osdSymbol - 1 : 0; + osdDisplayTemperature(elemPosX, elemPosY, symbol, sensorConfig->label, valid, temperature, sensorConfig->alarm_min, sensorConfig->alarm_max); } #endif static void osdFormatCoordinate(char *buff, char sym, int32_t val) { - // up to 4 for number + 1 for the symbol + null terminator + fill the rest with decimals - const int coordinateLength = osdConfig()->coordinate_digits + 1; + // up to 4 for number + 1 for the symbol + null terminator + fill the rest with decimals + const int coordinateLength = osdConfig()->coordinate_digits + 1; - buff[0] = sym; - int32_t integerPart = val / GPS_DEGREES_DIVIDER; - // Latitude maximum integer width is 3 (-90) while - // longitude maximum integer width is 4 (-180). - int integerDigits = tfp_sprintf(buff + 1, (integerPart == 0 && val < 0) ? "-%d" : "%d", (int)integerPart); - // We can show up to 7 digits in decimalPart. - int32_t decimalPart = abs(val % (int)GPS_DEGREES_DIVIDER); - STATIC_ASSERT(GPS_DEGREES_DIVIDER == 1e7, adjust_max_decimal_digits); - int decimalDigits; - bool bfcompat = false; // Assume BFCOMPAT mode is no enabled + buff[0] = sym; + int32_t integerPart = val / GPS_DEGREES_DIVIDER; + // Latitude maximum integer width is 3 (-90) while + // longitude maximum integer width is 4 (-180). + int integerDigits = tfp_sprintf(buff + 1, (integerPart == 0 && val < 0) ? "-%d" : "%d", (int)integerPart); + // We can show up to 7 digits in decimalPart. + int32_t decimalPart = abs(val % (int)GPS_DEGREES_DIVIDER); + STATIC_ASSERT(GPS_DEGREES_DIVIDER == 1e7, adjust_max_decimal_digits); + int decimalDigits; + bool bfcompat = false; // Assume BFCOMPAT mode is no enabled #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if(isBfCompatibleVideoSystem(osdConfig())) { - bfcompat = true; - } + if(isBfCompatibleVideoSystem(osdConfig())) { + bfcompat = true; + } #endif - if (!bfcompat) { - decimalDigits = tfp_sprintf(buff + 1 + integerDigits, "%07d", (int)decimalPart); - // Embbed the decimal separator - buff[1 + integerDigits - 1] += SYM_ZERO_HALF_TRAILING_DOT - '0'; - buff[1 + integerDigits] += SYM_ZERO_HALF_LEADING_DOT - '0'; - } else { - // BFCOMPAT mode enabled - decimalDigits = tfp_sprintf(buff + 1 + integerDigits, ".%06d", (int)decimalPart); - } - // Fill up to coordinateLength with zeros - int total = 1 + integerDigits + decimalDigits; - while(total < coordinateLength) { - buff[total] = '0'; - total++; - } - buff[coordinateLength] = '\0'; + if (!bfcompat) { + decimalDigits = tfp_sprintf(buff + 1 + integerDigits, "%07d", (int)decimalPart); + // Embbed the decimal separator + buff[1 + integerDigits - 1] += SYM_ZERO_HALF_TRAILING_DOT - '0'; + buff[1 + integerDigits] += SYM_ZERO_HALF_LEADING_DOT - '0'; + } else { + // BFCOMPAT mode enabled + decimalDigits = tfp_sprintf(buff + 1 + integerDigits, ".%06d", (int)decimalPart); + } + // Fill up to coordinateLength with zeros + int total = 1 + integerDigits + decimalDigits; + while(total < coordinateLength) { + buff[total] = '0'; + total++; + } + buff[coordinateLength] = '\0'; } static void osdFormatCraftName(char *buff) { - if (strlen(systemConfig()->craftName) == 0) - strcpy(buff, "CRAFT_NAME"); - else { - for (int i = 0; i < MAX_NAME_LENGTH; i++) { - buff[i] = sl_toupper((unsigned char)systemConfig()->craftName[i]); - if (systemConfig()->craftName[i] == 0) - break; - } - } + if (strlen(systemConfig()->craftName) == 0) + strcpy(buff, "CRAFT_NAME"); + else { + for (int i = 0; i < MAX_NAME_LENGTH; i++) { + buff[i] = sl_toupper((unsigned char)systemConfig()->craftName[i]); + if (systemConfig()->craftName[i] == 0) + break; + } + } } void osdFormatPilotName(char *buff) { - if (strlen(systemConfig()->pilotName) == 0) - strcpy(buff, "PILOT_NAME"); - else { - for (int i = 0; i < MAX_NAME_LENGTH; i++) { - buff[i] = sl_toupper((unsigned char)systemConfig()->pilotName[i]); - if (systemConfig()->pilotName[i] == 0) - break; - } - } + if (strlen(systemConfig()->pilotName) == 0) + strcpy(buff, "PILOT_NAME"); + else { + for (int i = 0; i < MAX_NAME_LENGTH; i++) { + buff[i] = sl_toupper((unsigned char)systemConfig()->pilotName[i]); + if (systemConfig()->pilotName[i] == 0) + break; + } + } } static const char * osdArmingDisabledReasonMessage(void) { - const char *message = NULL; - char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; + const char *message = NULL; + char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; - switch (isArmingDisabledReason()) { - case ARMING_DISABLED_FAILSAFE_SYSTEM: - // See handling of FAILSAFE_RX_LOSS_MONITORING in failsafe.c - if (failsafePhase() == FAILSAFE_RX_LOSS_MONITORING) { - if (failsafeIsReceivingRxData()) { - // If we're not using sticks, it means the ARM switch - // hasn't been off since entering FAILSAFE_RX_LOSS_MONITORING - // yet - return OSD_MESSAGE_STR(OSD_MSG_TURN_ARM_SW_OFF); - } - // Not receiving RX data - return OSD_MESSAGE_STR(OSD_MSG_RC_RX_LINK_LOST); - } - return OSD_MESSAGE_STR(OSD_MSG_DISABLED_BY_FS); - case ARMING_DISABLED_NOT_LEVEL: - return OSD_MESSAGE_STR(OSD_MSG_AIRCRAFT_UNLEVEL); - case ARMING_DISABLED_SENSORS_CALIBRATING: - return OSD_MESSAGE_STR(OSD_MSG_SENSORS_CAL); - case ARMING_DISABLED_SYSTEM_OVERLOADED: - return OSD_MESSAGE_STR(OSD_MSG_SYS_OVERLOADED); - case ARMING_DISABLED_NAVIGATION_UNSAFE: - // Check the exact reason - switch (navigationIsBlockingArming(NULL)) { - char buf[6]; - case NAV_ARMING_BLOCKER_NONE: - break; - case NAV_ARMING_BLOCKER_MISSING_GPS_FIX: - return OSD_MESSAGE_STR(OSD_MSG_WAITING_GPS_FIX); - case NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE: - return OSD_MESSAGE_STR(OSD_MSG_DISABLE_NAV_FIRST); - case NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR: - osdFormatDistanceSymbol(buf, distanceToFirstWP(), 0); - tfp_sprintf(messageBuf, "FIRST WP TOO FAR (%s)", buf); - return message = messageBuf; - case NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR: - return OSD_MESSAGE_STR(OSD_MSG_JUMP_WP_MISCONFIG); - } - break; - case ARMING_DISABLED_COMPASS_NOT_CALIBRATED: - return OSD_MESSAGE_STR(OSD_MSG_MAG_NOT_CAL); - case ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED: - return OSD_MESSAGE_STR(OSD_MSG_ACC_NOT_CAL); - case ARMING_DISABLED_ARM_SWITCH: - return OSD_MESSAGE_STR(OSD_MSG_DISARM_1ST); - case ARMING_DISABLED_HARDWARE_FAILURE: - { - if (!HW_SENSOR_IS_HEALTHY(getHwGyroStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_GYRO_FAILURE); - } - if (!HW_SENSOR_IS_HEALTHY(getHwAccelerometerStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_ACC_FAIL); - } - if (!HW_SENSOR_IS_HEALTHY(getHwCompassStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_MAG_FAIL); - } - if (!HW_SENSOR_IS_HEALTHY(getHwBarometerStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_BARO_FAIL); - } - if (!HW_SENSOR_IS_HEALTHY(getHwGPSStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_GPS_FAIL); - } - if (!HW_SENSOR_IS_HEALTHY(getHwRangefinderStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_RANGEFINDER_FAIL); - } - if (!HW_SENSOR_IS_HEALTHY(getHwPitotmeterStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_PITOT_FAIL); - } - } - return OSD_MESSAGE_STR(OSD_MSG_HW_FAIL); - case ARMING_DISABLED_BOXFAILSAFE: - return OSD_MESSAGE_STR(OSD_MSG_FS_EN); - case ARMING_DISABLED_BOXKILLSWITCH: - return OSD_MESSAGE_STR(OSD_MSG_KILL_SW_EN); - case ARMING_DISABLED_RC_LINK: - return OSD_MESSAGE_STR(OSD_MSG_NO_RC_LINK); - case ARMING_DISABLED_THROTTLE: - return OSD_MESSAGE_STR(OSD_MSG_THROTTLE_NOT_LOW); - case ARMING_DISABLED_ROLLPITCH_NOT_CENTERED: - return OSD_MESSAGE_STR(OSD_MSG_ROLLPITCH_OFFCENTER); - case ARMING_DISABLED_SERVO_AUTOTRIM: - return OSD_MESSAGE_STR(OSD_MSG_AUTOTRIM_ACTIVE); - case ARMING_DISABLED_OOM: - return OSD_MESSAGE_STR(OSD_MSG_NOT_ENOUGH_MEMORY); - case ARMING_DISABLED_INVALID_SETTING: - return OSD_MESSAGE_STR(OSD_MSG_INVALID_SETTING); - case ARMING_DISABLED_CLI: - return OSD_MESSAGE_STR(OSD_MSG_CLI_ACTIVE); - case ARMING_DISABLED_PWM_OUTPUT_ERROR: - return OSD_MESSAGE_STR(OSD_MSG_PWM_INIT_ERROR); - case ARMING_DISABLED_NO_PREARM: - return OSD_MESSAGE_STR(OSD_MSG_NO_PREARM); - case ARMING_DISABLED_DSHOT_BEEPER: - return OSD_MESSAGE_STR(OSD_MSG_DSHOT_BEEPER); - // Cases without message - case ARMING_DISABLED_LANDING_DETECTED: - FALLTHROUGH; - case ARMING_DISABLED_CMS_MENU: - FALLTHROUGH; - case ARMING_DISABLED_OSD_MENU: - FALLTHROUGH; - case ARMING_DISABLED_ALL_FLAGS: - FALLTHROUGH; - case ARMED: - FALLTHROUGH; - case SIMULATOR_MODE_HITL: - FALLTHROUGH; - case SIMULATOR_MODE_SITL: - FALLTHROUGH; - case WAS_EVER_ARMED: - break; - } - return NULL; + switch (isArmingDisabledReason()) { + case ARMING_DISABLED_FAILSAFE_SYSTEM: + // See handling of FAILSAFE_RX_LOSS_MONITORING in failsafe.c + if (failsafePhase() == FAILSAFE_RX_LOSS_MONITORING) { + if (failsafeIsReceivingRxData()) { + // If we're not using sticks, it means the ARM switch + // hasn't been off since entering FAILSAFE_RX_LOSS_MONITORING + // yet + return OSD_MESSAGE_STR(OSD_MSG_TURN_ARM_SW_OFF); + } + // Not receiving RX data + return OSD_MESSAGE_STR(OSD_MSG_RC_RX_LINK_LOST); + } + return OSD_MESSAGE_STR(OSD_MSG_DISABLED_BY_FS); + case ARMING_DISABLED_NOT_LEVEL: + return OSD_MESSAGE_STR(OSD_MSG_AIRCRAFT_UNLEVEL); + case ARMING_DISABLED_SENSORS_CALIBRATING: + return OSD_MESSAGE_STR(OSD_MSG_SENSORS_CAL); + case ARMING_DISABLED_SYSTEM_OVERLOADED: + return OSD_MESSAGE_STR(OSD_MSG_SYS_OVERLOADED); + case ARMING_DISABLED_NAVIGATION_UNSAFE: + // Check the exact reason + switch (navigationIsBlockingArming(NULL)) { + char buf[6]; + case NAV_ARMING_BLOCKER_NONE: + break; + case NAV_ARMING_BLOCKER_MISSING_GPS_FIX: + return OSD_MESSAGE_STR(OSD_MSG_WAITING_GPS_FIX); + case NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE: + return OSD_MESSAGE_STR(OSD_MSG_DISABLE_NAV_FIRST); + case NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR: + osdFormatDistanceSymbol(buf, distanceToFirstWP(), 0); + tfp_sprintf(messageBuf, "FIRST WP TOO FAR (%s)", buf); + return message = messageBuf; + case NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR: + return OSD_MESSAGE_STR(OSD_MSG_JUMP_WP_MISCONFIG); + } + break; + case ARMING_DISABLED_COMPASS_NOT_CALIBRATED: + return OSD_MESSAGE_STR(OSD_MSG_MAG_NOT_CAL); + case ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED: + return OSD_MESSAGE_STR(OSD_MSG_ACC_NOT_CAL); + case ARMING_DISABLED_ARM_SWITCH: + return OSD_MESSAGE_STR(OSD_MSG_DISARM_1ST); + case ARMING_DISABLED_HARDWARE_FAILURE: + { + if (!HW_SENSOR_IS_HEALTHY(getHwGyroStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_GYRO_FAILURE); + } + if (!HW_SENSOR_IS_HEALTHY(getHwAccelerometerStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_ACC_FAIL); + } + if (!HW_SENSOR_IS_HEALTHY(getHwCompassStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_MAG_FAIL); + } + if (!HW_SENSOR_IS_HEALTHY(getHwBarometerStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_BARO_FAIL); + } + if (!HW_SENSOR_IS_HEALTHY(getHwGPSStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_GPS_FAIL); + } + if (!HW_SENSOR_IS_HEALTHY(getHwRangefinderStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_RANGEFINDER_FAIL); + } + if (!HW_SENSOR_IS_HEALTHY(getHwPitotmeterStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_PITOT_FAIL); + } + } + return OSD_MESSAGE_STR(OSD_MSG_HW_FAIL); + case ARMING_DISABLED_BOXFAILSAFE: + return OSD_MESSAGE_STR(OSD_MSG_FS_EN); + case ARMING_DISABLED_BOXKILLSWITCH: + return OSD_MESSAGE_STR(OSD_MSG_KILL_SW_EN); + case ARMING_DISABLED_RC_LINK: + return OSD_MESSAGE_STR(OSD_MSG_NO_RC_LINK); + case ARMING_DISABLED_THROTTLE: + return OSD_MESSAGE_STR(OSD_MSG_THROTTLE_NOT_LOW); + case ARMING_DISABLED_ROLLPITCH_NOT_CENTERED: + return OSD_MESSAGE_STR(OSD_MSG_ROLLPITCH_OFFCENTER); + case ARMING_DISABLED_SERVO_AUTOTRIM: + return OSD_MESSAGE_STR(OSD_MSG_AUTOTRIM_ACTIVE); + case ARMING_DISABLED_OOM: + return OSD_MESSAGE_STR(OSD_MSG_NOT_ENOUGH_MEMORY); + case ARMING_DISABLED_INVALID_SETTING: + return OSD_MESSAGE_STR(OSD_MSG_INVALID_SETTING); + case ARMING_DISABLED_CLI: + return OSD_MESSAGE_STR(OSD_MSG_CLI_ACTIVE); + case ARMING_DISABLED_PWM_OUTPUT_ERROR: + return OSD_MESSAGE_STR(OSD_MSG_PWM_INIT_ERROR); + case ARMING_DISABLED_NO_PREARM: + return OSD_MESSAGE_STR(OSD_MSG_NO_PREARM); + case ARMING_DISABLED_DSHOT_BEEPER: + return OSD_MESSAGE_STR(OSD_MSG_DSHOT_BEEPER); + // Cases without message + case ARMING_DISABLED_LANDING_DETECTED: + FALLTHROUGH; + case ARMING_DISABLED_CMS_MENU: + FALLTHROUGH; + case ARMING_DISABLED_OSD_MENU: + FALLTHROUGH; + case ARMING_DISABLED_ALL_FLAGS: + FALLTHROUGH; + case ARMED: + FALLTHROUGH; + case SIMULATOR_MODE_HITL: + FALLTHROUGH; + case SIMULATOR_MODE_SITL: + FALLTHROUGH; + case WAS_EVER_ARMED: + break; + } + return NULL; } static const char * osdFailsafePhaseMessage(void) { - // See failsafe.h for each phase explanation - switch (failsafePhase()) { - case FAILSAFE_RETURN_TO_HOME: - // XXX: Keep this in sync with OSD_FLYMODE. - return OSD_MESSAGE_STR(OSD_MSG_RTH_FS); - case FAILSAFE_LANDING: - // This should be considered an emergengy landing - return OSD_MESSAGE_STR(OSD_MSG_EMERG_LANDING_FS); - case FAILSAFE_RX_LOSS_MONITORING: - // Only reachable from FAILSAFE_LANDED, which performs - // a disarm. Since aircraft has been disarmed, we no - // longer show failsafe details. - FALLTHROUGH; - case FAILSAFE_LANDED: - // Very brief, disarms and transitions into - // FAILSAFE_RX_LOSS_MONITORING. Note that it prevents - // further rearming via ARMING_DISABLED_FAILSAFE_SYSTEM, - // so we'll show the user how to re-arm in when - // that flag is the reason to prevent arming. - FALLTHROUGH; - case FAILSAFE_RX_LOSS_IDLE: - // This only happens when user has chosen NONE as FS - // procedure. The recovery messages should be enough. - FALLTHROUGH; - case FAILSAFE_IDLE: - // Failsafe not active - FALLTHROUGH; - case FAILSAFE_RX_LOSS_DETECTED: - // Very brief, changes to FAILSAFE_RX_LOSS_RECOVERED - // or the FS procedure immediately. - FALLTHROUGH; - case FAILSAFE_RX_LOSS_RECOVERED: - // Exiting failsafe - break; - } - return NULL; + // See failsafe.h for each phase explanation + switch (failsafePhase()) { + case FAILSAFE_RETURN_TO_HOME: + // XXX: Keep this in sync with OSD_FLYMODE. + return OSD_MESSAGE_STR(OSD_MSG_RTH_FS); + case FAILSAFE_LANDING: + // This should be considered an emergengy landing + return OSD_MESSAGE_STR(OSD_MSG_EMERG_LANDING_FS); + case FAILSAFE_RX_LOSS_MONITORING: + // Only reachable from FAILSAFE_LANDED, which performs + // a disarm. Since aircraft has been disarmed, we no + // longer show failsafe details. + FALLTHROUGH; + case FAILSAFE_LANDED: + // Very brief, disarms and transitions into + // FAILSAFE_RX_LOSS_MONITORING. Note that it prevents + // further rearming via ARMING_DISABLED_FAILSAFE_SYSTEM, + // so we'll show the user how to re-arm in when + // that flag is the reason to prevent arming. + FALLTHROUGH; + case FAILSAFE_RX_LOSS_IDLE: + // This only happens when user has chosen NONE as FS + // procedure. The recovery messages should be enough. + FALLTHROUGH; + case FAILSAFE_IDLE: + // Failsafe not active + FALLTHROUGH; + case FAILSAFE_RX_LOSS_DETECTED: + // Very brief, changes to FAILSAFE_RX_LOSS_RECOVERED + // or the FS procedure immediately. + FALLTHROUGH; + case FAILSAFE_RX_LOSS_RECOVERED: + // Exiting failsafe + break; + } + return NULL; } static const char * osdFailsafeInfoMessage(void) { - if (failsafeIsReceivingRxData()) { - // User must move sticks to exit FS mode - return OSD_MESSAGE_STR(OSD_MSG_MOVE_EXIT_FS); - } - return OSD_MESSAGE_STR(OSD_MSG_RC_RX_LINK_LOST); + if (failsafeIsReceivingRxData()) { + // User must move sticks to exit FS mode + return OSD_MESSAGE_STR(OSD_MSG_MOVE_EXIT_FS); + } + return OSD_MESSAGE_STR(OSD_MSG_RC_RX_LINK_LOST); } #if defined(USE_SAFE_HOME) static const char * divertingToSafehomeMessage(void) { if (NAV_Status.state != MW_NAV_STATE_HOVER_ABOVE_HOME && safehome_applied) { - return OSD_MESSAGE_STR(OSD_MSG_DIVERT_SAFEHOME); + return OSD_MESSAGE_STR(OSD_MSG_DIVERT_SAFEHOME); } return NULL; } @@ -995,72 +995,72 @@ static const char * divertingToSafehomeMessage(void) static const char * navigationStateMessage(void) { - switch (NAV_Status.state) { - case MW_NAV_STATE_NONE: - break; - case MW_NAV_STATE_RTH_START: - return OSD_MESSAGE_STR(OSD_MSG_STARTING_RTH); - case MW_NAV_STATE_RTH_CLIMB: - return OSD_MESSAGE_STR(OSD_MSG_RTH_CLIMB); - case MW_NAV_STATE_RTH_ENROUTE: - if (posControl.flags.rthTrackbackActive) { - return OSD_MESSAGE_STR(OSD_MSG_RTH_TRACKBACK); - } else { - return OSD_MESSAGE_STR(OSD_MSG_HEADING_HOME); - } - case MW_NAV_STATE_HOLD_INFINIT: - // Used by HOLD flight modes. No information to add. - break; - case MW_NAV_STATE_HOLD_TIMED: - // "HOLDING WP FOR xx S" Countdown added in osdGetSystemMessage - break; - case MW_NAV_STATE_WP_ENROUTE: - // "TO WP" + WP countdown added in osdGetSystemMessage - break; - case MW_NAV_STATE_PROCESS_NEXT: - return OSD_MESSAGE_STR(OSD_MSG_PREPARE_NEXT_WP); - case MW_NAV_STATE_DO_JUMP: - // Not used - break; - case MW_NAV_STATE_LAND_START: - // Not used - break; - case MW_NAV_STATE_EMERGENCY_LANDING: - return OSD_MESSAGE_STR(OSD_MSG_EMERG_LANDING); - case MW_NAV_STATE_LAND_IN_PROGRESS: - return OSD_MESSAGE_STR(OSD_MSG_LANDING); - case MW_NAV_STATE_HOVER_ABOVE_HOME: - if (STATE(FIXED_WING_LEGACY)) { + switch (NAV_Status.state) { + case MW_NAV_STATE_NONE: + break; + case MW_NAV_STATE_RTH_START: + return OSD_MESSAGE_STR(OSD_MSG_STARTING_RTH); + case MW_NAV_STATE_RTH_CLIMB: + return OSD_MESSAGE_STR(OSD_MSG_RTH_CLIMB); + case MW_NAV_STATE_RTH_ENROUTE: + if (posControl.flags.rthTrackbackActive) { + return OSD_MESSAGE_STR(OSD_MSG_RTH_TRACKBACK); + } else { + return OSD_MESSAGE_STR(OSD_MSG_HEADING_HOME); + } + case MW_NAV_STATE_HOLD_INFINIT: + // Used by HOLD flight modes. No information to add. + break; + case MW_NAV_STATE_HOLD_TIMED: + // "HOLDING WP FOR xx S" Countdown added in osdGetSystemMessage + break; + case MW_NAV_STATE_WP_ENROUTE: + // "TO WP" + WP countdown added in osdGetSystemMessage + break; + case MW_NAV_STATE_PROCESS_NEXT: + return OSD_MESSAGE_STR(OSD_MSG_PREPARE_NEXT_WP); + case MW_NAV_STATE_DO_JUMP: + // Not used + break; + case MW_NAV_STATE_LAND_START: + // Not used + break; + case MW_NAV_STATE_EMERGENCY_LANDING: + return OSD_MESSAGE_STR(OSD_MSG_EMERG_LANDING); + case MW_NAV_STATE_LAND_IN_PROGRESS: + return OSD_MESSAGE_STR(OSD_MSG_LANDING); + case MW_NAV_STATE_HOVER_ABOVE_HOME: + if (STATE(FIXED_WING_LEGACY)) { #if defined(USE_SAFE_HOME) - if (safehome_applied) { - return OSD_MESSAGE_STR(OSD_MSG_LOITERING_SAFEHOME); - } + if (safehome_applied) { + return OSD_MESSAGE_STR(OSD_MSG_LOITERING_SAFEHOME); + } #endif - return OSD_MESSAGE_STR(OSD_MSG_LOITERING_HOME); - } - return OSD_MESSAGE_STR(OSD_MSG_HOVERING); - case MW_NAV_STATE_LANDED: - return OSD_MESSAGE_STR(OSD_MSG_LANDED); - case MW_NAV_STATE_LAND_SETTLE: - return OSD_MESSAGE_STR(OSD_MSG_PREPARING_LAND); - case MW_NAV_STATE_LAND_START_DESCENT: - // Not used - break; - } - return NULL; + return OSD_MESSAGE_STR(OSD_MSG_LOITERING_HOME); + } + return OSD_MESSAGE_STR(OSD_MSG_HOVERING); + case MW_NAV_STATE_LANDED: + return OSD_MESSAGE_STR(OSD_MSG_LANDED); + case MW_NAV_STATE_LAND_SETTLE: + return OSD_MESSAGE_STR(OSD_MSG_PREPARING_LAND); + case MW_NAV_STATE_LAND_START_DESCENT: + // Not used + break; + } + return NULL; } static void osdFormatMessage(char *buff, size_t size, const char *message, bool isCenteredText) { - // String is always filled with Blanks - memset(buff, SYM_BLANK, size); - if (message) { - size_t messageLength = strlen(message); - int rem = isCenteredText ? MAX(0, (int)size - (int)messageLength) : 0; - strncpy(buff + rem / 2, message, MIN((int)size - rem / 2, (int)messageLength)); - } - // Ensure buff is zero terminated - buff[size] = '\0'; + // String is always filled with Blanks + memset(buff, SYM_BLANK, size); + if (message) { + size_t messageLength = strlen(message); + int rem = isCenteredText ? MAX(0, (int)size - (int)messageLength) : 0; + strncpy(buff + rem / 2, message, MIN((int)size - rem / 2, (int)messageLength)); + } + // Ensure buff is zero terminated + buff[size] = '\0'; } /** @@ -1069,25 +1069,25 @@ static void osdFormatMessage(char *buff, size_t size, const char *message, bool **/ static void osdFormatBatteryChargeSymbol(char *buff) { - uint8_t p = calculateBatteryPercentage(); - p = (100 - p) / 16.6; - buff[0] = SYM_BATT_FULL + p; + uint8_t p = calculateBatteryPercentage(); + p = (100 - p) / 16.6; + buff[0] = SYM_BATT_FULL + p; } static void osdUpdateBatteryCapacityOrVoltageTextAttributes(textAttributes_t *attr) { - const batteryState_e batteryState = getBatteryState(); + const batteryState_e batteryState = getBatteryState(); - if (batteryState == BATTERY_WARNING || batteryState == BATTERY_CRITICAL) { - TEXT_ATTRIBUTES_ADD_BLINK(*attr); - } + if (batteryState == BATTERY_WARNING || batteryState == BATTERY_CRITICAL) { + TEXT_ATTRIBUTES_ADD_BLINK(*attr); + } } void osdCrosshairPosition(uint8_t *x, uint8_t *y) { - *x = osdDisplayPort->cols / 2; - *y = osdDisplayPort->rows / 2; - *y -= osdConfig()->horizon_offset; // positive horizon_offset moves the HUD up, negative moves down + *x = osdDisplayPort->cols / 2; + *y = osdDisplayPort->rows / 2; + *y -= osdConfig()->horizon_offset; // positive horizon_offset moves the HUD up, negative moves down } /** @@ -1096,13 +1096,13 @@ void osdCrosshairPosition(uint8_t *x, uint8_t *y) */ bool osdUsingScaledThrottle(void) { - bool usingScaledThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_SCALED_THROTTLE_POS]); - bool usingRCThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_THROTTLE_POS]); + bool usingScaledThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_SCALED_THROTTLE_POS]); + bool usingRCThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_THROTTLE_POS]); - if (!usingScaledThrottle && !usingRCThrottle) - usingScaledThrottle = true; + if (!usingScaledThrottle && !usingRCThrottle) + usingScaledThrottle = true; - return usingScaledThrottle; + return usingScaledThrottle; } /** @@ -1111,26 +1111,26 @@ bool osdUsingScaledThrottle(void) **/ static void osdFormatThrottlePosition(char *buff, bool useScaled, textAttributes_t *elemAttr) { - if (useScaled) { - buff[0] = SYM_SCALE; - } else { - buff[0] = SYM_BLANK; - } - buff[1] = SYM_THR; - if (navigationIsControllingThrottle()) { - buff[0] = SYM_AUTO_THR0; - buff[1] = SYM_AUTO_THR1; - if (isFixedWingAutoThrottleManuallyIncreased()) { - TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr); - } - useScaled = true; - } + if (useScaled) { + buff[0] = SYM_SCALE; + } else { + buff[0] = SYM_BLANK; + } + buff[1] = SYM_THR; + if (navigationIsControllingThrottle()) { + buff[0] = SYM_AUTO_THR0; + buff[1] = SYM_AUTO_THR1; + if (isFixedWingAutoThrottleManuallyIncreased()) { + TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr); + } + useScaled = true; + } #ifdef USE_POWER_LIMITS - if (powerLimiterIsLimiting()) { - TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr); - } + if (powerLimiterIsLimiting()) { + TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr); + } #endif - tfp_sprintf(buff + 2, "%3d", getThrottlePercent(useScaled)); + tfp_sprintf(buff + 2, "%3d", getThrottlePercent(useScaled)); } /** @@ -1138,110 +1138,110 @@ static void osdFormatThrottlePosition(char *buff, bool useScaled, textAttributes **/ static void osdFormatGVar(char *buff, uint8_t index) { - buff[0] = 'G'; - buff[1] = '0'+index; - buff[2] = ':'; - #ifdef USE_PROGRAMMING_FRAMEWORK - osdFormatCentiNumber(buff + 3, (int32_t)gvGet(index)*(int32_t)100, 1, 0, 0, 5); - #endif + buff[0] = 'G'; + buff[1] = '0'+index; + buff[2] = ':'; + #ifdef USE_PROGRAMMING_FRAMEWORK + osdFormatCentiNumber(buff + 3, (int32_t)gvGet(index)*(int32_t)100, 1, 0, 0, 5); + #endif } #if defined(USE_ESC_SENSOR) static void osdFormatRpm(char *buff, uint32_t rpm) { - buff[0] = SYM_RPM; - if (rpm) { - if ( digitCount(rpm) > osdConfig()->esc_rpm_precision) { - uint8_t rpmMaxDecimals = (osdConfig()->esc_rpm_precision - 3); - osdFormatCentiNumber(buff + 1, rpm / 10, 0, rpmMaxDecimals, rpmMaxDecimals, osdConfig()->esc_rpm_precision-1); - buff[osdConfig()->esc_rpm_precision] = 'K'; - buff[osdConfig()->esc_rpm_precision+1] = '\0'; - } - else { - switch(osdConfig()->esc_rpm_precision) { - case 6: - tfp_sprintf(buff + 1, "%6lu", rpm); - break; - case 5: - tfp_sprintf(buff + 1, "%5lu", rpm); - break; - case 4: - tfp_sprintf(buff + 1, "%4lu", rpm); - break; - case 3: - default: - tfp_sprintf(buff + 1, "%3lu", rpm); - break; - } + buff[0] = SYM_RPM; + if (rpm) { + if ( digitCount(rpm) > osdConfig()->esc_rpm_precision) { + uint8_t rpmMaxDecimals = (osdConfig()->esc_rpm_precision - 3); + osdFormatCentiNumber(buff + 1, rpm / 10, 0, rpmMaxDecimals, rpmMaxDecimals, osdConfig()->esc_rpm_precision-1); + buff[osdConfig()->esc_rpm_precision] = 'K'; + buff[osdConfig()->esc_rpm_precision+1] = '\0'; + } + else { + switch(osdConfig()->esc_rpm_precision) { + case 6: + tfp_sprintf(buff + 1, "%6lu", rpm); + break; + case 5: + tfp_sprintf(buff + 1, "%5lu", rpm); + break; + case 4: + tfp_sprintf(buff + 1, "%4lu", rpm); + break; + case 3: + default: + tfp_sprintf(buff + 1, "%3lu", rpm); + break; + } - } - } - else { - uint8_t buffPos = 1; - while (buffPos <=( osdConfig()->esc_rpm_precision)) { - strcpy(buff + buffPos++, "-"); - } - } + } + } + else { + uint8_t buffPos = 1; + while (buffPos <=( osdConfig()->esc_rpm_precision)) { + strcpy(buff + buffPos++, "-"); + } + } } #endif int32_t osdGetAltitude(void) { - return getEstimatedActualPosition(Z); + return getEstimatedActualPosition(Z); } static inline int32_t osdGetAltitudeMsl(void) { - return getEstimatedActualPosition(Z)+GPS_home.alt; + return getEstimatedActualPosition(Z)+GPS_home.alt; } uint16_t osdGetRemainingGlideTime(void) { - float value = getEstimatedActualVelocity(Z); - static pt1Filter_t glideTimeFilterState; - const timeMs_t curTimeMs = millis(); - static timeMs_t glideTimeUpdatedMs; + float value = getEstimatedActualVelocity(Z); + static pt1Filter_t glideTimeFilterState; + const timeMs_t curTimeMs = millis(); + static timeMs_t glideTimeUpdatedMs; - value = pt1FilterApply4(&glideTimeFilterState, isnormal(value) ? value : 0, 0.5, MS2S(curTimeMs - glideTimeUpdatedMs)); - glideTimeUpdatedMs = curTimeMs; + value = pt1FilterApply4(&glideTimeFilterState, isnormal(value) ? value : 0, 0.5, MS2S(curTimeMs - glideTimeUpdatedMs)); + glideTimeUpdatedMs = curTimeMs; - if (value < 0) { - value = osdGetAltitude() / abs((int)value); - } else { - value = 0; - } + if (value < 0) { + value = osdGetAltitude() / abs((int)value); + } else { + value = 0; + } - return (uint16_t)roundf(value); + return (uint16_t)roundf(value); } static bool osdIsHeadingValid(void) { - return isImuHeadingValid(); + return isImuHeadingValid(); } int16_t osdGetHeading(void) { - return attitude.values.yaw; + return attitude.values.yaw; } int16_t osdGetPanServoOffset(void) { - int8_t servoIndex = osdConfig()->pan_servo_index; - int16_t servoPosition = servo[servoIndex]; - int16_t servoMiddle = servoParams(servoIndex)->middle; - return (int16_t)CENTIDEGREES_TO_DEGREES((servoPosition - servoMiddle) * osdConfig()->pan_servo_pwm2centideg); + int8_t servoIndex = osdConfig()->pan_servo_index; + int16_t servoPosition = servo[servoIndex]; + int16_t servoMiddle = servoParams(servoIndex)->middle; + return (int16_t)CENTIDEGREES_TO_DEGREES((servoPosition - servoMiddle) * osdConfig()->pan_servo_pwm2centideg); } // Returns a heading angle in degrees normalized to [0, 360). int osdGetHeadingAngle(int angle) { - while (angle < 0) { - angle += 360; - } - while (angle >= 360) { - angle -= 360; - } - return angle; + while (angle < 0) { + angle += 360; + } + while (angle >= 360) { + angle -= 360; + } + return angle; } #if defined(USE_GPS) @@ -1255,141 +1255,141 @@ int osdGetHeadingAngle(int angle) * erasing all screen on each redraw. */ static void osdDrawMap(int referenceHeading, uint16_t referenceSym, uint16_t centerSym, - uint32_t poiDistance, int16_t poiDirection, uint16_t poiSymbol, - uint16_t *drawn, uint32_t *usedScale) + uint32_t poiDistance, int16_t poiDirection, uint16_t poiSymbol, + uint16_t *drawn, uint32_t *usedScale) { - // TODO: These need to be tested with several setups. We might - // need to make them configurable. - const int hMargin = 5; - const int vMargin = 3; + // TODO: These need to be tested with several setups. We might + // need to make them configurable. + const int hMargin = 5; + const int vMargin = 3; - // TODO: Get this from the display driver? - const int charWidth = 12; - const int charHeight = 18; + // TODO: Get this from the display driver? + const int charWidth = 12; + const int charHeight = 18; - uint8_t minX = hMargin; - uint8_t maxX = osdDisplayPort->cols - 1 - hMargin; - uint8_t minY = vMargin; - uint8_t maxY = osdDisplayPort->rows - 1 - vMargin; - uint8_t midX = osdDisplayPort->cols / 2; - uint8_t midY = osdDisplayPort->rows / 2; + uint8_t minX = hMargin; + uint8_t maxX = osdDisplayPort->cols - 1 - hMargin; + uint8_t minY = vMargin; + uint8_t maxY = osdDisplayPort->rows - 1 - vMargin; + uint8_t midX = osdDisplayPort->cols / 2; + uint8_t midY = osdDisplayPort->rows / 2; - // Fixed marks - displayWriteChar(osdDisplayPort, midX, midY, centerSym); + // Fixed marks + displayWriteChar(osdDisplayPort, midX, midY, centerSym); - // First, erase the previous drawing. - if (OSD_VISIBLE(*drawn)) { - displayWriteChar(osdDisplayPort, OSD_X(*drawn), OSD_Y(*drawn), SYM_BLANK); - *drawn = 0; - } + // First, erase the previous drawing. + if (OSD_VISIBLE(*drawn)) { + displayWriteChar(osdDisplayPort, OSD_X(*drawn), OSD_Y(*drawn), SYM_BLANK); + *drawn = 0; + } - uint32_t initialScale; - const unsigned scaleMultiplier = 2; - // We try to reduce the scale when the POI will be around half the distance - // between the center and the closers map edge, to avoid too much jumping - const int scaleReductionMultiplier = MIN(midX - hMargin, midY - vMargin) / 2; + uint32_t initialScale; + const unsigned scaleMultiplier = 2; + // We try to reduce the scale when the POI will be around half the distance + // between the center and the closers map edge, to avoid too much jumping + const int scaleReductionMultiplier = MIN(midX - hMargin, midY - vMargin) / 2; - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - initialScale = 16; // 16m ~= 0.01miles - break; - case OSD_UNIT_GA: - initialScale = 18; // 18m ~= 0.01 nautical miles - break; - default: - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - initialScale = 10; // 10m as initial scale - break; - } + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + initialScale = 16; // 16m ~= 0.01miles + break; + case OSD_UNIT_GA: + initialScale = 18; // 18m ~= 0.01 nautical miles + break; + default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + initialScale = 10; // 10m as initial scale + break; + } - // Try to keep the same scale when getting closer until we draw over the center point - uint32_t scale = initialScale; - if (*usedScale) { - scale = *usedScale; - if (scale > initialScale && poiDistance < *usedScale * scaleReductionMultiplier) { - scale /= scaleMultiplier; - } - } + // Try to keep the same scale when getting closer until we draw over the center point + uint32_t scale = initialScale; + if (*usedScale) { + scale = *usedScale; + if (scale > initialScale && poiDistance < *usedScale * scaleReductionMultiplier) { + scale /= scaleMultiplier; + } + } - if (STATE(GPS_FIX)) { + if (STATE(GPS_FIX)) { - int directionToPoi = osdGetHeadingAngle(poiDirection - referenceHeading); - float poiAngle = DEGREES_TO_RADIANS(directionToPoi); - float poiSin = sin_approx(poiAngle); - float poiCos = cos_approx(poiAngle); + int directionToPoi = osdGetHeadingAngle(poiDirection - referenceHeading); + float poiAngle = DEGREES_TO_RADIANS(directionToPoi); + float poiSin = sin_approx(poiAngle); + float poiCos = cos_approx(poiAngle); - // Now start looking for a valid scale that lets us draw everything - int ii; - for (ii = 0; ii < 50; ii++) { - // Calculate location of the aircraft in map - int points = poiDistance / ((float)scale / charHeight); + // Now start looking for a valid scale that lets us draw everything + int ii; + for (ii = 0; ii < 50; ii++) { + // Calculate location of the aircraft in map + int points = poiDistance / ((float)scale / charHeight); - float pointsX = points * poiSin; - int poiX = midX - roundf(pointsX / charWidth); - if (poiX < minX || poiX > maxX) { - scale *= scaleMultiplier; - continue; - } + float pointsX = points * poiSin; + int poiX = midX - roundf(pointsX / charWidth); + if (poiX < minX || poiX > maxX) { + scale *= scaleMultiplier; + continue; + } - float pointsY = points * poiCos; - int poiY = midY + roundf(pointsY / charHeight); - if (poiY < minY || poiY > maxY) { - scale *= scaleMultiplier; - continue; - } + float pointsY = points * poiCos; + int poiY = midY + roundf(pointsY / charHeight); + if (poiY < minY || poiY > maxY) { + scale *= scaleMultiplier; + continue; + } - if (poiX == midX && poiY == midY) { - // We're over the map center symbol, so we would be drawing - // over it even if we increased the scale. Alternate between - // drawing the center symbol or drawing the POI. - if (centerSym != SYM_BLANK && OSD_ALTERNATING_CHOICES(1000, 2) == 0) { - break; - } - } else { + if (poiX == midX && poiY == midY) { + // We're over the map center symbol, so we would be drawing + // over it even if we increased the scale. Alternate between + // drawing the center symbol or drawing the POI. + if (centerSym != SYM_BLANK && OSD_ALTERNATING_CHOICES(1000, 2) == 0) { + break; + } + } else { - uint16_t c; - if (displayReadCharWithAttr(osdDisplayPort, poiX, poiY, &c, NULL) && c != SYM_BLANK) { - // Something else written here, increase scale. If the display doesn't support reading - // back characters, we assume there's nothing. - // - // If we're close to the center, decrease scale. Otherwise increase it. - uint8_t centerDeltaX = (maxX - minX) / (scaleMultiplier * 2); - uint8_t centerDeltaY = (maxY - minY) / (scaleMultiplier * 2); - if (poiX >= midX - centerDeltaX && poiX <= midX + centerDeltaX && - poiY >= midY - centerDeltaY && poiY <= midY + centerDeltaY && - scale > scaleMultiplier) { + uint16_t c; + if (displayReadCharWithAttr(osdDisplayPort, poiX, poiY, &c, NULL) && c != SYM_BLANK) { + // Something else written here, increase scale. If the display doesn't support reading + // back characters, we assume there's nothing. + // + // If we're close to the center, decrease scale. Otherwise increase it. + uint8_t centerDeltaX = (maxX - minX) / (scaleMultiplier * 2); + uint8_t centerDeltaY = (maxY - minY) / (scaleMultiplier * 2); + if (poiX >= midX - centerDeltaX && poiX <= midX + centerDeltaX && + poiY >= midY - centerDeltaY && poiY <= midY + centerDeltaY && + scale > scaleMultiplier) { - scale /= scaleMultiplier; - } else { - scale *= scaleMultiplier; - } - continue; - } - } + scale /= scaleMultiplier; + } else { + scale *= scaleMultiplier; + } + continue; + } + } - // Draw the point on the map - if (poiSymbol == SYM_ARROW_UP) { - // Drawing aircraft, rotate - int mapHeading = osdGetHeadingAngle(DECIDEGREES_TO_DEGREES(osdGetHeading()) - referenceHeading); - poiSymbol += mapHeading * 2 / 45; - } - displayWriteChar(osdDisplayPort, poiX, poiY, poiSymbol); + // Draw the point on the map + if (poiSymbol == SYM_ARROW_UP) { + // Drawing aircraft, rotate + int mapHeading = osdGetHeadingAngle(DECIDEGREES_TO_DEGREES(osdGetHeading()) - referenceHeading); + poiSymbol += mapHeading * 2 / 45; + } + displayWriteChar(osdDisplayPort, poiX, poiY, poiSymbol); - // Update saved location - *drawn = OSD_POS(poiX, poiY) | OSD_VISIBLE_FLAG; - break; - } - } + // Update saved location + *drawn = OSD_POS(poiX, poiY) | OSD_VISIBLE_FLAG; + break; + } + } - *usedScale = scale; + *usedScale = scale; - // Update global map data for scale and reference - osdMapData.scale = scale; - osdMapData.referenceSymbol = referenceSym; + // Update global map data for scale and reference + osdMapData.scale = scale; + osdMapData.referenceSymbol = referenceSym; } /* Draws a map with the home in the center and the craft moving around. @@ -1397,7 +1397,7 @@ static void osdDrawMap(int referenceHeading, uint16_t referenceSym, uint16_t cen */ static void osdDrawHomeMap(int referenceHeading, uint8_t referenceSym, uint16_t *drawn, uint32_t *usedScale) { - osdDrawMap(referenceHeading, referenceSym, SYM_HOME, GPS_distanceToHome, GPS_directionToHome, SYM_ARROW_UP, drawn, usedScale); + osdDrawMap(referenceHeading, referenceSym, SYM_HOME, GPS_distanceToHome, GPS_directionToHome, SYM_ARROW_UP, drawn, usedScale); } /* Draws a map with the aircraft in the center and the home moving around. @@ -1405,3015 +1405,3113 @@ static void osdDrawHomeMap(int referenceHeading, uint8_t referenceSym, uint16_t */ static void osdDrawRadar(uint16_t *drawn, uint32_t *usedScale) { - int16_t reference = DECIDEGREES_TO_DEGREES(osdGetHeading()); - int16_t poiDirection = osdGetHeadingAngle(GPS_directionToHome + 180); - osdDrawMap(reference, 0, SYM_ARROW_UP, GPS_distanceToHome, poiDirection, SYM_HOME, drawn, usedScale); + int16_t reference = DECIDEGREES_TO_DEGREES(osdGetHeading()); + int16_t poiDirection = osdGetHeadingAngle(GPS_directionToHome + 180); + osdDrawMap(reference, 0, SYM_ARROW_UP, GPS_distanceToHome, poiDirection, SYM_HOME, drawn, usedScale); } static uint16_t crc_accumulate(uint8_t data, uint16_t crcAccum) { - uint8_t tmp; - tmp = data ^ (uint8_t)(crcAccum & 0xff); - tmp ^= (tmp << 4); - crcAccum = (crcAccum >> 8) ^ (tmp << 8) ^ (tmp << 3) ^ (tmp >> 4); - return crcAccum; + uint8_t tmp; + tmp = data ^ (uint8_t)(crcAccum & 0xff); + tmp ^= (tmp << 4); + crcAccum = (crcAccum >> 8) ^ (tmp << 8) ^ (tmp << 3) ^ (tmp >> 4); + return crcAccum; } static void osdDisplayTelemetry(void) { - uint32_t trk_data; - uint16_t trk_crc = 0; - char trk_buffer[31]; - static int16_t trk_elevation = 127; - static uint16_t trk_bearing = 0; + uint32_t trk_data; + uint16_t trk_crc = 0; + char trk_buffer[31]; + static int16_t trk_elevation = 127; + static uint16_t trk_bearing = 0; - if (ARMING_FLAG(ARMED)) { - if (STATE(GPS_FIX)){ - if (GPS_distanceToHome > 5) { - trk_bearing = GPS_directionToHome; - trk_bearing += 360 + 180; - trk_bearing %= 360; - int32_t alt = CENTIMETERS_TO_METERS(osdGetAltitude()); - float at = atan2(alt, GPS_distanceToHome); - trk_elevation = at * 57.2957795f; // 57.2957795 = 1 rad - trk_elevation += 37; // because elevation in telemetry should be from -37 to 90 - if (trk_elevation < 0) { - trk_elevation = 0; - } - } - } - } - else{ - trk_elevation = 127; - trk_bearing = 0; - } + if (ARMING_FLAG(ARMED)) { + if (STATE(GPS_FIX)){ + if (GPS_distanceToHome > 5) { + trk_bearing = GPS_directionToHome; + trk_bearing += 360 + 180; + trk_bearing %= 360; + int32_t alt = CENTIMETERS_TO_METERS(osdGetAltitude()); + float at = atan2(alt, GPS_distanceToHome); + trk_elevation = at * 57.2957795f; // 57.2957795 = 1 rad + trk_elevation += 37; // because elevation in telemetry should be from -37 to 90 + if (trk_elevation < 0) { + trk_elevation = 0; + } + } + } + } + else{ + trk_elevation = 127; + trk_bearing = 0; + } - trk_data = 0; // bit 0 - packet type 0 = bearing/elevation, 1 = 2 byte data packet - trk_data = trk_data | (uint32_t)(0x7F & trk_elevation) << 1; // bits 1-7 - elevation angle to target. NOTE number is abused. constrained value of -37 to 90 sent as 0 to 127. - trk_data = trk_data | (uint32_t)trk_bearing << 8; // bits 8-17 - bearing angle to target. 0 = true north. 0 to 360 - trk_crc = crc_accumulate(0xFF & trk_data, trk_crc); // CRC First Byte bits 0-7 - trk_crc = crc_accumulate(0xFF & trk_bearing, trk_crc); // CRC Second Byte bits 8-15 - trk_crc = crc_accumulate(trk_bearing >> 8, trk_crc); // CRC Third Byte bits 16-17 - trk_data = trk_data | (uint32_t)trk_crc << 17; // bits 18-29 CRC & 0x3FFFF + trk_data = 0; // bit 0 - packet type 0 = bearing/elevation, 1 = 2 byte data packet + trk_data = trk_data | (uint32_t)(0x7F & trk_elevation) << 1; // bits 1-7 - elevation angle to target. NOTE number is abused. constrained value of -37 to 90 sent as 0 to 127. + trk_data = trk_data | (uint32_t)trk_bearing << 8; // bits 8-17 - bearing angle to target. 0 = true north. 0 to 360 + trk_crc = crc_accumulate(0xFF & trk_data, trk_crc); // CRC First Byte bits 0-7 + trk_crc = crc_accumulate(0xFF & trk_bearing, trk_crc); // CRC Second Byte bits 8-15 + trk_crc = crc_accumulate(trk_bearing >> 8, trk_crc); // CRC Third Byte bits 16-17 + trk_data = trk_data | (uint32_t)trk_crc << 17; // bits 18-29 CRC & 0x3FFFF - for (uint8_t t_ctr = 0; t_ctr < 30; t_ctr++) { // Prepare screen buffer and write data line. - if (trk_data & (uint32_t)1 << t_ctr){ - trk_buffer[29 - t_ctr] = SYM_TELEMETRY_0; - } - else{ - trk_buffer[29 - t_ctr] = SYM_TELEMETRY_1; - } - } - trk_buffer[30] = 0; - displayWrite(osdDisplayPort, 0, 0, trk_buffer); - if (osdConfig()->telemetry>1){ - displayWrite(osdDisplayPort, 0, 3, trk_buffer); // Test display because normal telemetry line is not visible - } + for (uint8_t t_ctr = 0; t_ctr < 30; t_ctr++) { // Prepare screen buffer and write data line. + if (trk_data & (uint32_t)1 << t_ctr){ + trk_buffer[29 - t_ctr] = SYM_TELEMETRY_0; + } + else{ + trk_buffer[29 - t_ctr] = SYM_TELEMETRY_1; + } + } + trk_buffer[30] = 0; + displayWrite(osdDisplayPort, 0, 0, trk_buffer); + if (osdConfig()->telemetry>1){ + displayWrite(osdDisplayPort, 0, 3, trk_buffer); // Test display because normal telemetry line is not visible + } } #endif static void osdFormatPidControllerOutput(char *buff, const char *label, const pidController_t *pidController, uint8_t scale, bool showDecimal) { - strcpy(buff, label); - for (uint8_t i = strlen(label); i < 5; ++i) buff[i] = ' '; - uint8_t decimals = showDecimal ? 1 : 0; - osdFormatCentiNumber(buff + 5, pidController->proportional * scale, 0, decimals, 0, 4); - buff[9] = ' '; - osdFormatCentiNumber(buff + 10, pidController->integrator * scale, 0, decimals, 0, 4); - buff[14] = ' '; - osdFormatCentiNumber(buff + 15, pidController->derivative * scale, 0, decimals, 0, 4); - buff[19] = ' '; - osdFormatCentiNumber(buff + 20, pidController->output_constrained * scale, 0, decimals, 0, 4); - buff[24] = '\0'; + strcpy(buff, label); + for (uint8_t i = strlen(label); i < 5; ++i) buff[i] = ' '; + uint8_t decimals = showDecimal ? 1 : 0; + osdFormatCentiNumber(buff + 5, pidController->proportional * scale, 0, decimals, 0, 4); + buff[9] = ' '; + osdFormatCentiNumber(buff + 10, pidController->integrator * scale, 0, decimals, 0, 4); + buff[14] = ' '; + osdFormatCentiNumber(buff + 15, pidController->derivative * scale, 0, decimals, 0, 4); + buff[19] = ' '; + osdFormatCentiNumber(buff + 20, pidController->output_constrained * scale, 0, decimals, 0, 4); + buff[24] = '\0'; } static void osdDisplayBatteryVoltage(uint8_t elemPosX, uint8_t elemPosY, uint16_t voltage, uint8_t digits, uint8_t decimals) { - char buff[7]; - textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; + char buff[7]; + textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; - osdFormatBatteryChargeSymbol(buff); - buff[1] = '\0'; - osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); + osdFormatBatteryChargeSymbol(buff); + buff[1] = '\0'; + osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); - elemAttr = TEXT_ATTRIBUTES_NONE; - digits = MIN(digits, 5); - osdFormatCentiNumber(buff, voltage, 0, decimals, 0, digits); - buff[digits] = SYM_VOLT; - buff[digits+1] = '\0'; - const batteryState_e batteryVoltageState = checkBatteryVoltageState(); - if (batteryVoltageState == BATTERY_CRITICAL || batteryVoltageState == BATTERY_WARNING) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - displayWriteWithAttr(osdDisplayPort, elemPosX + 1, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + digits = MIN(digits, 5); + osdFormatCentiNumber(buff, voltage, 0, decimals, 0, digits); + buff[digits] = SYM_VOLT; + buff[digits+1] = '\0'; + const batteryState_e batteryVoltageState = checkBatteryVoltageState(); + if (batteryVoltageState == BATTERY_CRITICAL || batteryVoltageState == BATTERY_WARNING) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + displayWriteWithAttr(osdDisplayPort, elemPosX + 1, elemPosY, buff, elemAttr); } static void osdDisplayFlightPIDValues(uint8_t elemPosX, uint8_t elemPosY, const char *str, pidIndex_e pidIndex, adjustmentFunction_e adjFuncP, adjustmentFunction_e adjFuncI, adjustmentFunction_e adjFuncD, adjustmentFunction_e adjFuncFF) { - textAttributes_t elemAttr; - char buff[4]; + textAttributes_t elemAttr; + char buff[4]; - const pid8_t *pid = &pidBank()->pid[pidIndex]; - pidType_e pidType = pidIndexGetType(pidIndex); + const pid8_t *pid = &pidBank()->pid[pidIndex]; + pidType_e pidType = pidIndexGetType(pidIndex); - displayWrite(osdDisplayPort, elemPosX, elemPosY, str); + displayWrite(osdDisplayPort, elemPosX, elemPosY, str); - if (pidType == PID_TYPE_NONE) { - // PID is not used in this configuration. Draw dashes. - // XXX: Keep this in sync with the %3d format and spacing used below - displayWrite(osdDisplayPort, elemPosX + 6, elemPosY, "- - - -"); - return; - } + if (pidType == PID_TYPE_NONE) { + // PID is not used in this configuration. Draw dashes. + // XXX: Keep this in sync with the %3d format and spacing used below + displayWrite(osdDisplayPort, elemPosX + 6, elemPosY, "- - - -"); + return; + } - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pid->P); - if ((isAdjustmentFunctionSelected(adjFuncP)) || (((adjFuncP == ADJUSTMENT_ROLL_P) || (adjFuncP == ADJUSTMENT_PITCH_P)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_P)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pid->P); + if ((isAdjustmentFunctionSelected(adjFuncP)) || (((adjFuncP == ADJUSTMENT_ROLL_P) || (adjFuncP == ADJUSTMENT_PITCH_P)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_P)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pid->I); - if ((isAdjustmentFunctionSelected(adjFuncI)) || (((adjFuncI == ADJUSTMENT_ROLL_I) || (adjFuncI == ADJUSTMENT_PITCH_I)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_I)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 8, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pid->I); + if ((isAdjustmentFunctionSelected(adjFuncI)) || (((adjFuncI == ADJUSTMENT_ROLL_I) || (adjFuncI == ADJUSTMENT_PITCH_I)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_I)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 8, elemPosY, buff, elemAttr); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pid->D); - if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D) || (adjFuncD == ADJUSTMENT_PITCH_D)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 12, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pid->D); + if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D) || (adjFuncD == ADJUSTMENT_PITCH_D)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 12, elemPosY, buff, elemAttr); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pid->FF); - if ((isAdjustmentFunctionSelected(adjFuncFF)) || (((adjFuncFF == ADJUSTMENT_ROLL_FF) || (adjFuncFF == ADJUSTMENT_PITCH_FF)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_FF)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 16, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pid->FF); + if ((isAdjustmentFunctionSelected(adjFuncFF)) || (((adjFuncFF == ADJUSTMENT_ROLL_FF) || (adjFuncFF == ADJUSTMENT_PITCH_FF)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_FF)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 16, elemPosY, buff, elemAttr); } static void osdDisplayNavPIDValues(uint8_t elemPosX, uint8_t elemPosY, const char *str, pidIndex_e pidIndex, adjustmentFunction_e adjFuncP, adjustmentFunction_e adjFuncI, adjustmentFunction_e adjFuncD) { - textAttributes_t elemAttr; - char buff[4]; + textAttributes_t elemAttr; + char buff[4]; - const pid8_t *pid = &pidBank()->pid[pidIndex]; - pidType_e pidType = pidIndexGetType(pidIndex); + const pid8_t *pid = &pidBank()->pid[pidIndex]; + pidType_e pidType = pidIndexGetType(pidIndex); - displayWrite(osdDisplayPort, elemPosX, elemPosY, str); + displayWrite(osdDisplayPort, elemPosX, elemPosY, str); - if (pidType == PID_TYPE_NONE) { - // PID is not used in this configuration. Draw dashes. - // XXX: Keep this in sync with the %3d format and spacing used below - displayWrite(osdDisplayPort, elemPosX + 6, elemPosY, "- - -"); - return; - } + if (pidType == PID_TYPE_NONE) { + // PID is not used in this configuration. Draw dashes. + // XXX: Keep this in sync with the %3d format and spacing used below + displayWrite(osdDisplayPort, elemPosX + 6, elemPosY, "- - -"); + return; + } - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pid->P); - if ((isAdjustmentFunctionSelected(adjFuncP)) || (((adjFuncP == ADJUSTMENT_ROLL_P) || (adjFuncP == ADJUSTMENT_PITCH_P)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_P)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pid->P); + if ((isAdjustmentFunctionSelected(adjFuncP)) || (((adjFuncP == ADJUSTMENT_ROLL_P) || (adjFuncP == ADJUSTMENT_PITCH_P)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_P)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pid->I); - if ((isAdjustmentFunctionSelected(adjFuncI)) || (((adjFuncI == ADJUSTMENT_ROLL_I) || (adjFuncI == ADJUSTMENT_PITCH_I)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_I)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 8, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pid->I); + if ((isAdjustmentFunctionSelected(adjFuncI)) || (((adjFuncI == ADJUSTMENT_ROLL_I) || (adjFuncI == ADJUSTMENT_PITCH_I)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_I)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 8, elemPosY, buff, elemAttr); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pidType == PID_TYPE_PIFF ? pid->FF : pid->D); - if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D) || (adjFuncD == ADJUSTMENT_PITCH_D)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 12, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pidType == PID_TYPE_PIFF ? pid->FF : pid->D); + if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D) || (adjFuncD == ADJUSTMENT_PITCH_D)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 12, elemPosY, buff, elemAttr); } static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY, const char *str, const uint8_t valueOffset, const float value, const uint8_t valueLength, const uint8_t maxDecimals, adjustmentFunction_e adjFunc) { - char buff[8]; - textAttributes_t elemAttr; - displayWrite(osdDisplayPort, elemPosX, elemPosY, str); + char buff[8]; + textAttributes_t elemAttr; + displayWrite(osdDisplayPort, elemPosX, elemPosY, str); - elemAttr = TEXT_ATTRIBUTES_NONE; - osdFormatCentiNumber(buff, value * 100, 0, maxDecimals, 0, MIN(valueLength, 8)); - if (isAdjustmentFunctionSelected(adjFunc)) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + strlen(str) + 1 + valueOffset, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + osdFormatCentiNumber(buff, value * 100, 0, maxDecimals, 0, MIN(valueLength, 8)); + if (isAdjustmentFunctionSelected(adjFunc)) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + strlen(str) + 1 + valueOffset, elemPosY, buff, elemAttr); } int8_t getGeoWaypointNumber(int8_t waypointIndex) { - static int8_t lastWaypointIndex = 1; - static int8_t geoWaypointIndex; + static int8_t lastWaypointIndex = 1; + static int8_t geoWaypointIndex; - if (waypointIndex != lastWaypointIndex) { - lastWaypointIndex = geoWaypointIndex = waypointIndex; - for (uint8_t i = posControl.startWpIndex; i <= waypointIndex; i++) { - if (posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || - posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD || - posControl.waypointList[i].action == NAV_WP_ACTION_JUMP) { - geoWaypointIndex -= 1; - } - } - } + if (waypointIndex != lastWaypointIndex) { + lastWaypointIndex = geoWaypointIndex = waypointIndex; + for (uint8_t i = posControl.startWpIndex; i <= waypointIndex; i++) { + if (posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || + posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD || + posControl.waypointList[i].action == NAV_WP_ACTION_JUMP) { + geoWaypointIndex -= 1; + } + } + } - return geoWaypointIndex - posControl.startWpIndex + 1; + return geoWaypointIndex - posControl.startWpIndex + 1; } void osdDisplaySwitchIndicator(const char *swName, int rcValue, char *buff) { - int8_t ptr = 0; + int8_t ptr = 0; - if (osdConfig()->osd_switch_indicators_align_left) { - for (ptr = 0; ptr < constrain(strlen(swName), 0, OSD_SWITCH_INDICATOR_NAME_LENGTH); ptr++) { - buff[ptr] = swName[ptr]; - } + if (osdConfig()->osd_switch_indicators_align_left) { + for (ptr = 0; ptr < constrain(strlen(swName), 0, OSD_SWITCH_INDICATOR_NAME_LENGTH); ptr++) { + buff[ptr] = swName[ptr]; + } - if ( rcValue < 1333) { - buff[ptr++] = SYM_SWITCH_INDICATOR_LOW; - } else if ( rcValue > 1666) { - buff[ptr++] = SYM_SWITCH_INDICATOR_HIGH; - } else { - buff[ptr++] = SYM_SWITCH_INDICATOR_MID; - } - } else { - if ( rcValue < 1333) { - buff[ptr++] = SYM_SWITCH_INDICATOR_LOW; - } else if ( rcValue > 1666) { - buff[ptr++] = SYM_SWITCH_INDICATOR_HIGH; - } else { - buff[ptr++] = SYM_SWITCH_INDICATOR_MID; - } + if ( rcValue < 1333) { + buff[ptr++] = SYM_SWITCH_INDICATOR_LOW; + } else if ( rcValue > 1666) { + buff[ptr++] = SYM_SWITCH_INDICATOR_HIGH; + } else { + buff[ptr++] = SYM_SWITCH_INDICATOR_MID; + } + } else { + if ( rcValue < 1333) { + buff[ptr++] = SYM_SWITCH_INDICATOR_LOW; + } else if ( rcValue > 1666) { + buff[ptr++] = SYM_SWITCH_INDICATOR_HIGH; + } else { + buff[ptr++] = SYM_SWITCH_INDICATOR_MID; + } - for (ptr = 1; ptr < constrain(strlen(swName), 0, OSD_SWITCH_INDICATOR_NAME_LENGTH) + 1; ptr++) { - buff[ptr] = swName[ptr-1]; - } + for (ptr = 1; ptr < constrain(strlen(swName), 0, OSD_SWITCH_INDICATOR_NAME_LENGTH) + 1; ptr++) { + buff[ptr] = swName[ptr-1]; + } - ptr++; - } + ptr++; + } - buff[ptr] = '\0'; + buff[ptr] = '\0'; } static bool osdDrawSingleElement(uint8_t item) { - uint16_t pos = osdLayoutsConfig()->item_pos[currentLayout][item]; - if (!OSD_VISIBLE(pos)) { - return false; - } - uint8_t elemPosX = OSD_X(pos); - uint8_t elemPosY = OSD_Y(pos); - textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; - char buff[32] = {0}; + uint16_t pos = osdLayoutsConfig()->item_pos[currentLayout][item]; + if (!OSD_VISIBLE(pos)) { + return false; + } + uint8_t elemPosX = OSD_X(pos); + uint8_t elemPosY = OSD_Y(pos); + textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; + char buff[32] = {0}; - switch (item) { - case OSD_RSSI_VALUE: - { - uint16_t osdRssi = osdConvertRSSI(); - buff[0] = SYM_RSSI; - tfp_sprintf(buff + 1, "%2d", osdRssi); - if (osdRssi < osdConfig()->rssi_alarm) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } + switch (item) { + case OSD_RSSI_VALUE: + { + uint16_t osdRssi = osdConvertRSSI(); + buff[0] = SYM_RSSI; + tfp_sprintf(buff + 1, "%2d", osdRssi); + if (osdRssi < osdConfig()->rssi_alarm) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } - case OSD_MAIN_BATT_VOLTAGE: { - uint8_t base_digits = 2U; + case OSD_MAIN_BATT_VOLTAGE: { + uint8_t base_digits = 2U; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if(isBfCompatibleVideoSystem(osdConfig())) { - base_digits = 3U; // Add extra digit to account for decimal point taking an extra character space - } + if(isBfCompatibleVideoSystem(osdConfig())) { + base_digits = 3U; // Add extra digit to account for decimal point taking an extra character space + } #endif - osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawVoltage(), base_digits + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals); - return true; - } + osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawVoltage(), base_digits + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals); + return true; + } - case OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE: { - uint8_t base_digits = 2U; + case OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE: { + uint8_t base_digits = 2U; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if(isBfCompatibleVideoSystem(osdConfig())) { - base_digits = 3U; // Add extra digit to account for decimal point taking an extra character space - } + if(isBfCompatibleVideoSystem(osdConfig())) { + base_digits = 3U; // Add extra digit to account for decimal point taking an extra character space + } #endif - osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedVoltage(), base_digits + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals); - return true; - } + osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedVoltage(), base_digits + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals); + return true; + } - case OSD_CURRENT_DRAW: { - osdFormatCentiNumber(buff, getAmperage(), 0, 2, 0, 3); - buff[3] = SYM_AMP; - buff[4] = '\0'; + case OSD_CURRENT_DRAW: { + osdFormatCentiNumber(buff, getAmperage(), 0, 2, 0, 3); + buff[3] = SYM_AMP; + buff[4] = '\0'; - uint8_t current_alarm = osdConfig()->current_alarm; - if ((current_alarm > 0) && ((getAmperage() / 100.0f) > current_alarm)) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } + uint8_t current_alarm = osdConfig()->current_alarm; + if ((current_alarm > 0) && ((getAmperage() / 100.0f) > current_alarm)) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } - case OSD_MAH_DRAWN: { - uint8_t mah_digits = osdConfig()->mAh_used_precision; // Initialize to config value - bool bfcompat = false; // Assume BFCOMPAT is off + case OSD_MAH_DRAWN: { + uint8_t mah_digits = osdConfig()->mAh_used_precision; // Initialize to config value + bool bfcompat = false; // Assume BFCOMPAT is off #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if (isBfCompatibleVideoSystem(osdConfig())) { - bfcompat = true; - } + if (isBfCompatibleVideoSystem(osdConfig())) { + bfcompat = true; + } #endif - if (bfcompat) { - //BFcompat is unable to work with scaled values and it only has mAh symbol to work with - tfp_sprintf(buff, "%5d", (int)getMAhDrawn()); // Use 5 digits to allow 10Ah+ packs - buff[5] = SYM_MAH; - buff[6] = '\0'; - } else { - if (osdFormatCentiNumber(buff, getMAhDrawn() * 100, 1000, 0, (mah_digits - 2), mah_digits)) { - // Shown in Ah - buff[mah_digits] = SYM_AH; - } else { - // Shown in mAh - buff[mah_digits] = SYM_MAH; - } - buff[mah_digits + 1] = '\0'; - } + if (bfcompat) { + //BFcompat is unable to work with scaled values and it only has mAh symbol to work with + tfp_sprintf(buff, "%5d", (int)getMAhDrawn()); // Use 5 digits to allow 10Ah+ packs + buff[5] = SYM_MAH; + buff[6] = '\0'; + } else { + if (osdFormatCentiNumber(buff, getMAhDrawn() * 100, 1000, 0, (mah_digits - 2), mah_digits)) { + // Shown in Ah + buff[mah_digits] = SYM_AH; + } else { + // Shown in mAh + buff[mah_digits] = SYM_MAH; + } + buff[mah_digits + 1] = '\0'; + } - osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); - break; - } + osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); + break; + } - case OSD_WH_DRAWN: - osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3); - osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); - buff[3] = SYM_WH; - buff[4] = '\0'; - break; + case OSD_WH_DRAWN: + osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3); + osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); + buff[3] = SYM_WH; + buff[4] = '\0'; + break; - case OSD_BATTERY_REMAINING_CAPACITY: + case OSD_BATTERY_REMAINING_CAPACITY: - if (currentBatteryProfile->capacity.value == 0) - tfp_sprintf(buff, " NA"); - else if (!batteryWasFullWhenPluggedIn()) - tfp_sprintf(buff, " NF"); - else if (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH) - tfp_sprintf(buff, "%4lu", (unsigned long)getBatteryRemainingCapacity()); - else // currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH - osdFormatCentiNumber(buff + 1, getBatteryRemainingCapacity() / 10, 0, 2, 0, 3); + if (currentBatteryProfile->capacity.value == 0) + tfp_sprintf(buff, " NA"); + else if (!batteryWasFullWhenPluggedIn()) + tfp_sprintf(buff, " NF"); + else if (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH) + tfp_sprintf(buff, "%4lu", (unsigned long)getBatteryRemainingCapacity()); + else // currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH + osdFormatCentiNumber(buff + 1, getBatteryRemainingCapacity() / 10, 0, 2, 0, 3); - buff[4] = currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH ? SYM_MAH : SYM_WH; - buff[5] = '\0'; + buff[4] = currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH ? SYM_MAH : SYM_WH; + buff[5] = '\0'; - if (batteryUsesCapacityThresholds()) { - osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); - } + if (batteryUsesCapacityThresholds()) { + osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); + } - break; + break; - case OSD_BATTERY_REMAINING_PERCENT: - osdFormatBatteryChargeSymbol(buff); - tfp_sprintf(buff + 1, "%3d%%", calculateBatteryPercentage()); - osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); - break; + case OSD_BATTERY_REMAINING_PERCENT: + osdFormatBatteryChargeSymbol(buff); + tfp_sprintf(buff + 1, "%3d%%", calculateBatteryPercentage()); + osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); + break; - case OSD_POWER_SUPPLY_IMPEDANCE: - if (isPowerSupplyImpedanceValid()) - tfp_sprintf(buff, "%3d", getPowerSupplyImpedance()); - else - strcpy(buff, "---"); - buff[3] = SYM_MILLIOHM; - buff[4] = '\0'; - break; + case OSD_POWER_SUPPLY_IMPEDANCE: + if (isPowerSupplyImpedanceValid()) + tfp_sprintf(buff, "%3d", getPowerSupplyImpedance()); + else + strcpy(buff, "---"); + buff[3] = SYM_MILLIOHM; + buff[4] = '\0'; + break; #ifdef USE_GPS - case OSD_GPS_SATS: - buff[0] = SYM_SAT_L; - buff[1] = SYM_SAT_R; - tfp_sprintf(buff + 2, "%2d", gpsSol.numSat); - if (!STATE(GPS_FIX)) { - if (getHwGPSStatus() == HW_SENSOR_UNAVAILABLE || getHwGPSStatus() == HW_SENSOR_UNHEALTHY) { - strcpy(buff + 2, "X!"); - } - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; + case OSD_GPS_SATS: + buff[0] = SYM_SAT_L; + buff[1] = SYM_SAT_R; + tfp_sprintf(buff + 2, "%2d", gpsSol.numSat); + if (!STATE(GPS_FIX)) { + if (getHwGPSStatus() == HW_SENSOR_UNAVAILABLE || getHwGPSStatus() == HW_SENSOR_UNHEALTHY) { + strcpy(buff + 2, "X!"); + } + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; - case OSD_GPS_SPEED: - osdFormatVelocityStr(buff, gpsSol.groundSpeed, false, false); - break; + case OSD_GPS_SPEED: + osdFormatVelocityStr(buff, gpsSol.groundSpeed, false, false); + break; - case OSD_GPS_MAX_SPEED: - osdFormatVelocityStr(buff, stats.max_speed, false, true); - break; + case OSD_GPS_MAX_SPEED: + osdFormatVelocityStr(buff, stats.max_speed, false, true); + break; - case OSD_3D_SPEED: - osdFormatVelocityStr(buff, osdGet3DSpeed(), true, false); - break; + case OSD_3D_SPEED: + osdFormatVelocityStr(buff, osdGet3DSpeed(), true, false); + break; - case OSD_3D_MAX_SPEED: - osdFormatVelocityStr(buff, stats.max_3D_speed, true, true); - break; + case OSD_3D_MAX_SPEED: + osdFormatVelocityStr(buff, stats.max_3D_speed, true, true); + break; - case OSD_GLIDESLOPE: - { - float horizontalSpeed = gpsSol.groundSpeed; - float sinkRate = -getEstimatedActualVelocity(Z); - static pt1Filter_t gsFilterState; - const timeMs_t currentTimeMs = millis(); - static timeMs_t gsUpdatedTimeMs; - float glideSlope = horizontalSpeed / sinkRate; - glideSlope = pt1FilterApply4(&gsFilterState, isnormal(glideSlope) ? glideSlope : 200, 0.5, MS2S(currentTimeMs - gsUpdatedTimeMs)); - gsUpdatedTimeMs = currentTimeMs; + case OSD_GLIDESLOPE: + { + float horizontalSpeed = gpsSol.groundSpeed; + float sinkRate = -getEstimatedActualVelocity(Z); + static pt1Filter_t gsFilterState; + const timeMs_t currentTimeMs = millis(); + static timeMs_t gsUpdatedTimeMs; + float glideSlope = horizontalSpeed / sinkRate; + glideSlope = pt1FilterApply4(&gsFilterState, isnormal(glideSlope) ? glideSlope : 200, 0.5, MS2S(currentTimeMs - gsUpdatedTimeMs)); + gsUpdatedTimeMs = currentTimeMs; - buff[0] = SYM_GLIDESLOPE; - if (glideSlope > 0.0f && glideSlope < 100.0f) { - osdFormatCentiNumber(buff + 1, glideSlope * 100.0f, 0, 2, 0, 3); - } else { - buff[1] = buff[2] = buff[3] = '-'; - } - buff[4] = '\0'; - break; - } + buff[0] = SYM_GLIDESLOPE; + if (glideSlope > 0.0f && glideSlope < 100.0f) { + osdFormatCentiNumber(buff + 1, glideSlope * 100.0f, 0, 2, 0, 3); + } else { + buff[1] = buff[2] = buff[3] = '-'; + } + buff[4] = '\0'; + break; + } - case OSD_GPS_LAT: - osdFormatCoordinate(buff, SYM_LAT, gpsSol.llh.lat); - break; + case OSD_GPS_LAT: + osdFormatCoordinate(buff, SYM_LAT, gpsSol.llh.lat); + break; - case OSD_GPS_LON: - osdFormatCoordinate(buff, SYM_LON, gpsSol.llh.lon); - break; + case OSD_GPS_LON: + osdFormatCoordinate(buff, SYM_LON, gpsSol.llh.lon); + break; - case OSD_HOME_DIR: - { - if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && isImuHeadingValid()) { - if (GPS_distanceToHome < (navConfig()->general.min_rth_distance / 100) ) { - displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_HOME_NEAR); - } - else - { - int16_t panHomeDirOffset = 0; - if (!(osdConfig()->pan_servo_pwm2centideg == 0)){ - panHomeDirOffset = osdGetPanServoOffset(); - } - int16_t flightDirection = STATE(AIRPLANE) ? CENTIDEGREES_TO_DEGREES(posControl.actualState.cog) : DECIDEGREES_TO_DEGREES(osdGetHeading()); - int homeDirection = GPS_directionToHome - flightDirection + panHomeDirOffset; - osdDrawDirArrow(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), homeDirection); - } - } else { - // No home or no fix or unknown heading, blink. - // If we're unarmed, show the arrow pointing up so users can see the arrow - // while configuring the OSD. If we're armed, show a '-' indicating that - // we don't know the direction to home. - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, ARMING_FLAG(ARMED) ? '-' : SYM_ARROW_UP, elemAttr); - } - return true; - } + case OSD_HOME_DIR: + { + if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && isImuHeadingValid()) { + if (GPS_distanceToHome < (navConfig()->general.min_rth_distance / 100) ) { + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_HOME_NEAR); + } + else + { + int16_t panHomeDirOffset = 0; + if (!(osdConfig()->pan_servo_pwm2centideg == 0)){ + panHomeDirOffset = osdGetPanServoOffset(); + } + int16_t flightDirection = STATE(AIRPLANE) ? CENTIDEGREES_TO_DEGREES(posControl.actualState.cog) : DECIDEGREES_TO_DEGREES(osdGetHeading()); + int homeDirection = GPS_directionToHome - flightDirection + panHomeDirOffset; + osdDrawDirArrow(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), homeDirection); + } + } else { + // No home or no fix or unknown heading, blink. + // If we're unarmed, show the arrow pointing up so users can see the arrow + // while configuring the OSD. If we're armed, show a '-' indicating that + // we don't know the direction to home. + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, ARMING_FLAG(ARMED) ? '-' : SYM_ARROW_UP, elemAttr); + } + return true; + } - case OSD_HOME_HEADING_ERROR: - { - buff[0] = SYM_HOME; - buff[1] = SYM_HEADING; + case OSD_HOME_HEADING_ERROR: + { + buff[0] = SYM_HOME; + buff[1] = SYM_HEADING; - if (isImuHeadingValid() && navigationPositionEstimateIsHealthy()) { - int16_t h = lrintf(CENTIDEGREES_TO_DEGREES((float)wrap_18000(DEGREES_TO_CENTIDEGREES((int32_t)GPS_directionToHome) - (STATE(AIRPLANE) ? posControl.actualState.cog : DECIDEGREES_TO_CENTIDEGREES((int32_t)osdGetHeading()))))); - tfp_sprintf(buff + 2, "%4d", h); - } else { - strcpy(buff + 2, "----"); - } + if (isImuHeadingValid() && navigationPositionEstimateIsHealthy()) { + int16_t h = lrintf(CENTIDEGREES_TO_DEGREES((float)wrap_18000(DEGREES_TO_CENTIDEGREES((int32_t)GPS_directionToHome) - (STATE(AIRPLANE) ? posControl.actualState.cog : DECIDEGREES_TO_CENTIDEGREES((int32_t)osdGetHeading()))))); + tfp_sprintf(buff + 2, "%4d", h); + } else { + strcpy(buff + 2, "----"); + } - buff[6] = SYM_DEGREES; - buff[7] = '\0'; - break; - } + buff[6] = SYM_DEGREES; + buff[7] = '\0'; + break; + } - case OSD_HOME_DIST: - { - buff[0] = SYM_HOME; - uint32_t distance_to_home_cm = GPS_distanceToHome * 100; - osdFormatDistanceSymbol(&buff[1], distance_to_home_cm, 0); + case OSD_HOME_DIST: + { + buff[0] = SYM_HOME; + uint32_t distance_to_home_cm = GPS_distanceToHome * 100; + osdFormatDistanceSymbol(&buff[1], distance_to_home_cm, 0); - uint16_t dist_alarm = osdConfig()->dist_alarm; - if (dist_alarm > 0 && GPS_distanceToHome > dist_alarm) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } - break; + uint16_t dist_alarm = osdConfig()->dist_alarm; + if (dist_alarm > 0 && GPS_distanceToHome > dist_alarm) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + break; - case OSD_TRIP_DIST: - buff[0] = SYM_TOTAL; - osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); - break; + case OSD_TRIP_DIST: + buff[0] = SYM_TOTAL; + osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); + break; - case OSD_GROUND_COURSE: - { - buff[0] = SYM_GROUND_COURSE; - if (osdIsHeadingValid()) { - tfp_sprintf(&buff[1], "%3d", (int16_t)CENTIDEGREES_TO_DEGREES(posControl.actualState.cog)); - } else { - buff[1] = buff[2] = buff[3] = '-'; - } - buff[4] = SYM_DEGREES; - buff[5] = '\0'; - break; - } + case OSD_GROUND_COURSE: + { + buff[0] = SYM_GROUND_COURSE; + if (osdIsHeadingValid()) { + tfp_sprintf(&buff[1], "%3d", (int16_t)CENTIDEGREES_TO_DEGREES(posControl.actualState.cog)); + } else { + buff[1] = buff[2] = buff[3] = '-'; + } + buff[4] = SYM_DEGREES; + buff[5] = '\0'; + break; + } - case OSD_COURSE_HOLD_ERROR: - { - if (ARMING_FLAG(ARMED) && !FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { - displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); - return true; - } + case OSD_COURSE_HOLD_ERROR: + { + if (ARMING_FLAG(ARMED) && !FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { + displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); + return true; + } - buff[0] = SYM_HEADING; + buff[0] = SYM_HEADING; - if ((!ARMING_FLAG(ARMED)) || (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && isAdjustingPosition())) { - buff[1] = buff[2] = buff[3] = '-'; - } else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { - int16_t herr = lrintf(CENTIDEGREES_TO_DEGREES((float)navigationGetHeadingError())); - if (ABS(herr) > 99) - strcpy(buff + 1, ">99"); - else - tfp_sprintf(buff + 1, "%3d", herr); - } + if ((!ARMING_FLAG(ARMED)) || (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && isAdjustingPosition())) { + buff[1] = buff[2] = buff[3] = '-'; + } else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { + int16_t herr = lrintf(CENTIDEGREES_TO_DEGREES((float)navigationGetHeadingError())); + if (ABS(herr) > 99) + strcpy(buff + 1, ">99"); + else + tfp_sprintf(buff + 1, "%3d", herr); + } - buff[4] = SYM_DEGREES; - buff[5] = '\0'; - break; - } + buff[4] = SYM_DEGREES; + buff[5] = '\0'; + break; + } - case OSD_COURSE_HOLD_ADJUSTMENT: - { - int16_t heading_adjust = lrintf(CENTIDEGREES_TO_DEGREES((float)getCruiseHeadingAdjustment())); + case OSD_COURSE_HOLD_ADJUSTMENT: + { + int16_t heading_adjust = lrintf(CENTIDEGREES_TO_DEGREES((float)getCruiseHeadingAdjustment())); - if (ARMING_FLAG(ARMED) && ((!FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) || !(isAdjustingPosition() || isAdjustingHeading() || (heading_adjust != 0)))) { - displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); - return true; - } + if (ARMING_FLAG(ARMED) && ((!FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) || !(isAdjustingPosition() || isAdjustingHeading() || (heading_adjust != 0)))) { + displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); + return true; + } - buff[0] = SYM_HEADING; + buff[0] = SYM_HEADING; - if (!ARMING_FLAG(ARMED)) { - buff[1] = buff[2] = buff[3] = buff[4] = '-'; - } else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { - tfp_sprintf(buff + 1, "%4d", heading_adjust); - } + if (!ARMING_FLAG(ARMED)) { + buff[1] = buff[2] = buff[3] = buff[4] = '-'; + } else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { + tfp_sprintf(buff + 1, "%4d", heading_adjust); + } - buff[5] = SYM_DEGREES; - buff[6] = '\0'; - break; - } + buff[5] = SYM_DEGREES; + buff[6] = '\0'; + break; + } - case OSD_CROSS_TRACK_ERROR: - { - if (isWaypointNavTrackingActive()) { - buff[0] = SYM_CROSS_TRACK_ERROR; - osdFormatDistanceSymbol(buff + 1, navigationGetCrossTrackError(), 0); - } else { - displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); - return true; - } - break; - } + case OSD_CROSS_TRACK_ERROR: + { + if (isWaypointNavTrackingActive()) { + buff[0] = SYM_CROSS_TRACK_ERROR; + osdFormatDistanceSymbol(buff + 1, navigationGetCrossTrackError(), 0); + } else { + displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); + return true; + } + break; + } - case OSD_GPS_HDOP: - { - buff[0] = SYM_HDP_L; - buff[1] = SYM_HDP_R; - int32_t centiHDOP = 100 * gpsSol.hdop / HDOP_SCALE; - uint8_t digits = 2U; + case OSD_GPS_HDOP: + { + buff[0] = SYM_HDP_L; + buff[1] = SYM_HDP_R; + int32_t centiHDOP = 100 * gpsSol.hdop / HDOP_SCALE; + uint8_t digits = 2U; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values - if (isBfCompatibleVideoSystem(osdConfig())) { - digits = 3U; - } + if (isBfCompatibleVideoSystem(osdConfig())) { + digits = 3U; + } #endif - osdFormatCentiNumber(&buff[2], centiHDOP, 0, 1, 0, digits); - break; - } + osdFormatCentiNumber(&buff[2], centiHDOP, 0, 1, 0, digits); + break; + } - case OSD_MAP_NORTH: - { - static uint16_t drawn = 0; - static uint32_t scale = 0; - osdDrawHomeMap(0, 'N', &drawn, &scale); - return true; - } - case OSD_MAP_TAKEOFF: - { - static uint16_t drawn = 0; - static uint32_t scale = 0; - osdDrawHomeMap(CENTIDEGREES_TO_DEGREES(navigationGetHomeHeading()), 'T', &drawn, &scale); - return true; - } - case OSD_RADAR: - { - static uint16_t drawn = 0; - static uint32_t scale = 0; - osdDrawRadar(&drawn, &scale); - return true; - } + case OSD_MAP_NORTH: + { + static uint16_t drawn = 0; + static uint32_t scale = 0; + osdDrawHomeMap(0, 'N', &drawn, &scale); + return true; + } + case OSD_MAP_TAKEOFF: + { + static uint16_t drawn = 0; + static uint32_t scale = 0; + osdDrawHomeMap(CENTIDEGREES_TO_DEGREES(navigationGetHomeHeading()), 'T', &drawn, &scale); + return true; + } + case OSD_RADAR: + { + static uint16_t drawn = 0; + static uint32_t scale = 0; + osdDrawRadar(&drawn, &scale); + return true; + } #endif // GPS - case OSD_ALTITUDE: - { - int32_t alt = osdGetAltitude(); - osdFormatAltitudeSymbol(buff, alt); + case OSD_ALTITUDE: + { + int32_t alt = osdGetAltitude(); + osdFormatAltitudeSymbol(buff, alt); - uint16_t alt_alarm = osdConfig()->alt_alarm; - uint16_t neg_alt_alarm = osdConfig()->neg_alt_alarm; - if ((alt_alarm > 0 && CENTIMETERS_TO_METERS(alt) > alt_alarm) || - (neg_alt_alarm > 0 && alt < 0 && -CENTIMETERS_TO_METERS(alt) > neg_alt_alarm)) { + uint16_t alt_alarm = osdConfig()->alt_alarm; + uint16_t neg_alt_alarm = osdConfig()->neg_alt_alarm; + if ((alt_alarm > 0 && CENTIMETERS_TO_METERS(alt) > alt_alarm) || + (neg_alt_alarm > 0 && alt < 0 && -CENTIMETERS_TO_METERS(alt) > neg_alt_alarm)) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } - case OSD_ALTITUDE_MSL: - { - int32_t alt = osdGetAltitudeMsl(); - osdFormatAltitudeSymbol(buff, alt); - break; - } + case OSD_ALTITUDE_MSL: + { + int32_t alt = osdGetAltitudeMsl(); + osdFormatAltitudeSymbol(buff, alt); + break; + } #ifdef USE_RANGEFINDER - case OSD_RANGEFINDER: - { - int32_t range = rangefinderGetLatestRawAltitude(); - if (range < 0) { - buff[0] = '-'; - buff[1] = '-'; - buff[2] = '-'; - } else { - osdFormatDistanceSymbol(buff, range, 1); - } - } - break; + case OSD_RANGEFINDER: + { + int32_t range = rangefinderGetLatestRawAltitude(); + if (range < 0) { + buff[0] = '-'; + buff[1] = '-'; + buff[2] = '-'; + } else { + osdFormatDistanceSymbol(buff, range, 1); + } + } + break; #endif - case OSD_ONTIME: - { - osdFormatOnTime(buff); - break; - } + case OSD_ONTIME: + { + osdFormatOnTime(buff); + break; + } - case OSD_FLYTIME: - { - osdFormatFlyTime(buff, &elemAttr); - break; - } + case OSD_FLYTIME: + { + osdFormatFlyTime(buff, &elemAttr); + break; + } - case OSD_ONTIME_FLYTIME: - { - if (ARMING_FLAG(ARMED)) { - osdFormatFlyTime(buff, &elemAttr); - } else { - osdFormatOnTime(buff); - } - break; - } + case OSD_ONTIME_FLYTIME: + { + if (ARMING_FLAG(ARMED)) { + osdFormatFlyTime(buff, &elemAttr); + } else { + osdFormatOnTime(buff); + } + break; + } - case OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH: - { - /*static int32_t updatedTimeSeconds = 0;*/ - static int32_t timeSeconds = -1; + case OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH: + { + /*static int32_t updatedTimeSeconds = 0;*/ + static int32_t timeSeconds = -1; #if defined(USE_ADC) && defined(USE_GPS) - static timeUs_t updatedTimestamp = 0; - timeUs_t currentTimeUs = micros(); - if (cmpTimeUs(currentTimeUs, updatedTimestamp) >= MS2US(1000)) { + static timeUs_t updatedTimestamp = 0; + timeUs_t currentTimeUs = micros(); + if (cmpTimeUs(currentTimeUs, updatedTimestamp) >= MS2US(1000)) { #ifdef USE_WIND_ESTIMATOR - timeSeconds = calculateRemainingFlightTimeBeforeRTH(osdConfig()->estimations_wind_compensation); + timeSeconds = calculateRemainingFlightTimeBeforeRTH(osdConfig()->estimations_wind_compensation); #else - timeSeconds = calculateRemainingFlightTimeBeforeRTH(false); + timeSeconds = calculateRemainingFlightTimeBeforeRTH(false); #endif - updatedTimestamp = currentTimeUs; - } + updatedTimestamp = currentTimeUs; + } #endif - if ((!ARMING_FLAG(ARMED)) || (timeSeconds == -1)) { - buff[0] = SYM_FLIGHT_MINS_REMAINING; - strcpy(buff + 1, "--:--"); + if ((!ARMING_FLAG(ARMED)) || (timeSeconds == -1)) { + buff[0] = SYM_FLIGHT_MINS_REMAINING; + strcpy(buff + 1, "--:--"); #if defined(USE_ADC) && defined(USE_GPS) - updatedTimestamp = 0; + updatedTimestamp = 0; #endif - } else if (timeSeconds == -2) { - // Wind is too strong to come back with cruise throttle - buff[0] = SYM_FLIGHT_MINS_REMAINING; - buff[1] = buff[2] = buff[4] = buff[5] = SYM_WIND_HORIZONTAL; - buff[3] = ':'; - buff[6] = '\0'; - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } else { - osdFormatTime(buff, timeSeconds, SYM_FLIGHT_MINS_REMAINING, SYM_FLIGHT_HOURS_REMAINING); - if (timeSeconds == 0) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } - break; + } else if (timeSeconds == -2) { + // Wind is too strong to come back with cruise throttle + buff[0] = SYM_FLIGHT_MINS_REMAINING; + buff[1] = buff[2] = buff[4] = buff[5] = SYM_WIND_HORIZONTAL; + buff[3] = ':'; + buff[6] = '\0'; + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } else { + osdFormatTime(buff, timeSeconds, SYM_FLIGHT_MINS_REMAINING, SYM_FLIGHT_HOURS_REMAINING); + if (timeSeconds == 0) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + break; - case OSD_REMAINING_DISTANCE_BEFORE_RTH:; - static int32_t distanceMeters = -1; + case OSD_REMAINING_DISTANCE_BEFORE_RTH:; + static int32_t distanceMeters = -1; #if defined(USE_ADC) && defined(USE_GPS) - static timeUs_t updatedTimestamp = 0; - timeUs_t currentTimeUs = micros(); - if (cmpTimeUs(currentTimeUs, updatedTimestamp) >= MS2US(1000)) { + static timeUs_t updatedTimestamp = 0; + timeUs_t currentTimeUs = micros(); + if (cmpTimeUs(currentTimeUs, updatedTimestamp) >= MS2US(1000)) { #ifdef USE_WIND_ESTIMATOR - distanceMeters = calculateRemainingDistanceBeforeRTH(osdConfig()->estimations_wind_compensation); + distanceMeters = calculateRemainingDistanceBeforeRTH(osdConfig()->estimations_wind_compensation); #else - distanceMeters = calculateRemainingDistanceBeforeRTH(false); + distanceMeters = calculateRemainingDistanceBeforeRTH(false); #endif - updatedTimestamp = currentTimeUs; - } + updatedTimestamp = currentTimeUs; + } #endif - //buff[0] = SYM_TRIP_DIST; - displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_FLIGHT_DIST_REMAINING); - if ((!ARMING_FLAG(ARMED)) || (distanceMeters == -1)) { - buff[4] = SYM_BLANK; - buff[5] = '\0'; - strcpy(buff + 1, "---"); - } else if (distanceMeters == -2) { - // Wind is too strong to come back with cruise throttle - buff[1] = buff[2] = buff[3] = SYM_WIND_HORIZONTAL; - switch ((osd_unit_e)osdConfig()->units){ - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - buff[4] = SYM_DIST_MI; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - buff[4] = SYM_DIST_KM; - break; - case OSD_UNIT_GA: - buff[4] = SYM_DIST_NM; - break; - } - buff[5] = '\0'; - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } else { - osdFormatDistanceSymbol(buff + 1, distanceMeters * 100, 0); - if (distanceMeters == 0) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; + //buff[0] = SYM_TRIP_DIST; + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_FLIGHT_DIST_REMAINING); + if ((!ARMING_FLAG(ARMED)) || (distanceMeters == -1)) { + buff[4] = SYM_BLANK; + buff[5] = '\0'; + strcpy(buff + 1, "---"); + } else if (distanceMeters == -2) { + // Wind is too strong to come back with cruise throttle + buff[1] = buff[2] = buff[3] = SYM_WIND_HORIZONTAL; + switch ((osd_unit_e)osdConfig()->units){ + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + buff[4] = SYM_DIST_MI; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + buff[4] = SYM_DIST_KM; + break; + case OSD_UNIT_GA: + buff[4] = SYM_DIST_NM; + break; + } + buff[5] = '\0'; + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } else { + osdFormatDistanceSymbol(buff + 1, distanceMeters * 100, 0); + if (distanceMeters == 0) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; - case OSD_FLYMODE: - { - char *p = "ACRO"; + case OSD_FLYMODE: + { + char *p = "ACRO"; - if (FLIGHT_MODE(FAILSAFE_MODE)) - p = "!FS!"; - else if (FLIGHT_MODE(MANUAL_MODE)) - p = "MANU"; - else if (FLIGHT_MODE(TURTLE_MODE)) - p = "TURT"; - else if (FLIGHT_MODE(NAV_RTH_MODE)) - p = isWaypointMissionRTHActive() ? "WRTH" : "RTH "; - else if (FLIGHT_MODE(NAV_POSHOLD_MODE) && STATE(AIRPLANE)) - p = "LOTR"; - else if (FLIGHT_MODE(NAV_POSHOLD_MODE)) - p = "HOLD"; - else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)) - p = "CRUZ"; - else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) - p = "CRSH"; - else if (FLIGHT_MODE(NAV_WP_MODE)) - p = " WP "; - else if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && navigationRequiresAngleMode()) { - // If navigationRequiresAngleMode() returns false when ALTHOLD is active, - // it means it can be combined with ANGLE, HORIZON, ACRO, etc... - // and its display is handled by OSD_MESSAGES rather than OSD_FLYMODE. - p = " AH "; - } - else if (FLIGHT_MODE(ANGLE_MODE)) - p = "ANGL"; - else if (FLIGHT_MODE(HORIZON_MODE)) - p = "HOR "; + if (FLIGHT_MODE(FAILSAFE_MODE)) + p = "!FS!"; + else if (FLIGHT_MODE(MANUAL_MODE)) + p = "MANU"; + else if (FLIGHT_MODE(TURTLE_MODE)) + p = "TURT"; + else if (FLIGHT_MODE(NAV_RTH_MODE)) + p = isWaypointMissionRTHActive() ? "WRTH" : "RTH "; + else if (FLIGHT_MODE(NAV_POSHOLD_MODE) && STATE(AIRPLANE)) + p = "LOTR"; + else if (FLIGHT_MODE(NAV_POSHOLD_MODE)) + p = "HOLD"; + else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)) + p = "CRUZ"; + else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) + p = "CRSH"; + else if (FLIGHT_MODE(NAV_WP_MODE)) + p = " WP "; + else if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && navigationRequiresAngleMode()) { + // If navigationRequiresAngleMode() returns false when ALTHOLD is active, + // it means it can be combined with ANGLE, HORIZON, ACRO, etc... + // and its display is handled by OSD_MESSAGES rather than OSD_FLYMODE. + p = " AH "; + } + else if (FLIGHT_MODE(ANGLE_MODE)) + p = "ANGL"; + else if (FLIGHT_MODE(HORIZON_MODE)) + p = "HOR "; - displayWrite(osdDisplayPort, elemPosX, elemPosY, p); - return true; - } + displayWrite(osdDisplayPort, elemPosX, elemPosY, p); + return true; + } - case OSD_CRAFT_NAME: - osdFormatCraftName(buff); - break; + case OSD_CRAFT_NAME: + osdFormatCraftName(buff); + break; - case OSD_PILOT_NAME: - osdFormatPilotName(buff); - break; + case OSD_PILOT_NAME: + osdFormatPilotName(buff); + break; - case OSD_THROTTLE_POS: - { - osdFormatThrottlePosition(buff, false, &elemAttr); - break; - } + case OSD_THROTTLE_POS: + { + osdFormatThrottlePosition(buff, false, &elemAttr); + break; + } - case OSD_VTX_CHANNEL: - { - vtxDeviceOsdInfo_t osdInfo; - vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo); + case OSD_VTX_CHANNEL: + { + vtxDeviceOsdInfo_t osdInfo; + vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo); - tfp_sprintf(buff, "CH:%c%s:", osdInfo.bandLetter, osdInfo.channelName); - displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); + tfp_sprintf(buff, "CH:%c%s:", osdInfo.bandLetter, osdInfo.channelName); + displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); - tfp_sprintf(buff, "%c", osdInfo.powerIndexLetter); - if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 6, elemPosY, buff, elemAttr); - return true; - } - break; + tfp_sprintf(buff, "%c", osdInfo.powerIndexLetter); + if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 6, elemPosY, buff, elemAttr); + return true; + } + break; - case OSD_VTX_POWER: - { - vtxDeviceOsdInfo_t osdInfo; - vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo); + case OSD_VTX_POWER: + { + vtxDeviceOsdInfo_t osdInfo; + vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo); - tfp_sprintf(buff, "%c", SYM_VTX_POWER); - displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); + tfp_sprintf(buff, "%c", SYM_VTX_POWER); + displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); - tfp_sprintf(buff, "%c", osdInfo.powerIndexLetter); - if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); - return true; - } + tfp_sprintf(buff, "%c", osdInfo.powerIndexLetter); + if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); + return true; + } #if defined(USE_SERIALRX_CRSF) - case OSD_CRSF_RSSI_DBM: - { - int16_t rssi = rxLinkStatistics.uplinkRSSI; - buff[0] = (rxLinkStatistics.activeAntenna == 0) ? SYM_RSSI : SYM_2RSS; // Separate symbols for each antenna - if (rssi <= -100) { - tfp_sprintf(buff + 1, "%4d%c", rssi, SYM_DBM); - } else { - tfp_sprintf(buff + 1, "%3d%c%c", rssi, SYM_DBM, ' '); - } - if (!failsafeIsReceivingRxData()){ - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } else if (osdConfig()->rssi_dbm_alarm && rssi < osdConfig()->rssi_dbm_alarm) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } - case OSD_CRSF_LQ: - { - buff[0] = SYM_LQ; - int16_t statsLQ = rxLinkStatistics.uplinkLQ; - int16_t scaledLQ = scaleRange(constrain(statsLQ, 0, 100), 0, 100, 170, 300); - switch (osdConfig()->crsf_lq_format) { - case OSD_CRSF_LQ_TYPE1: - if (!failsafeIsReceivingRxData()) { - tfp_sprintf(buff+1, "%3d", 0); - } else { - tfp_sprintf(buff+1, "%3d", rxLinkStatistics.uplinkLQ); - } - break; - case OSD_CRSF_LQ_TYPE2: - if (!failsafeIsReceivingRxData()) { - tfp_sprintf(buff+1, "%s:%3d", " ", 0); - } else { - tfp_sprintf(buff+1, "%d:%3d", rxLinkStatistics.rfMode, rxLinkStatistics.uplinkLQ); - } - break; - case OSD_CRSF_LQ_TYPE3: - if (!failsafeIsReceivingRxData()) { - tfp_sprintf(buff+1, "%3d", 0); - } else { - tfp_sprintf(buff+1, "%3d", rxLinkStatistics.rfMode >= 2 ? scaledLQ : rxLinkStatistics.uplinkLQ); - } - break; - } - if (!failsafeIsReceivingRxData()) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } else if (rxLinkStatistics.uplinkLQ < osdConfig()->link_quality_alarm) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } + case OSD_CRSF_RSSI_DBM: + { + int16_t rssi = rxLinkStatistics.uplinkRSSI; + buff[0] = (rxLinkStatistics.activeAntenna == 0) ? SYM_RSSI : SYM_2RSS; // Separate symbols for each antenna + if (rssi <= -100) { + tfp_sprintf(buff + 1, "%4d%c", rssi, SYM_DBM); + } else { + tfp_sprintf(buff + 1, "%3d%c%c", rssi, SYM_DBM, ' '); + } + if (!failsafeIsReceivingRxData()){ + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } else if (osdConfig()->rssi_dbm_alarm && rssi < osdConfig()->rssi_dbm_alarm) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } + case OSD_CRSF_LQ: + { + buff[0] = SYM_LQ; + int16_t statsLQ = rxLinkStatistics.uplinkLQ; + int16_t scaledLQ = scaleRange(constrain(statsLQ, 0, 100), 0, 100, 170, 300); + switch (osdConfig()->crsf_lq_format) { + case OSD_CRSF_LQ_TYPE1: + if (!failsafeIsReceivingRxData()) { + tfp_sprintf(buff+1, "%3d", 0); + } else { + tfp_sprintf(buff+1, "%3d", rxLinkStatistics.uplinkLQ); + } + break; + case OSD_CRSF_LQ_TYPE2: + if (!failsafeIsReceivingRxData()) { + tfp_sprintf(buff+1, "%s:%3d", " ", 0); + } else { + tfp_sprintf(buff+1, "%d:%3d", rxLinkStatistics.rfMode, rxLinkStatistics.uplinkLQ); + } + break; + case OSD_CRSF_LQ_TYPE3: + if (!failsafeIsReceivingRxData()) { + tfp_sprintf(buff+1, "%3d", 0); + } else { + tfp_sprintf(buff+1, "%3d", rxLinkStatistics.rfMode >= 2 ? scaledLQ : rxLinkStatistics.uplinkLQ); + } + break; + } + if (!failsafeIsReceivingRxData()) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } else if (rxLinkStatistics.uplinkLQ < osdConfig()->link_quality_alarm) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } - case OSD_CRSF_SNR_DB: - { - static pt1Filter_t snrFilterState; - static timeMs_t snrUpdated = 0; - int8_t snrFiltered = pt1FilterApply4(&snrFilterState, rxLinkStatistics.uplinkSNR, 0.5f, MS2S(millis() - snrUpdated)); - snrUpdated = millis(); + case OSD_CRSF_SNR_DB: + { + static pt1Filter_t snrFilterState; + static timeMs_t snrUpdated = 0; + int8_t snrFiltered = pt1FilterApply4(&snrFilterState, rxLinkStatistics.uplinkSNR, 0.5f, MS2S(millis() - snrUpdated)); + snrUpdated = millis(); - const char* showsnr = "-20"; - const char* hidesnr = " "; - if (snrFiltered > osdConfig()->snr_alarm) { - if (cmsInMenu) { - buff[0] = SYM_SNR; - tfp_sprintf(buff + 1, "%s%c", showsnr, SYM_DB); - } else { - buff[0] = SYM_BLANK; - tfp_sprintf(buff + 1, "%s%c", hidesnr, SYM_BLANK); - } - } else if (snrFiltered <= osdConfig()->snr_alarm) { - buff[0] = SYM_SNR; - if (snrFiltered <= -10) { - tfp_sprintf(buff + 1, "%3d%c", snrFiltered, SYM_DB); - } else { - tfp_sprintf(buff + 1, "%2d%c%c", snrFiltered, SYM_DB, ' '); - } - } - break; - } + const char* showsnr = "-20"; + const char* hidesnr = " "; + if (snrFiltered > osdConfig()->snr_alarm) { + if (cmsInMenu) { + buff[0] = SYM_SNR; + tfp_sprintf(buff + 1, "%s%c", showsnr, SYM_DB); + } else { + buff[0] = SYM_BLANK; + tfp_sprintf(buff + 1, "%s%c", hidesnr, SYM_BLANK); + } + } else if (snrFiltered <= osdConfig()->snr_alarm) { + buff[0] = SYM_SNR; + if (snrFiltered <= -10) { + tfp_sprintf(buff + 1, "%3d%c", snrFiltered, SYM_DB); + } else { + tfp_sprintf(buff + 1, "%2d%c%c", snrFiltered, SYM_DB, ' '); + } + } + break; + } - case OSD_CRSF_TX_POWER: - { - if (!failsafeIsReceivingRxData()) - tfp_sprintf(buff, "%s%c", " ", SYM_BLANK); - else - tfp_sprintf(buff, "%4d%c", rxLinkStatistics.uplinkTXPower, SYM_MW); - break; - } + case OSD_CRSF_TX_POWER: + { + if (!failsafeIsReceivingRxData()) + tfp_sprintf(buff, "%s%c", " ", SYM_BLANK); + else + tfp_sprintf(buff, "%4d%c", rxLinkStatistics.uplinkTXPower, SYM_MW); + break; + } #endif - case OSD_CROSSHAIRS: // Hud is a sub-element of the crosshair + case OSD_CROSSHAIRS: // Hud is a sub-element of the crosshair - osdCrosshairPosition(&elemPosX, &elemPosY); - osdHudDrawCrosshair(osdGetDisplayPortCanvas(), elemPosX, elemPosY); + osdCrosshairPosition(&elemPosX, &elemPosY); + osdHudDrawCrosshair(osdGetDisplayPortCanvas(), elemPosX, elemPosY); - if (osdConfig()->hud_homing && STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && isImuHeadingValid()) { - osdHudDrawHoming(elemPosX, elemPosY); - } + if (osdConfig()->hud_homing && STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && isImuHeadingValid()) { + osdHudDrawHoming(elemPosX, elemPosY); + } - if (STATE(GPS_FIX) && isImuHeadingValid()) { + if (STATE(GPS_FIX) && isImuHeadingValid()) { - if (osdConfig()->hud_homepoint || osdConfig()->hud_radar_disp > 0 || osdConfig()->hud_wp_disp > 0) { - osdHudClear(); - } + if (osdConfig()->hud_homepoint || osdConfig()->hud_radar_disp > 0 || osdConfig()->hud_wp_disp > 0) { + osdHudClear(); + } - // -------- POI : Home point + // -------- POI : Home point - if (osdConfig()->hud_homepoint) { // Display the home point (H) - osdHudDrawPoi(GPS_distanceToHome, GPS_directionToHome, -osdGetAltitude() / 100, 0, SYM_HOME, 0 , 0); - } + if (osdConfig()->hud_homepoint) { // Display the home point (H) + osdHudDrawPoi(GPS_distanceToHome, GPS_directionToHome, -osdGetAltitude() / 100, 0, SYM_HOME, 0 , 0); + } - // -------- POI : Nearby aircrafts from ESP32 radar + // -------- POI : Nearby aircrafts from ESP32 radar - if (osdConfig()->hud_radar_disp > 0) { // Display the POI from the radar - for (uint8_t i = 0; i < osdConfig()->hud_radar_disp; i++) { - if (radar_pois[i].gps.lat != 0 && radar_pois[i].gps.lon != 0 && radar_pois[i].state < 2) { // state 2 means POI has been lost and must be skipped - fpVector3_t poi; - geoConvertGeodeticToLocal(&poi, &posControl.gpsOrigin, &radar_pois[i].gps, GEO_ALT_RELATIVE); - radar_pois[i].distance = calculateDistanceToDestination(&poi) / 100; // In meters + if (osdConfig()->hud_radar_disp > 0) { // Display the POI from the radar + for (uint8_t i = 0; i < osdConfig()->hud_radar_disp; i++) { + if (radar_pois[i].gps.lat != 0 && radar_pois[i].gps.lon != 0 && radar_pois[i].state < 2) { // state 2 means POI has been lost and must be skipped + fpVector3_t poi; + geoConvertGeodeticToLocal(&poi, &posControl.gpsOrigin, &radar_pois[i].gps, GEO_ALT_RELATIVE); + radar_pois[i].distance = calculateDistanceToDestination(&poi) / 100; // In meters - if (radar_pois[i].distance >= osdConfig()->hud_radar_range_min && radar_pois[i].distance <= osdConfig()->hud_radar_range_max) { - radar_pois[i].direction = calculateBearingToDestination(&poi) / 100; // In ° - radar_pois[i].altitude = (radar_pois[i].gps.alt - osdGetAltitudeMsl()) / 100; - osdHudDrawPoi(radar_pois[i].distance, osdGetHeadingAngle(radar_pois[i].direction), radar_pois[i].altitude, 1, 65 + i, radar_pois[i].heading, radar_pois[i].lq); - } - } - } - } + if (radar_pois[i].distance >= osdConfig()->hud_radar_range_min && radar_pois[i].distance <= osdConfig()->hud_radar_range_max) { + radar_pois[i].direction = calculateBearingToDestination(&poi) / 100; // In ° + radar_pois[i].altitude = (radar_pois[i].gps.alt - osdGetAltitudeMsl()) / 100; + osdHudDrawPoi(radar_pois[i].distance, osdGetHeadingAngle(radar_pois[i].direction), radar_pois[i].altitude, 1, 65 + i, radar_pois[i].heading, radar_pois[i].lq); + } + } + } + } - // -------- POI : Next waypoints from navigation + // -------- POI : Next waypoints from navigation - if (osdConfig()->hud_wp_disp > 0 && posControl.waypointListValid && posControl.waypointCount > 0) { // Display the next waypoints - gpsLocation_t wp2; - int j; + if (osdConfig()->hud_wp_disp > 0 && posControl.waypointListValid && posControl.waypointCount > 0) { // Display the next waypoints + gpsLocation_t wp2; + int j; - for (int i = osdConfig()->hud_wp_disp - 1; i >= 0 ; i--) { // Display in reverse order so the next WP is always written on top - j = posControl.activeWaypointIndex + i; - if (j > posControl.startWpIndex + posControl.waypointCount - 1) { // limit to max WP index for mission - break; - } - if (posControl.waypointList[j].lat != 0 && posControl.waypointList[j].lon != 0) { - wp2.lat = posControl.waypointList[j].lat; - wp2.lon = posControl.waypointList[j].lon; - wp2.alt = posControl.waypointList[j].alt; - fpVector3_t poi; - geoConvertGeodeticToLocal(&poi, &posControl.gpsOrigin, &wp2, waypointMissionAltConvMode(posControl.waypointList[j].p3)); - int32_t altConvModeAltitude = waypointMissionAltConvMode(posControl.waypointList[j].p3) == GEO_ALT_ABSOLUTE ? osdGetAltitudeMsl() : osdGetAltitude(); - j = getGeoWaypointNumber(j); - while (j > 9) j -= 10; // Only the last digit displayed if WP>=10, no room for more (48 = ascii 0) - osdHudDrawPoi(calculateDistanceToDestination(&poi) / 100, osdGetHeadingAngle(calculateBearingToDestination(&poi) / 100), (posControl.waypointList[j].alt - altConvModeAltitude)/ 100, 2, SYM_WAYPOINT, 48 + j, i); - } - } - } - } + for (int i = osdConfig()->hud_wp_disp - 1; i >= 0 ; i--) { // Display in reverse order so the next WP is always written on top + j = posControl.activeWaypointIndex + i; + if (j > posControl.startWpIndex + posControl.waypointCount - 1) { // limit to max WP index for mission + break; + } + if (posControl.waypointList[j].lat != 0 && posControl.waypointList[j].lon != 0) { + wp2.lat = posControl.waypointList[j].lat; + wp2.lon = posControl.waypointList[j].lon; + wp2.alt = posControl.waypointList[j].alt; + fpVector3_t poi; + geoConvertGeodeticToLocal(&poi, &posControl.gpsOrigin, &wp2, waypointMissionAltConvMode(posControl.waypointList[j].p3)); + int32_t altConvModeAltitude = waypointMissionAltConvMode(posControl.waypointList[j].p3) == GEO_ALT_ABSOLUTE ? osdGetAltitudeMsl() : osdGetAltitude(); + j = getGeoWaypointNumber(j); + while (j > 9) j -= 10; // Only the last digit displayed if WP>=10, no room for more (48 = ascii 0) + osdHudDrawPoi(calculateDistanceToDestination(&poi) / 100, osdGetHeadingAngle(calculateBearingToDestination(&poi) / 100), (posControl.waypointList[j].alt - altConvModeAltitude)/ 100, 2, SYM_WAYPOINT, 48 + j, i); + } + } + } + } - return true; - break; + return true; + break; - case OSD_ATTITUDE_ROLL: - buff[0] = SYM_ROLL_LEVEL; - if (ABS(attitude.values.roll) >= 1) - buff[0] += (attitude.values.roll < 0 ? -1 : 1); - osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.roll)), 0, 1, 0, 3); - break; + case OSD_ATTITUDE_ROLL: + buff[0] = SYM_ROLL_LEVEL; + if (ABS(attitude.values.roll) >= 1) + buff[0] += (attitude.values.roll < 0 ? -1 : 1); + osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.roll)), 0, 1, 0, 3); + break; - case OSD_ATTITUDE_PITCH: - if (ABS(attitude.values.pitch) < 1) - buff[0] = 'P'; - else if (attitude.values.pitch > 0) - buff[0] = SYM_PITCH_DOWN; - else if (attitude.values.pitch < 0) - buff[0] = SYM_PITCH_UP; - osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.pitch)), 0, 1, 0, 3); - break; + case OSD_ATTITUDE_PITCH: + if (ABS(attitude.values.pitch) < 1) + buff[0] = 'P'; + else if (attitude.values.pitch > 0) + buff[0] = SYM_PITCH_DOWN; + else if (attitude.values.pitch < 0) + buff[0] = SYM_PITCH_UP; + osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.pitch)), 0, 1, 0, 3); + break; - case OSD_ARTIFICIAL_HORIZON: - { - float rollAngle = DECIDEGREES_TO_RADIANS(attitude.values.roll); - float pitchAngle = DECIDEGREES_TO_RADIANS(attitude.values.pitch); + case OSD_ARTIFICIAL_HORIZON: + { + float rollAngle = DECIDEGREES_TO_RADIANS(attitude.values.roll); + float pitchAngle = DECIDEGREES_TO_RADIANS(attitude.values.pitch); - pitchAngle -= osdConfig()->ahi_camera_uptilt_comp ? DEGREES_TO_RADIANS(osdConfig()->camera_uptilt) : 0; - pitchAngle += DEGREES_TO_RADIANS(getFixedWingLevelTrim()); - if (osdConfig()->ahi_reverse_roll) { - rollAngle = -rollAngle; - } - osdDrawArtificialHorizon(osdDisplayPort, osdGetDisplayPortCanvas(), - OSD_DRAW_POINT_GRID(elemPosX, elemPosY), rollAngle, pitchAngle); - osdDrawSingleElement(OSD_HORIZON_SIDEBARS); - osdDrawSingleElement(OSD_CROSSHAIRS); + pitchAngle -= osdConfig()->ahi_camera_uptilt_comp ? DEGREES_TO_RADIANS(osdConfig()->camera_uptilt) : 0; + pitchAngle += DEGREES_TO_RADIANS(getFixedWingLevelTrim()); + if (osdConfig()->ahi_reverse_roll) { + rollAngle = -rollAngle; + } + osdDrawArtificialHorizon(osdDisplayPort, osdGetDisplayPortCanvas(), + OSD_DRAW_POINT_GRID(elemPosX, elemPosY), rollAngle, pitchAngle); + osdDrawSingleElement(OSD_HORIZON_SIDEBARS); + osdDrawSingleElement(OSD_CROSSHAIRS); - return true; - } + return true; + } - case OSD_HORIZON_SIDEBARS: - { - osdDrawSidebars(osdDisplayPort, osdGetDisplayPortCanvas()); - return true; - } + case OSD_HORIZON_SIDEBARS: + { + osdDrawSidebars(osdDisplayPort, osdGetDisplayPortCanvas()); + return true; + } #if defined(USE_BARO) || defined(USE_GPS) - case OSD_VARIO: - { - float zvel = getEstimatedActualVelocity(Z); - osdDrawVario(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), zvel); - return true; - } + case OSD_VARIO: + { + float zvel = getEstimatedActualVelocity(Z); + osdDrawVario(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), zvel); + return true; + } - case OSD_VARIO_NUM: - { - int16_t value = getEstimatedActualVelocity(Z); - char sym; - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - // Convert to centifeet/s - value = CENTIMETERS_TO_CENTIFEET(value); - sym = SYM_FTS; - break; - case OSD_UNIT_GA: - // Convert to centi-100feet/min - value = CENTIMETERS_TO_FEET(value * 60); - sym = SYM_100FTM; - break; - default: - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - // Already in cm/s - sym = SYM_MS; - break; - } + case OSD_VARIO_NUM: + { + int16_t value = getEstimatedActualVelocity(Z); + char sym; + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + // Convert to centifeet/s + value = CENTIMETERS_TO_CENTIFEET(value); + sym = SYM_FTS; + break; + case OSD_UNIT_GA: + // Convert to centi-100feet/min + value = CENTIMETERS_TO_FEET(value * 60); + sym = SYM_100FTM; + break; + default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + // Already in cm/s + sym = SYM_MS; + break; + } - osdFormatCentiNumber(buff, value, 0, 1, 0, 3); - buff[3] = sym; - buff[4] = '\0'; - break; - } - case OSD_CLIMB_EFFICIENCY: - { - // amperage is in centi amps (10mA), vertical speed is in cms/s. We want - // Ah/dist only to show when vertical speed > 1m/s. - static pt1Filter_t veFilterState; - static timeUs_t vEfficiencyUpdated = 0; - int32_t value = 0; - timeUs_t currentTimeUs = micros(); - timeDelta_t vEfficiencyTimeDelta = cmpTimeUs(currentTimeUs, vEfficiencyUpdated); - if (getEstimatedActualVelocity(Z) > 0) { - if (vEfficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { - // Centiamps (kept for osdFormatCentiNumber) / m/s - Will appear as A / m/s in OSD - value = pt1FilterApply4(&veFilterState, (float)getAmperage() / (getEstimatedActualVelocity(Z) / 100.0f), 1, US2S(vEfficiencyTimeDelta)); + osdFormatCentiNumber(buff, value, 0, 1, 0, 3); + buff[3] = sym; + buff[4] = '\0'; + break; + } + case OSD_CLIMB_EFFICIENCY: + { + // amperage is in centi amps (10mA), vertical speed is in cms/s. We want + // Ah/dist only to show when vertical speed > 1m/s. + static pt1Filter_t veFilterState; + static timeUs_t vEfficiencyUpdated = 0; + int32_t value = 0; + timeUs_t currentTimeUs = micros(); + timeDelta_t vEfficiencyTimeDelta = cmpTimeUs(currentTimeUs, vEfficiencyUpdated); + if (getEstimatedActualVelocity(Z) > 0) { + if (vEfficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { + // Centiamps (kept for osdFormatCentiNumber) / m/s - Will appear as A / m/s in OSD + value = pt1FilterApply4(&veFilterState, (float)getAmperage() / (getEstimatedActualVelocity(Z) / 100.0f), 1, US2S(vEfficiencyTimeDelta)); - vEfficiencyUpdated = currentTimeUs; - } else { - value = veFilterState.state; - } - } - bool efficiencyValid = (value > 0) && (getEstimatedActualVelocity(Z) > 100); - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_GA: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - // mAh/foot - if (efficiencyValid) { - osdFormatCentiNumber(buff, (value * METERS_PER_FOOT), 1, 2, 2, 3); - tfp_sprintf(buff, "%s%c%c", buff, SYM_AH_V_FT_0, SYM_AH_V_FT_1); - } else { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_AH_V_FT_0; - buff[4] = SYM_AH_V_FT_1; - buff[5] = '\0'; - } - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - // mAh/metre - if (efficiencyValid) { - osdFormatCentiNumber(buff, value, 1, 2, 2, 3); - tfp_sprintf(buff, "%s%c%c", buff, SYM_AH_V_M_0, SYM_AH_V_M_1); - } else { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_AH_V_M_0; - buff[4] = SYM_AH_V_M_1; - buff[5] = '\0'; - } - break; - } - break; - } - case OSD_GLIDE_TIME_REMAINING: - { - uint16_t glideTime = osdGetRemainingGlideTime(); - buff[0] = SYM_GLIDE_MINS; - if (glideTime > 0) { - // Maximum value we can show in minutes is 99 minutes and 59 seconds. It is extremely unlikely that glide - // time will be longer than 99 minutes. If it is, it will show 99:^^ - if (glideTime > (99 * 60) + 59) { - tfp_sprintf(buff + 1, "%02d:", (int)(glideTime / 60)); - buff[4] = SYM_DIRECTION; - buff[5] = SYM_DIRECTION; - } else { - tfp_sprintf(buff + 1, "%02d:%02d", (int)(glideTime / 60), (int)(glideTime % 60)); - } - } else { - tfp_sprintf(buff + 1, "%s", "--:--"); - } - buff[6] = '\0'; - break; - } - case OSD_GLIDE_RANGE: - { - uint16_t glideSeconds = osdGetRemainingGlideTime(); - buff[0] = SYM_GLIDE_DIST; - if (glideSeconds > 0) { - uint32_t glideRangeCM = glideSeconds * gpsSol.groundSpeed; - osdFormatDistanceSymbol(buff + 1, glideRangeCM, 0); - } else { - tfp_sprintf(buff + 1, "%s%c", "---", SYM_BLANK); - buff[5] = '\0'; - } - break; - } + vEfficiencyUpdated = currentTimeUs; + } else { + value = veFilterState.state; + } + } + bool efficiencyValid = (value > 0) && (getEstimatedActualVelocity(Z) > 100); + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + // mAh/foot + if (efficiencyValid) { + osdFormatCentiNumber(buff, (value * METERS_PER_FOOT), 1, 2, 2, 3); + tfp_sprintf(buff, "%s%c%c", buff, SYM_AH_V_FT_0, SYM_AH_V_FT_1); + } else { + buff[0] = buff[1] = buff[2] = '-'; + buff[3] = SYM_AH_V_FT_0; + buff[4] = SYM_AH_V_FT_1; + buff[5] = '\0'; + } + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + // mAh/metre + if (efficiencyValid) { + osdFormatCentiNumber(buff, value, 1, 2, 2, 3); + tfp_sprintf(buff, "%s%c%c", buff, SYM_AH_V_M_0, SYM_AH_V_M_1); + } else { + buff[0] = buff[1] = buff[2] = '-'; + buff[3] = SYM_AH_V_M_0; + buff[4] = SYM_AH_V_M_1; + buff[5] = '\0'; + } + break; + } + break; + } + case OSD_GLIDE_TIME_REMAINING: + { + uint16_t glideTime = osdGetRemainingGlideTime(); + buff[0] = SYM_GLIDE_MINS; + if (glideTime > 0) { + // Maximum value we can show in minutes is 99 minutes and 59 seconds. It is extremely unlikely that glide + // time will be longer than 99 minutes. If it is, it will show 99:^^ + if (glideTime > (99 * 60) + 59) { + tfp_sprintf(buff + 1, "%02d:", (int)(glideTime / 60)); + buff[4] = SYM_DIRECTION; + buff[5] = SYM_DIRECTION; + } else { + tfp_sprintf(buff + 1, "%02d:%02d", (int)(glideTime / 60), (int)(glideTime % 60)); + } + } else { + tfp_sprintf(buff + 1, "%s", "--:--"); + } + buff[6] = '\0'; + break; + } + case OSD_GLIDE_RANGE: + { + uint16_t glideSeconds = osdGetRemainingGlideTime(); + buff[0] = SYM_GLIDE_DIST; + if (glideSeconds > 0) { + uint32_t glideRangeCM = glideSeconds * gpsSol.groundSpeed; + osdFormatDistanceSymbol(buff + 1, glideRangeCM, 0); + } else { + tfp_sprintf(buff + 1, "%s%c", "---", SYM_BLANK); + buff[5] = '\0'; + } + break; + } #endif - case OSD_SWITCH_INDICATOR_0: - osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator0_name, rxGetChannelValue(osdConfig()->osd_switch_indicator0_channel - 1), buff); - break; + case OSD_SWITCH_INDICATOR_0: + osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator0_name, rxGetChannelValue(osdConfig()->osd_switch_indicator0_channel - 1), buff); + break; - case OSD_SWITCH_INDICATOR_1: - osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator1_name, rxGetChannelValue(osdConfig()->osd_switch_indicator1_channel - 1), buff); - break; + case OSD_SWITCH_INDICATOR_1: + osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator1_name, rxGetChannelValue(osdConfig()->osd_switch_indicator1_channel - 1), buff); + break; - case OSD_SWITCH_INDICATOR_2: - osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator2_name, rxGetChannelValue(osdConfig()->osd_switch_indicator2_channel - 1), buff); - break; + case OSD_SWITCH_INDICATOR_2: + osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator2_name, rxGetChannelValue(osdConfig()->osd_switch_indicator2_channel - 1), buff); + break; - case OSD_SWITCH_INDICATOR_3: - osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator3_name, rxGetChannelValue(osdConfig()->osd_switch_indicator3_channel - 1), buff); - break; + case OSD_SWITCH_INDICATOR_3: + osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator3_name, rxGetChannelValue(osdConfig()->osd_switch_indicator3_channel - 1), buff); + break; - case OSD_PAN_SERVO_CENTRED: - { - int16_t panOffset = osdGetPanServoOffset(); - const timeMs_t panServoTimeNow = millis(); - static timeMs_t panServoTimeOffCentre = 0; + case OSD_PAN_SERVO_CENTRED: + { + int16_t panOffset = osdGetPanServoOffset(); + const timeMs_t panServoTimeNow = millis(); + static timeMs_t panServoTimeOffCentre = 0; - if (panOffset < 0) { - if (osdConfig()->pan_servo_offcentre_warning != 0 && panOffset >= -osdConfig()->pan_servo_offcentre_warning) { - if (panServoTimeOffCentre == 0) { - panServoTimeOffCentre = panServoTimeNow; - } else if (panServoTimeNow >= (panServoTimeOffCentre + 10000 )) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } else { - panServoTimeOffCentre = 0; - } + if (panOffset < 0) { + if (osdConfig()->pan_servo_offcentre_warning != 0 && panOffset >= -osdConfig()->pan_servo_offcentre_warning) { + if (panServoTimeOffCentre == 0) { + panServoTimeOffCentre = panServoTimeNow; + } else if (panServoTimeNow >= (panServoTimeOffCentre + 10000 )) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } else { + panServoTimeOffCentre = 0; + } - if (osdConfig()->pan_servo_indicator_show_degrees) { - tfp_sprintf(buff, "%3d%c", -panOffset, SYM_DEGREES); - displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); - } - displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_R, elemAttr); - } else if (panOffset > 0) { - if (osdConfig()->pan_servo_offcentre_warning != 0 && panOffset <= osdConfig()->pan_servo_offcentre_warning) { - if (panServoTimeOffCentre == 0) { - panServoTimeOffCentre = panServoTimeNow; - } else if (panServoTimeNow >= (panServoTimeOffCentre + 10000 )) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } else { - panServoTimeOffCentre = 0; - } + if (osdConfig()->pan_servo_indicator_show_degrees) { + tfp_sprintf(buff, "%3d%c", -panOffset, SYM_DEGREES); + displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); + } + displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_R, elemAttr); + } else if (panOffset > 0) { + if (osdConfig()->pan_servo_offcentre_warning != 0 && panOffset <= osdConfig()->pan_servo_offcentre_warning) { + if (panServoTimeOffCentre == 0) { + panServoTimeOffCentre = panServoTimeNow; + } else if (panServoTimeNow >= (panServoTimeOffCentre + 10000 )) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } else { + panServoTimeOffCentre = 0; + } - if (osdConfig()->pan_servo_indicator_show_degrees) { - tfp_sprintf(buff, "%3d%c", panOffset, SYM_DEGREES); - displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); - } - displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_L, elemAttr); - } else { - panServoTimeOffCentre = 0; + if (osdConfig()->pan_servo_indicator_show_degrees) { + tfp_sprintf(buff, "%3d%c", panOffset, SYM_DEGREES); + displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); + } + displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_L, elemAttr); + } else { + panServoTimeOffCentre = 0; - if (osdConfig()->pan_servo_indicator_show_degrees) { - tfp_sprintf(buff, "%3d%c", panOffset, SYM_DEGREES); - displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); - } - displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_CENTRED); - } + if (osdConfig()->pan_servo_indicator_show_degrees) { + tfp_sprintf(buff, "%3d%c", panOffset, SYM_DEGREES); + displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); + } + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_CENTRED); + } - return true; - } - break; + return true; + } + break; - case OSD_ACTIVE_PROFILE: - tfp_sprintf(buff, "%c%u", SYM_PROFILE, (getConfigProfile() + 1)); - displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); - break; + case OSD_ACTIVE_PROFILE: + tfp_sprintf(buff, "%c%u", SYM_PROFILE, (getConfigProfile() + 1)); + displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); + break; - case OSD_ROLL_PIDS: - osdDisplayFlightPIDValues(elemPosX, elemPosY, "ROL", PID_ROLL, ADJUSTMENT_ROLL_P, ADJUSTMENT_ROLL_I, ADJUSTMENT_ROLL_D, ADJUSTMENT_ROLL_FF); - return true; + case OSD_ROLL_PIDS: + osdDisplayFlightPIDValues(elemPosX, elemPosY, "ROL", PID_ROLL, ADJUSTMENT_ROLL_P, ADJUSTMENT_ROLL_I, ADJUSTMENT_ROLL_D, ADJUSTMENT_ROLL_FF); + return true; - case OSD_PITCH_PIDS: - osdDisplayFlightPIDValues(elemPosX, elemPosY, "PIT", PID_PITCH, ADJUSTMENT_PITCH_P, ADJUSTMENT_PITCH_I, ADJUSTMENT_PITCH_D, ADJUSTMENT_PITCH_FF); - return true; + case OSD_PITCH_PIDS: + osdDisplayFlightPIDValues(elemPosX, elemPosY, "PIT", PID_PITCH, ADJUSTMENT_PITCH_P, ADJUSTMENT_PITCH_I, ADJUSTMENT_PITCH_D, ADJUSTMENT_PITCH_FF); + return true; - case OSD_YAW_PIDS: - osdDisplayFlightPIDValues(elemPosX, elemPosY, "YAW", PID_YAW, ADJUSTMENT_YAW_P, ADJUSTMENT_YAW_I, ADJUSTMENT_YAW_D, ADJUSTMENT_YAW_FF); - return true; + case OSD_YAW_PIDS: + osdDisplayFlightPIDValues(elemPosX, elemPosY, "YAW", PID_YAW, ADJUSTMENT_YAW_P, ADJUSTMENT_YAW_I, ADJUSTMENT_YAW_D, ADJUSTMENT_YAW_FF); + return true; - case OSD_LEVEL_PIDS: - osdDisplayNavPIDValues(elemPosX, elemPosY, "LEV", PID_LEVEL, ADJUSTMENT_LEVEL_P, ADJUSTMENT_LEVEL_I, ADJUSTMENT_LEVEL_D); - return true; + case OSD_LEVEL_PIDS: + osdDisplayNavPIDValues(elemPosX, elemPosY, "LEV", PID_LEVEL, ADJUSTMENT_LEVEL_P, ADJUSTMENT_LEVEL_I, ADJUSTMENT_LEVEL_D); + return true; - case OSD_POS_XY_PIDS: - osdDisplayNavPIDValues(elemPosX, elemPosY, "PXY", PID_POS_XY, ADJUSTMENT_POS_XY_P, ADJUSTMENT_POS_XY_I, ADJUSTMENT_POS_XY_D); - return true; + case OSD_POS_XY_PIDS: + osdDisplayNavPIDValues(elemPosX, elemPosY, "PXY", PID_POS_XY, ADJUSTMENT_POS_XY_P, ADJUSTMENT_POS_XY_I, ADJUSTMENT_POS_XY_D); + return true; - case OSD_POS_Z_PIDS: - osdDisplayNavPIDValues(elemPosX, elemPosY, "PZ", PID_POS_Z, ADJUSTMENT_POS_Z_P, ADJUSTMENT_POS_Z_I, ADJUSTMENT_POS_Z_D); - return true; + case OSD_POS_Z_PIDS: + osdDisplayNavPIDValues(elemPosX, elemPosY, "PZ", PID_POS_Z, ADJUSTMENT_POS_Z_P, ADJUSTMENT_POS_Z_I, ADJUSTMENT_POS_Z_D); + return true; - case OSD_VEL_XY_PIDS: - osdDisplayNavPIDValues(elemPosX, elemPosY, "VXY", PID_VEL_XY, ADJUSTMENT_VEL_XY_P, ADJUSTMENT_VEL_XY_I, ADJUSTMENT_VEL_XY_D); - return true; + case OSD_VEL_XY_PIDS: + osdDisplayNavPIDValues(elemPosX, elemPosY, "VXY", PID_VEL_XY, ADJUSTMENT_VEL_XY_P, ADJUSTMENT_VEL_XY_I, ADJUSTMENT_VEL_XY_D); + return true; - case OSD_VEL_Z_PIDS: - osdDisplayNavPIDValues(elemPosX, elemPosY, "VZ", PID_VEL_Z, ADJUSTMENT_VEL_Z_P, ADJUSTMENT_VEL_Z_I, ADJUSTMENT_VEL_Z_D); - return true; + case OSD_VEL_Z_PIDS: + osdDisplayNavPIDValues(elemPosX, elemPosY, "VZ", PID_VEL_Z, ADJUSTMENT_VEL_Z_P, ADJUSTMENT_VEL_Z_I, ADJUSTMENT_VEL_Z_D); + return true; - case OSD_HEADING_P: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "HP", 0, pidBank()->pid[PID_HEADING].P, 3, 0, ADJUSTMENT_HEADING_P); - return true; + case OSD_HEADING_P: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "HP", 0, pidBank()->pid[PID_HEADING].P, 3, 0, ADJUSTMENT_HEADING_P); + return true; - case OSD_BOARD_ALIGN_ROLL: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "AR", 0, DECIDEGREES_TO_DEGREES((float)boardAlignment()->rollDeciDegrees), 4, 1, ADJUSTMENT_ROLL_BOARD_ALIGNMENT); - return true; + case OSD_BOARD_ALIGN_ROLL: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "AR", 0, DECIDEGREES_TO_DEGREES((float)boardAlignment()->rollDeciDegrees), 4, 1, ADJUSTMENT_ROLL_BOARD_ALIGNMENT); + return true; - case OSD_BOARD_ALIGN_PITCH: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "AP", 0, DECIDEGREES_TO_DEGREES((float)boardAlignment()->pitchDeciDegrees), 4, 1, ADJUSTMENT_PITCH_BOARD_ALIGNMENT); - return true; + case OSD_BOARD_ALIGN_PITCH: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "AP", 0, DECIDEGREES_TO_DEGREES((float)boardAlignment()->pitchDeciDegrees), 4, 1, ADJUSTMENT_PITCH_BOARD_ALIGNMENT); + return true; - case OSD_RC_EXPO: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "EXP", 0, currentControlRateProfile->stabilized.rcExpo8, 3, 0, ADJUSTMENT_RC_EXPO); - return true; + case OSD_RC_EXPO: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "EXP", 0, currentControlRateProfile->stabilized.rcExpo8, 3, 0, ADJUSTMENT_RC_EXPO); + return true; - case OSD_RC_YAW_EXPO: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "YEX", 0, currentControlRateProfile->stabilized.rcYawExpo8, 3, 0, ADJUSTMENT_RC_YAW_EXPO); - return true; + case OSD_RC_YAW_EXPO: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "YEX", 0, currentControlRateProfile->stabilized.rcYawExpo8, 3, 0, ADJUSTMENT_RC_YAW_EXPO); + return true; - case OSD_THROTTLE_EXPO: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "TEX", 0, currentControlRateProfile->throttle.rcExpo8, 3, 0, ADJUSTMENT_THROTTLE_EXPO); - return true; + case OSD_THROTTLE_EXPO: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "TEX", 0, currentControlRateProfile->throttle.rcExpo8, 3, 0, ADJUSTMENT_THROTTLE_EXPO); + return true; - case OSD_PITCH_RATE: - displayWrite(osdDisplayPort, elemPosX, elemPosY, "SPR"); + case OSD_PITCH_RATE: + displayWrite(osdDisplayPort, elemPosX, elemPosY, "SPR"); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", currentControlRateProfile->stabilized.rates[FD_PITCH]); - if (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_RATE)) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); - return true; + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", currentControlRateProfile->stabilized.rates[FD_PITCH]); + if (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_RATE)) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); + return true; - case OSD_ROLL_RATE: - displayWrite(osdDisplayPort, elemPosX, elemPosY, "SRR"); + case OSD_ROLL_RATE: + displayWrite(osdDisplayPort, elemPosX, elemPosY, "SRR"); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", currentControlRateProfile->stabilized.rates[FD_ROLL]); - if (isAdjustmentFunctionSelected(ADJUSTMENT_ROLL_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_RATE)) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); - return true; + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", currentControlRateProfile->stabilized.rates[FD_ROLL]); + if (isAdjustmentFunctionSelected(ADJUSTMENT_ROLL_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_RATE)) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); + return true; - case OSD_YAW_RATE: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "SYR", 0, currentControlRateProfile->stabilized.rates[FD_YAW], 3, 0, ADJUSTMENT_YAW_RATE); - return true; + case OSD_YAW_RATE: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "SYR", 0, currentControlRateProfile->stabilized.rates[FD_YAW], 3, 0, ADJUSTMENT_YAW_RATE); + return true; - case OSD_MANUAL_RC_EXPO: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "MEX", 0, currentControlRateProfile->manual.rcExpo8, 3, 0, ADJUSTMENT_MANUAL_RC_EXPO); - return true; + case OSD_MANUAL_RC_EXPO: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "MEX", 0, currentControlRateProfile->manual.rcExpo8, 3, 0, ADJUSTMENT_MANUAL_RC_EXPO); + return true; - case OSD_MANUAL_RC_YAW_EXPO: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "MYX", 0, currentControlRateProfile->manual.rcYawExpo8, 3, 0, ADJUSTMENT_MANUAL_RC_YAW_EXPO); - return true; + case OSD_MANUAL_RC_YAW_EXPO: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "MYX", 0, currentControlRateProfile->manual.rcYawExpo8, 3, 0, ADJUSTMENT_MANUAL_RC_YAW_EXPO); + return true; - case OSD_MANUAL_PITCH_RATE: - displayWrite(osdDisplayPort, elemPosX, elemPosY, "MPR"); + case OSD_MANUAL_PITCH_RATE: + displayWrite(osdDisplayPort, elemPosX, elemPosY, "MPR"); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", currentControlRateProfile->manual.rates[FD_PITCH]); - if (isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_PITCH_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_PITCH_ROLL_RATE)) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); - return true; + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", currentControlRateProfile->manual.rates[FD_PITCH]); + if (isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_PITCH_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_PITCH_ROLL_RATE)) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); + return true; - case OSD_MANUAL_ROLL_RATE: - displayWrite(osdDisplayPort, elemPosX, elemPosY, "MRR"); + case OSD_MANUAL_ROLL_RATE: + displayWrite(osdDisplayPort, elemPosX, elemPosY, "MRR"); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", currentControlRateProfile->manual.rates[FD_ROLL]); - if (isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_ROLL_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_PITCH_ROLL_RATE)) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); - return true; + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", currentControlRateProfile->manual.rates[FD_ROLL]); + if (isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_ROLL_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_PITCH_ROLL_RATE)) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); + return true; - case OSD_MANUAL_YAW_RATE: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "MYR", 0, currentControlRateProfile->stabilized.rates[FD_YAW], 3, 0, ADJUSTMENT_YAW_RATE); - return true; + case OSD_MANUAL_YAW_RATE: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "MYR", 0, currentControlRateProfile->stabilized.rates[FD_YAW], 3, 0, ADJUSTMENT_YAW_RATE); + return true; - case OSD_NAV_FW_CRUISE_THR: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CRZ", 0, currentBatteryProfile->nav.fw.cruise_throttle, 4, 0, ADJUSTMENT_NAV_FW_CRUISE_THR); - return true; + case OSD_NAV_FW_CRUISE_THR: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CRZ", 0, currentBatteryProfile->nav.fw.cruise_throttle, 4, 0, ADJUSTMENT_NAV_FW_CRUISE_THR); + return true; - case OSD_NAV_FW_PITCH2THR: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "P2T", 0, currentBatteryProfile->nav.fw.pitch_to_throttle, 3, 0, ADJUSTMENT_NAV_FW_PITCH2THR); - return true; + case OSD_NAV_FW_PITCH2THR: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "P2T", 0, currentBatteryProfile->nav.fw.pitch_to_throttle, 3, 0, ADJUSTMENT_NAV_FW_PITCH2THR); + return true; - case OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "0TP", 0, (float)navConfig()->fw.minThrottleDownPitchAngle / 10, 3, 1, ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE); - return true; + case OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "0TP", 0, (float)navConfig()->fw.minThrottleDownPitchAngle / 10, 3, 1, ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE); + return true; - case OSD_FW_ALT_PID_OUTPUTS: - { - const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); - osdFormatPidControllerOutput(buff, "PZO", &nav_pids->fw_alt, 10, true); // display requested pitch degrees - break; - } + case OSD_FW_ALT_PID_OUTPUTS: + { + const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); + osdFormatPidControllerOutput(buff, "PZO", &nav_pids->fw_alt, 10, true); // display requested pitch degrees + break; + } - case OSD_FW_POS_PID_OUTPUTS: - { - const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); // display requested roll degrees - osdFormatPidControllerOutput(buff, "PXYO", &nav_pids->fw_nav, 1, true); - break; - } + case OSD_FW_POS_PID_OUTPUTS: + { + const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); // display requested roll degrees + osdFormatPidControllerOutput(buff, "PXYO", &nav_pids->fw_nav, 1, true); + break; + } - case OSD_MC_VEL_Z_PID_OUTPUTS: - { - const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); - osdFormatPidControllerOutput(buff, "VZO", &nav_pids->vel[Z], 100, false); // display throttle adjustment µs - break; - } + case OSD_MC_VEL_Z_PID_OUTPUTS: + { + const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); + osdFormatPidControllerOutput(buff, "VZO", &nav_pids->vel[Z], 100, false); // display throttle adjustment µs + break; + } - case OSD_MC_VEL_X_PID_OUTPUTS: - { - const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); - osdFormatPidControllerOutput(buff, "VXO", &nav_pids->vel[X], 100, false); // display requested acceleration cm/s^2 - break; - } + case OSD_MC_VEL_X_PID_OUTPUTS: + { + const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); + osdFormatPidControllerOutput(buff, "VXO", &nav_pids->vel[X], 100, false); // display requested acceleration cm/s^2 + break; + } - case OSD_MC_VEL_Y_PID_OUTPUTS: - { - const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); - osdFormatPidControllerOutput(buff, "VYO", &nav_pids->vel[Y], 100, false); // display requested acceleration cm/s^2 - break; - } + case OSD_MC_VEL_Y_PID_OUTPUTS: + { + const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); + osdFormatPidControllerOutput(buff, "VYO", &nav_pids->vel[Y], 100, false); // display requested acceleration cm/s^2 + break; + } - case OSD_MC_POS_XYZ_P_OUTPUTS: - { - const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); - strcpy(buff, "POSO "); - // display requested velocity cm/s - tfp_sprintf(buff + 5, "%4d", (int)lrintf(nav_pids->pos[X].output_constrained * 100)); - buff[9] = ' '; - tfp_sprintf(buff + 10, "%4d", (int)lrintf(nav_pids->pos[Y].output_constrained * 100)); - buff[14] = ' '; - tfp_sprintf(buff + 15, "%4d", (int)lrintf(nav_pids->pos[Z].output_constrained * 100)); - buff[19] = '\0'; - break; - } + case OSD_MC_POS_XYZ_P_OUTPUTS: + { + const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); + strcpy(buff, "POSO "); + // display requested velocity cm/s + tfp_sprintf(buff + 5, "%4d", (int)lrintf(nav_pids->pos[X].output_constrained * 100)); + buff[9] = ' '; + tfp_sprintf(buff + 10, "%4d", (int)lrintf(nav_pids->pos[Y].output_constrained * 100)); + buff[14] = ' '; + tfp_sprintf(buff + 15, "%4d", (int)lrintf(nav_pids->pos[Z].output_constrained * 100)); + buff[19] = '\0'; + break; + } - case OSD_POWER: - { - bool kiloWatt = osdFormatCentiNumber(buff, getPower(), 1000, 2, 2, 3); - buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; - buff[4] = '\0'; + case OSD_POWER: + { + bool kiloWatt = osdFormatCentiNumber(buff, getPower(), 1000, 2, 2, 3); + buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; + buff[4] = '\0'; - uint8_t current_alarm = osdConfig()->current_alarm; - if ((current_alarm > 0) && ((getAmperage() / 100.0f) > current_alarm)) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } + uint8_t current_alarm = osdConfig()->current_alarm; + if ((current_alarm > 0) && ((getAmperage() / 100.0f) > current_alarm)) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } - case OSD_AIR_SPEED: - { - #ifdef USE_PITOT - buff[0] = SYM_AIR; + case OSD_AIR_SPEED: + { + #ifdef USE_PITOT + buff[0] = SYM_AIR; - if (pitotIsHealthy()) - { - const float airspeed_estimate = getAirspeedEstimate(); - osdFormatVelocityStr(buff + 1, airspeed_estimate, false, false); - if ((osdConfig()->airspeed_alarm_min != 0 && airspeed_estimate < osdConfig()->airspeed_alarm_min) || - (osdConfig()->airspeed_alarm_max != 0 && airspeed_estimate > osdConfig()->airspeed_alarm_max)) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } - else - { - strcpy(buff + 1, " X!"); - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - #else - return false; - #endif - break; - } + if (pitotIsHealthy()) + { + const float airspeed_estimate = getAirspeedEstimate(); + osdFormatVelocityStr(buff + 1, airspeed_estimate, false, false); + if ((osdConfig()->airspeed_alarm_min != 0 && airspeed_estimate < osdConfig()->airspeed_alarm_min) || + (osdConfig()->airspeed_alarm_max != 0 && airspeed_estimate > osdConfig()->airspeed_alarm_max)) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + else + { + strcpy(buff + 1, " X!"); + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + #else + return false; + #endif + break; + } - case OSD_AIR_MAX_SPEED: - { - #ifdef USE_PITOT - buff[0] = SYM_MAX; - buff[1] = SYM_AIR; - osdFormatVelocityStr(buff + 2, stats.max_air_speed, false, false); - #else - return false; - #endif - break; - } + case OSD_AIR_MAX_SPEED: + { + #ifdef USE_PITOT + buff[0] = SYM_MAX; + buff[1] = SYM_AIR; + osdFormatVelocityStr(buff + 2, stats.max_air_speed, false, false); + #else + return false; + #endif + break; + } - case OSD_RTC_TIME: - { - // RTC not configured will show 00:00 - dateTime_t dateTime; - rtcGetDateTimeLocal(&dateTime); - buff[0] = SYM_CLOCK; - tfp_sprintf(buff + 1, "%02u:%02u:%02u", dateTime.hours, dateTime.minutes, dateTime.seconds); - break; - } + case OSD_RTC_TIME: + { + // RTC not configured will show 00:00 + dateTime_t dateTime; + rtcGetDateTimeLocal(&dateTime); + buff[0] = SYM_CLOCK; + tfp_sprintf(buff + 1, "%02u:%02u:%02u", dateTime.hours, dateTime.minutes, dateTime.seconds); + break; + } - case OSD_MESSAGES: - { - elemAttr = osdGetSystemMessage(buff, OSD_MESSAGE_LENGTH, true); - break; - } + case OSD_MESSAGES: + { + elemAttr = osdGetSystemMessage(buff, OSD_MESSAGE_LENGTH, true); + break; + } - case OSD_VERSION: - { - tfp_sprintf(buff, "INAV %s", FC_VERSION_STRING); - displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); - break; - } + case OSD_VERSION: + { + tfp_sprintf(buff, "INAV %s", FC_VERSION_STRING); + displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); + break; + } - case OSD_MAIN_BATT_CELL_VOLTAGE: - { - uint8_t base_digits = 3U; + case OSD_MAIN_BATT_CELL_VOLTAGE: + { + uint8_t base_digits = 3U; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if(isBfCompatibleVideoSystem(osdConfig())) { - base_digits = 4U; // Add extra digit to account for decimal point taking an extra character space - } + if(isBfCompatibleVideoSystem(osdConfig())) { + base_digits = 4U; // Add extra digit to account for decimal point taking an extra character space + } #endif - osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawAverageCellVoltage(), base_digits, 2); - return true; - } + osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawAverageCellVoltage(), base_digits, 2); + return true; + } - case OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE: - { - uint8_t base_digits = 3U; + case OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE: + { + uint8_t base_digits = 3U; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if(isBfCompatibleVideoSystem(osdConfig())) { - base_digits = 4U; // Add extra digit to account for decimal point taking an extra character space - } + if(isBfCompatibleVideoSystem(osdConfig())) { + base_digits = 4U; // Add extra digit to account for decimal point taking an extra character space + } #endif - osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedAverageCellVoltage(), base_digits, 2); - return true; - } + osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedAverageCellVoltage(), base_digits, 2); + return true; + } - case OSD_SCALED_THROTTLE_POS: - { - osdFormatThrottlePosition(buff, true, &elemAttr); - break; - } + case OSD_SCALED_THROTTLE_POS: + { + osdFormatThrottlePosition(buff, true, &elemAttr); + break; + } - case OSD_HEADING: - { - buff[0] = SYM_HEADING; - if (osdIsHeadingValid()) { - int16_t h = DECIDEGREES_TO_DEGREES(osdGetHeading()); - if (h < 0) { - h += 360; - } - tfp_sprintf(&buff[1], "%3d", h); - } else { - buff[1] = buff[2] = buff[3] = '-'; - } - buff[4] = SYM_DEGREES; - buff[5] = '\0'; - break; - } + case OSD_HEADING: + { + buff[0] = SYM_HEADING; + if (osdIsHeadingValid()) { + int16_t h = DECIDEGREES_TO_DEGREES(osdGetHeading()); + if (h < 0) { + h += 360; + } + tfp_sprintf(&buff[1], "%3d", h); + } else { + buff[1] = buff[2] = buff[3] = '-'; + } + buff[4] = SYM_DEGREES; + buff[5] = '\0'; + break; + } - case OSD_HEADING_GRAPH: - { - if (osdIsHeadingValid()) { - osdDrawHeadingGraph(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), osdGetHeading()); - return true; - } else { - buff[0] = buff[2] = buff[4] = buff[6] = buff[8] = SYM_HEADING_LINE; - buff[1] = buff[3] = buff[5] = buff[7] = SYM_HEADING_DIVIDED_LINE; - buff[OSD_HEADING_GRAPH_WIDTH] = '\0'; - } - break; - } + case OSD_HEADING_GRAPH: + { + if (osdIsHeadingValid()) { + osdDrawHeadingGraph(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), osdGetHeading()); + return true; + } else { + buff[0] = buff[2] = buff[4] = buff[6] = buff[8] = SYM_HEADING_LINE; + buff[1] = buff[3] = buff[5] = buff[7] = SYM_HEADING_DIVIDED_LINE; + buff[OSD_HEADING_GRAPH_WIDTH] = '\0'; + } + break; + } - case OSD_EFFICIENCY_MAH_PER_KM: - { - // amperage is in centi amps, speed is in cms/s. We want - // mah/km. Only show when ground speed > 1m/s. - static pt1Filter_t eFilterState; - static timeUs_t efficiencyUpdated = 0; - int32_t value = 0; - bool moreThanAh = false; - timeUs_t currentTimeUs = micros(); - timeDelta_t efficiencyTimeDelta = cmpTimeUs(currentTimeUs, efficiencyUpdated); - uint8_t digits = 3U; + case OSD_EFFICIENCY_MAH_PER_KM: + { + // amperage is in centi amps, speed is in cms/s. We want + // mah/km. Only show when ground speed > 1m/s. + static pt1Filter_t eFilterState; + static timeUs_t efficiencyUpdated = 0; + int32_t value = 0; + bool moreThanAh = false; + timeUs_t currentTimeUs = micros(); + timeDelta_t efficiencyTimeDelta = cmpTimeUs(currentTimeUs, efficiencyUpdated); + uint8_t digits = 3U; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values - if (isBfCompatibleVideoSystem(osdConfig())) { - // Increase number of digits so values above 99 don't get scaled by osdFormatCentiNumber - digits = 4U; - } + if (isBfCompatibleVideoSystem(osdConfig())) { + // Increase number of digits so values above 99 don't get scaled by osdFormatCentiNumber + digits = 4U; + } #endif - if (STATE(GPS_FIX) && gpsSol.groundSpeed > 0) { - if (efficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { - value = pt1FilterApply4(&eFilterState, ((float)getAmperage() / gpsSol.groundSpeed) / 0.0036f, - 1, US2S(efficiencyTimeDelta)); + if (STATE(GPS_FIX) && gpsSol.groundSpeed > 0) { + if (efficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { + value = pt1FilterApply4(&eFilterState, ((float)getAmperage() / gpsSol.groundSpeed) / 0.0036f, + 1, US2S(efficiencyTimeDelta)); - efficiencyUpdated = currentTimeUs; - } else { - value = eFilterState.state; - } - } - bool efficiencyValid = (value > 0) && (gpsSol.groundSpeed > 100); - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10, 1000, 0, 2, digits); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_MI); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = buff[3] = '-'; - buff[digits] = SYM_MAH_MI_0; // This will overwrite the "-" at buff[3] if not in BFCOMPAT mode - buff[digits + 1] = SYM_MAH_MI_1; - buff[digits + 2] = '\0'; - } - break; - case OSD_UNIT_GA: - moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10, 1000, 0, 2, digits); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = buff[3] = '-'; - buff[digits] = SYM_MAH_NM_0; - buff[digits + 1] = SYM_MAH_NM_1; - buff[digits + 2] = '\0'; - } - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - moreThanAh = osdFormatCentiNumber(buff, value * 100, 1000, 0, 2, digits); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_KM); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = buff[3] = '-'; - buff[digits] = SYM_MAH_KM_0; - buff[digits + 1] = SYM_MAH_KM_1; - buff[digits + 2] = '\0'; - } - break; - } - break; - } + efficiencyUpdated = currentTimeUs; + } else { + value = eFilterState.state; + } + } + bool efficiencyValid = (value > 0) && (gpsSol.groundSpeed > 100); + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10, 1000, 0, 2, digits); + if (!moreThanAh) { + tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); + } else { + tfp_sprintf(buff, "%s%c", buff, SYM_AH_MI); + } + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = buff[3] = '-'; + buff[digits] = SYM_MAH_MI_0; // This will overwrite the "-" at buff[3] if not in BFCOMPAT mode + buff[digits + 1] = SYM_MAH_MI_1; + buff[digits + 2] = '\0'; + } + break; + case OSD_UNIT_GA: + moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10, 1000, 0, 2, digits); + if (!moreThanAh) { + tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); + } else { + tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM); + } + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = buff[3] = '-'; + buff[digits] = SYM_MAH_NM_0; + buff[digits + 1] = SYM_MAH_NM_1; + buff[digits + 2] = '\0'; + } + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + moreThanAh = osdFormatCentiNumber(buff, value * 100, 1000, 0, 2, digits); + if (!moreThanAh) { + tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); + } else { + tfp_sprintf(buff, "%s%c", buff, SYM_AH_KM); + } + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = buff[3] = '-'; + buff[digits] = SYM_MAH_KM_0; + buff[digits + 1] = SYM_MAH_KM_1; + buff[digits + 2] = '\0'; + } + break; + } + break; + } - case OSD_EFFICIENCY_WH_PER_KM: - { - // amperage is in centi amps, speed is in cms/s. We want - // mWh/km. Only show when ground speed > 1m/s. - static pt1Filter_t eFilterState; - static timeUs_t efficiencyUpdated = 0; - int32_t value = 0; - timeUs_t currentTimeUs = micros(); - timeDelta_t efficiencyTimeDelta = cmpTimeUs(currentTimeUs, efficiencyUpdated); - if (STATE(GPS_FIX) && gpsSol.groundSpeed > 0) { - if (efficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { - value = pt1FilterApply4(&eFilterState, ((float)getPower() / gpsSol.groundSpeed) / 0.0036f, - 1, US2S(efficiencyTimeDelta)); + case OSD_EFFICIENCY_WH_PER_KM: + { + // amperage is in centi amps, speed is in cms/s. We want + // mWh/km. Only show when ground speed > 1m/s. + static pt1Filter_t eFilterState; + static timeUs_t efficiencyUpdated = 0; + int32_t value = 0; + timeUs_t currentTimeUs = micros(); + timeDelta_t efficiencyTimeDelta = cmpTimeUs(currentTimeUs, efficiencyUpdated); + if (STATE(GPS_FIX) && gpsSol.groundSpeed > 0) { + if (efficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { + value = pt1FilterApply4(&eFilterState, ((float)getPower() / gpsSol.groundSpeed) / 0.0036f, + 1, US2S(efficiencyTimeDelta)); - efficiencyUpdated = currentTimeUs; - } else { - value = eFilterState.state; - } - } - bool efficiencyValid = (value > 0) && (gpsSol.groundSpeed > 100); - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10000, 0, 2, 0, 3); - buff[3] = SYM_WH_MI; - break; - case OSD_UNIT_GA: - osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10000, 0, 2, 0, 3); - buff[3] = SYM_WH_NM; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - osdFormatCentiNumber(buff, value / 10, 0, 2, 0, 3); - buff[3] = SYM_WH_KM; - break; - } - buff[4] = '\0'; - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - } - break; - } + efficiencyUpdated = currentTimeUs; + } else { + value = eFilterState.state; + } + } + bool efficiencyValid = (value > 0) && (gpsSol.groundSpeed > 100); + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10000, 0, 2, 0, 3); + buff[3] = SYM_WH_MI; + break; + case OSD_UNIT_GA: + osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10000, 0, 2, 0, 3); + buff[3] = SYM_WH_NM; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + osdFormatCentiNumber(buff, value / 10, 0, 2, 0, 3); + buff[3] = SYM_WH_KM; + break; + } + buff[4] = '\0'; + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + } + break; + } - case OSD_GFORCE: - { - buff[0] = SYM_GFORCE; - osdFormatCentiNumber(buff + 1, GForce, 0, 2, 0, 3); - if (GForce > osdConfig()->gforce_alarm * 100) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } + case OSD_GFORCE: + { + buff[0] = SYM_GFORCE; + osdFormatCentiNumber(buff + 1, GForce, 0, 2, 0, 3); + if (GForce > osdConfig()->gforce_alarm * 100) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } - case OSD_GFORCE_X: - case OSD_GFORCE_Y: - case OSD_GFORCE_Z: - { - float GForceValue = GForceAxis[item - OSD_GFORCE_X]; - buff[0] = SYM_GFORCE_X + item - OSD_GFORCE_X; - osdFormatCentiNumber(buff + 1, GForceValue, 0, 2, 0, 4); - if ((GForceValue < osdConfig()->gforce_axis_alarm_min * 100) || (GForceValue > osdConfig()->gforce_axis_alarm_max * 100)) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } - case OSD_DEBUG: - { - /* - * Longest representable string is -2147483648 does not fit in the screen. - * Only 7 digits for negative and 8 digits for positive values allowed - */ - for (uint8_t bufferIndex = 0; bufferIndex < DEBUG32_VALUE_COUNT; ++elemPosY, bufferIndex += 2) { - tfp_sprintf( - buff, - "[%u]=%8ld [%u]=%8ld", - bufferIndex, - (long)constrain(debug[bufferIndex], -9999999, 99999999), - bufferIndex+1, - (long)constrain(debug[bufferIndex+1], -9999999, 99999999) - ); - displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); - } - break; - } + case OSD_GFORCE_X: + case OSD_GFORCE_Y: + case OSD_GFORCE_Z: + { + float GForceValue = GForceAxis[item - OSD_GFORCE_X]; + buff[0] = SYM_GFORCE_X + item - OSD_GFORCE_X; + osdFormatCentiNumber(buff + 1, GForceValue, 0, 2, 0, 4); + if ((GForceValue < osdConfig()->gforce_axis_alarm_min * 100) || (GForceValue > osdConfig()->gforce_axis_alarm_max * 100)) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } + case OSD_DEBUG: + { + /* + * Longest representable string is -2147483648 does not fit in the screen. + * Only 7 digits for negative and 8 digits for positive values allowed + */ + for (uint8_t bufferIndex = 0; bufferIndex < DEBUG32_VALUE_COUNT; ++elemPosY, bufferIndex += 2) { + tfp_sprintf( + buff, + "[%u]=%8ld [%u]=%8ld", + bufferIndex, + (long)constrain(debug[bufferIndex], -9999999, 99999999), + bufferIndex+1, + (long)constrain(debug[bufferIndex+1], -9999999, 99999999) + ); + displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); + } + break; + } - case OSD_IMU_TEMPERATURE: - { - int16_t temperature; - const bool valid = getIMUTemperature(&temperature); - osdDisplayTemperature(elemPosX, elemPosY, SYM_IMU_TEMP, NULL, valid, temperature, osdConfig()->imu_temp_alarm_min, osdConfig()->imu_temp_alarm_max); - return true; - } + case OSD_IMU_TEMPERATURE: + { + int16_t temperature; + const bool valid = getIMUTemperature(&temperature); + osdDisplayTemperature(elemPosX, elemPosY, SYM_IMU_TEMP, NULL, valid, temperature, osdConfig()->imu_temp_alarm_min, osdConfig()->imu_temp_alarm_max); + return true; + } - case OSD_BARO_TEMPERATURE: - { - int16_t temperature; - const bool valid = getBaroTemperature(&temperature); - osdDisplayTemperature(elemPosX, elemPosY, SYM_BARO_TEMP, NULL, valid, temperature, osdConfig()->imu_temp_alarm_min, osdConfig()->imu_temp_alarm_max); - return true; - } + case OSD_BARO_TEMPERATURE: + { + int16_t temperature; + const bool valid = getBaroTemperature(&temperature); + osdDisplayTemperature(elemPosX, elemPosY, SYM_BARO_TEMP, NULL, valid, temperature, osdConfig()->imu_temp_alarm_min, osdConfig()->imu_temp_alarm_max); + return true; + } #ifdef USE_TEMPERATURE_SENSOR - case OSD_TEMP_SENSOR_0_TEMPERATURE: - case OSD_TEMP_SENSOR_1_TEMPERATURE: - case OSD_TEMP_SENSOR_2_TEMPERATURE: - case OSD_TEMP_SENSOR_3_TEMPERATURE: - case OSD_TEMP_SENSOR_4_TEMPERATURE: - case OSD_TEMP_SENSOR_5_TEMPERATURE: - case OSD_TEMP_SENSOR_6_TEMPERATURE: - case OSD_TEMP_SENSOR_7_TEMPERATURE: - { - osdDisplayTemperatureSensor(elemPosX, elemPosY, item - OSD_TEMP_SENSOR_0_TEMPERATURE); - return true; - } + case OSD_TEMP_SENSOR_0_TEMPERATURE: + case OSD_TEMP_SENSOR_1_TEMPERATURE: + case OSD_TEMP_SENSOR_2_TEMPERATURE: + case OSD_TEMP_SENSOR_3_TEMPERATURE: + case OSD_TEMP_SENSOR_4_TEMPERATURE: + case OSD_TEMP_SENSOR_5_TEMPERATURE: + case OSD_TEMP_SENSOR_6_TEMPERATURE: + case OSD_TEMP_SENSOR_7_TEMPERATURE: + { + osdDisplayTemperatureSensor(elemPosX, elemPosY, item - OSD_TEMP_SENSOR_0_TEMPERATURE); + return true; + } #endif /* ifdef USE_TEMPERATURE_SENSOR */ - case OSD_WIND_SPEED_HORIZONTAL: + case OSD_WIND_SPEED_HORIZONTAL: #ifdef USE_WIND_ESTIMATOR - { - bool valid = isEstimatedWindSpeedValid(); - float horizontalWindSpeed; - uint16_t angle; - horizontalWindSpeed = getEstimatedHorizontalWindSpeed(&angle); - int16_t windDirection = osdGetHeadingAngle( CENTIDEGREES_TO_DEGREES((int)angle) - DECIDEGREES_TO_DEGREES(attitude.values.yaw) + 22); - buff[0] = SYM_WIND_HORIZONTAL; - buff[1] = SYM_DIRECTION + (windDirection*2 / 90); - osdFormatWindSpeedStr(buff + 2, horizontalWindSpeed, valid); - break; - } + { + bool valid = isEstimatedWindSpeedValid(); + float horizontalWindSpeed; + uint16_t angle; + horizontalWindSpeed = getEstimatedHorizontalWindSpeed(&angle); + int16_t windDirection = osdGetHeadingAngle( CENTIDEGREES_TO_DEGREES((int)angle) - DECIDEGREES_TO_DEGREES(attitude.values.yaw) + 22); + buff[0] = SYM_WIND_HORIZONTAL; + buff[1] = SYM_DIRECTION + (windDirection*2 / 90); + osdFormatWindSpeedStr(buff + 2, horizontalWindSpeed, valid); + break; + } #else - return false; + return false; #endif - case OSD_WIND_SPEED_VERTICAL: + case OSD_WIND_SPEED_VERTICAL: #ifdef USE_WIND_ESTIMATOR - { - buff[0] = SYM_WIND_VERTICAL; - buff[1] = SYM_BLANK; - bool valid = isEstimatedWindSpeedValid(); - float verticalWindSpeed; - verticalWindSpeed = -getEstimatedWindSpeed(Z); //from NED to NEU - if (verticalWindSpeed < 0) { - buff[1] = SYM_AH_DIRECTION_DOWN; - verticalWindSpeed = -verticalWindSpeed; - } else { - buff[1] = SYM_AH_DIRECTION_UP; - } - osdFormatWindSpeedStr(buff + 2, verticalWindSpeed, valid); - break; - } + { + buff[0] = SYM_WIND_VERTICAL; + buff[1] = SYM_BLANK; + bool valid = isEstimatedWindSpeedValid(); + float verticalWindSpeed; + verticalWindSpeed = -getEstimatedWindSpeed(Z); //from NED to NEU + if (verticalWindSpeed < 0) { + buff[1] = SYM_AH_DIRECTION_DOWN; + verticalWindSpeed = -verticalWindSpeed; + } else { + buff[1] = SYM_AH_DIRECTION_UP; + } + osdFormatWindSpeedStr(buff + 2, verticalWindSpeed, valid); + break; + } #else - return false; + return false; #endif - case OSD_PLUS_CODE: - { - STATIC_ASSERT(GPS_DEGREES_DIVIDER == OLC_DEG_MULTIPLIER, invalid_olc_deg_multiplier); - int digits = osdConfig()->plus_code_digits; - int digitsRemoved = osdConfig()->plus_code_short * 2; - if (STATE(GPS_FIX)) { - olc_encode(gpsSol.llh.lat, gpsSol.llh.lon, digits, buff, sizeof(buff)); - } else { - // +codes with > 8 digits have a + at the 9th digit - // and we only support 10 and up. - memset(buff, '-', digits + 1); - buff[8] = '+'; - buff[digits + 1] = '\0'; - } - // Optionally trim digits from the left - memmove(buff, buff+digitsRemoved, strlen(buff) + digitsRemoved); - buff[digits + 1 - digitsRemoved] = '\0'; - break; - } + case OSD_PLUS_CODE: + { + STATIC_ASSERT(GPS_DEGREES_DIVIDER == OLC_DEG_MULTIPLIER, invalid_olc_deg_multiplier); + int digits = osdConfig()->plus_code_digits; + int digitsRemoved = osdConfig()->plus_code_short * 2; + if (STATE(GPS_FIX)) { + olc_encode(gpsSol.llh.lat, gpsSol.llh.lon, digits, buff, sizeof(buff)); + } else { + // +codes with > 8 digits have a + at the 9th digit + // and we only support 10 and up. + memset(buff, '-', digits + 1); + buff[8] = '+'; + buff[digits + 1] = '\0'; + } + // Optionally trim digits from the left + memmove(buff, buff+digitsRemoved, strlen(buff) + digitsRemoved); + buff[digits + 1 - digitsRemoved] = '\0'; + break; + } - case OSD_AZIMUTH: - { + case OSD_AZIMUTH: + { - buff[0] = SYM_AZIMUTH; - if (osdIsHeadingValid()) { - int16_t h = GPS_directionToHome; - if (h < 0) { - h += 360; - } - if (h >= 180) - h = h - 180; - else - h = h + 180; + buff[0] = SYM_AZIMUTH; + if (osdIsHeadingValid()) { + int16_t h = GPS_directionToHome; + if (h < 0) { + h += 360; + } + if (h >= 180) + h = h - 180; + else + h = h + 180; - tfp_sprintf(&buff[1], "%3d", h); - } else { - buff[1] = buff[2] = buff[3] = '-'; - } - buff[4] = SYM_DEGREES; - buff[5] = '\0'; - break; - } + tfp_sprintf(&buff[1], "%3d", h); + } else { + buff[1] = buff[2] = buff[3] = '-'; + } + buff[4] = SYM_DEGREES; + buff[5] = '\0'; + break; + } - case OSD_MAP_SCALE: - { - float scaleToUnit; - int scaleUnitDivisor; - char symUnscaled; - char symScaled; - int maxDecimals; + case OSD_MAP_SCALE: + { + float scaleToUnit; + int scaleUnitDivisor; + char symUnscaled; + char symScaled; + int maxDecimals; - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - scaleToUnit = 100 / 1609.3440f; // scale to 0.01mi for osdFormatCentiNumber() - scaleUnitDivisor = 0; - symUnscaled = SYM_MI; - symScaled = SYM_MI; - maxDecimals = 2; - break; - case OSD_UNIT_GA: - scaleToUnit = 100 / 1852.0010f; // scale to 0.01mi for osdFormatCentiNumber() - scaleUnitDivisor = 0; - symUnscaled = SYM_NM; - symScaled = SYM_NM; - maxDecimals = 2; - break; - default: - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - scaleToUnit = 100; // scale to cm for osdFormatCentiNumber() - scaleUnitDivisor = 1000; // Convert to km when scale gets bigger than 999m - symUnscaled = SYM_M; - symScaled = SYM_KM; - maxDecimals = 0; - break; - } - buff[0] = SYM_SCALE; - if (osdMapData.scale > 0) { - bool scaled = osdFormatCentiNumber(&buff[1], osdMapData.scale * scaleToUnit, scaleUnitDivisor, maxDecimals, 2, 3); - buff[4] = scaled ? symScaled : symUnscaled; - // Make sure this is cleared if the map stops being drawn - osdMapData.scale = 0; - } else { - memset(&buff[1], '-', 4); - } - buff[5] = '\0'; - break; - } - case OSD_MAP_REFERENCE: - { - char referenceSymbol; - if (osdMapData.referenceSymbol) { - referenceSymbol = osdMapData.referenceSymbol; - // Make sure this is cleared if the map stops being drawn - osdMapData.referenceSymbol = 0; - } else { - referenceSymbol = '-'; - } - displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_DIRECTION); - displayWriteChar(osdDisplayPort, elemPosX, elemPosY + 1, referenceSymbol); - return true; - } + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + scaleToUnit = 100 / 1609.3440f; // scale to 0.01mi for osdFormatCentiNumber() + scaleUnitDivisor = 0; + symUnscaled = SYM_MI; + symScaled = SYM_MI; + maxDecimals = 2; + break; + case OSD_UNIT_GA: + scaleToUnit = 100 / 1852.0010f; // scale to 0.01mi for osdFormatCentiNumber() + scaleUnitDivisor = 0; + symUnscaled = SYM_NM; + symScaled = SYM_NM; + maxDecimals = 2; + break; + default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + scaleToUnit = 100; // scale to cm for osdFormatCentiNumber() + scaleUnitDivisor = 1000; // Convert to km when scale gets bigger than 999m + symUnscaled = SYM_M; + symScaled = SYM_KM; + maxDecimals = 0; + break; + } + buff[0] = SYM_SCALE; + if (osdMapData.scale > 0) { + bool scaled = osdFormatCentiNumber(&buff[1], osdMapData.scale * scaleToUnit, scaleUnitDivisor, maxDecimals, 2, 3); + buff[4] = scaled ? symScaled : symUnscaled; + // Make sure this is cleared if the map stops being drawn + osdMapData.scale = 0; + } else { + memset(&buff[1], '-', 4); + } + buff[5] = '\0'; + break; + } + case OSD_MAP_REFERENCE: + { + char referenceSymbol; + if (osdMapData.referenceSymbol) { + referenceSymbol = osdMapData.referenceSymbol; + // Make sure this is cleared if the map stops being drawn + osdMapData.referenceSymbol = 0; + } else { + referenceSymbol = '-'; + } + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_DIRECTION); + displayWriteChar(osdDisplayPort, elemPosX, elemPosY + 1, referenceSymbol); + return true; + } - case OSD_GVAR_0: - { - osdFormatGVar(buff, 0); - break; - } - case OSD_GVAR_1: - { - osdFormatGVar(buff, 1); - break; - } - case OSD_GVAR_2: - { - osdFormatGVar(buff, 2); - break; - } - case OSD_GVAR_3: - { - osdFormatGVar(buff, 3); - break; - } + case OSD_GVAR_0: + { + osdFormatGVar(buff, 0); + break; + } + case OSD_GVAR_1: + { + osdFormatGVar(buff, 1); + break; + } + case OSD_GVAR_2: + { + osdFormatGVar(buff, 2); + break; + } + case OSD_GVAR_3: + { + osdFormatGVar(buff, 3); + break; + } #if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE) - case OSD_RC_SOURCE: - { - const char *source_text = IS_RC_MODE_ACTIVE(BOXMSPRCOVERRIDE) && !mspOverrideIsInFailsafe() ? "MSP" : "STD"; - if (IS_RC_MODE_ACTIVE(BOXMSPRCOVERRIDE) && mspOverrideIsInFailsafe()) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, source_text, elemAttr); - return true; - } + case OSD_RC_SOURCE: + { + const char *source_text = IS_RC_MODE_ACTIVE(BOXMSPRCOVERRIDE) && !mspOverrideIsInFailsafe() ? "MSP" : "STD"; + if (IS_RC_MODE_ACTIVE(BOXMSPRCOVERRIDE) && mspOverrideIsInFailsafe()) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, source_text, elemAttr); + return true; + } #endif #if defined(USE_ESC_SENSOR) - case OSD_ESC_RPM: - { - escSensorData_t * escSensor = escSensorGetData(); - if (escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE) { - osdFormatRpm(buff, escSensor->rpm); - } - else { - osdFormatRpm(buff, 0); - } - break; - } - case OSD_ESC_TEMPERATURE: - { - escSensorData_t * escSensor = escSensorGetData(); - bool escTemperatureValid = escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE; - osdDisplayTemperature(elemPosX, elemPosY, SYM_ESC_TEMP, NULL, escTemperatureValid, (escSensor->temperature)*10, osdConfig()->esc_temp_alarm_min, osdConfig()->esc_temp_alarm_max); - return true; - } + case OSD_ESC_RPM: + { + escSensorData_t * escSensor = escSensorGetData(); + if (escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE) { + osdFormatRpm(buff, escSensor->rpm); + } + else { + osdFormatRpm(buff, 0); + } + break; + } + case OSD_ESC_TEMPERATURE: + { + escSensorData_t * escSensor = escSensorGetData(); + bool escTemperatureValid = escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE; + osdDisplayTemperature(elemPosX, elemPosY, SYM_ESC_TEMP, NULL, escTemperatureValid, (escSensor->temperature)*10, osdConfig()->esc_temp_alarm_min, osdConfig()->esc_temp_alarm_max); + return true; + } #endif - case OSD_TPA: - { - char buff[4]; - textAttributes_t attr; + case OSD_TPA: + { + char buff[4]; + textAttributes_t attr; - displayWrite(osdDisplayPort, elemPosX, elemPosY, "TPA"); - attr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", currentControlRateProfile->throttle.dynPID); - if (isAdjustmentFunctionSelected(ADJUSTMENT_TPA)) { - TEXT_ATTRIBUTES_ADD_BLINK(attr); - } - displayWriteWithAttr(osdDisplayPort, elemPosX + 5, elemPosY, buff, attr); + displayWrite(osdDisplayPort, elemPosX, elemPosY, "TPA"); + attr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", currentControlRateProfile->throttle.dynPID); + if (isAdjustmentFunctionSelected(ADJUSTMENT_TPA)) { + TEXT_ATTRIBUTES_ADD_BLINK(attr); + } + displayWriteWithAttr(osdDisplayPort, elemPosX + 5, elemPosY, buff, attr); - displayWrite(osdDisplayPort, elemPosX, elemPosY + 1, "BP"); - attr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%4d", currentControlRateProfile->throttle.pa_breakpoint); - if (isAdjustmentFunctionSelected(ADJUSTMENT_TPA_BREAKPOINT)) { - TEXT_ATTRIBUTES_ADD_BLINK(attr); - } - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY + 1, buff, attr); + displayWrite(osdDisplayPort, elemPosX, elemPosY + 1, "BP"); + attr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%4d", currentControlRateProfile->throttle.pa_breakpoint); + if (isAdjustmentFunctionSelected(ADJUSTMENT_TPA_BREAKPOINT)) { + TEXT_ATTRIBUTES_ADD_BLINK(attr); + } + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY + 1, buff, attr); - return true; - } - case OSD_TPA_TIME_CONSTANT: - { - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "TPA TC", 0, currentControlRateProfile->throttle.fixedWingTauMs, 4, 0, ADJUSTMENT_FW_TPA_TIME_CONSTANT); - return true; - } - case OSD_FW_LEVEL_TRIM: - { - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "LEVEL", 0, getFixedWingLevelTrim(), 3, 1, ADJUSTMENT_FW_LEVEL_TRIM); - return true; - } + return true; + } + case OSD_TPA_TIME_CONSTANT: + { + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "TPA TC", 0, currentControlRateProfile->throttle.fixedWingTauMs, 4, 0, ADJUSTMENT_FW_TPA_TIME_CONSTANT); + return true; + } + case OSD_FW_LEVEL_TRIM: + { + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "LEVEL", 0, getFixedWingLevelTrim(), 3, 1, ADJUSTMENT_FW_LEVEL_TRIM); + return true; + } - case OSD_NAV_FW_CONTROL_SMOOTHNESS: - { - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CTL S", 0, navConfig()->fw.control_smoothness, 1, 0, ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS); - return true; - } + case OSD_NAV_FW_CONTROL_SMOOTHNESS: + { + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CTL S", 0, navConfig()->fw.control_smoothness, 1, 0, ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS); + return true; + } #ifdef USE_MULTI_MISSION - case OSD_NAV_WP_MULTI_MISSION_INDEX: - { - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "WP NO", 0, navConfig()->general.waypoint_multi_mission_index, 1, 0, ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX); - return true; - } + case OSD_NAV_WP_MULTI_MISSION_INDEX: + { + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "WP NO", 0, navConfig()->general.waypoint_multi_mission_index, 1, 0, ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX); + return true; + } #endif - case OSD_MISSION: - { - if (IS_RC_MODE_ACTIVE(BOXPLANWPMISSION)) { - char buf[5]; - switch (posControl.wpMissionPlannerStatus) { - case WP_PLAN_WAIT: - strcpy(buf, "WAIT"); - break; - case WP_PLAN_SAVE: - strcpy(buf, "SAVE"); - break; - case WP_PLAN_OK: - strcpy(buf, " OK "); - break; - case WP_PLAN_FULL: - strcpy(buf, "FULL"); - } - tfp_sprintf(buff, "%s>%2uWP", buf, posControl.wpPlannerActiveWPIndex); - } else if (posControl.wpPlannerActiveWPIndex){ - tfp_sprintf(buff, "PLAN>%2uWP", posControl.waypointCount); // mission planner mision active - } + case OSD_MISSION: + { + if (IS_RC_MODE_ACTIVE(BOXPLANWPMISSION)) { + char buf[5]; + switch (posControl.wpMissionPlannerStatus) { + case WP_PLAN_WAIT: + strcpy(buf, "WAIT"); + break; + case WP_PLAN_SAVE: + strcpy(buf, "SAVE"); + break; + case WP_PLAN_OK: + strcpy(buf, " OK "); + break; + case WP_PLAN_FULL: + strcpy(buf, "FULL"); + } + tfp_sprintf(buff, "%s>%2uWP", buf, posControl.wpPlannerActiveWPIndex); + } else if (posControl.wpPlannerActiveWPIndex){ + tfp_sprintf(buff, "PLAN>%2uWP", posControl.waypointCount); // mission planner mision active + } #ifdef USE_MULTI_MISSION - else { - if (ARMING_FLAG(ARMED) && !(IS_RC_MODE_ACTIVE(BOXCHANGEMISSION) && posControl.multiMissionCount > 1)){ - // Limit field size when Armed, only show selected mission - tfp_sprintf(buff, "M%u ", posControl.loadedMultiMissionIndex); - } else if (posControl.multiMissionCount) { - if (navConfig()->general.waypoint_multi_mission_index != posControl.loadedMultiMissionIndex) { - tfp_sprintf(buff, "M%u/%u>LOAD", navConfig()->general.waypoint_multi_mission_index, posControl.multiMissionCount); - } else { - if (posControl.waypointListValid && posControl.waypointCount > 0) { - tfp_sprintf(buff, "M%u/%u>%2uWP", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); - } else { - tfp_sprintf(buff, "M0/%u> 0WP", posControl.multiMissionCount); - } - } - } else { // no multi mission loaded - show active WP count from other source - tfp_sprintf(buff, "WP CNT>%2u", posControl.waypointCount); - } - } + else { + if (ARMING_FLAG(ARMED) && !(IS_RC_MODE_ACTIVE(BOXCHANGEMISSION) && posControl.multiMissionCount > 1)){ + // Limit field size when Armed, only show selected mission + tfp_sprintf(buff, "M%u ", posControl.loadedMultiMissionIndex); + } else if (posControl.multiMissionCount) { + if (navConfig()->general.waypoint_multi_mission_index != posControl.loadedMultiMissionIndex) { + tfp_sprintf(buff, "M%u/%u>LOAD", navConfig()->general.waypoint_multi_mission_index, posControl.multiMissionCount); + } else { + if (posControl.waypointListValid && posControl.waypointCount > 0) { + tfp_sprintf(buff, "M%u/%u>%2uWP", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); + } else { + tfp_sprintf(buff, "M0/%u> 0WP", posControl.multiMissionCount); + } + } + } else { // no multi mission loaded - show active WP count from other source + tfp_sprintf(buff, "WP CNT>%2u", posControl.waypointCount); + } + } #endif - displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); - return true; - } + displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); + return true; + } #ifdef USE_POWER_LIMITS - case OSD_PLIMIT_REMAINING_BURST_TIME: - osdFormatCentiNumber(buff, powerLimiterGetRemainingBurstTime() * 100, 0, 1, 0, 3); - buff[3] = 'S'; - buff[4] = '\0'; - break; + case OSD_PLIMIT_REMAINING_BURST_TIME: + osdFormatCentiNumber(buff, powerLimiterGetRemainingBurstTime() * 100, 0, 1, 0, 3); + buff[3] = 'S'; + buff[4] = '\0'; + break; - case OSD_PLIMIT_ACTIVE_CURRENT_LIMIT: - if (currentBatteryProfile->powerLimits.continuousCurrent) { - osdFormatCentiNumber(buff, powerLimiterGetActiveCurrentLimit(), 0, 2, 0, 3); - buff[3] = SYM_AMP; - buff[4] = '\0'; + case OSD_PLIMIT_ACTIVE_CURRENT_LIMIT: + if (currentBatteryProfile->powerLimits.continuousCurrent) { + osdFormatCentiNumber(buff, powerLimiterGetActiveCurrentLimit(), 0, 2, 0, 3); + buff[3] = SYM_AMP; + buff[4] = '\0'; - if (powerLimiterIsLimitingCurrent()) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } - break; + if (powerLimiterIsLimitingCurrent()) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + break; #ifdef USE_ADC - case OSD_PLIMIT_ACTIVE_POWER_LIMIT: - { - if (currentBatteryProfile->powerLimits.continuousPower) { - bool kiloWatt = osdFormatCentiNumber(buff, powerLimiterGetActivePowerLimit(), 1000, 2, 2, 3); - buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; - buff[4] = '\0'; + case OSD_PLIMIT_ACTIVE_POWER_LIMIT: + { + if (currentBatteryProfile->powerLimits.continuousPower) { + bool kiloWatt = osdFormatCentiNumber(buff, powerLimiterGetActivePowerLimit(), 1000, 2, 2, 3); + buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; + buff[4] = '\0'; - if (powerLimiterIsLimitingPower()) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } - break; - } + if (powerLimiterIsLimitingPower()) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + break; + } #endif // USE_ADC #endif // USE_POWER_LIMITS - default: - return false; - } + default: + return false; + } - displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); - return true; + displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); + return true; } uint8_t osdIncElementIndex(uint8_t elementIndex) { - ++elementIndex; + ++elementIndex; - if (elementIndex == OSD_ARTIFICIAL_HORIZON) { // always drawn last so skip - elementIndex++; - } + if (elementIndex == OSD_ARTIFICIAL_HORIZON) { // always drawn last so skip + elementIndex++; + } #ifndef USE_TEMPERATURE_SENSOR - if (elementIndex == OSD_TEMP_SENSOR_0_TEMPERATURE) { - elementIndex = OSD_ALTITUDE_MSL; - } + if (elementIndex == OSD_TEMP_SENSOR_0_TEMPERATURE) { + elementIndex = OSD_ALTITUDE_MSL; + } #endif - if (!(feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER))) { - if (elementIndex == OSD_POWER) { - elementIndex = OSD_GPS_LON; - } - if (elementIndex == OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE) { - elementIndex = OSD_LEVEL_PIDS; - } + if (!(feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER))) { + if (elementIndex == OSD_POWER) { + elementIndex = OSD_GPS_LON; + } + if (elementIndex == OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE) { + elementIndex = OSD_LEVEL_PIDS; + } #ifdef USE_POWER_LIMITS - if (elementIndex == OSD_PLIMIT_REMAINING_BURST_TIME) { - elementIndex = OSD_GLIDESLOPE; - } + if (elementIndex == OSD_PLIMIT_REMAINING_BURST_TIME) { + elementIndex = OSD_GLIDESLOPE; + } #endif - } + } #ifndef USE_POWER_LIMITS - if (elementIndex == OSD_PLIMIT_REMAINING_BURST_TIME) { - elementIndex = OSD_GLIDESLOPE; - } + if (elementIndex == OSD_PLIMIT_REMAINING_BURST_TIME) { + elementIndex = OSD_GLIDESLOPE; + } #endif - if (!feature(FEATURE_CURRENT_METER)) { - if (elementIndex == OSD_CURRENT_DRAW) { - elementIndex = OSD_GPS_SPEED; - } - if (elementIndex == OSD_EFFICIENCY_MAH_PER_KM) { - elementIndex = OSD_BATTERY_REMAINING_PERCENT; - } - if (elementIndex == OSD_EFFICIENCY_WH_PER_KM) { - elementIndex = OSD_TRIP_DIST; - } - if (elementIndex == OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH) { - elementIndex = OSD_HOME_HEADING_ERROR; - } - if (elementIndex == OSD_CLIMB_EFFICIENCY) { - elementIndex = OSD_NAV_WP_MULTI_MISSION_INDEX; - } - } + if (!feature(FEATURE_CURRENT_METER)) { + if (elementIndex == OSD_CURRENT_DRAW) { + elementIndex = OSD_GPS_SPEED; + } + if (elementIndex == OSD_EFFICIENCY_MAH_PER_KM) { + elementIndex = OSD_BATTERY_REMAINING_PERCENT; + } + if (elementIndex == OSD_EFFICIENCY_WH_PER_KM) { + elementIndex = OSD_TRIP_DIST; + } + if (elementIndex == OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH) { + elementIndex = OSD_HOME_HEADING_ERROR; + } + if (elementIndex == OSD_CLIMB_EFFICIENCY) { + elementIndex = OSD_NAV_WP_MULTI_MISSION_INDEX; + } + } - if (!STATE(ESC_SENSOR_ENABLED)) { - if (elementIndex == OSD_ESC_RPM) { - elementIndex = OSD_AZIMUTH; - } - } + if (!STATE(ESC_SENSOR_ENABLED)) { + if (elementIndex == OSD_ESC_RPM) { + elementIndex = OSD_AZIMUTH; + } + } - if (!feature(FEATURE_GPS)) { - if (elementIndex == OSD_GPS_HDOP || elementIndex == OSD_TRIP_DIST || elementIndex == OSD_3D_SPEED || elementIndex == OSD_MISSION || - elementIndex == OSD_AZIMUTH || elementIndex == OSD_BATTERY_REMAINING_CAPACITY || elementIndex == OSD_EFFICIENCY_MAH_PER_KM) { - elementIndex++; - } - if (elementIndex == OSD_HEADING_GRAPH && !sensors(SENSOR_MAG)) { - elementIndex = feature(FEATURE_CURRENT_METER) ? OSD_WH_DRAWN : OSD_BATTERY_REMAINING_PERCENT; - } - if (elementIndex == OSD_EFFICIENCY_WH_PER_KM) { - elementIndex = OSD_ATTITUDE_PITCH; - } - if (elementIndex == OSD_GPS_SPEED) { - elementIndex = OSD_ALTITUDE; - } - if (elementIndex == OSD_GPS_LON) { - elementIndex = sensors(SENSOR_MAG) ? OSD_HEADING : OSD_VARIO; - } - if (elementIndex == OSD_MAP_NORTH) { - elementIndex = feature(FEATURE_CURRENT_METER) ? OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE : OSD_LEVEL_PIDS; - } - if (elementIndex == OSD_PLUS_CODE) { - elementIndex = OSD_GFORCE; - } - if (elementIndex == OSD_GLIDESLOPE) { - elementIndex = OSD_AIR_MAX_SPEED; - } - if (elementIndex == OSD_GLIDE_RANGE) { - elementIndex = feature(FEATURE_CURRENT_METER) ? OSD_CLIMB_EFFICIENCY : OSD_PILOT_NAME; - } - if (elementIndex == OSD_NAV_WP_MULTI_MISSION_INDEX) { - elementIndex = OSD_PILOT_NAME; - } - } + if (!feature(FEATURE_GPS)) { + if (elementIndex == OSD_GPS_HDOP || elementIndex == OSD_TRIP_DIST || elementIndex == OSD_3D_SPEED || elementIndex == OSD_MISSION || + elementIndex == OSD_AZIMUTH || elementIndex == OSD_BATTERY_REMAINING_CAPACITY || elementIndex == OSD_EFFICIENCY_MAH_PER_KM) { + elementIndex++; + } + if (elementIndex == OSD_HEADING_GRAPH && !sensors(SENSOR_MAG)) { + elementIndex = feature(FEATURE_CURRENT_METER) ? OSD_WH_DRAWN : OSD_BATTERY_REMAINING_PERCENT; + } + if (elementIndex == OSD_EFFICIENCY_WH_PER_KM) { + elementIndex = OSD_ATTITUDE_PITCH; + } + if (elementIndex == OSD_GPS_SPEED) { + elementIndex = OSD_ALTITUDE; + } + if (elementIndex == OSD_GPS_LON) { + elementIndex = sensors(SENSOR_MAG) ? OSD_HEADING : OSD_VARIO; + } + if (elementIndex == OSD_MAP_NORTH) { + elementIndex = feature(FEATURE_CURRENT_METER) ? OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE : OSD_LEVEL_PIDS; + } + if (elementIndex == OSD_PLUS_CODE) { + elementIndex = OSD_GFORCE; + } + if (elementIndex == OSD_GLIDESLOPE) { + elementIndex = OSD_AIR_MAX_SPEED; + } + if (elementIndex == OSD_GLIDE_RANGE) { + elementIndex = feature(FEATURE_CURRENT_METER) ? OSD_CLIMB_EFFICIENCY : OSD_PILOT_NAME; + } + if (elementIndex == OSD_NAV_WP_MULTI_MISSION_INDEX) { + elementIndex = OSD_PILOT_NAME; + } + } - if (!sensors(SENSOR_ACC)) { - if (elementIndex == OSD_CROSSHAIRS) { - elementIndex = OSD_ONTIME; - } - if (elementIndex == OSD_GFORCE) { - elementIndex = OSD_RC_SOURCE; - } - } + if (!sensors(SENSOR_ACC)) { + if (elementIndex == OSD_CROSSHAIRS) { + elementIndex = OSD_ONTIME; + } + if (elementIndex == OSD_GFORCE) { + elementIndex = OSD_RC_SOURCE; + } + } - if (elementIndex == OSD_ITEM_COUNT) { - elementIndex = 0; - } - return elementIndex; + if (elementIndex == OSD_ITEM_COUNT) { + elementIndex = 0; + } + return elementIndex; } void osdDrawNextElement(void) { - static uint8_t elementIndex = 0; - // Flag for end of loop, also prevents infinite loop when no elements are enabled - uint8_t index = elementIndex; - do { - elementIndex = osdIncElementIndex(elementIndex); - } while (!osdDrawSingleElement(elementIndex) && index != elementIndex); + static uint8_t elementIndex = 0; + // Flag for end of loop, also prevents infinite loop when no elements are enabled + uint8_t index = elementIndex; + do { + elementIndex = osdIncElementIndex(elementIndex); + } while (!osdDrawSingleElement(elementIndex) && index != elementIndex); - // Draw artificial horizon + tracking telemtry last - osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON); - if (osdConfig()->telemetry>0){ - osdDisplayTelemetry(); - } + // Draw artificial horizon + tracking telemtry last + osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON); + if (osdConfig()->telemetry>0){ + osdDisplayTelemetry(); + } } PG_RESET_TEMPLATE(osdConfig_t, osdConfig, - .rssi_alarm = SETTING_OSD_RSSI_ALARM_DEFAULT, - .time_alarm = SETTING_OSD_TIME_ALARM_DEFAULT, - .alt_alarm = SETTING_OSD_ALT_ALARM_DEFAULT, - .dist_alarm = SETTING_OSD_DIST_ALARM_DEFAULT, - .neg_alt_alarm = SETTING_OSD_NEG_ALT_ALARM_DEFAULT, - .current_alarm = SETTING_OSD_CURRENT_ALARM_DEFAULT, - .imu_temp_alarm_min = SETTING_OSD_IMU_TEMP_ALARM_MIN_DEFAULT, - .imu_temp_alarm_max = SETTING_OSD_IMU_TEMP_ALARM_MAX_DEFAULT, - .esc_temp_alarm_min = SETTING_OSD_ESC_TEMP_ALARM_MIN_DEFAULT, - .esc_temp_alarm_max = SETTING_OSD_ESC_TEMP_ALARM_MAX_DEFAULT, - .gforce_alarm = SETTING_OSD_GFORCE_ALARM_DEFAULT, - .gforce_axis_alarm_min = SETTING_OSD_GFORCE_AXIS_ALARM_MIN_DEFAULT, - .gforce_axis_alarm_max = SETTING_OSD_GFORCE_AXIS_ALARM_MAX_DEFAULT, + .rssi_alarm = SETTING_OSD_RSSI_ALARM_DEFAULT, + .time_alarm = SETTING_OSD_TIME_ALARM_DEFAULT, + .alt_alarm = SETTING_OSD_ALT_ALARM_DEFAULT, + .dist_alarm = SETTING_OSD_DIST_ALARM_DEFAULT, + .neg_alt_alarm = SETTING_OSD_NEG_ALT_ALARM_DEFAULT, + .current_alarm = SETTING_OSD_CURRENT_ALARM_DEFAULT, + .imu_temp_alarm_min = SETTING_OSD_IMU_TEMP_ALARM_MIN_DEFAULT, + .imu_temp_alarm_max = SETTING_OSD_IMU_TEMP_ALARM_MAX_DEFAULT, + .esc_temp_alarm_min = SETTING_OSD_ESC_TEMP_ALARM_MIN_DEFAULT, + .esc_temp_alarm_max = SETTING_OSD_ESC_TEMP_ALARM_MAX_DEFAULT, + .gforce_alarm = SETTING_OSD_GFORCE_ALARM_DEFAULT, + .gforce_axis_alarm_min = SETTING_OSD_GFORCE_AXIS_ALARM_MIN_DEFAULT, + .gforce_axis_alarm_max = SETTING_OSD_GFORCE_AXIS_ALARM_MAX_DEFAULT, #ifdef USE_BARO - .baro_temp_alarm_min = SETTING_OSD_BARO_TEMP_ALARM_MIN_DEFAULT, - .baro_temp_alarm_max = SETTING_OSD_BARO_TEMP_ALARM_MAX_DEFAULT, + .baro_temp_alarm_min = SETTING_OSD_BARO_TEMP_ALARM_MIN_DEFAULT, + .baro_temp_alarm_max = SETTING_OSD_BARO_TEMP_ALARM_MAX_DEFAULT, #endif #ifdef USE_SERIALRX_CRSF - .snr_alarm = SETTING_OSD_SNR_ALARM_DEFAULT, - .crsf_lq_format = SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT, - .link_quality_alarm = SETTING_OSD_LINK_QUALITY_ALARM_DEFAULT, - .rssi_dbm_alarm = SETTING_OSD_RSSI_DBM_ALARM_DEFAULT, - .rssi_dbm_max = SETTING_OSD_RSSI_DBM_MAX_DEFAULT, - .rssi_dbm_min = SETTING_OSD_RSSI_DBM_MIN_DEFAULT, + .snr_alarm = SETTING_OSD_SNR_ALARM_DEFAULT, + .crsf_lq_format = SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT, + .link_quality_alarm = SETTING_OSD_LINK_QUALITY_ALARM_DEFAULT, + .rssi_dbm_alarm = SETTING_OSD_RSSI_DBM_ALARM_DEFAULT, + .rssi_dbm_max = SETTING_OSD_RSSI_DBM_MAX_DEFAULT, + .rssi_dbm_min = SETTING_OSD_RSSI_DBM_MIN_DEFAULT, #endif #ifdef USE_TEMPERATURE_SENSOR - .temp_label_align = SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT, + .temp_label_align = SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT, #endif #ifdef USE_PITOT - .airspeed_alarm_min = SETTING_OSD_AIRSPEED_ALARM_MIN_DEFAULT, - .airspeed_alarm_max = SETTING_OSD_AIRSPEED_ALARM_MAX_DEFAULT, + .airspeed_alarm_min = SETTING_OSD_AIRSPEED_ALARM_MIN_DEFAULT, + .airspeed_alarm_max = SETTING_OSD_AIRSPEED_ALARM_MAX_DEFAULT, #endif - .video_system = SETTING_OSD_VIDEO_SYSTEM_DEFAULT, - .row_shiftdown = SETTING_OSD_ROW_SHIFTDOWN_DEFAULT, - .msp_displayport_fullframe_interval = SETTING_OSD_MSP_DISPLAYPORT_FULLFRAME_INTERVAL_DEFAULT, + .video_system = SETTING_OSD_VIDEO_SYSTEM_DEFAULT, + .row_shiftdown = SETTING_OSD_ROW_SHIFTDOWN_DEFAULT, + .msp_displayport_fullframe_interval = SETTING_OSD_MSP_DISPLAYPORT_FULLFRAME_INTERVAL_DEFAULT, - .ahi_reverse_roll = SETTING_OSD_AHI_REVERSE_ROLL_DEFAULT, - .ahi_max_pitch = SETTING_OSD_AHI_MAX_PITCH_DEFAULT, - .crosshairs_style = SETTING_OSD_CROSSHAIRS_STYLE_DEFAULT, - .horizon_offset = SETTING_OSD_HORIZON_OFFSET_DEFAULT, - .camera_uptilt = SETTING_OSD_CAMERA_UPTILT_DEFAULT, - .ahi_camera_uptilt_comp = SETTING_OSD_AHI_CAMERA_UPTILT_COMP_DEFAULT, - .camera_fov_h = SETTING_OSD_CAMERA_FOV_H_DEFAULT, - .camera_fov_v = SETTING_OSD_CAMERA_FOV_V_DEFAULT, - .hud_margin_h = SETTING_OSD_HUD_MARGIN_H_DEFAULT, - .hud_margin_v = SETTING_OSD_HUD_MARGIN_V_DEFAULT, - .hud_homing = SETTING_OSD_HUD_HOMING_DEFAULT, - .hud_homepoint = SETTING_OSD_HUD_HOMEPOINT_DEFAULT, - .hud_radar_disp = SETTING_OSD_HUD_RADAR_DISP_DEFAULT, - .hud_radar_range_min = SETTING_OSD_HUD_RADAR_RANGE_MIN_DEFAULT, - .hud_radar_range_max = SETTING_OSD_HUD_RADAR_RANGE_MAX_DEFAULT, - .hud_radar_alt_difference_display_time = SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_DEFAULT, - .hud_radar_distance_display_time = SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_DEFAULT, - .hud_wp_disp = SETTING_OSD_HUD_WP_DISP_DEFAULT, - .left_sidebar_scroll = SETTING_OSD_LEFT_SIDEBAR_SCROLL_DEFAULT, - .right_sidebar_scroll = SETTING_OSD_RIGHT_SIDEBAR_SCROLL_DEFAULT, - .sidebar_scroll_arrows = SETTING_OSD_SIDEBAR_SCROLL_ARROWS_DEFAULT, - .sidebar_horizontal_offset = SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_DEFAULT, - .left_sidebar_scroll_step = SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_DEFAULT, - .right_sidebar_scroll_step = SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_DEFAULT, - .sidebar_height = SETTING_OSD_SIDEBAR_HEIGHT_DEFAULT, - .ahi_pitch_interval = SETTING_OSD_AHI_PITCH_INTERVAL_DEFAULT, - .osd_home_position_arm_screen = SETTING_OSD_HOME_POSITION_ARM_SCREEN_DEFAULT, - .pan_servo_index = SETTING_OSD_PAN_SERVO_INDEX_DEFAULT, - .pan_servo_pwm2centideg = SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_DEFAULT, - .pan_servo_offcentre_warning = SETTING_OSD_PAN_SERVO_OFFCENTRE_WARNING_DEFAULT, - .pan_servo_indicator_show_degrees = SETTING_OSD_PAN_SERVO_INDICATOR_SHOW_DEGREES_DEFAULT, - .esc_rpm_precision = SETTING_OSD_ESC_RPM_PRECISION_DEFAULT, - .mAh_used_precision = SETTING_OSD_MAH_USED_PRECISION_DEFAULT, - .osd_switch_indicator0_name = SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_DEFAULT, - .osd_switch_indicator0_channel = SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_DEFAULT, - .osd_switch_indicator1_name = SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_DEFAULT, - .osd_switch_indicator1_channel = SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_DEFAULT, - .osd_switch_indicator2_name = SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_DEFAULT, - .osd_switch_indicator2_channel = SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_DEFAULT, - .osd_switch_indicator3_name = SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_DEFAULT, - .osd_switch_indicator3_channel = SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_DEFAULT, - .osd_switch_indicators_align_left = SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_DEFAULT, - .system_msg_display_time = SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_DEFAULT, - .units = SETTING_OSD_UNITS_DEFAULT, - .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT, + .ahi_reverse_roll = SETTING_OSD_AHI_REVERSE_ROLL_DEFAULT, + .ahi_max_pitch = SETTING_OSD_AHI_MAX_PITCH_DEFAULT, + .crosshairs_style = SETTING_OSD_CROSSHAIRS_STYLE_DEFAULT, + .horizon_offset = SETTING_OSD_HORIZON_OFFSET_DEFAULT, + .camera_uptilt = SETTING_OSD_CAMERA_UPTILT_DEFAULT, + .ahi_camera_uptilt_comp = SETTING_OSD_AHI_CAMERA_UPTILT_COMP_DEFAULT, + .camera_fov_h = SETTING_OSD_CAMERA_FOV_H_DEFAULT, + .camera_fov_v = SETTING_OSD_CAMERA_FOV_V_DEFAULT, + .hud_margin_h = SETTING_OSD_HUD_MARGIN_H_DEFAULT, + .hud_margin_v = SETTING_OSD_HUD_MARGIN_V_DEFAULT, + .hud_homing = SETTING_OSD_HUD_HOMING_DEFAULT, + .hud_homepoint = SETTING_OSD_HUD_HOMEPOINT_DEFAULT, + .hud_radar_disp = SETTING_OSD_HUD_RADAR_DISP_DEFAULT, + .hud_radar_range_min = SETTING_OSD_HUD_RADAR_RANGE_MIN_DEFAULT, + .hud_radar_range_max = SETTING_OSD_HUD_RADAR_RANGE_MAX_DEFAULT, + .hud_radar_alt_difference_display_time = SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_DEFAULT, + .hud_radar_distance_display_time = SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_DEFAULT, + .hud_wp_disp = SETTING_OSD_HUD_WP_DISP_DEFAULT, + .left_sidebar_scroll = SETTING_OSD_LEFT_SIDEBAR_SCROLL_DEFAULT, + .right_sidebar_scroll = SETTING_OSD_RIGHT_SIDEBAR_SCROLL_DEFAULT, + .sidebar_scroll_arrows = SETTING_OSD_SIDEBAR_SCROLL_ARROWS_DEFAULT, + .sidebar_horizontal_offset = SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_DEFAULT, + .left_sidebar_scroll_step = SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_DEFAULT, + .right_sidebar_scroll_step = SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_DEFAULT, + .sidebar_height = SETTING_OSD_SIDEBAR_HEIGHT_DEFAULT, + .ahi_pitch_interval = SETTING_OSD_AHI_PITCH_INTERVAL_DEFAULT, + .osd_home_position_arm_screen = SETTING_OSD_HOME_POSITION_ARM_SCREEN_DEFAULT, + .pan_servo_index = SETTING_OSD_PAN_SERVO_INDEX_DEFAULT, + .pan_servo_pwm2centideg = SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_DEFAULT, + .pan_servo_offcentre_warning = SETTING_OSD_PAN_SERVO_OFFCENTRE_WARNING_DEFAULT, + .pan_servo_indicator_show_degrees = SETTING_OSD_PAN_SERVO_INDICATOR_SHOW_DEGREES_DEFAULT, + .esc_rpm_precision = SETTING_OSD_ESC_RPM_PRECISION_DEFAULT, + .mAh_used_precision = SETTING_OSD_MAH_USED_PRECISION_DEFAULT, + .osd_switch_indicator0_name = SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_DEFAULT, + .osd_switch_indicator0_channel = SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_DEFAULT, + .osd_switch_indicator1_name = SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_DEFAULT, + .osd_switch_indicator1_channel = SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_DEFAULT, + .osd_switch_indicator2_name = SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_DEFAULT, + .osd_switch_indicator2_channel = SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_DEFAULT, + .osd_switch_indicator3_name = SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_DEFAULT, + .osd_switch_indicator3_channel = SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_DEFAULT, + .osd_switch_indicators_align_left = SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_DEFAULT, + .system_msg_display_time = SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_DEFAULT, + .units = SETTING_OSD_UNITS_DEFAULT, + .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT, #ifdef USE_WIND_ESTIMATOR - .estimations_wind_compensation = SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT, + .estimations_wind_compensation = SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT, #endif - .coordinate_digits = SETTING_OSD_COORDINATE_DIGITS_DEFAULT, + .coordinate_digits = SETTING_OSD_COORDINATE_DIGITS_DEFAULT, - .osd_failsafe_switch_layout = SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_DEFAULT, + .osd_failsafe_switch_layout = SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_DEFAULT, - .plus_code_digits = SETTING_OSD_PLUS_CODE_DIGITS_DEFAULT, - .plus_code_short = SETTING_OSD_PLUS_CODE_SHORT_DEFAULT, + .plus_code_digits = SETTING_OSD_PLUS_CODE_DIGITS_DEFAULT, + .plus_code_short = SETTING_OSD_PLUS_CODE_SHORT_DEFAULT, - .ahi_width = SETTING_OSD_AHI_WIDTH_DEFAULT, - .ahi_height = SETTING_OSD_AHI_HEIGHT_DEFAULT, - .ahi_vertical_offset = SETTING_OSD_AHI_VERTICAL_OFFSET_DEFAULT, - .ahi_bordered = SETTING_OSD_AHI_BORDERED_DEFAULT, - .ahi_style = SETTING_OSD_AHI_STYLE_DEFAULT, + .ahi_width = SETTING_OSD_AHI_WIDTH_DEFAULT, + .ahi_height = SETTING_OSD_AHI_HEIGHT_DEFAULT, + .ahi_vertical_offset = SETTING_OSD_AHI_VERTICAL_OFFSET_DEFAULT, + .ahi_bordered = SETTING_OSD_AHI_BORDERED_DEFAULT, + .ahi_style = SETTING_OSD_AHI_STYLE_DEFAULT, - .force_grid = SETTING_OSD_FORCE_GRID_DEFAULT, + .force_grid = SETTING_OSD_FORCE_GRID_DEFAULT, - .stats_energy_unit = SETTING_OSD_STATS_ENERGY_UNIT_DEFAULT, - .stats_min_voltage_unit = SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_DEFAULT, - .stats_page_auto_swap_time = SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_DEFAULT + .stats_energy_unit = SETTING_OSD_STATS_ENERGY_UNIT_DEFAULT, + .stats_min_voltage_unit = SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_DEFAULT, + .stats_page_auto_swap_time = SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_DEFAULT ); void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) { - osdLayoutsConfig->item_pos[0][OSD_ALTITUDE] = OSD_POS(1, 0) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 0) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1); + osdLayoutsConfig->item_pos[0][OSD_ALTITUDE] = OSD_POS(1, 0) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 0) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1); - osdLayoutsConfig->item_pos[0][OSD_RSSI_VALUE] = OSD_POS(23, 0) | OSD_VISIBLE_FLAG; - //line 2 - osdLayoutsConfig->item_pos[0][OSD_HOME_DIST] = OSD_POS(1, 1); - osdLayoutsConfig->item_pos[0][OSD_TRIP_DIST] = OSD_POS(1, 2); - osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_CELL_VOLTAGE] = OSD_POS(12, 1); - osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1); - osdLayoutsConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1); - osdLayoutsConfig->item_pos[0][OSD_3D_SPEED] = OSD_POS(23, 1); - osdLayoutsConfig->item_pos[0][OSD_GLIDESLOPE] = OSD_POS(23, 2); + osdLayoutsConfig->item_pos[0][OSD_RSSI_VALUE] = OSD_POS(23, 0) | OSD_VISIBLE_FLAG; + //line 2 + osdLayoutsConfig->item_pos[0][OSD_HOME_DIST] = OSD_POS(1, 1); + osdLayoutsConfig->item_pos[0][OSD_TRIP_DIST] = OSD_POS(1, 2); + osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_CELL_VOLTAGE] = OSD_POS(12, 1); + osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1); + osdLayoutsConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1); + osdLayoutsConfig->item_pos[0][OSD_3D_SPEED] = OSD_POS(23, 1); + osdLayoutsConfig->item_pos[0][OSD_GLIDESLOPE] = OSD_POS(23, 2); - osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_SCALED_THROTTLE_POS] = OSD_POS(6, 2); - osdLayoutsConfig->item_pos[0][OSD_HEADING] = OSD_POS(12, 2); - osdLayoutsConfig->item_pos[0][OSD_GROUND_COURSE] = OSD_POS(12, 3); - osdLayoutsConfig->item_pos[0][OSD_COURSE_HOLD_ERROR] = OSD_POS(12, 2); - osdLayoutsConfig->item_pos[0][OSD_COURSE_HOLD_ADJUSTMENT] = OSD_POS(12, 2); - osdLayoutsConfig->item_pos[0][OSD_CROSS_TRACK_ERROR] = OSD_POS(12, 3); - osdLayoutsConfig->item_pos[0][OSD_HEADING_GRAPH] = OSD_POS(18, 2); - osdLayoutsConfig->item_pos[0][OSD_CURRENT_DRAW] = OSD_POS(2, 3) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_MAH_DRAWN] = OSD_POS(1, 4) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_WH_DRAWN] = OSD_POS(1, 5); - osdLayoutsConfig->item_pos[0][OSD_BATTERY_REMAINING_CAPACITY] = OSD_POS(1, 6); - osdLayoutsConfig->item_pos[0][OSD_BATTERY_REMAINING_PERCENT] = OSD_POS(1, 7); - osdLayoutsConfig->item_pos[0][OSD_POWER_SUPPLY_IMPEDANCE] = OSD_POS(1, 8); + osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_SCALED_THROTTLE_POS] = OSD_POS(6, 2); + osdLayoutsConfig->item_pos[0][OSD_HEADING] = OSD_POS(12, 2); + osdLayoutsConfig->item_pos[0][OSD_GROUND_COURSE] = OSD_POS(12, 3); + osdLayoutsConfig->item_pos[0][OSD_COURSE_HOLD_ERROR] = OSD_POS(12, 2); + osdLayoutsConfig->item_pos[0][OSD_COURSE_HOLD_ADJUSTMENT] = OSD_POS(12, 2); + osdLayoutsConfig->item_pos[0][OSD_CROSS_TRACK_ERROR] = OSD_POS(12, 3); + osdLayoutsConfig->item_pos[0][OSD_HEADING_GRAPH] = OSD_POS(18, 2); + osdLayoutsConfig->item_pos[0][OSD_CURRENT_DRAW] = OSD_POS(2, 3) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_MAH_DRAWN] = OSD_POS(1, 4) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_WH_DRAWN] = OSD_POS(1, 5); + osdLayoutsConfig->item_pos[0][OSD_BATTERY_REMAINING_CAPACITY] = OSD_POS(1, 6); + osdLayoutsConfig->item_pos[0][OSD_BATTERY_REMAINING_PERCENT] = OSD_POS(1, 7); + osdLayoutsConfig->item_pos[0][OSD_POWER_SUPPLY_IMPEDANCE] = OSD_POS(1, 8); - osdLayoutsConfig->item_pos[0][OSD_EFFICIENCY_MAH_PER_KM] = OSD_POS(1, 5); - osdLayoutsConfig->item_pos[0][OSD_EFFICIENCY_WH_PER_KM] = OSD_POS(1, 5); + osdLayoutsConfig->item_pos[0][OSD_EFFICIENCY_MAH_PER_KM] = OSD_POS(1, 5); + osdLayoutsConfig->item_pos[0][OSD_EFFICIENCY_WH_PER_KM] = OSD_POS(1, 5); - osdLayoutsConfig->item_pos[0][OSD_ATTITUDE_ROLL] = OSD_POS(1, 7); - osdLayoutsConfig->item_pos[0][OSD_ATTITUDE_PITCH] = OSD_POS(1, 8); + osdLayoutsConfig->item_pos[0][OSD_ATTITUDE_ROLL] = OSD_POS(1, 7); + osdLayoutsConfig->item_pos[0][OSD_ATTITUDE_PITCH] = OSD_POS(1, 8); - // avoid OSD_VARIO under OSD_CROSSHAIRS - osdLayoutsConfig->item_pos[0][OSD_VARIO] = OSD_POS(23, 5); - // OSD_VARIO_NUM at the right of OSD_VARIO - osdLayoutsConfig->item_pos[0][OSD_VARIO_NUM] = OSD_POS(24, 7); - osdLayoutsConfig->item_pos[0][OSD_HOME_DIR] = OSD_POS(14, 11); - osdLayoutsConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6); - osdLayoutsConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6); + // avoid OSD_VARIO under OSD_CROSSHAIRS + osdLayoutsConfig->item_pos[0][OSD_VARIO] = OSD_POS(23, 5); + // OSD_VARIO_NUM at the right of OSD_VARIO + osdLayoutsConfig->item_pos[0][OSD_VARIO_NUM] = OSD_POS(24, 7); + osdLayoutsConfig->item_pos[0][OSD_HOME_DIR] = OSD_POS(14, 11); + osdLayoutsConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6); + osdLayoutsConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6); - osdLayoutsConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2); - osdLayoutsConfig->item_pos[0][OSD_PILOT_NAME] = OSD_POS(20, 3); - osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6); + osdLayoutsConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2); + osdLayoutsConfig->item_pos[0][OSD_PILOT_NAME] = OSD_POS(20, 3); + osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6); #ifdef USE_SERIALRX_CRSF - osdLayoutsConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(23, 12); - osdLayoutsConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(23, 11); - osdLayoutsConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(24, 9); - osdLayoutsConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(24, 10); + osdLayoutsConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(23, 12); + osdLayoutsConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(23, 11); + osdLayoutsConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(24, 9); + osdLayoutsConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(24, 10); #endif - osdLayoutsConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8); - osdLayoutsConfig->item_pos[0][OSD_FLYTIME] = OSD_POS(23, 9); - osdLayoutsConfig->item_pos[0][OSD_ONTIME_FLYTIME] = OSD_POS(23, 11) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_RTC_TIME] = OSD_POS(23, 12); - osdLayoutsConfig->item_pos[0][OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH] = OSD_POS(23, 7); - osdLayoutsConfig->item_pos[0][OSD_REMAINING_DISTANCE_BEFORE_RTH] = OSD_POS(23, 6); + osdLayoutsConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8); + osdLayoutsConfig->item_pos[0][OSD_FLYTIME] = OSD_POS(23, 9); + osdLayoutsConfig->item_pos[0][OSD_ONTIME_FLYTIME] = OSD_POS(23, 11) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_RTC_TIME] = OSD_POS(23, 12); + osdLayoutsConfig->item_pos[0][OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH] = OSD_POS(23, 7); + osdLayoutsConfig->item_pos[0][OSD_REMAINING_DISTANCE_BEFORE_RTH] = OSD_POS(23, 6); - osdLayoutsConfig->item_pos[0][OSD_MISSION] = OSD_POS(0, 10); - osdLayoutsConfig->item_pos[0][OSD_GPS_SATS] = OSD_POS(0, 11) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_GPS_HDOP] = OSD_POS(0, 10); + osdLayoutsConfig->item_pos[0][OSD_MISSION] = OSD_POS(0, 10); + osdLayoutsConfig->item_pos[0][OSD_GPS_SATS] = OSD_POS(0, 11) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_GPS_HDOP] = OSD_POS(0, 10); - osdLayoutsConfig->item_pos[0][OSD_GPS_LAT] = OSD_POS(0, 12); - // Put this on top of the latitude, since it's very unlikely - // that users will want to use both at the same time. - osdLayoutsConfig->item_pos[0][OSD_PLUS_CODE] = OSD_POS(0, 12); - osdLayoutsConfig->item_pos[0][OSD_FLYMODE] = OSD_POS(13, 12) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_GPS_LON] = OSD_POS(18, 12); + osdLayoutsConfig->item_pos[0][OSD_GPS_LAT] = OSD_POS(0, 12); + // Put this on top of the latitude, since it's very unlikely + // that users will want to use both at the same time. + osdLayoutsConfig->item_pos[0][OSD_PLUS_CODE] = OSD_POS(0, 12); + osdLayoutsConfig->item_pos[0][OSD_FLYMODE] = OSD_POS(13, 12) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_GPS_LON] = OSD_POS(18, 12); - osdLayoutsConfig->item_pos[0][OSD_AZIMUTH] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_AZIMUTH] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_ROLL_PIDS] = OSD_POS(2, 10); - osdLayoutsConfig->item_pos[0][OSD_PITCH_PIDS] = OSD_POS(2, 11); - osdLayoutsConfig->item_pos[0][OSD_YAW_PIDS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_LEVEL_PIDS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_POS_XY_PIDS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_POS_Z_PIDS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_VEL_XY_PIDS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_VEL_Z_PIDS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_HEADING_P] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_BOARD_ALIGN_ROLL] = OSD_POS(2, 10); - osdLayoutsConfig->item_pos[0][OSD_BOARD_ALIGN_PITCH] = OSD_POS(2, 11); - osdLayoutsConfig->item_pos[0][OSD_RC_EXPO] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_RC_YAW_EXPO] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_THROTTLE_EXPO] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_PITCH_RATE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_ROLL_RATE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_YAW_RATE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MANUAL_RC_EXPO] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MANUAL_RC_YAW_EXPO] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MANUAL_PITCH_RATE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MANUAL_ROLL_RATE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MANUAL_YAW_RATE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_NAV_FW_CRUISE_THR] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_NAV_FW_PITCH2THR] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_FW_ALT_PID_OUTPUTS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_FW_POS_PID_OUTPUTS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MC_VEL_X_PID_OUTPUTS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MC_VEL_Y_PID_OUTPUTS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MC_VEL_Z_PID_OUTPUTS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MC_POS_XYZ_P_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_ROLL_PIDS] = OSD_POS(2, 10); + osdLayoutsConfig->item_pos[0][OSD_PITCH_PIDS] = OSD_POS(2, 11); + osdLayoutsConfig->item_pos[0][OSD_YAW_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_LEVEL_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_POS_XY_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_POS_Z_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_VEL_XY_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_VEL_Z_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_HEADING_P] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_BOARD_ALIGN_ROLL] = OSD_POS(2, 10); + osdLayoutsConfig->item_pos[0][OSD_BOARD_ALIGN_PITCH] = OSD_POS(2, 11); + osdLayoutsConfig->item_pos[0][OSD_RC_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_RC_YAW_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_THROTTLE_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_PITCH_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_ROLL_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_YAW_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_RC_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_RC_YAW_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_PITCH_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_ROLL_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_YAW_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_NAV_FW_CRUISE_THR] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_NAV_FW_PITCH2THR] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_FW_ALT_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_FW_POS_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MC_VEL_X_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MC_VEL_Y_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MC_VEL_Z_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MC_POS_XYZ_P_OUTPUTS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_POWER] = OSD_POS(15, 1); + osdLayoutsConfig->item_pos[0][OSD_POWER] = OSD_POS(15, 1); - osdLayoutsConfig->item_pos[0][OSD_IMU_TEMPERATURE] = OSD_POS(19, 2); - osdLayoutsConfig->item_pos[0][OSD_BARO_TEMPERATURE] = OSD_POS(19, 3); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_0_TEMPERATURE] = OSD_POS(19, 4); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_1_TEMPERATURE] = OSD_POS(19, 5); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_2_TEMPERATURE] = OSD_POS(19, 6); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_3_TEMPERATURE] = OSD_POS(19, 7); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_4_TEMPERATURE] = OSD_POS(19, 8); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_5_TEMPERATURE] = OSD_POS(19, 9); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_6_TEMPERATURE] = OSD_POS(19, 10); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_7_TEMPERATURE] = OSD_POS(19, 11); + osdLayoutsConfig->item_pos[0][OSD_IMU_TEMPERATURE] = OSD_POS(19, 2); + osdLayoutsConfig->item_pos[0][OSD_BARO_TEMPERATURE] = OSD_POS(19, 3); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_0_TEMPERATURE] = OSD_POS(19, 4); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_1_TEMPERATURE] = OSD_POS(19, 5); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_2_TEMPERATURE] = OSD_POS(19, 6); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_3_TEMPERATURE] = OSD_POS(19, 7); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_4_TEMPERATURE] = OSD_POS(19, 8); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_5_TEMPERATURE] = OSD_POS(19, 9); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_6_TEMPERATURE] = OSD_POS(19, 10); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_7_TEMPERATURE] = OSD_POS(19, 11); - osdLayoutsConfig->item_pos[0][OSD_AIR_SPEED] = OSD_POS(3, 5); - osdLayoutsConfig->item_pos[0][OSD_WIND_SPEED_HORIZONTAL] = OSD_POS(3, 6); - osdLayoutsConfig->item_pos[0][OSD_WIND_SPEED_VERTICAL] = OSD_POS(3, 7); + osdLayoutsConfig->item_pos[0][OSD_AIR_SPEED] = OSD_POS(3, 5); + osdLayoutsConfig->item_pos[0][OSD_WIND_SPEED_HORIZONTAL] = OSD_POS(3, 6); + osdLayoutsConfig->item_pos[0][OSD_WIND_SPEED_VERTICAL] = OSD_POS(3, 7); - osdLayoutsConfig->item_pos[0][OSD_GFORCE] = OSD_POS(12, 4); - osdLayoutsConfig->item_pos[0][OSD_GFORCE_X] = OSD_POS(12, 5); - osdLayoutsConfig->item_pos[0][OSD_GFORCE_Y] = OSD_POS(12, 6); - osdLayoutsConfig->item_pos[0][OSD_GFORCE_Z] = OSD_POS(12, 7); + osdLayoutsConfig->item_pos[0][OSD_GFORCE] = OSD_POS(12, 4); + osdLayoutsConfig->item_pos[0][OSD_GFORCE_X] = OSD_POS(12, 5); + osdLayoutsConfig->item_pos[0][OSD_GFORCE_Y] = OSD_POS(12, 6); + osdLayoutsConfig->item_pos[0][OSD_GFORCE_Z] = OSD_POS(12, 7); - osdLayoutsConfig->item_pos[0][OSD_VTX_POWER] = OSD_POS(3, 5); + osdLayoutsConfig->item_pos[0][OSD_VTX_POWER] = OSD_POS(3, 5); - osdLayoutsConfig->item_pos[0][OSD_GVAR_0] = OSD_POS(1, 1); - osdLayoutsConfig->item_pos[0][OSD_GVAR_1] = OSD_POS(1, 2); - osdLayoutsConfig->item_pos[0][OSD_GVAR_2] = OSD_POS(1, 3); - osdLayoutsConfig->item_pos[0][OSD_GVAR_3] = OSD_POS(1, 4); + osdLayoutsConfig->item_pos[0][OSD_GVAR_0] = OSD_POS(1, 1); + osdLayoutsConfig->item_pos[0][OSD_GVAR_1] = OSD_POS(1, 2); + osdLayoutsConfig->item_pos[0][OSD_GVAR_2] = OSD_POS(1, 3); + osdLayoutsConfig->item_pos[0][OSD_GVAR_3] = OSD_POS(1, 4); - osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_0] = OSD_POS(2, 7); - osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_1] = OSD_POS(2, 8); - osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_2] = OSD_POS(2, 9); - osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_3] = OSD_POS(2, 10); + osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_0] = OSD_POS(2, 7); + osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_1] = OSD_POS(2, 8); + osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_2] = OSD_POS(2, 9); + osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_3] = OSD_POS(2, 10); #if defined(USE_ESC_SENSOR) - osdLayoutsConfig->item_pos[0][OSD_ESC_RPM] = OSD_POS(1, 2); - osdLayoutsConfig->item_pos[0][OSD_ESC_TEMPERATURE] = OSD_POS(1, 3); + osdLayoutsConfig->item_pos[0][OSD_ESC_RPM] = OSD_POS(1, 2); + osdLayoutsConfig->item_pos[0][OSD_ESC_TEMPERATURE] = OSD_POS(1, 3); #endif #if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE) - osdLayoutsConfig->item_pos[0][OSD_RC_SOURCE] = OSD_POS(3, 4); + osdLayoutsConfig->item_pos[0][OSD_RC_SOURCE] = OSD_POS(3, 4); #endif #ifdef USE_POWER_LIMITS - osdLayoutsConfig->item_pos[0][OSD_PLIMIT_REMAINING_BURST_TIME] = OSD_POS(3, 4); - osdLayoutsConfig->item_pos[0][OSD_PLIMIT_ACTIVE_CURRENT_LIMIT] = OSD_POS(3, 5); - osdLayoutsConfig->item_pos[0][OSD_PLIMIT_ACTIVE_POWER_LIMIT] = OSD_POS(3, 6); + osdLayoutsConfig->item_pos[0][OSD_PLIMIT_REMAINING_BURST_TIME] = OSD_POS(3, 4); + osdLayoutsConfig->item_pos[0][OSD_PLIMIT_ACTIVE_CURRENT_LIMIT] = OSD_POS(3, 5); + osdLayoutsConfig->item_pos[0][OSD_PLIMIT_ACTIVE_POWER_LIMIT] = OSD_POS(3, 6); #endif - // Under OSD_FLYMODE. TODO: Might not be visible on NTSC? - osdLayoutsConfig->item_pos[0][OSD_MESSAGES] = OSD_POS(1, 13) | OSD_VISIBLE_FLAG; + // Under OSD_FLYMODE. TODO: Might not be visible on NTSC? + osdLayoutsConfig->item_pos[0][OSD_MESSAGES] = OSD_POS(1, 13) | OSD_VISIBLE_FLAG; - for (unsigned ii = 1; ii < OSD_LAYOUT_COUNT; ii++) { - for (unsigned jj = 0; jj < ARRAYLEN(osdLayoutsConfig->item_pos[0]); jj++) { - osdLayoutsConfig->item_pos[ii][jj] = osdLayoutsConfig->item_pos[0][jj] & ~OSD_VISIBLE_FLAG; - } - } + for (unsigned ii = 1; ii < OSD_LAYOUT_COUNT; ii++) { + for (unsigned jj = 0; jj < ARRAYLEN(osdLayoutsConfig->item_pos[0]); jj++) { + osdLayoutsConfig->item_pos[ii][jj] = osdLayoutsConfig->item_pos[0][jj] & ~OSD_VISIBLE_FLAG; + } + } } static void osdSetNextRefreshIn(uint32_t timeMs) { - resumeRefreshAt = micros() + timeMs * 1000; - refreshWaitForResumeCmdRelease = true; + resumeRefreshAt = micros() + timeMs * 1000; + refreshWaitForResumeCmdRelease = true; } static void osdCompleteAsyncInitialization(void) { - if (!displayIsReady(osdDisplayPort)) { - // Update the display. - // XXX: Rename displayDrawScreen() and associated functions - // to displayUpdate() - displayDrawScreen(osdDisplayPort); - return; - } + if (!displayIsReady(osdDisplayPort)) { + // Update the display. + // XXX: Rename displayDrawScreen() and associated functions + // to displayUpdate() + displayDrawScreen(osdDisplayPort); + return; + } - osdDisplayIsReady = true; + osdDisplayIsReady = true; #if defined(USE_CANVAS) - if (osdConfig()->force_grid) { - osdDisplayHasCanvas = false; - } else { - osdDisplayHasCanvas = displayGetCanvas(&osdCanvas, osdDisplayPort); - } + if (osdConfig()->force_grid) { + osdDisplayHasCanvas = false; + } else { + osdDisplayHasCanvas = displayGetCanvas(&osdCanvas, osdDisplayPort); + } #endif - displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); - displayClearScreen(osdDisplayPort); + displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); + displayClearScreen(osdDisplayPort); - uint8_t y = 1; - displayFontMetadata_t metadata; - bool fontHasMetadata = displayGetFontMetadata(&metadata, osdDisplayPort); - LOG_DEBUG(OSD, "Font metadata version %s: %u (%u chars)", - fontHasMetadata ? "Y" : "N", metadata.version, metadata.charCount); + uint8_t y = 1; + displayFontMetadata_t metadata; + bool fontHasMetadata = displayGetFontMetadata(&metadata, osdDisplayPort); + LOG_DEBUG(OSD, "Font metadata version %s: %u (%u chars)", + fontHasMetadata ? "Y" : "N", metadata.version, metadata.charCount); - if (fontHasMetadata && metadata.charCount > 256) { - hasExtendedFont = true; - unsigned logo_c = SYM_LOGO_START; - unsigned logo_x = OSD_CENTER_LEN(SYM_LOGO_WIDTH); - for (unsigned ii = 0; ii < SYM_LOGO_HEIGHT; ii++) { - for (unsigned jj = 0; jj < SYM_LOGO_WIDTH; jj++) { - displayWriteChar(osdDisplayPort, logo_x + jj, y, logo_c++); - } - y++; - } - y++; - } else if (!fontHasMetadata) { - const char *m = "INVALID FONT"; - displayWrite(osdDisplayPort, OSD_CENTER_S(m), 3, m); - y = 4; - } + if (fontHasMetadata && metadata.charCount > 256) { + hasExtendedFont = true; + unsigned logo_c = SYM_LOGO_START; + unsigned logo_x = OSD_CENTER_LEN(SYM_LOGO_WIDTH); + for (unsigned ii = 0; ii < SYM_LOGO_HEIGHT; ii++) { + for (unsigned jj = 0; jj < SYM_LOGO_WIDTH; jj++) { + displayWriteChar(osdDisplayPort, logo_x + jj, y, logo_c++); + } + y++; + } + y++; + } else if (!fontHasMetadata) { + const char *m = "INVALID FONT"; + displayWrite(osdDisplayPort, OSD_CENTER_S(m), 3, m); + y = 4; + } - if (fontHasMetadata && metadata.version < OSD_MIN_FONT_VERSION) { - const char *m = "INVALID FONT VERSION"; - displayWrite(osdDisplayPort, OSD_CENTER_S(m), y++, m); - } + if (fontHasMetadata && metadata.version < OSD_MIN_FONT_VERSION) { + const char *m = "INVALID FONT VERSION"; + displayWrite(osdDisplayPort, OSD_CENTER_S(m), y++, m); + } - char string_buffer[30]; - tfp_sprintf(string_buffer, "INAV VERSION: %s", FC_VERSION_STRING); - uint8_t xPos = osdDisplayIsHD() ? 15 : 5; - displayWrite(osdDisplayPort, xPos, y++, string_buffer); + char string_buffer[30]; + tfp_sprintf(string_buffer, "INAV VERSION: %s", FC_VERSION_STRING); + uint8_t xPos = osdDisplayIsHD() ? 15 : 5; + displayWrite(osdDisplayPort, xPos, y++, string_buffer); #ifdef USE_CMS - displayWrite(osdDisplayPort, xPos+2, y++, CMS_STARTUP_HELP_TEXT1); - displayWrite(osdDisplayPort, xPos+6, y++, CMS_STARTUP_HELP_TEXT2); - displayWrite(osdDisplayPort, xPos+6, y++, CMS_STARTUP_HELP_TEXT3); + displayWrite(osdDisplayPort, xPos+2, y++, CMS_STARTUP_HELP_TEXT1); + displayWrite(osdDisplayPort, xPos+6, y++, CMS_STARTUP_HELP_TEXT2); + displayWrite(osdDisplayPort, xPos+6, y++, CMS_STARTUP_HELP_TEXT3); #endif #ifdef USE_STATS - uint8_t statNameX = osdDisplayIsHD() ? 14 : 4; - uint8_t statValueX = osdDisplayIsHD() ? 34 : 24; + uint8_t statNameX = osdDisplayIsHD() ? 14 : 4; + uint8_t statValueX = osdDisplayIsHD() ? 34 : 24; - if (statsConfig()->stats_enabled) { - displayWrite(osdDisplayPort, statNameX, ++y, "ODOMETER:"); - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_MILE)); - string_buffer[5] = SYM_MI; - break; - default: - case OSD_UNIT_GA: - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_NAUTICALMILE)); - string_buffer[5] = SYM_NM; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_KILOMETER)); - string_buffer[5] = SYM_KM; - break; - } - string_buffer[6] = '\0'; - displayWrite(osdDisplayPort, statValueX-5, y, string_buffer); + if (statsConfig()->stats_enabled) { + displayWrite(osdDisplayPort, statNameX, ++y, "ODOMETER:"); + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_MILE)); + string_buffer[5] = SYM_MI; + break; + default: + case OSD_UNIT_GA: + tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_NAUTICALMILE)); + string_buffer[5] = SYM_NM; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_KILOMETER)); + string_buffer[5] = SYM_KM; + break; + } + string_buffer[6] = '\0'; + displayWrite(osdDisplayPort, statValueX-5, y, string_buffer); - displayWrite(osdDisplayPort, statNameX, ++y, "TOTAL TIME:"); - uint32_t tot_mins = statsConfig()->stats_total_time / 60; - tfp_sprintf(string_buffer, "%2d:%02dHM", (int)(tot_mins / 60), (int)(tot_mins % 60)); - displayWrite(osdDisplayPort, statValueX-5, y, string_buffer); + displayWrite(osdDisplayPort, statNameX, ++y, "TOTAL TIME:"); + uint32_t tot_mins = statsConfig()->stats_total_time / 60; + tfp_sprintf(string_buffer, "%2d:%02dHM", (int)(tot_mins / 60), (int)(tot_mins % 60)); + displayWrite(osdDisplayPort, statValueX-5, y, string_buffer); #ifdef USE_ADC - if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) { - displayWrite(osdDisplayPort, statNameX, ++y, "TOTAL ENERGY:"); - osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4); - strcat(string_buffer, "\xAB"); // SYM_WH - displayWrite(osdDisplayPort, statValueX-4, y, string_buffer); + if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) { + displayWrite(osdDisplayPort, statNameX, ++y, "TOTAL ENERGY:"); + osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4); + strcat(string_buffer, "\xAB"); // SYM_WH + displayWrite(osdDisplayPort, statValueX-4, y, string_buffer); - displayWrite(osdDisplayPort, statNameX, ++y, "AVG EFFICIENCY:"); - if (statsConfig()->stats_total_dist) { - uint32_t avg_efficiency = statsConfig()->stats_total_energy / (statsConfig()->stats_total_dist / METERS_PER_KILOMETER); // mWh/km - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); - string_buffer[3] = SYM_WH_MI; - break; - case OSD_UNIT_GA: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); - string_buffer[3] = SYM_WH_NM; - break; - default: - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3); - string_buffer[3] = SYM_WH_KM; - break; - } - } else { - string_buffer[0] = string_buffer[1] = string_buffer[2] = '-'; - } - string_buffer[4] = '\0'; - displayWrite(osdDisplayPort, statValueX-3, y, string_buffer); - } + displayWrite(osdDisplayPort, statNameX, ++y, "AVG EFFICIENCY:"); + if (statsConfig()->stats_total_dist) { + uint32_t avg_efficiency = statsConfig()->stats_total_energy / (statsConfig()->stats_total_dist / METERS_PER_KILOMETER); // mWh/km + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); + string_buffer[3] = SYM_WH_MI; + break; + case OSD_UNIT_GA: + osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); + string_buffer[3] = SYM_WH_NM; + break; + default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3); + string_buffer[3] = SYM_WH_KM; + break; + } + } else { + string_buffer[0] = string_buffer[1] = string_buffer[2] = '-'; + } + string_buffer[4] = '\0'; + displayWrite(osdDisplayPort, statValueX-3, y, string_buffer); + } #endif // USE_ADC - } + } #endif - displayCommitTransaction(osdDisplayPort); - displayResync(osdDisplayPort); - osdSetNextRefreshIn(SPLASH_SCREEN_DISPLAY_TIME); + displayCommitTransaction(osdDisplayPort); + displayResync(osdDisplayPort); + osdSetNextRefreshIn(SPLASH_SCREEN_DISPLAY_TIME); } void osdInit(displayPort_t *osdDisplayPortToUse) { - if (!osdDisplayPortToUse) - return; + if (!osdDisplayPortToUse) + return; - BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(63,63)); + BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(63,63)); - osdDisplayPort = osdDisplayPortToUse; + osdDisplayPort = osdDisplayPortToUse; #ifdef USE_CMS - cmsDisplayPortRegister(osdDisplayPort); + cmsDisplayPortRegister(osdDisplayPort); #endif - armState = ARMING_FLAG(ARMED); - osdCompleteAsyncInitialization(); + armState = ARMING_FLAG(ARMED); + osdCompleteAsyncInitialization(); } static void osdResetStats(void) { - stats.max_current = 0; - stats.max_power = 0; - stats.max_speed = 0; - stats.max_3D_speed = 0; - stats.max_air_speed = 0; - stats.min_voltage = 5000; - stats.min_rssi = 99; - stats.min_lq = 300; - stats.min_rssi_dbm = 0; - stats.max_altitude = 0; + stats.max_current = 0; + stats.max_power = 0; + stats.max_speed = 0; + stats.max_3D_speed = 0; + stats.max_air_speed = 0; + stats.min_voltage = 5000; + stats.min_rssi = 99; + stats.min_lq = 300; + stats.min_rssi_dbm = 0; + stats.max_altitude = 0; } static void osdUpdateStats(void) { - int32_t value; + int32_t value; - if (feature(FEATURE_GPS)) { - value = osdGet3DSpeed(); - const float airspeed_estimate = getAirspeedEstimate(); + if (feature(FEATURE_GPS)) { + value = osdGet3DSpeed(); + const float airspeed_estimate = getAirspeedEstimate(); - if (stats.max_3D_speed < value) - stats.max_3D_speed = value; + if (stats.max_3D_speed < value) + stats.max_3D_speed = value; - if (stats.max_speed < gpsSol.groundSpeed) - stats.max_speed = gpsSol.groundSpeed; + if (stats.max_speed < gpsSol.groundSpeed) + stats.max_speed = gpsSol.groundSpeed; - if (stats.max_air_speed < airspeed_estimate) - stats.max_air_speed = airspeed_estimate; + if (stats.max_air_speed < airspeed_estimate) + stats.max_air_speed = airspeed_estimate; - if (stats.max_distance < GPS_distanceToHome) - stats.max_distance = GPS_distanceToHome; - } + if (stats.max_distance < GPS_distanceToHome) + stats.max_distance = GPS_distanceToHome; + } - value = getBatteryVoltage(); - if (stats.min_voltage > value) - stats.min_voltage = value; + value = getBatteryVoltage(); + if (stats.min_voltage > value) + stats.min_voltage = value; - value = abs(getAmperage()); - if (stats.max_current < value) - stats.max_current = value; + value = abs(getAmperage()); + if (stats.max_current < value) + stats.max_current = value; - value = labs(getPower()); - if (stats.max_power < value) - stats.max_power = value; + value = labs(getPower()); + if (stats.max_power < value) + stats.max_power = value; - value = osdConvertRSSI(); - if (stats.min_rssi > value) - stats.min_rssi = value; + value = osdConvertRSSI(); + if (stats.min_rssi > value) + stats.min_rssi = value; - value = osdGetCrsfLQ(); - if (stats.min_lq > value) - stats.min_lq = value; + value = osdGetCrsfLQ(); + if (stats.min_lq > value) + stats.min_lq = value; - if (!failsafeIsReceivingRxData()) - stats.min_lq = 0; + if (!failsafeIsReceivingRxData()) + stats.min_lq = 0; - value = osdGetCrsfdBm(); - if (stats.min_rssi_dbm > value) - stats.min_rssi_dbm = value; + value = osdGetCrsfdBm(); + if (stats.min_rssi_dbm > value) + stats.min_rssi_dbm = value; - stats.max_altitude = MAX(stats.max_altitude, osdGetAltitude()); + stats.max_altitude = MAX(stats.max_altitude, osdGetAltitude()); } static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) { - const char * disarmReasonStr[DISARM_REASON_COUNT] = { "UNKNOWN", "TIMEOUT", "STICKS", "SWITCH", "SWITCH", "KILLSW", "FAILSAFE", "NAV SYS", "LANDING"}; - uint8_t top = 1; // Start one line down leaving space at the top of the screen. - size_t multiValueLengthOffset = 0; + const char * disarmReasonStr[DISARM_REASON_COUNT] = { "UNKNOWN", "TIMEOUT", "STICKS", "SWITCH", "SWITCH", "KILLSW", "FAILSAFE", "NAV SYS", "LANDING"}; + uint8_t top = 1; // Start one line down leaving space at the top of the screen. + size_t multiValueLengthOffset = 0; - const uint8_t statNameX = osdDisplayIsHD() ? 11 : 1; - const uint8_t statValuesX = osdDisplayIsHD() ? 30 : 20; - char buff[10]; + const uint8_t statNameX = osdDisplayIsHD() ? 11 : 1; + const uint8_t statValuesX = osdDisplayIsHD() ? 30 : 20; + char buff[10]; - if (page > 1) - page = 0; + if (page > 1) + page = 0; - displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); - displayClearScreen(osdDisplayPort); + displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); + displayClearScreen(osdDisplayPort); - if (isSinglePageStatsCompatible) { - displayWrite(osdDisplayPort, statNameX, top++, "--- STATS ---"); - } else if (page == 0) { - displayWrite(osdDisplayPort, statNameX, top++, "--- STATS --- 1/2 ->"); - } else if (page == 1) { - displayWrite(osdDisplayPort, statNameX, top++, "--- STATS --- <- 2/2"); - } + if (isSinglePageStatsCompatible) { + displayWrite(osdDisplayPort, statNameX, top++, "--- STATS ---"); + } else if (page == 0) { + displayWrite(osdDisplayPort, statNameX, top++, "--- STATS --- 1/2 ->"); + } else if (page == 1) { + displayWrite(osdDisplayPort, statNameX, top++, "--- STATS --- <- 2/2"); + } - if (isSinglePageStatsCompatible || page == 0) { - if (feature(FEATURE_GPS)) { - if (isSinglePageStatsCompatible) { - displayWrite(osdDisplayPort, statNameX, top, "MAX/AVG SPEED :"); - osdFormatVelocityStr(buff, stats.max_3D_speed, true, false); - osdLeftAlignString(buff); - strcat(osdFormatTrimWhiteSpace(buff),"/"); - multiValueLengthOffset = strlen(buff); - displayWrite(osdDisplayPort, statValuesX, top, buff); - osdGenerateAverageVelocityStr(buff); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); - } else { - displayWrite(osdDisplayPort, statNameX, top, "MAX SPEED :"); - osdFormatVelocityStr(buff, stats.max_3D_speed, true, false); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + if (isSinglePageStatsCompatible || page == 0) { + if (feature(FEATURE_GPS)) { + if (isSinglePageStatsCompatible) { + displayWrite(osdDisplayPort, statNameX, top, "MAX/AVG SPEED :"); + osdFormatVelocityStr(buff, stats.max_3D_speed, true, false); + osdLeftAlignString(buff); + strcat(osdFormatTrimWhiteSpace(buff),"/"); + multiValueLengthOffset = strlen(buff); + displayWrite(osdDisplayPort, statValuesX, top, buff); + osdGenerateAverageVelocityStr(buff); + osdLeftAlignString(buff); + displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); + } else { + displayWrite(osdDisplayPort, statNameX, top, "MAX SPEED :"); + osdFormatVelocityStr(buff, stats.max_3D_speed, true, false); + osdLeftAlignString(buff); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - displayWrite(osdDisplayPort, statNameX, top, "AVG SPEED :"); - osdGenerateAverageVelocityStr(buff); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } + displayWrite(osdDisplayPort, statNameX, top, "AVG SPEED :"); + osdGenerateAverageVelocityStr(buff); + osdLeftAlignString(buff); + displayWrite(osdDisplayPort, statValuesX, top++, buff); + } - displayWrite(osdDisplayPort, statNameX, top, "MAX DISTANCE :"); - osdFormatDistanceStr(buff, stats.max_distance*100); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, statNameX, top, "MAX DISTANCE :"); + osdFormatDistanceStr(buff, stats.max_distance*100); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - displayWrite(osdDisplayPort, statNameX, top, "TRAVELED DISTANCE:"); - osdFormatDistanceStr(buff, getTotalTravelDistance()); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } + displayWrite(osdDisplayPort, statNameX, top, "TRAVELED DISTANCE:"); + osdFormatDistanceStr(buff, getTotalTravelDistance()); + displayWrite(osdDisplayPort, statValuesX, top++, buff); + } - displayWrite(osdDisplayPort, statNameX, top, "MAX ALTITUDE :"); - osdFormatAltitudeStr(buff, stats.max_altitude); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, statNameX, top, "MAX ALTITUDE :"); + osdFormatAltitudeStr(buff, stats.max_altitude); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - switch (rxConfig()->serialrx_provider) { - case SERIALRX_CRSF: - if (isSinglePageStatsCompatible) { - displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI %/DBM :"); - itoa(stats.min_rssi, buff, 10); - osdLeftAlignString(buff); - strcat(osdFormatTrimWhiteSpace(buff), "%/"); - multiValueLengthOffset = strlen(buff); - displayWrite(osdDisplayPort, statValuesX, top, buff); - itoa(stats.min_rssi_dbm, buff, 10); - tfp_sprintf(buff, "%s%c", buff, SYM_DBM); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); - } else { - displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI % :"); - itoa(stats.min_rssi, buff, 10); - strcat(buff, "%"); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + switch (rxConfig()->serialrx_provider) { + case SERIALRX_CRSF: + if (isSinglePageStatsCompatible) { + displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI %/DBM :"); + itoa(stats.min_rssi, buff, 10); + osdLeftAlignString(buff); + strcat(osdFormatTrimWhiteSpace(buff), "%/"); + multiValueLengthOffset = strlen(buff); + displayWrite(osdDisplayPort, statValuesX, top, buff); + itoa(stats.min_rssi_dbm, buff, 10); + tfp_sprintf(buff, "%s%c", buff, SYM_DBM); + osdLeftAlignString(buff); + displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); + } else { + displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI % :"); + itoa(stats.min_rssi, buff, 10); + strcat(buff, "%"); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI DBM :"); - itoa(stats.min_rssi_dbm, buff, 10); - tfp_sprintf(buff, "%s%c", buff, SYM_DBM); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } + displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI DBM :"); + itoa(stats.min_rssi_dbm, buff, 10); + tfp_sprintf(buff, "%s%c", buff, SYM_DBM); + displayWrite(osdDisplayPort, statValuesX, top++, buff); + } - displayWrite(osdDisplayPort, statNameX, top, "MIN LQ :"); - itoa(stats.min_lq, buff, 10); - strcat(buff, "%"); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - break; - default: - displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI :"); - itoa(stats.min_rssi, buff, 10); - strcat(buff, "%"); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } + displayWrite(osdDisplayPort, statNameX, top, "MIN LQ :"); + itoa(stats.min_lq, buff, 10); + strcat(buff, "%"); + displayWrite(osdDisplayPort, statValuesX, top++, buff); + break; + default: + displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI :"); + itoa(stats.min_rssi, buff, 10); + strcat(buff, "%"); + displayWrite(osdDisplayPort, statValuesX, top++, buff); + } - displayWrite(osdDisplayPort, statNameX, top, "FLY TIME :"); - uint16_t flySeconds = getFlightTime(); - uint16_t flyMinutes = flySeconds / 60; - flySeconds %= 60; - uint16_t flyHours = flyMinutes / 60; - flyMinutes %= 60; - tfp_sprintf(buff, "%02u:%02u:%02u", flyHours, flyMinutes, flySeconds); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, statNameX, top, "FLY TIME :"); + uint16_t flySeconds = getFlightTime(); + uint16_t flyMinutes = flySeconds / 60; + flySeconds %= 60; + uint16_t flyHours = flyMinutes / 60; + flyMinutes %= 60; + tfp_sprintf(buff, "%02u:%02u:%02u", flyHours, flyMinutes, flySeconds); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - displayWrite(osdDisplayPort, statNameX, top, "DISARMED BY :"); - displayWrite(osdDisplayPort, statValuesX, top++, disarmReasonStr[getDisarmReason()]); - } - - if (isSinglePageStatsCompatible || page == 1) { - if (osdConfig()->stats_min_voltage_unit == OSD_STATS_MIN_VOLTAGE_UNIT_BATTERY) { - displayWrite(osdDisplayPort, statNameX, top, "MIN BATTERY VOLT :"); - osdFormatCentiNumber(buff, stats.min_voltage, 0, osdConfig()->main_voltage_decimals, 0, osdConfig()->main_voltage_decimals + 2); - } else { - displayWrite(osdDisplayPort, statNameX, top, "MIN CELL VOLTAGE :"); - osdFormatCentiNumber(buff, stats.min_voltage/getBatteryCellCount(), 0, 2, 0, 3); - } - tfp_sprintf(buff, "%s%c", buff, SYM_VOLT); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, statNameX, top, "DISARMED BY :"); + displayWrite(osdDisplayPort, statValuesX, top++, disarmReasonStr[getDisarmReason()]); + } + + if (isSinglePageStatsCompatible || page == 1) { + if (osdConfig()->stats_min_voltage_unit == OSD_STATS_MIN_VOLTAGE_UNIT_BATTERY) { + displayWrite(osdDisplayPort, statNameX, top, "MIN BATTERY VOLT :"); + osdFormatCentiNumber(buff, stats.min_voltage, 0, osdConfig()->main_voltage_decimals, 0, osdConfig()->main_voltage_decimals + 2); + } else { + displayWrite(osdDisplayPort, statNameX, top, "MIN CELL VOLTAGE :"); + osdFormatCentiNumber(buff, stats.min_voltage/getBatteryCellCount(), 0, 2, 0, 3); + } + tfp_sprintf(buff, "%s%c", buff, SYM_VOLT); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - if (feature(FEATURE_CURRENT_METER)) { - displayWrite(osdDisplayPort, statNameX, top, "MAX CURRENT :"); - osdFormatCentiNumber(buff, stats.max_current, 0, 2, 0, 3); - tfp_sprintf(buff, "%s%c", buff, SYM_AMP); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + if (feature(FEATURE_CURRENT_METER)) { + displayWrite(osdDisplayPort, statNameX, top, "MAX CURRENT :"); + osdFormatCentiNumber(buff, stats.max_current, 0, 2, 0, 3); + tfp_sprintf(buff, "%s%c", buff, SYM_AMP); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - displayWrite(osdDisplayPort, statNameX, top, "MAX POWER :"); - bool kiloWatt = osdFormatCentiNumber(buff, stats.max_power, 1000, 2, 2, 3); - buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; - buff[4] = '\0'; - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, statNameX, top, "MAX POWER :"); + bool kiloWatt = osdFormatCentiNumber(buff, stats.max_power, 1000, 2, 2, 3); + buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; + buff[4] = '\0'; + displayWrite(osdDisplayPort, statValuesX, top++, buff); - displayWrite(osdDisplayPort, statNameX, top, "USED CAPACITY :"); - if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - tfp_sprintf(buff, "%d%c", (int)getMAhDrawn(), SYM_MAH); - } else { - osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3); - tfp_sprintf(buff, "%s%c", buff, SYM_WH); - } - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, statNameX, top, "USED CAPACITY :"); + if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { + tfp_sprintf(buff, "%d%c", (int)getMAhDrawn(), SYM_MAH); + } else { + osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3); + tfp_sprintf(buff, "%s%c", buff, SYM_WH); + } + displayWrite(osdDisplayPort, statValuesX, top++, buff); - int32_t totalDistance = getTotalTravelDistance(); - bool moreThanAh = false; - bool efficiencyValid = totalDistance >= 10000; - if (feature(FEATURE_GPS)) { - displayWrite(osdDisplayPort, statNameX, top, "AVG EFFICIENCY :"); - uint8_t digits = 3U; // Total number of digits (including decimal point) - #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values - if (isBfCompatibleVideoSystem(osdConfig())) { - // Add one digit so no switch to scaled decimal occurs above 99 - digits = 4U; - } - #endif - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_MILE / totalDistance), 1000, 0, 2, digits); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_MI); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_MAH_MI_0; - buff[4] = SYM_MAH_MI_1; - buff[5] = '\0'; - } - } else { - osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits); - tfp_sprintf(buff, "%s%c", buff, SYM_WH_MI); - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - } - } - break; - case OSD_UNIT_GA: - if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_NAUTICALMILE / totalDistance), 1000, 0, 2, digits); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_MAH_NM_0; - buff[4] = SYM_MAH_NM_1; - buff[5] = '\0'; - } - } else { - osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_NAUTICALMILE / totalDistance), 0, 2, 0, digits); - tfp_sprintf(buff, "%s%c", buff, SYM_WH_NM); - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - } - } - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000000.0f / totalDistance), 1000, 0, 2, digits); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_KM); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_MAH_KM_0; - buff[4] = SYM_MAH_KM_1; - buff[5] = '\0'; - } - } else { - osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10000.0f / totalDistance), 0, 2, 0, digits); - tfp_sprintf(buff, "%s%c", buff, SYM_WH_KM); - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - } - } - break; - } - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } - } + int32_t totalDistance = getTotalTravelDistance(); + bool moreThanAh = false; + bool efficiencyValid = totalDistance >= 10000; + if (feature(FEATURE_GPS)) { + displayWrite(osdDisplayPort, statNameX, top, "AVG EFFICIENCY :"); + uint8_t digits = 3U; // Total number of digits (including decimal point) + #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values + if (isBfCompatibleVideoSystem(osdConfig())) { + // Add one digit so no switch to scaled decimal occurs above 99 + digits = 4U; + } + #endif + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { + moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_MILE / totalDistance), 1000, 0, 2, digits); + if (!moreThanAh) { + tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); + } else { + tfp_sprintf(buff, "%s%c", buff, SYM_AH_MI); + } + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + buff[3] = SYM_MAH_MI_0; + buff[4] = SYM_MAH_MI_1; + buff[5] = '\0'; + } + } else { + osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits); + tfp_sprintf(buff, "%s%c", buff, SYM_WH_MI); + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + } + } + break; + case OSD_UNIT_GA: + if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { + moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_NAUTICALMILE / totalDistance), 1000, 0, 2, digits); + if (!moreThanAh) { + tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); + } else { + tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM); + } + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + buff[3] = SYM_MAH_NM_0; + buff[4] = SYM_MAH_NM_1; + buff[5] = '\0'; + } + } else { + osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_NAUTICALMILE / totalDistance), 0, 2, 0, digits); + tfp_sprintf(buff, "%s%c", buff, SYM_WH_NM); + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + } + } + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { + moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000000.0f / totalDistance), 1000, 0, 2, digits); + if (!moreThanAh) { + tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); + } else { + tfp_sprintf(buff, "%s%c", buff, SYM_AH_KM); + } + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + buff[3] = SYM_MAH_KM_0; + buff[4] = SYM_MAH_KM_1; + buff[5] = '\0'; + } + } else { + osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10000.0f / totalDistance), 0, 2, 0, digits); + tfp_sprintf(buff, "%s%c", buff, SYM_WH_KM); + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + } + } + break; + } + osdLeftAlignString(buff); + displayWrite(osdDisplayPort, statValuesX, top++, buff); + } + } - const float max_gforce = accGetMeasuredMaxG(); - displayWrite(osdDisplayPort, statNameX, top, "MAX G-FORCE :"); - osdFormatCentiNumber(buff, max_gforce * 100, 0, 2, 0, 3); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + const float max_gforce = accGetMeasuredMaxG(); + displayWrite(osdDisplayPort, statNameX, top, "MAX G-FORCE :"); + osdFormatCentiNumber(buff, max_gforce * 100, 0, 2, 0, 3); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - const acc_extremes_t *acc_extremes = accGetMeasuredExtremes(); - const float acc_extremes_min = acc_extremes[Z].min; - const float acc_extremes_max = acc_extremes[Z].max; - displayWrite(osdDisplayPort, statNameX, top, "MIN/MAX Z G-FORCE:"); - osdFormatCentiNumber(buff, acc_extremes_min * 100, 0, 2, 0, 4); - osdLeftAlignString(buff); - strcat(osdFormatTrimWhiteSpace(buff),"/"); - multiValueLengthOffset = strlen(buff); - displayWrite(osdDisplayPort, statValuesX, top, buff); - osdFormatCentiNumber(buff, acc_extremes_max * 100, 0, 2, 0, 3); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); - } + const acc_extremes_t *acc_extremes = accGetMeasuredExtremes(); + const float acc_extremes_min = acc_extremes[Z].min; + const float acc_extremes_max = acc_extremes[Z].max; + displayWrite(osdDisplayPort, statNameX, top, "MIN/MAX Z G-FORCE:"); + osdFormatCentiNumber(buff, acc_extremes_min * 100, 0, 2, 0, 4); + osdLeftAlignString(buff); + strcat(osdFormatTrimWhiteSpace(buff),"/"); + multiValueLengthOffset = strlen(buff); + displayWrite(osdDisplayPort, statValuesX, top, buff); + osdFormatCentiNumber(buff, acc_extremes_max * 100, 0, 2, 0, 3); + osdLeftAlignString(buff); + displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); + } - if (savingSettings == true) { - displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS)); - } else if (notify_settings_saved > 0) { - if (millis() > notify_settings_saved) { - notify_settings_saved = 0; - } else { - displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(OSD_MSG_SETTINGS_SAVED)); - } - } + if (savingSettings == true) { + displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS)); + } else if (notify_settings_saved > 0) { + if (millis() > notify_settings_saved) { + notify_settings_saved = 0; + } else { + displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(OSD_MSG_SETTINGS_SAVED)); + } + } - displayCommitTransaction(osdDisplayPort); + displayCommitTransaction(osdDisplayPort); } // HD arming screen. based on the minimum HD OSD grid size of 50 x 18 static void osdShowHDArmScreen(void) { - dateTime_t dt; - char buf[MAX(32, FORMATTED_DATE_TIME_BUFSIZE)]; - char craftNameBuf[MAX_NAME_LENGTH]; - char versionBuf[30]; - char *date; - char *time; + dateTime_t dt; + char buf[MAX(32, FORMATTED_DATE_TIME_BUFSIZE)]; + char craftNameBuf[MAX_NAME_LENGTH]; + char versionBuf[30]; + char *date; + char *time; + + uint8_t armScreenRow = 2; // Start at row 2 + + // Draw Logo(s) + uint8_t logoColOffset = floor((osdDisplayPort->cols - SYM_LOGO_WIDTH) / 2.0f); + // uint8_t logoColOffset = floor((osdDisplayPort->cols - ((using pilot logo) ? (SYM_LOGO_WIDTH * 2) : SYM_LOGO_WIDTH)) / 2.0f); + + // Draw INAV logo + unsigned logo_c = SYM_LOGO_START; + uint8_t logo_x = logoColOffset; + uint8_t logoRow = armScreenRow; + for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) { + for (uint8_t lCol = 0; lCol < SYM_LOGO_WIDTH; lCol++) { + displayWriteChar(osdDisplayPort, logo_x + lCol, logoRow, logo_c++); + } + logoRow++; + } + + // if (using pilot logo) { + logo_c = SYM_PILOT_LOGO_LRG_START; + logo_x = (logoColOffset * 2) + ((osdDisplayPort->cols % 2 == 0) ? 0 : 1); // Add extra 1 px space between logos, if the OSD has an odd number of columns + logoRow = armScreenRow; + for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) { + for (uint8_t lCol = 0; lCol < SYM_LOGO_WIDTH; lCol++) { + displayWriteChar(osdDisplayPort, logo_x + lCol, logoRow, logo_c++); + } + logoRow++; + } + // } // using pilot logo + + armScreenRow = logoRow + 2; + + strcpy(buf, "ARMED"); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow, buf); + armScreenRow += 2; + + if (strlen(systemConfig()->craftName) > 0) { + osdFormatCraftName(craftNameBuf); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(systemConfig()->craftName)) / 2, armScreenRow++, craftNameBuf ); + } + + if (posControl.waypointListValid && posControl.waypointCount > 0) { +#ifdef USE_MULTI_MISSION + tfp_sprintf(buf, "MISSION %u/%u (%u WP)", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); +#else + strcpy(buf, "*MISSION LOADED*"); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); +#endif + } + armScreenRow++; + +#if defined(USE_GPS) + if (feature(FEATURE_GPS)) { + if (STATE(GPS_FIX_HOME)) { + if (osdConfig()->osd_home_position_arm_screen){ + osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + osdFormatCoordinate(buf, SYM_LON, GPS_home.lon); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + int digits = osdConfig()->plus_code_digits; + olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + } + armScreenRow++; +#if defined (USE_SAFE_HOME) + if (safehome_distance) { // safehome found during arming + if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) { + strcpy(buf, "SAFEHOME FOUND; MODE OFF"); + } else { + char buf2[12]; // format the distance first + osdFormatDistanceStr(buf2, safehome_distance); + tfp_sprintf(buf, "%c - %s -> SAFEHOME %u", SYM_HOME, buf2, safehome_index); + } + textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT; + // write this message above the ARMED message to make it obvious (3rd parameter - row 7) + displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, 7, buf, elemAttr); + } +#endif + } else { + strcpy(buf, "!NO HOME POSITION!"); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + armScreenRow++; + } + } +#endif + + if (rtcGetDateTime(&dt)) { + dateTimeFormatLocal(buf, &dt); + dateTimeSplitFormatted(buf, &date, &time); + + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(date)) / 2, armScreenRow, date); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(time)) / 2, armScreenRow++, time); + armScreenRow += 2; + } + + tfp_sprintf(versionBuf, "INAV VERSION: %s", FC_VERSION_STRING); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, armScreenRow, versionBuf); } static void osdShowSDArmScreen(void) { - dateTime_t dt; - char buf[MAX(32, FORMATTED_DATE_TIME_BUFSIZE)]; - char craftNameBuf[MAX_NAME_LENGTH]; - char versionBuf[30]; - char *date; - char *time; - // We need 12 visible rows, start row never < first fully visible row 1 - uint8_t y = osdDisplayPort->rows > 13 ? (osdDisplayPort->rows - 12) / 2 : 1; + dateTime_t dt; + char buf[MAX(32, FORMATTED_DATE_TIME_BUFSIZE)]; + char craftNameBuf[MAX_NAME_LENGTH]; + char versionBuf[30]; + char *date; + char *time; + // We need 12 visible rows, start row never < first fully visible row 1 + uint8_t y = osdDisplayPort->rows > 13 ? (osdDisplayPort->rows - 12) / 2 : 1; - strcpy(buf, "ARMED"); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); - y += 2; + strcpy(buf, "ARMED"); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); + y += 2; - if (strlen(systemConfig()->craftName) > 0) { - osdFormatCraftName(craftNameBuf); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(systemConfig()->craftName)) / 2, y, craftNameBuf ); - y += 1; - } - if (posControl.waypointListValid && posControl.waypointCount > 0) { + if (strlen(systemConfig()->craftName) > 0) { + osdFormatCraftName(craftNameBuf); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(systemConfig()->craftName)) / 2, y, craftNameBuf ); + y += 1; + } + if (posControl.waypointListValid && posControl.waypointCount > 0) { #ifdef USE_MULTI_MISSION - tfp_sprintf(buf, "MISSION %u/%u (%u WP)", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); + tfp_sprintf(buf, "MISSION %u/%u (%u WP)", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); #else - strcpy(buf, "*MISSION LOADED*"); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); + strcpy(buf, "*MISSION LOADED*"); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); #endif - } - y += 1; + } + y += 1; #if defined(USE_GPS) - if (feature(FEATURE_GPS)) { - if (STATE(GPS_FIX_HOME)) { - if (osdConfig()->osd_home_position_arm_screen){ - osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); - osdFormatCoordinate(buf, SYM_LON, GPS_home.lon); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y + 1, buf); - int digits = osdConfig()->plus_code_digits; - olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y + 2, buf); - } - y += 4; + if (feature(FEATURE_GPS)) { + if (STATE(GPS_FIX_HOME)) { + if (osdConfig()->osd_home_position_arm_screen){ + osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); + osdFormatCoordinate(buf, SYM_LON, GPS_home.lon); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y + 1, buf); + int digits = osdConfig()->plus_code_digits; + olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y + 2, buf); + } + y += 4; #if defined (USE_SAFE_HOME) - if (safehome_distance) { // safehome found during arming - if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) { - strcpy(buf, "SAFEHOME FOUND; MODE OFF"); + if (safehome_distance) { // safehome found during arming + if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) { + strcpy(buf, "SAFEHOME FOUND; MODE OFF"); } else { char buf2[12]; // format the distance first osdFormatDistanceStr(buf2, safehome_distance); @@ -4422,246 +4520,246 @@ static void osdShowSDArmScreen(void) textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT; // write this message above the ARMED message to make it obvious displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y - 8, buf, elemAttr); - } + } #endif - } else { - strcpy(buf, "!NO HOME POSITION!"); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); - y += 1; - } - } + } else { + strcpy(buf, "!NO HOME POSITION!"); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); + y += 1; + } + } #endif - if (rtcGetDateTime(&dt)) { - dateTimeFormatLocal(buf, &dt); - dateTimeSplitFormatted(buf, &date, &time); + if (rtcGetDateTime(&dt)) { + dateTimeFormatLocal(buf, &dt); + dateTimeSplitFormatted(buf, &date, &time); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(date)) / 2, y, date); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(time)) / 2, y + 1, time); - y += 3; - } + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(date)) / 2, y, date); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(time)) / 2, y + 1, time); + y += 3; + } - tfp_sprintf(versionBuf, "INAV VERSION: %s", FC_VERSION_STRING); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, y, versionBuf); + tfp_sprintf(versionBuf, "INAV VERSION: %s", FC_VERSION_STRING); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, y, versionBuf); } // called when motors armed static void osdShowArmed(void) { - displayClearScreen(osdDisplayPort); + displayClearScreen(osdDisplayPort); - if (osdDisplayPort->rows >= OSD_STATS_SINGLE_PAGE_MIN_ROWS) { - osdShowHDArmScreen(); - } else { - osdShowSDArmScreen(); - } + if (osdDisplayPort->rows >= OSD_STATS_SINGLE_PAGE_MIN_ROWS) { + osdShowHDArmScreen(); + } else { + osdShowSDArmScreen(); + } } static void osdFilterData(timeUs_t currentTimeUs) { - static timeUs_t lastRefresh = 0; - float refresh_dT = US2S(cmpTimeUs(currentTimeUs, lastRefresh)); + static timeUs_t lastRefresh = 0; + float refresh_dT = US2S(cmpTimeUs(currentTimeUs, lastRefresh)); - GForce = fast_fsqrtf(vectorNormSquared(&imuMeasuredAccelBF)) / GRAVITY_MSS; - for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) GForceAxis[axis] = imuMeasuredAccelBF.v[axis] / GRAVITY_MSS; + GForce = fast_fsqrtf(vectorNormSquared(&imuMeasuredAccelBF)) / GRAVITY_MSS; + for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) GForceAxis[axis] = imuMeasuredAccelBF.v[axis] / GRAVITY_MSS; - if (lastRefresh) { - GForce = pt1FilterApply3(&GForceFilter, GForce, refresh_dT); - for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) pt1FilterApply3(GForceFilterAxis + axis, GForceAxis[axis], refresh_dT); - } else { - pt1FilterInitRC(&GForceFilter, GFORCE_FILTER_TC, 0); - pt1FilterReset(&GForceFilter, GForce); + if (lastRefresh) { + GForce = pt1FilterApply3(&GForceFilter, GForce, refresh_dT); + for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) pt1FilterApply3(GForceFilterAxis + axis, GForceAxis[axis], refresh_dT); + } else { + pt1FilterInitRC(&GForceFilter, GFORCE_FILTER_TC, 0); + pt1FilterReset(&GForceFilter, GForce); - for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) { - pt1FilterInitRC(GForceFilterAxis + axis, GFORCE_FILTER_TC, 0); - pt1FilterReset(GForceFilterAxis + axis, GForceAxis[axis]); - } - } + for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) { + pt1FilterInitRC(GForceFilterAxis + axis, GFORCE_FILTER_TC, 0); + pt1FilterReset(GForceFilterAxis + axis, GForceAxis[axis]); + } + } - lastRefresh = currentTimeUs; + lastRefresh = currentTimeUs; } // Detect when the user is holding the roll stick to the right static bool osdIsPageUpStickCommandHeld(void) { - static int pageUpHoldCount = 1; + static int pageUpHoldCount = 1; - bool keyHeld = false; + bool keyHeld = false; - if (IS_HI(ROLL)) { - keyHeld = true; - } + if (IS_HI(ROLL)) { + keyHeld = true; + } - if (!keyHeld) { - pageUpHoldCount = 1; - } else { - ++pageUpHoldCount; - } + if (!keyHeld) { + pageUpHoldCount = 1; + } else { + ++pageUpHoldCount; + } - if (pageUpHoldCount > 20) { - pageUpHoldCount = 1; - return true; - } + if (pageUpHoldCount > 20) { + pageUpHoldCount = 1; + return true; + } - return false; + return false; } // Detect when the user is holding the roll stick to the left static bool osdIsPageDownStickCommandHeld(void) { - static int pageDownHoldCount = 1; + static int pageDownHoldCount = 1; - bool keyHeld = false; - if (IS_LO(ROLL)) { - keyHeld = true; - } + bool keyHeld = false; + if (IS_LO(ROLL)) { + keyHeld = true; + } - if (!keyHeld) { - pageDownHoldCount = 1; - } else { - ++pageDownHoldCount; - } + if (!keyHeld) { + pageDownHoldCount = 1; + } else { + ++pageDownHoldCount; + } - if (pageDownHoldCount > 20) { - pageDownHoldCount = 1; - return true; - } + if (pageDownHoldCount > 20) { + pageDownHoldCount = 1; + return true; + } - return false; + return false; } static void osdRefresh(timeUs_t currentTimeUs) { - osdFilterData(currentTimeUs); + osdFilterData(currentTimeUs); #ifdef USE_CMS - if (IS_RC_MODE_ACTIVE(BOXOSD) && (!cmsInMenu) && !(osdConfig()->osd_failsafe_switch_layout && FLIGHT_MODE(FAILSAFE_MODE))) { + if (IS_RC_MODE_ACTIVE(BOXOSD) && (!cmsInMenu) && !(osdConfig()->osd_failsafe_switch_layout && FLIGHT_MODE(FAILSAFE_MODE))) { #else - if (IS_RC_MODE_ACTIVE(BOXOSD) && !(osdConfig()->osd_failsafe_switch_layout && FLIGHT_MODE(FAILSAFE_MODE))) { + if (IS_RC_MODE_ACTIVE(BOXOSD) && !(osdConfig()->osd_failsafe_switch_layout && FLIGHT_MODE(FAILSAFE_MODE))) { #endif - displayClearScreen(osdDisplayPort); - armState = ARMING_FLAG(ARMED); - return; - } + displayClearScreen(osdDisplayPort); + armState = ARMING_FLAG(ARMED); + return; + } - bool statsSinglePageCompatible = (osdDisplayPort->rows >= OSD_STATS_SINGLE_PAGE_MIN_ROWS); - static uint8_t statsCurrentPage = 0; - static bool statsDisplayed = false; - static bool statsAutoPagingEnabled = true; + bool statsSinglePageCompatible = (osdDisplayPort->rows >= OSD_STATS_SINGLE_PAGE_MIN_ROWS); + static uint8_t statsCurrentPage = 0; + static bool statsDisplayed = false; + static bool statsAutoPagingEnabled = true; - // Detect arm/disarm - if (armState != ARMING_FLAG(ARMED)) { - if (ARMING_FLAG(ARMED)) { - // Display the "Arming" screen - statsDisplayed = false; - osdResetStats(); - osdShowArmed(); - uint32_t delay = ARMED_SCREEN_DISPLAY_TIME; + // Detect arm/disarm + if (armState != ARMING_FLAG(ARMED)) { + if (ARMING_FLAG(ARMED)) { + // Display the "Arming" screen + statsDisplayed = false; + osdResetStats(); + osdShowArmed(); + uint32_t delay = ARMED_SCREEN_DISPLAY_TIME; #if defined(USE_SAFE_HOME) - if (safehome_distance) - delay *= 3; + if (safehome_distance) + delay *= 3; #endif - osdSetNextRefreshIn(delay); - } else { - // Display the "Stats" screen - statsDisplayed = true; - statsCurrentPage = 0; - statsAutoPagingEnabled = osdConfig()->stats_page_auto_swap_time > 0 ? true : false; - osdShowStats(statsSinglePageCompatible, statsCurrentPage); - osdSetNextRefreshIn(STATS_SCREEN_DISPLAY_TIME); - } + osdSetNextRefreshIn(delay); + } else { + // Display the "Stats" screen + statsDisplayed = true; + statsCurrentPage = 0; + statsAutoPagingEnabled = osdConfig()->stats_page_auto_swap_time > 0 ? true : false; + osdShowStats(statsSinglePageCompatible, statsCurrentPage); + osdSetNextRefreshIn(STATS_SCREEN_DISPLAY_TIME); + } - armState = ARMING_FLAG(ARMED); - } + armState = ARMING_FLAG(ARMED); + } - // This block is entered when we're showing the "Splash", "Armed" or "Stats" screens - if (resumeRefreshAt) { - - // Handle events only when the "Stats" screen is being displayed. - if (statsDisplayed) { + // This block is entered when we're showing the "Splash", "Armed" or "Stats" screens + if (resumeRefreshAt) { + + // Handle events only when the "Stats" screen is being displayed. + if (statsDisplayed) { - // Manual paging stick commands are only applicable to multi-page stats. - // ****************************** - // For single-page stats, this effectively disables the ability to cancel the - // automatic paging/updates with the stick commands. So unless stats_page_auto_swap_time - // is set to 0 or greater than 4 (saved settings display interval is 5 seconds), then - // "Saved Settings" should display if it is active within the refresh interval. - // ****************************** - // With multi-page stats, "Saved Settings" could also be missed if the user - // has canceled automatic paging using the stick commands, because that is only - // updated when osdShowStats() is called. So, in that case, they would only see - // the "Saved Settings" message if they happen to manually change pages using the - // stick commands within the interval the message is displayed. - bool manualPageUpRequested = false; - bool manualPageDownRequested = false; - if (!statsSinglePageCompatible) { - // These methods ensure the paging stick commands are held for a brief period - // Otherwise it can result in a race condition where the stats are - // updated too quickly and can result in partial blanks, etc. - if (osdIsPageUpStickCommandHeld()) { - manualPageUpRequested = true; - statsAutoPagingEnabled = false; - } else if (osdIsPageDownStickCommandHeld()) { - manualPageDownRequested = true; - statsAutoPagingEnabled = false; - } - } + // Manual paging stick commands are only applicable to multi-page stats. + // ****************************** + // For single-page stats, this effectively disables the ability to cancel the + // automatic paging/updates with the stick commands. So unless stats_page_auto_swap_time + // is set to 0 or greater than 4 (saved settings display interval is 5 seconds), then + // "Saved Settings" should display if it is active within the refresh interval. + // ****************************** + // With multi-page stats, "Saved Settings" could also be missed if the user + // has canceled automatic paging using the stick commands, because that is only + // updated when osdShowStats() is called. So, in that case, they would only see + // the "Saved Settings" message if they happen to manually change pages using the + // stick commands within the interval the message is displayed. + bool manualPageUpRequested = false; + bool manualPageDownRequested = false; + if (!statsSinglePageCompatible) { + // These methods ensure the paging stick commands are held for a brief period + // Otherwise it can result in a race condition where the stats are + // updated too quickly and can result in partial blanks, etc. + if (osdIsPageUpStickCommandHeld()) { + manualPageUpRequested = true; + statsAutoPagingEnabled = false; + } else if (osdIsPageDownStickCommandHeld()) { + manualPageDownRequested = true; + statsAutoPagingEnabled = false; + } + } - if (statsAutoPagingEnabled) { - // Alternate screens for multi-page stats. - // Also, refreshes screen at swap interval for single-page stats. - if (OSD_ALTERNATING_CHOICES((osdConfig()->stats_page_auto_swap_time * 1000), 2)) { - if (statsCurrentPage == 0) { - osdShowStats(statsSinglePageCompatible, statsCurrentPage); - statsCurrentPage = 1; - } - } else { - if (statsCurrentPage == 1) { - osdShowStats(statsSinglePageCompatible, statsCurrentPage); - statsCurrentPage = 0; - } - } - } else { - // Process manual page change events for multi-page stats. - if (manualPageUpRequested) { - osdShowStats(statsSinglePageCompatible, 1); - statsCurrentPage = 1; - } else if (manualPageDownRequested) { - osdShowStats(statsSinglePageCompatible, 0); - statsCurrentPage = 0; - } - } - } + if (statsAutoPagingEnabled) { + // Alternate screens for multi-page stats. + // Also, refreshes screen at swap interval for single-page stats. + if (OSD_ALTERNATING_CHOICES((osdConfig()->stats_page_auto_swap_time * 1000), 2)) { + if (statsCurrentPage == 0) { + osdShowStats(statsSinglePageCompatible, statsCurrentPage); + statsCurrentPage = 1; + } + } else { + if (statsCurrentPage == 1) { + osdShowStats(statsSinglePageCompatible, statsCurrentPage); + statsCurrentPage = 0; + } + } + } else { + // Process manual page change events for multi-page stats. + if (manualPageUpRequested) { + osdShowStats(statsSinglePageCompatible, 1); + statsCurrentPage = 1; + } else if (manualPageDownRequested) { + osdShowStats(statsSinglePageCompatible, 0); + statsCurrentPage = 0; + } + } + } - // Handle events when either "Splash", "Armed" or "Stats" screens are displayed. - if ((currentTimeUs > resumeRefreshAt) || OSD_RESUME_UPDATES_STICK_COMMAND) { - // Time elapsed or canceled by stick commands. - // Exit to normal OSD operation. - displayClearScreen(osdDisplayPort); - resumeRefreshAt = 0; - statsDisplayed = false; - } else { - // Continue "Splash", "Armed" or "Stats" screens. - displayHeartbeat(osdDisplayPort); - } - - return; - } + // Handle events when either "Splash", "Armed" or "Stats" screens are displayed. + if ((currentTimeUs > resumeRefreshAt) || OSD_RESUME_UPDATES_STICK_COMMAND) { + // Time elapsed or canceled by stick commands. + // Exit to normal OSD operation. + displayClearScreen(osdDisplayPort); + resumeRefreshAt = 0; + statsDisplayed = false; + } else { + // Continue "Splash", "Armed" or "Stats" screens. + displayHeartbeat(osdDisplayPort); + } + + return; + } #ifdef USE_CMS - if (!displayIsGrabbed(osdDisplayPort)) { - displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); - if (fullRedraw) { - displayClearScreen(osdDisplayPort); - fullRedraw = false; - } - osdDrawNextElement(); - displayHeartbeat(osdDisplayPort); - displayCommitTransaction(osdDisplayPort); + if (!displayIsGrabbed(osdDisplayPort)) { + displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); + if (fullRedraw) { + displayClearScreen(osdDisplayPort); + fullRedraw = false; + } + osdDrawNextElement(); + displayHeartbeat(osdDisplayPort); + displayCommitTransaction(osdDisplayPort); #ifdef OSD_CALLS_CMS - } else { - cmsUpdate(currentTimeUs); + } else { + cmsUpdate(currentTimeUs); #endif - } + } #endif } @@ -4670,318 +4768,318 @@ static void osdRefresh(timeUs_t currentTimeUs) */ void osdUpdate(timeUs_t currentTimeUs) { - static uint32_t counter = 0; + static uint32_t counter = 0; - // don't touch buffers if DMA transaction is in progress - if (displayIsTransferInProgress(osdDisplayPort)) { - return; - } + // don't touch buffers if DMA transaction is in progress + if (displayIsTransferInProgress(osdDisplayPort)) { + return; + } - if (!osdDisplayIsReady) { - osdCompleteAsyncInitialization(); - return; - } + if (!osdDisplayIsReady) { + osdCompleteAsyncInitialization(); + return; + } #if defined(OSD_ALTERNATE_LAYOUT_COUNT) && OSD_ALTERNATE_LAYOUT_COUNT > 0 - // Check if the layout has changed. Higher numbered - // boxes take priority. - unsigned activeLayout; - if (layoutOverride >= 0) { - activeLayout = layoutOverride; - // Check for timed override, it will go into effect on - // the next OSD iteration - if (layoutOverrideUntil > 0 && millis() > layoutOverrideUntil) { - layoutOverrideUntil = 0; - layoutOverride = -1; - } - } else if (osdConfig()->osd_failsafe_switch_layout && FLIGHT_MODE(FAILSAFE_MODE)) { - activeLayout = 0; - } else { + // Check if the layout has changed. Higher numbered + // boxes take priority. + unsigned activeLayout; + if (layoutOverride >= 0) { + activeLayout = layoutOverride; + // Check for timed override, it will go into effect on + // the next OSD iteration + if (layoutOverrideUntil > 0 && millis() > layoutOverrideUntil) { + layoutOverrideUntil = 0; + layoutOverride = -1; + } + } else if (osdConfig()->osd_failsafe_switch_layout && FLIGHT_MODE(FAILSAFE_MODE)) { + activeLayout = 0; + } else { #if OSD_ALTERNATE_LAYOUT_COUNT > 2 - if (IS_RC_MODE_ACTIVE(BOXOSDALT3)) - activeLayout = 3; - else + if (IS_RC_MODE_ACTIVE(BOXOSDALT3)) + activeLayout = 3; + else #endif #if OSD_ALTERNATE_LAYOUT_COUNT > 1 - if (IS_RC_MODE_ACTIVE(BOXOSDALT2)) - activeLayout = 2; - else + if (IS_RC_MODE_ACTIVE(BOXOSDALT2)) + activeLayout = 2; + else #endif - if (IS_RC_MODE_ACTIVE(BOXOSDALT1)) - activeLayout = 1; - else + if (IS_RC_MODE_ACTIVE(BOXOSDALT1)) + activeLayout = 1; + else #ifdef USE_PROGRAMMING_FRAMEWORK - if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT)) - activeLayout = constrain(logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT], 0, OSD_ALTERNATE_LAYOUT_COUNT); - else + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT)) + activeLayout = constrain(logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT], 0, OSD_ALTERNATE_LAYOUT_COUNT); + else #endif - activeLayout = 0; - } - if (currentLayout != activeLayout) { - currentLayout = activeLayout; - osdStartFullRedraw(); - } + activeLayout = 0; + } + if (currentLayout != activeLayout) { + currentLayout = activeLayout; + osdStartFullRedraw(); + } #endif #define DRAW_FREQ_DENOM 4 #define STATS_FREQ_DENOM 50 - counter++; + counter++; - if ((counter % STATS_FREQ_DENOM) == 0) { - osdUpdateStats(); - } + if ((counter % STATS_FREQ_DENOM) == 0) { + osdUpdateStats(); + } - if ((counter % DRAW_FREQ_DENOM) == 0) { - // redraw values in buffer - osdRefresh(currentTimeUs); - } else { - // rest of time redraw screen - displayDrawScreen(osdDisplayPort); - } + if ((counter % DRAW_FREQ_DENOM) == 0) { + // redraw values in buffer + osdRefresh(currentTimeUs); + } else { + // rest of time redraw screen + displayDrawScreen(osdDisplayPort); + } #ifdef USE_CMS - // do not allow ARM if we are in menu - if (displayIsGrabbed(osdDisplayPort)) { - ENABLE_ARMING_FLAG(ARMING_DISABLED_OSD_MENU); - } else { - DISABLE_ARMING_FLAG(ARMING_DISABLED_OSD_MENU); - } + // do not allow ARM if we are in menu + if (displayIsGrabbed(osdDisplayPort)) { + ENABLE_ARMING_FLAG(ARMING_DISABLED_OSD_MENU); + } else { + DISABLE_ARMING_FLAG(ARMING_DISABLED_OSD_MENU); + } #endif } void osdStartFullRedraw(void) { - fullRedraw = true; + fullRedraw = true; } void osdOverrideLayout(int layout, timeMs_t duration) { - layoutOverride = constrain(layout, -1, ARRAYLEN(osdLayoutsConfig()->item_pos) - 1); - if (layoutOverride >= 0 && duration > 0) { - layoutOverrideUntil = millis() + duration; - } else { - layoutOverrideUntil = 0; - } + layoutOverride = constrain(layout, -1, ARRAYLEN(osdLayoutsConfig()->item_pos) - 1); + if (layoutOverride >= 0 && duration > 0) { + layoutOverrideUntil = millis() + duration; + } else { + layoutOverrideUntil = 0; + } } int osdGetActiveLayout(bool *overridden) { - if (overridden) { - *overridden = layoutOverride >= 0; - } - return currentLayout; + if (overridden) { + *overridden = layoutOverride >= 0; + } + return currentLayout; } bool osdItemIsFixed(osd_items_e item) { - return item == OSD_CROSSHAIRS || - item == OSD_ARTIFICIAL_HORIZON || - item == OSD_HORIZON_SIDEBARS; + return item == OSD_CROSSHAIRS || + item == OSD_ARTIFICIAL_HORIZON || + item == OSD_HORIZON_SIDEBARS; } displayPort_t *osdGetDisplayPort(void) { - return osdDisplayPort; + return osdDisplayPort; } displayCanvas_t *osdGetDisplayPortCanvas(void) { #if defined(USE_CANVAS) - if (osdDisplayHasCanvas) { - return &osdCanvas; - } + if (osdDisplayHasCanvas) { + return &osdCanvas; + } #endif - return NULL; + return NULL; } timeMs_t systemMessageCycleTime(unsigned messageCount, const char **messages){ - uint8_t i = 0; - float factor = 1.0f; - while (i < messageCount) { - if ((float)strlen(messages[i]) / 15.0f > factor) { - factor = (float)strlen(messages[i]) / 15.0f; - } - i++; - } - return osdConfig()->system_msg_display_time * factor; + uint8_t i = 0; + float factor = 1.0f; + while (i < messageCount) { + if ((float)strlen(messages[i]) / 15.0f > factor) { + factor = (float)strlen(messages[i]) / 15.0f; + } + i++; + } + return osdConfig()->system_msg_display_time * factor; } textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenteredText) { - textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; + textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; - if (buff != NULL) { - const char *message = NULL; - char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; - // We might have up to 5 messages to show. - const char *messages[5]; - unsigned messageCount = 0; - const char *failsafeInfoMessage = NULL; - const char *invertedInfoMessage = NULL; + if (buff != NULL) { + const char *message = NULL; + char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; + // We might have up to 5 messages to show. + const char *messages[5]; + unsigned messageCount = 0; + const char *failsafeInfoMessage = NULL; + const char *invertedInfoMessage = NULL; - if (ARMING_FLAG(ARMED)) { - if (FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) { - if (isWaypointMissionRTHActive()) { - // if RTH activated whilst WP mode selected, remind pilot to cancel WP mode to exit RTH - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_RTH_CANCEL); - } - if (navGetCurrentStateFlags() & NAV_AUTO_WP_DONE) { - messages[messageCount++] = STATE(LANDING_DETECTED) ? OSD_MESSAGE_STR(OSD_MSG_WP_LANDED) : OSD_MESSAGE_STR(OSD_MSG_WP_FINISHED); - } else if (NAV_Status.state == MW_NAV_STATE_WP_ENROUTE) { - // Countdown display for remaining Waypoints - char buf[6]; - osdFormatDistanceSymbol(buf, posControl.wpDistance, 0); - tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", getGeoWaypointNumber(posControl.activeWaypointIndex), posControl.geoWaypointCount, buf); - messages[messageCount++] = messageBuf; - } else if (NAV_Status.state == MW_NAV_STATE_HOLD_TIMED) { - if (navConfig()->general.waypoint_enforce_altitude && !posControl.wpAltitudeReached) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ADJUSTING_WP_ALT); - } else { - // WP hold time countdown in seconds - timeMs_t currentTime = millis(); - int holdTimeRemaining = posControl.waypointList[posControl.activeWaypointIndex].p1 - (int)(MS2S(currentTime - posControl.wpReachedTime)); - holdTimeRemaining = holdTimeRemaining >= 0 ? holdTimeRemaining : 0; + if (ARMING_FLAG(ARMED)) { + if (FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) { + if (isWaypointMissionRTHActive()) { + // if RTH activated whilst WP mode selected, remind pilot to cancel WP mode to exit RTH + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_RTH_CANCEL); + } + if (navGetCurrentStateFlags() & NAV_AUTO_WP_DONE) { + messages[messageCount++] = STATE(LANDING_DETECTED) ? OSD_MESSAGE_STR(OSD_MSG_WP_LANDED) : OSD_MESSAGE_STR(OSD_MSG_WP_FINISHED); + } else if (NAV_Status.state == MW_NAV_STATE_WP_ENROUTE) { + // Countdown display for remaining Waypoints + char buf[6]; + osdFormatDistanceSymbol(buf, posControl.wpDistance, 0); + tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", getGeoWaypointNumber(posControl.activeWaypointIndex), posControl.geoWaypointCount, buf); + messages[messageCount++] = messageBuf; + } else if (NAV_Status.state == MW_NAV_STATE_HOLD_TIMED) { + if (navConfig()->general.waypoint_enforce_altitude && !posControl.wpAltitudeReached) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ADJUSTING_WP_ALT); + } else { + // WP hold time countdown in seconds + timeMs_t currentTime = millis(); + int holdTimeRemaining = posControl.waypointList[posControl.activeWaypointIndex].p1 - (int)(MS2S(currentTime - posControl.wpReachedTime)); + holdTimeRemaining = holdTimeRemaining >= 0 ? holdTimeRemaining : 0; - tfp_sprintf(messageBuf, "HOLDING WP FOR %2u S", holdTimeRemaining); + tfp_sprintf(messageBuf, "HOLDING WP FOR %2u S", holdTimeRemaining); - messages[messageCount++] = messageBuf; - } - } else { - const char *navStateMessage = navigationStateMessage(); - if (navStateMessage) { - messages[messageCount++] = navStateMessage; - } - } + messages[messageCount++] = messageBuf; + } + } else { + const char *navStateMessage = navigationStateMessage(); + if (navStateMessage) { + messages[messageCount++] = navStateMessage; + } + } #if defined(USE_SAFE_HOME) - const char *safehomeMessage = divertingToSafehomeMessage(); - if (safehomeMessage) { - messages[messageCount++] = safehomeMessage; - } + const char *safehomeMessage = divertingToSafehomeMessage(); + if (safehomeMessage) { + messages[messageCount++] = safehomeMessage; + } #endif - if (FLIGHT_MODE(FAILSAFE_MODE)) { - // In FS mode while being armed too - const char *failsafePhaseMessage = osdFailsafePhaseMessage(); - failsafeInfoMessage = osdFailsafeInfoMessage(); + if (FLIGHT_MODE(FAILSAFE_MODE)) { + // In FS mode while being armed too + const char *failsafePhaseMessage = osdFailsafePhaseMessage(); + failsafeInfoMessage = osdFailsafeInfoMessage(); - if (failsafePhaseMessage) { - messages[messageCount++] = failsafePhaseMessage; - } - if (failsafeInfoMessage) { - messages[messageCount++] = failsafeInfoMessage; - } - } - } else { /* messages shown only when Failsafe, WP, RTH or Emergency Landing not active */ - if (STATE(FIXED_WING_LEGACY) && (navGetCurrentStateFlags() & NAV_CTL_LAUNCH)) { - messages[messageCount++] = navConfig()->fw.launch_manual_throttle ? OSD_MESSAGE_STR(OSD_MSG_AUTOLAUNCH_MANUAL) : - OSD_MESSAGE_STR(OSD_MSG_AUTOLAUNCH); - const char *launchStateMessage = fixedWingLaunchStateMessage(); - if (launchStateMessage) { - messages[messageCount++] = launchStateMessage; - } - } else { - if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && !navigationRequiresAngleMode()) { - // ALTHOLD might be enabled alongside ANGLE/HORIZON/ACRO - // when it doesn't require ANGLE mode (required only in FW - // right now). If if requires ANGLE, its display is handled - // by OSD_FLYMODE. - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ALTITUDE_HOLD); - } - if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM) && !feature(FEATURE_FW_AUTOTRIM)) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTRIM); - } - if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE)) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTUNE); - if (FLIGHT_MODE(MANUAL_MODE)) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTUNE_ACRO); - } - } - if (IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE) || (navigationRequiresAngleMode() && !navigationIsControllingAltitude()))) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOLEVEL); - } - if (FLIGHT_MODE(HEADFREE_MODE)) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_HEADFREE); - } - if (FLIGHT_MODE(SOARING_MODE)) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_NAV_SOARING); - } - if (posControl.flags.wpMissionPlannerActive) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_MISSION_PLANNER); - } - if (STATE(LANDING_DETECTED)) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_LANDED); - } - } - } - } else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) { - unsigned invalidIndex; + if (failsafePhaseMessage) { + messages[messageCount++] = failsafePhaseMessage; + } + if (failsafeInfoMessage) { + messages[messageCount++] = failsafeInfoMessage; + } + } + } else { /* messages shown only when Failsafe, WP, RTH or Emergency Landing not active */ + if (STATE(FIXED_WING_LEGACY) && (navGetCurrentStateFlags() & NAV_CTL_LAUNCH)) { + messages[messageCount++] = navConfig()->fw.launch_manual_throttle ? OSD_MESSAGE_STR(OSD_MSG_AUTOLAUNCH_MANUAL) : + OSD_MESSAGE_STR(OSD_MSG_AUTOLAUNCH); + const char *launchStateMessage = fixedWingLaunchStateMessage(); + if (launchStateMessage) { + messages[messageCount++] = launchStateMessage; + } + } else { + if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && !navigationRequiresAngleMode()) { + // ALTHOLD might be enabled alongside ANGLE/HORIZON/ACRO + // when it doesn't require ANGLE mode (required only in FW + // right now). If if requires ANGLE, its display is handled + // by OSD_FLYMODE. + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ALTITUDE_HOLD); + } + if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM) && !feature(FEATURE_FW_AUTOTRIM)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTRIM); + } + if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTUNE); + if (FLIGHT_MODE(MANUAL_MODE)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTUNE_ACRO); + } + } + if (IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE) || (navigationRequiresAngleMode() && !navigationIsControllingAltitude()))) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOLEVEL); + } + if (FLIGHT_MODE(HEADFREE_MODE)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_HEADFREE); + } + if (FLIGHT_MODE(SOARING_MODE)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_NAV_SOARING); + } + if (posControl.flags.wpMissionPlannerActive) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_MISSION_PLANNER); + } + if (STATE(LANDING_DETECTED)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_LANDED); + } + } + } + } else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) { + unsigned invalidIndex; - // Check if we're unable to arm for some reason - if (ARMING_FLAG(ARMING_DISABLED_INVALID_SETTING) && !settingsValidate(&invalidIndex)) { + // Check if we're unable to arm for some reason + if (ARMING_FLAG(ARMING_DISABLED_INVALID_SETTING) && !settingsValidate(&invalidIndex)) { - const setting_t *setting = settingGet(invalidIndex); - settingGetName(setting, messageBuf); - for (int ii = 0; messageBuf[ii]; ii++) { - messageBuf[ii] = sl_toupper(messageBuf[ii]); - } - invertedInfoMessage = messageBuf; - messages[messageCount++] = invertedInfoMessage; + const setting_t *setting = settingGet(invalidIndex); + settingGetName(setting, messageBuf); + for (int ii = 0; messageBuf[ii]; ii++) { + messageBuf[ii] = sl_toupper(messageBuf[ii]); + } + invertedInfoMessage = messageBuf; + messages[messageCount++] = invertedInfoMessage; - invertedInfoMessage = OSD_MESSAGE_STR(OSD_MSG_INVALID_SETTING); - messages[messageCount++] = invertedInfoMessage; + invertedInfoMessage = OSD_MESSAGE_STR(OSD_MSG_INVALID_SETTING); + messages[messageCount++] = invertedInfoMessage; - } else { + } else { - invertedInfoMessage = OSD_MESSAGE_STR(OSD_MSG_UNABLE_ARM); - messages[messageCount++] = invertedInfoMessage; + invertedInfoMessage = OSD_MESSAGE_STR(OSD_MSG_UNABLE_ARM); + messages[messageCount++] = invertedInfoMessage; - // Show the reason for not arming - messages[messageCount++] = osdArmingDisabledReasonMessage(); + // Show the reason for not arming + messages[messageCount++] = osdArmingDisabledReasonMessage(); - } - } else if (!ARMING_FLAG(ARMED)) { - if (isWaypointListValid()) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_MISSION_LOADED); - } - } + } + } else if (!ARMING_FLAG(ARMED)) { + if (isWaypointListValid()) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_MISSION_LOADED); + } + } - /* Messages that are shown regardless of Arming state */ + /* Messages that are shown regardless of Arming state */ - if (savingSettings == true) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS); - } else if (notify_settings_saved > 0) { - if (millis() > notify_settings_saved) { - notify_settings_saved = 0; - } else { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_SETTINGS_SAVED); - } - } + if (savingSettings == true) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS); + } else if (notify_settings_saved > 0) { + if (millis() > notify_settings_saved) { + notify_settings_saved = 0; + } else { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_SETTINGS_SAVED); + } + } #ifdef USE_DEV_TOOLS - if (systemConfig()->groundTestMode) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_GRD_TEST_MODE); - } + if (systemConfig()->groundTestMode) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_GRD_TEST_MODE); + } #endif - if (messageCount > 0) { - message = messages[OSD_ALTERNATING_CHOICES(systemMessageCycleTime(messageCount, messages), messageCount)]; - if (message == failsafeInfoMessage) { - // failsafeInfoMessage is not useful for recovering - // a lost model, but might help avoiding a crash. - // Blink to grab user attention. - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } else if (message == invertedInfoMessage) { - TEXT_ATTRIBUTES_ADD_INVERTED(elemAttr); - } - // We're shoing either failsafePhaseMessage or - // navStateMessage. Don't BLINK here since - // having this text available might be crucial - // during a lost aircraft recovery and blinking - // will cause it to be missing from some frames. - } + if (messageCount > 0) { + message = messages[OSD_ALTERNATING_CHOICES(systemMessageCycleTime(messageCount, messages), messageCount)]; + if (message == failsafeInfoMessage) { + // failsafeInfoMessage is not useful for recovering + // a lost model, but might help avoiding a crash. + // Blink to grab user attention. + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } else if (message == invertedInfoMessage) { + TEXT_ATTRIBUTES_ADD_INVERTED(elemAttr); + } + // We're shoing either failsafePhaseMessage or + // navStateMessage. Don't BLINK here since + // having this text available might be crucial + // during a lost aircraft recovery and blinking + // will cause it to be missing from some frames. + } - osdFormatMessage(buff, buff_size, message, isCenteredText); - } - return elemAttr; + osdFormatMessage(buff, buff_size, message, isCenteredText); + } + return elemAttr; } -#endif // OSD +#endif // OSD \ No newline at end of file From 2c05e400485b8386e6c7b1d0252386653ff58ffd Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 27 Aug 2023 16:46:44 +0100 Subject: [PATCH 065/175] Tested and working in HITL --- src/main/io/osd.c | 24 +++++++++++++----------- src/main/navigation/navigation.c | 3 +++ 2 files changed, 16 insertions(+), 11 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index e0c3359436..8e00ce1086 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1842,33 +1842,35 @@ static bool osdDrawSingleElement(uint8_t item) osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); break; - case OSD_ODOMETER: -#ifdef USE_STATS + case OSD_ODOMETER: { displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_ODOMETER); - int odometerDist = (int)statsConfig()->stats_total_dist + (getTotalTravelDistance() / 100); + uint32_t odometerDist = getTotalTravelDistance() / 100; +#ifdef USE_STATS + odometerDist+= statsConfig()->stats_total_dist; +#endif switch (osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - tfp_sprintf(buff+1, "%7d", (int)(odometerDist / METERS_PER_MILE)); - buff[6] = SYM_MI; + tfp_sprintf(buff, "%5d", (int)(odometerDist / METERS_PER_MILE)); + buff[5] = SYM_MI; break; default: case OSD_UNIT_GA: - tfp_sprintf(buff+1, "%7d", (int)(odometerDist / METERS_PER_NAUTICALMILE)); - buff[6] = SYM_NM; + tfp_sprintf(buff, "%5d", (int)(odometerDist / METERS_PER_NAUTICALMILE)); + buff[5] = SYM_NM; break; case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - tfp_sprintf(buff+1, "%7d", (int)(odometerDist / METERS_PER_KILOMETER)); - buff[6] = SYM_KM; + tfp_sprintf(buff, "%5d", (int)(odometerDist / METERS_PER_KILOMETER)); + buff[5] = SYM_KM; break; } - buff[7] = '\0'; + buff[6] = '\0'; + elemPosX++; } -#endif break; case OSD_GROUND_COURSE: diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index e164b33ab5..43319e06ea 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2755,6 +2755,9 @@ static void updateNavigationFlightStatistics(void) } } +/* + * Total travel distance in cm + */ uint32_t getTotalTravelDistance(void) { return lrintf(posControl.totalTripDistance); From 6e58a94cf3a9230096cffb21c6816b92eebcd47a Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 27 Aug 2023 23:28:04 +0100 Subject: [PATCH 066/175] Change logic + add gyro check for MR --- src/main/fc/fc_core.c | 38 ++++++++++++++------------------ src/main/navigation/navigation.c | 20 ++++++++++++----- 2 files changed, 30 insertions(+), 28 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 60c658809e..a00e797242 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -119,8 +119,7 @@ uint8_t motorControlEnable = false; static bool isRXDataNew; static disarmReason_t lastDisarmReason = DISARM_NONE; timeUs_t lastDisarmTimeUs = 0; -timeMs_t emergInflightRearmTimeout = 0; -timeMs_t mcEmergRearmStabiliseTimeout = 0; +timeMs_t emergRearmStabiliseTimeout = 0; static bool prearmWasReset = false; // Prearm must be reset (RC Mode not active) before arming is possible static timeMs_t prearmActivationTime = 0; @@ -435,10 +434,6 @@ void disarm(disarmReason_t disarmReason) if (ARMING_FLAG(ARMED)) { lastDisarmReason = disarmReason; lastDisarmTimeUs = micros(); - if (disarmReason == DISARM_SWITCH || disarmReason == DISARM_KILLSWITCH) { - emergInflightRearmTimeout = isProbablyStillFlying() ? US2MS(lastDisarmTimeUs) + EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS : 0; - } - DISABLE_ARMING_FLAG(ARMED); #ifdef USE_BLACKBOX @@ -508,24 +503,24 @@ bool emergencyArmingUpdate(bool armingSwitchIsOn) bool emergInflightRearmEnabled(void) { - /* Emergency rearm allowed within emergInflightRearmTimeout window. - * On MR emergency rearm only allowed after 1.5s if MR dropping or climbing after disarm, i.e. still in flight */ - + /* Emergency rearm allowed within 5s timeout period after disarm if craft still flying */ timeMs_t currentTimeMs = millis(); - if (!emergInflightRearmTimeout || currentTimeMs > emergInflightRearmTimeout) { + emergRearmStabiliseTimeout = 0; + + if ((lastDisarmReason != DISARM_SWITCH && lastDisarmReason != DISARM_KILLSWITCH) || + (currentTimeMs > US2MS(lastDisarmTimeUs) + EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS)) { return false; } - if (STATE(MULTIROTOR)) { - uint16_t mcFlightSanityCheckTime = EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS - 1500; // check MR vertical speed at least 1.5 sec after disarm - if (fabsf(getEstimatedActualVelocity(Z)) < 100.0f && (emergInflightRearmTimeout - currentTimeMs < mcFlightSanityCheckTime)) { - return false; // MR doesn't appear to be flying so don't allow emergency rearm - } else { - mcEmergRearmStabiliseTimeout = currentTimeMs + 5000; // activate Angle mode for 5s after rearm to help stabilise MR - } + if (isProbablyStillFlying()) { + emergRearmStabiliseTimeout = currentTimeMs + 5000; // activate Angle mode for 5s after rearm to help stabilise craft + return true; + } else if (STATE(MULTIROTOR) && (currentTimeMs > US2MS(lastDisarmTimeUs) + 1500) && fabsf(getEstimatedActualVelocity(Z)) > 100.0f) { + // allow emergency rearm if MR has vertical speed at least 1.5 sec after disarm indicating still flying + return true; } - return true; + return false; // craft doesn't appear to be flying, don't allow emergency rearm } void tryArm(void) @@ -564,7 +559,6 @@ void tryArm(void) } lastDisarmReason = DISARM_NONE; - emergInflightRearmTimeout = 0; ENABLE_ARMING_FLAG(ARMED); ENABLE_ARMING_FLAG(WAS_EVER_ARMED); @@ -667,9 +661,9 @@ void processRx(timeUs_t currentTimeUs) processRcAdjustments(CONST_CAST(controlRateConfig_t*, currentControlRateProfile), canUseRxData); } - // Angle mode forced on briefly after multirotor emergency inflight rearm to help stabilise attitude - bool mcEmergRearmAngleEnforce = STATE(MULTIROTOR) && mcEmergRearmStabiliseTimeout > millis(); - bool autoEnableAngle = failsafeRequiresAngleMode() || navigationRequiresAngleMode() || mcEmergRearmAngleEnforce; + // Angle mode forced on briefly after emergency inflight rearm to help stabilise attitude (currently limited to MR) + bool emergRearmAngleEnforce = STATE(MULTIROTOR) && emergRearmStabiliseTimeout > US2MS(currentTimeUs); + bool autoEnableAngle = failsafeRequiresAngleMode() || navigationRequiresAngleMode() || emergRearmAngleEnforce; bool canUseHorizonMode = true; if (sensors(SENSOR_ACC) && (IS_RC_MODE_ACTIVE(BOXANGLE) || autoEnableAngle)) { diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 759ddd42f3..eba38c68b1 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -61,6 +61,7 @@ #include "sensors/acceleration.h" #include "sensors/boardalignment.h" #include "sensors/battery.h" +#include "sensors/gyro.h" #include "programming/global_variables.h" @@ -2808,13 +2809,16 @@ void updateLandingStatus(timeMs_t currentTimeMs) DEBUG_SET(DEBUG_LANDING, 1, STATE(LANDING_DETECTED)); if (!ARMING_FLAG(ARMED)) { - resetLandingDetector(); - landingDetectorIsActive = false; - + if (STATE(LANDING_DETECTED)) { + resetLandingDetector(); + landingDetectorIsActive = false; + } if (!IS_RC_MODE_ACTIVE(BOXARM)) { DISABLE_ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED); } return; + } else if (getArmTime() < 0.25f && landingDetectorIsActive) { // force reset landing detector immediately after arming + landingDetectorIsActive = false; } if (!landingDetectorIsActive) { @@ -2854,10 +2858,14 @@ bool isFlightDetected(void) bool isProbablyStillFlying(void) { - // Multirotor flight sanity checked after disarm so always true here - bool inFlightSanityCheck = STATE(MULTIROTOR) || (STATE(AIRPLANE) && isGPSHeadingValid()); + bool inFlightSanityCheck; + if (STATE(MULTIROTOR)) { + inFlightSanityCheck = posControl.actualState.velXY > MC_LAND_CHECK_VEL_XY_MOVING || averageAbsGyroRates() > 4.0f; + } else { + inFlightSanityCheck = isGPSHeadingValid(); + } - return landingDetectorIsActive && !STATE(LANDING_DETECTED) && inFlightSanityCheck; + return landingDetectorIsActive && inFlightSanityCheck; } /*----------------------------------------------------------- From 1338fb4a54fcf891a175c5285ca48bfe991b34dd Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Mon, 28 Aug 2023 12:47:11 +0100 Subject: [PATCH 067/175] Update fc_core.h --- src/main/fc/fc_core.h | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/fc/fc_core.h b/src/main/fc/fc_core.h index 1d34e31742..37d0bbda79 100644 --- a/src/main/fc/fc_core.h +++ b/src/main/fc/fc_core.h @@ -43,7 +43,6 @@ void tryArm(void); disarmReason_t getDisarmReason(void); bool emergencyArmingUpdate(bool armingSwitchIsOn); -bool emergInflightRearmEnabled(void); bool areSensorsCalibrating(void); float getFlightTime(void); From 524b0d0bf41f73f621f0677023abd1bc8b2a3012 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Mon, 28 Aug 2023 17:48:55 +0100 Subject: [PATCH 068/175] Final updates - Converted Maths.h to tabs - Added leading zeros to odometer and decimal place --- src/main/common/maths.h | 93 ++++++++++++++-------------- src/main/fc/stats.h | 4 +- src/main/io/osd.c | 130 ++++++++++++++++++++-------------------- src/main/io/osd.h | 2 +- src/main/io/osd_hud.c | 12 ++-- src/main/io/osd_utils.c | 14 ++++- src/main/io/osd_utils.h | 2 +- 7 files changed, 133 insertions(+), 124 deletions(-) diff --git a/src/main/common/maths.h b/src/main/common/maths.h index cc3d1bc517..b803f64086 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -29,11 +29,11 @@ //#define VERY_FAST_MATH // order 7 approximation // Use floating point M_PI instead explicitly. -#define M_PIf 3.14159265358979323846f -#define M_LN2f 0.69314718055994530942f -#define M_Ef 2.71828182845904523536f +#define M_PIf 3.14159265358979323846f +#define M_LN2f 0.69314718055994530942f +#define M_Ef 2.71828182845904523536f -#define RAD (M_PIf / 180.0f) +#define RAD (M_PIf / 180.0f) #define DEGREES_TO_CENTIDEGREES(angle) ((angle) * 100) #define CENTIDEGREES_TO_DEGREES(angle) ((angle) / 100.0f) @@ -56,47 +56,47 @@ #define RADIANS_TO_CENTIDEGREES(angle) (((angle) * 100.0f) / RAD) #define CENTIDEGREES_TO_RADIANS(angle) (((angle) / 100.0f) * RAD) -#define CENTIMETERS_TO_CENTIFEET(cm) (cm / 0.3048f) -#define CENTIMETERS_TO_FEET(cm) (cm / 30.48f) -#define CENTIMETERS_TO_METERS(cm) (cm / 100.0f) +#define CENTIMETERS_TO_CENTIFEET(cm) (cm / 0.3048f) +#define CENTIMETERS_TO_FEET(cm) (cm / 30.48f) +#define CENTIMETERS_TO_METERS(cm) (cm / 100.0f) -#define METERS_TO_CENTIMETERS(m) (m * 100) +#define METERS_TO_CENTIMETERS(m) (m * 100) -#define CMSEC_TO_CENTIMPH(cms) (cms * 2.2369363f) -#define CMSEC_TO_CENTIKPH(cms) (cms * 3.6f) -#define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845f) +#define CMSEC_TO_CENTIMPH(cms) (cms * 2.2369363f) +#define CMSEC_TO_CENTIKPH(cms) (cms * 3.6f) +#define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845f) #define C_TO_KELVIN(temp) (temp + 273.15f) // Standard Sea Level values // Ref:https://en.wikipedia.org/wiki/Standard_sea_level -#define SSL_AIR_DENSITY 1.225f // kg/m^3 -#define SSL_AIR_PRESSURE 101325.01576f // Pascal -#define SSL_AIR_TEMPERATURE 288.15f // K +#define SSL_AIR_DENSITY 1.225f // kg/m^3 +#define SSL_AIR_PRESSURE 101325.01576f // Pascal +#define SSL_AIR_TEMPERATURE 288.15f // K // copied from https://code.google.com/p/cxutil/source/browse/include/cxutil/utility.h#70 -#define _CHOOSE2(binoper, lexpr, lvar, rexpr, rvar) \ - ( __extension__ ({ \ - __typeof__(lexpr) lvar = (lexpr); \ - __typeof__(rexpr) rvar = (rexpr); \ - lvar binoper rvar ? lvar : rvar; \ - })) +#define _CHOOSE2(binoper, lexpr, lvar, rexpr, rvar) \ + ( __extension__ ({ \ + __typeof__(lexpr) lvar = (lexpr); \ + __typeof__(rexpr) rvar = (rexpr); \ + lvar binoper rvar ? lvar : rvar; \ + })) #define _CHOOSE_VAR2(prefix, unique) prefix##unique #define _CHOOSE_VAR(prefix, unique) _CHOOSE_VAR2(prefix, unique) -#define _CHOOSE(binoper, lexpr, rexpr) \ - _CHOOSE2( \ - binoper, \ - lexpr, _CHOOSE_VAR(_left, __COUNTER__), \ - rexpr, _CHOOSE_VAR(_right, __COUNTER__) \ - ) +#define _CHOOSE(binoper, lexpr, rexpr) \ + _CHOOSE2( \ + binoper, \ + lexpr, _CHOOSE_VAR(_left, __COUNTER__), \ + rexpr, _CHOOSE_VAR(_right, __COUNTER__) \ + ) #define MIN(a, b) _CHOOSE(<, a, b) #define MAX(a, b) _CHOOSE(>, a, b) -#define _ABS_II(x, var) \ - ( __extension__ ({ \ - __typeof__(x) var = (x); \ - var < 0 ? -var : var; \ - })) +#define _ABS_II(x, var) \ + ( __extension__ ({ \ + __typeof__(x) var = (x); \ + var < 0 ? -var : var; \ + })) #define _ABS_I(x, var) _ABS_II(x, var) #define ABS(x) _ABS_I(x, _CHOOSE_VAR(_abs, __COUNTER__)) @@ -104,36 +104,35 @@ // Floating point Euler angles. typedef struct fp_angles { - float roll; - float pitch; - float yaw; + float roll; + float pitch; + float yaw; } fp_angles_def; typedef union { - float raw[3]; - fp_angles_def angles; + float raw[3]; + fp_angles_def angles; } fp_angles_t; -typedef struct stdev_s -{ - float m_oldM, m_newM, m_oldS, m_newS; - int m_n; +typedef struct stdev_s { + float m_oldM, m_newM, m_oldS, m_newS; + int m_n; } stdev_t; typedef struct filterWithBufferSample_s { - float value; - uint32_t timestamp; + float value; + uint32_t timestamp; } filterWithBufferSample_t; typedef struct filterWithBufferState_s { - uint16_t filter_size; - uint16_t sample_index; - filterWithBufferSample_t * samples; + uint16_t filter_size; + uint16_t sample_index; + filterWithBufferSample_t * samples; } filterWithBufferState_t; typedef struct { - float XtY[4]; - float XtX[4][4]; + float XtY[4]; + float XtX[4][4]; } sensorCalibrationState_t; void sensorCalibrationResetState(sensorCalibrationState_t * state); diff --git a/src/main/fc/stats.h b/src/main/fc/stats.h index 275460643c..54b676f657 100644 --- a/src/main/fc/stats.h +++ b/src/main/fc/stats.h @@ -3,8 +3,8 @@ #ifdef USE_STATS typedef struct statsConfig_s { - uint32_t stats_total_time; // [s] - uint32_t stats_total_dist; // [m] + uint32_t stats_total_time; // [Seconds] + uint32_t stats_total_dist; // [Metres] #ifdef USE_ADC uint32_t stats_total_energy; // deciWatt hour (x0.1Wh) #endif diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 395d78fee4..4fa8b56f3c 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -311,7 +311,7 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_MILE, decimals, 3, digits)) { + if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_MILE, decimals, 3, digits, false)) { buff[sym_index] = symbol_mi; } else { buff[sym_index] = symbol_ft; @@ -321,7 +321,7 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - if (osdFormatCentiNumber(buff, dist, METERS_PER_KILOMETER, decimals, 3, digits)) { + if (osdFormatCentiNumber(buff, dist, METERS_PER_KILOMETER, decimals, 3, digits, false)) { buff[sym_index] = symbol_km; } else { buff[sym_index] = symbol_m; @@ -329,7 +329,7 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) buff[sym_index + 1] = '\0'; break; case OSD_UNIT_GA: - if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), (uint32_t)FEET_PER_NAUTICALMILE, decimals, 3, digits)) { + if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), (uint32_t)FEET_PER_NAUTICALMILE, decimals, 3, digits, false)) { buff[sym_index] = symbol_nm; } else { buff[sym_index] = symbol_ft; @@ -484,7 +484,7 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) break; } - osdFormatCentiNumber(buff, centivalue, 0, 2, 0, 3); + osdFormatCentiNumber(buff, centivalue, 0, 2, 0, 3, false); if (!isValid && ((millis() / 1000) % 4 < 2)) suffix = '*'; @@ -557,7 +557,7 @@ void osdFormatAltitudeSymbol(char *buff, int32_t alt) case OSD_UNIT_GA: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - if (osdFormatCentiNumber(buff + totalDigits - digits, CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, digits)) { + if (osdFormatCentiNumber(buff + totalDigits - digits, CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, digits, false)) { // Scaled to kft buff[symbolIndex++] = symbolKFt; } else { @@ -570,7 +570,7 @@ void osdFormatAltitudeSymbol(char *buff, int32_t alt) FALLTHROUGH; case OSD_UNIT_METRIC: // alt is alredy in cm - if (osdFormatCentiNumber(buff + totalDigits - digits, alt, 1000, 0, 2, digits)) { + if (osdFormatCentiNumber(buff + totalDigits - digits, alt, 1000, 0, 2, digits, false)) { // Scaled to km buff[symbolIndex++] = SYM_ALT_KM; } else { @@ -1142,7 +1142,7 @@ static void osdFormatGVar(char *buff, uint8_t index) buff[1] = '0'+index; buff[2] = ':'; #ifdef USE_PROGRAMMING_FRAMEWORK - osdFormatCentiNumber(buff + 3, (int32_t)gvGet(index)*(int32_t)100, 1, 0, 0, 5); + osdFormatCentiNumber(buff + 3, (int32_t)gvGet(index)*(int32_t)100, 1, 0, 0, 5, false); #endif } @@ -1153,7 +1153,7 @@ static void osdFormatRpm(char *buff, uint32_t rpm) if (rpm) { if ( digitCount(rpm) > osdConfig()->esc_rpm_precision) { uint8_t rpmMaxDecimals = (osdConfig()->esc_rpm_precision - 3); - osdFormatCentiNumber(buff + 1, rpm / 10, 0, rpmMaxDecimals, rpmMaxDecimals, osdConfig()->esc_rpm_precision-1); + osdFormatCentiNumber(buff + 1, rpm / 10, 0, rpmMaxDecimals, rpmMaxDecimals, osdConfig()->esc_rpm_precision-1, false); buff[osdConfig()->esc_rpm_precision] = 'K'; buff[osdConfig()->esc_rpm_precision+1] = '\0'; } @@ -1477,13 +1477,13 @@ static void osdFormatPidControllerOutput(char *buff, const char *label, const pi strcpy(buff, label); for (uint8_t i = strlen(label); i < 5; ++i) buff[i] = ' '; uint8_t decimals = showDecimal ? 1 : 0; - osdFormatCentiNumber(buff + 5, pidController->proportional * scale, 0, decimals, 0, 4); + osdFormatCentiNumber(buff + 5, pidController->proportional * scale, 0, decimals, 0, 4, false); buff[9] = ' '; - osdFormatCentiNumber(buff + 10, pidController->integrator * scale, 0, decimals, 0, 4); + osdFormatCentiNumber(buff + 10, pidController->integrator * scale, 0, decimals, 0, 4, false); buff[14] = ' '; - osdFormatCentiNumber(buff + 15, pidController->derivative * scale, 0, decimals, 0, 4); + osdFormatCentiNumber(buff + 15, pidController->derivative * scale, 0, decimals, 0, 4, false); buff[19] = ' '; - osdFormatCentiNumber(buff + 20, pidController->output_constrained * scale, 0, decimals, 0, 4); + osdFormatCentiNumber(buff + 20, pidController->output_constrained * scale, 0, decimals, 0, 4, false); buff[24] = '\0'; } @@ -1499,7 +1499,7 @@ static void osdDisplayBatteryVoltage(uint8_t elemPosX, uint8_t elemPosY, uint16_ elemAttr = TEXT_ATTRIBUTES_NONE; digits = MIN(digits, 5); - osdFormatCentiNumber(buff, voltage, 0, decimals, 0, digits); + osdFormatCentiNumber(buff, voltage, 0, decimals, 0, digits, false); buff[digits] = SYM_VOLT; buff[digits+1] = '\0'; const batteryState_e batteryVoltageState = checkBatteryVoltageState(); @@ -1593,7 +1593,7 @@ static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY, displayWrite(osdDisplayPort, elemPosX, elemPosY, str); elemAttr = TEXT_ATTRIBUTES_NONE; - osdFormatCentiNumber(buff, value * 100, 0, maxDecimals, 0, MIN(valueLength, 8)); + osdFormatCentiNumber(buff, value * 100, 0, maxDecimals, 0, MIN(valueLength, 8), false); if (isAdjustmentFunctionSelected(adjFunc)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); displayWriteWithAttr(osdDisplayPort, elemPosX + strlen(str) + 1 + valueOffset, elemPosY, buff, elemAttr); @@ -1698,7 +1698,7 @@ static bool osdDrawSingleElement(uint8_t item) } case OSD_CURRENT_DRAW: { - osdFormatCentiNumber(buff, getAmperage(), 0, 2, 0, 3); + osdFormatCentiNumber(buff, getAmperage(), 0, 2, 0, 3, false); buff[3] = SYM_AMP; buff[4] = '\0'; @@ -1725,7 +1725,7 @@ static bool osdDrawSingleElement(uint8_t item) buff[5] = SYM_MAH; buff[6] = '\0'; } else { - if (osdFormatCentiNumber(buff, getMAhDrawn() * 100, 1000, 0, (mah_digits - 2), mah_digits)) { + if (osdFormatCentiNumber(buff, getMAhDrawn() * 100, 1000, 0, (mah_digits - 2), mah_digits, false)) { // Shown in Ah buff[mah_digits] = SYM_AH; } else { @@ -1740,7 +1740,7 @@ static bool osdDrawSingleElement(uint8_t item) } case OSD_WH_DRAWN: - osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3); + osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3, false); osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); buff[3] = SYM_WH; buff[4] = '\0'; @@ -1755,7 +1755,7 @@ static bool osdDrawSingleElement(uint8_t item) else if (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH) tfp_sprintf(buff, "%4lu", (unsigned long)getBatteryRemainingCapacity()); else // currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH - osdFormatCentiNumber(buff + 1, getBatteryRemainingCapacity() / 10, 0, 2, 0, 3); + osdFormatCentiNumber(buff + 1, getBatteryRemainingCapacity() / 10, 0, 2, 0, 3, false); buff[4] = currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH ? SYM_MAH : SYM_WH; buff[5] = '\0'; @@ -1823,7 +1823,7 @@ static bool osdDrawSingleElement(uint8_t item) buff[0] = SYM_GLIDESLOPE; if (glideSlope > 0.0f && glideSlope < 100.0f) { - osdFormatCentiNumber(buff + 1, glideSlope * 100.0f, 0, 2, 0, 3); + osdFormatCentiNumber(buff + 1, glideSlope * 100.0f, 0, 2, 0, 3, false); } else { buff[1] = buff[2] = buff[3] = '-'; } @@ -1904,30 +1904,32 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_ODOMETER: { displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_ODOMETER); - uint32_t odometerDist = getTotalTravelDistance() / 100; + uint32_t odometerDist = (uint32_t)(getTotalTravelDistance() / 100); #ifdef USE_STATS odometerDist+= statsConfig()->stats_total_dist; #endif + odometerDist = odometerDist / 10; + switch (osdConfig()->units) { case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - tfp_sprintf(buff, "%5d", (int)(odometerDist / METERS_PER_MILE)); - buff[5] = SYM_MI; + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(odometerDist), FEET_PER_MILE, 1, 0, 6, true); + buff[6] = SYM_MI; break; default: case OSD_UNIT_GA: - tfp_sprintf(buff, "%5d", (int)(odometerDist / METERS_PER_NAUTICALMILE)); - buff[5] = SYM_NM; + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(odometerDist), (uint32_t)FEET_PER_NAUTICALMILE, 1, 0, 6, true); + buff[6] = SYM_NM; break; case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - tfp_sprintf(buff, "%5d", (int)(odometerDist / METERS_PER_KILOMETER)); - buff[5] = SYM_KM; + osdFormatCentiNumber(buff, odometerDist, METERS_PER_KILOMETER, 1, 0, 6, true); + buff[6] = SYM_KM; break; } - buff[6] = '\0'; + buff[7] = '\0'; elemPosX++; } break; @@ -2014,7 +2016,7 @@ static bool osdDrawSingleElement(uint8_t item) digits = 3U; } #endif - osdFormatCentiNumber(&buff[2], centiHDOP, 0, 1, 0, digits); + osdFormatCentiNumber(&buff[2], centiHDOP, 0, 1, 0, digits, false); break; } @@ -2444,7 +2446,7 @@ static bool osdDrawSingleElement(uint8_t item) buff[0] = SYM_ROLL_LEVEL; if (ABS(attitude.values.roll) >= 1) buff[0] += (attitude.values.roll < 0 ? -1 : 1); - osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.roll)), 0, 1, 0, 3); + osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.roll)), 0, 1, 0, 3, false); break; case OSD_ATTITUDE_PITCH: @@ -2454,7 +2456,7 @@ static bool osdDrawSingleElement(uint8_t item) buff[0] = SYM_PITCH_DOWN; else if (attitude.values.pitch < 0) buff[0] = SYM_PITCH_UP; - osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.pitch)), 0, 1, 0, 3); + osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.pitch)), 0, 1, 0, 3, false); break; case OSD_ARTIFICIAL_HORIZON: @@ -2515,7 +2517,7 @@ static bool osdDrawSingleElement(uint8_t item) break; } - osdFormatCentiNumber(buff, value, 0, 1, 0, 3); + osdFormatCentiNumber(buff, value, 0, 1, 0, 3, false); buff[3] = sym; buff[4] = '\0'; break; @@ -2548,7 +2550,7 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_UNIT_IMPERIAL: // mAh/foot if (efficiencyValid) { - osdFormatCentiNumber(buff, (value * METERS_PER_FOOT), 1, 2, 2, 3); + osdFormatCentiNumber(buff, (value * METERS_PER_FOOT), 1, 2, 2, 3, false); tfp_sprintf(buff, "%s%c%c", buff, SYM_AH_V_FT_0, SYM_AH_V_FT_1); } else { buff[0] = buff[1] = buff[2] = '-'; @@ -2562,7 +2564,7 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_UNIT_METRIC: // mAh/metre if (efficiencyValid) { - osdFormatCentiNumber(buff, value, 1, 2, 2, 3); + osdFormatCentiNumber(buff, value, 1, 2, 2, 3, false); tfp_sprintf(buff, "%s%c%c", buff, SYM_AH_V_M_0, SYM_AH_V_M_1); } else { buff[0] = buff[1] = buff[2] = '-'; @@ -2857,7 +2859,7 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_POWER: { - bool kiloWatt = osdFormatCentiNumber(buff, getPower(), 1000, 2, 2, 3); + bool kiloWatt = osdFormatCentiNumber(buff, getPower(), 1000, 2, 2, 3, false); buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; buff[4] = '\0'; @@ -3020,7 +3022,7 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10, 1000, 0, 2, digits); + moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10, 1000, 0, 2, digits, false); if (!moreThanAh) { tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); } else { @@ -3034,7 +3036,7 @@ static bool osdDrawSingleElement(uint8_t item) } break; case OSD_UNIT_GA: - moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10, 1000, 0, 2, digits); + moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10, 1000, 0, 2, digits, false); if (!moreThanAh) { tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); } else { @@ -3050,7 +3052,7 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - moreThanAh = osdFormatCentiNumber(buff, value * 100, 1000, 0, 2, digits); + moreThanAh = osdFormatCentiNumber(buff, value * 100, 1000, 0, 2, digits, false); if (!moreThanAh) { tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); } else { @@ -3091,17 +3093,17 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10000, 0, 2, 0, 3); + osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10000, 0, 2, 0, 3, false); buff[3] = SYM_WH_MI; break; case OSD_UNIT_GA: - osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10000, 0, 2, 0, 3); + osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10000, 0, 2, 0, 3, false); buff[3] = SYM_WH_NM; break; case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - osdFormatCentiNumber(buff, value / 10, 0, 2, 0, 3); + osdFormatCentiNumber(buff, value / 10, 0, 2, 0, 3, false); buff[3] = SYM_WH_KM; break; } @@ -3115,7 +3117,7 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_GFORCE: { buff[0] = SYM_GFORCE; - osdFormatCentiNumber(buff + 1, GForce, 0, 2, 0, 3); + osdFormatCentiNumber(buff + 1, GForce, 0, 2, 0, 3, false); if (GForce > osdConfig()->gforce_alarm * 100) { TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); } @@ -3128,7 +3130,7 @@ static bool osdDrawSingleElement(uint8_t item) { float GForceValue = GForceAxis[item - OSD_GFORCE_X]; buff[0] = SYM_GFORCE_X + item - OSD_GFORCE_X; - osdFormatCentiNumber(buff + 1, GForceValue, 0, 2, 0, 4); + osdFormatCentiNumber(buff + 1, GForceValue, 0, 2, 0, 4, false); if ((GForceValue < osdConfig()->gforce_axis_alarm_min * 100) || (GForceValue > osdConfig()->gforce_axis_alarm_max * 100)) { TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); } @@ -3304,7 +3306,7 @@ static bool osdDrawSingleElement(uint8_t item) } buff[0] = SYM_SCALE; if (osdMapData.scale > 0) { - bool scaled = osdFormatCentiNumber(&buff[1], osdMapData.scale * scaleToUnit, scaleUnitDivisor, maxDecimals, 2, 3); + bool scaled = osdFormatCentiNumber(&buff[1], osdMapData.scale * scaleToUnit, scaleUnitDivisor, maxDecimals, 2, 3, false); buff[4] = scaled ? symScaled : symUnscaled; // Make sure this is cleared if the map stops being drawn osdMapData.scale = 0; @@ -3473,14 +3475,14 @@ static bool osdDrawSingleElement(uint8_t item) #ifdef USE_POWER_LIMITS case OSD_PLIMIT_REMAINING_BURST_TIME: - osdFormatCentiNumber(buff, powerLimiterGetRemainingBurstTime() * 100, 0, 1, 0, 3); + osdFormatCentiNumber(buff, powerLimiterGetRemainingBurstTime() * 100, 0, 1, 0, 3, false); buff[3] = 'S'; buff[4] = '\0'; break; case OSD_PLIMIT_ACTIVE_CURRENT_LIMIT: if (currentBatteryProfile->powerLimits.continuousCurrent) { - osdFormatCentiNumber(buff, powerLimiterGetActiveCurrentLimit(), 0, 2, 0, 3); + osdFormatCentiNumber(buff, powerLimiterGetActiveCurrentLimit(), 0, 2, 0, 3, false); buff[3] = SYM_AMP; buff[4] = '\0'; @@ -3494,7 +3496,7 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_PLIMIT_ACTIVE_POWER_LIMIT: { if (currentBatteryProfile->powerLimits.continuousPower) { - bool kiloWatt = osdFormatCentiNumber(buff, powerLimiterGetActivePowerLimit(), 1000, 2, 2, 3); + bool kiloWatt = osdFormatCentiNumber(buff, powerLimiterGetActivePowerLimit(), 1000, 2, 2, 3, false); buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; buff[4] = '\0'; @@ -4017,7 +4019,7 @@ static void osdCompleteAsyncInitialization(void) #ifdef USE_ADC if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) { displayWrite(osdDisplayPort, statNameX, ++y, "TOTAL ENERGY:"); - osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4); + osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4, false); strcat(string_buffer, "\xAB"); // SYM_WH displayWrite(osdDisplayPort, statValueX-4, y, string_buffer); @@ -4028,18 +4030,18 @@ static void osdCompleteAsyncInitialization(void) case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); + osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3, false); string_buffer[3] = SYM_WH_MI; break; case OSD_UNIT_GA: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); + osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3, false); string_buffer[3] = SYM_WH_NM; break; default: case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3); + osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3, false); string_buffer[3] = SYM_WH_KM; break; } @@ -4254,22 +4256,22 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) if (isSinglePageStatsCompatible || page == 1) { if (osdConfig()->stats_min_voltage_unit == OSD_STATS_MIN_VOLTAGE_UNIT_BATTERY) { displayWrite(osdDisplayPort, statNameX, top, "MIN BATTERY VOLT :"); - osdFormatCentiNumber(buff, stats.min_voltage, 0, osdConfig()->main_voltage_decimals, 0, osdConfig()->main_voltage_decimals + 2); + osdFormatCentiNumber(buff, stats.min_voltage, 0, osdConfig()->main_voltage_decimals, 0, osdConfig()->main_voltage_decimals + 2, false); } else { displayWrite(osdDisplayPort, statNameX, top, "MIN CELL VOLTAGE :"); - osdFormatCentiNumber(buff, stats.min_voltage/getBatteryCellCount(), 0, 2, 0, 3); + osdFormatCentiNumber(buff, stats.min_voltage/getBatteryCellCount(), 0, 2, 0, 3, false); } tfp_sprintf(buff, "%s%c", buff, SYM_VOLT); displayWrite(osdDisplayPort, statValuesX, top++, buff); if (feature(FEATURE_CURRENT_METER)) { displayWrite(osdDisplayPort, statNameX, top, "MAX CURRENT :"); - osdFormatCentiNumber(buff, stats.max_current, 0, 2, 0, 3); + osdFormatCentiNumber(buff, stats.max_current, 0, 2, 0, 3, false); tfp_sprintf(buff, "%s%c", buff, SYM_AMP); displayWrite(osdDisplayPort, statValuesX, top++, buff); displayWrite(osdDisplayPort, statNameX, top, "MAX POWER :"); - bool kiloWatt = osdFormatCentiNumber(buff, stats.max_power, 1000, 2, 2, 3); + bool kiloWatt = osdFormatCentiNumber(buff, stats.max_power, 1000, 2, 2, 3, false); buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; buff[4] = '\0'; displayWrite(osdDisplayPort, statValuesX, top++, buff); @@ -4278,7 +4280,7 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { tfp_sprintf(buff, "%d%c", (int)getMAhDrawn(), SYM_MAH); } else { - osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3); + osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3, false); tfp_sprintf(buff, "%s%c", buff, SYM_WH); } displayWrite(osdDisplayPort, statValuesX, top++, buff); @@ -4300,7 +4302,7 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) FALLTHROUGH; case OSD_UNIT_IMPERIAL: if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_MILE / totalDistance), 1000, 0, 2, digits); + moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_MILE / totalDistance), 1000, 0, 2, digits, false); if (!moreThanAh) { tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); } else { @@ -4313,7 +4315,7 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) buff[5] = '\0'; } } else { - osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits); + osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits, false); tfp_sprintf(buff, "%s%c", buff, SYM_WH_MI); if (!efficiencyValid) { buff[0] = buff[1] = buff[2] = '-'; @@ -4322,7 +4324,7 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) break; case OSD_UNIT_GA: if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_NAUTICALMILE / totalDistance), 1000, 0, 2, digits); + moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_NAUTICALMILE / totalDistance), 1000, 0, 2, digits, false); if (!moreThanAh) { tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); } else { @@ -4335,7 +4337,7 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) buff[5] = '\0'; } } else { - osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_NAUTICALMILE / totalDistance), 0, 2, 0, digits); + osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_NAUTICALMILE / totalDistance), 0, 2, 0, digits, false); tfp_sprintf(buff, "%s%c", buff, SYM_WH_NM); if (!efficiencyValid) { buff[0] = buff[1] = buff[2] = '-'; @@ -4346,7 +4348,7 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) FALLTHROUGH; case OSD_UNIT_METRIC: if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000000.0f / totalDistance), 1000, 0, 2, digits); + moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000000.0f / totalDistance), 1000, 0, 2, digits, false); if (!moreThanAh) { tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); } else { @@ -4359,7 +4361,7 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) buff[5] = '\0'; } } else { - osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10000.0f / totalDistance), 0, 2, 0, digits); + osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10000.0f / totalDistance), 0, 2, 0, digits, false); tfp_sprintf(buff, "%s%c", buff, SYM_WH_KM); if (!efficiencyValid) { buff[0] = buff[1] = buff[2] = '-'; @@ -4374,19 +4376,19 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) const float max_gforce = accGetMeasuredMaxG(); displayWrite(osdDisplayPort, statNameX, top, "MAX G-FORCE :"); - osdFormatCentiNumber(buff, max_gforce * 100, 0, 2, 0, 3); + osdFormatCentiNumber(buff, max_gforce * 100, 0, 2, 0, 3, false); displayWrite(osdDisplayPort, statValuesX, top++, buff); const acc_extremes_t *acc_extremes = accGetMeasuredExtremes(); const float acc_extremes_min = acc_extremes[Z].min; const float acc_extremes_max = acc_extremes[Z].max; displayWrite(osdDisplayPort, statNameX, top, "MIN/MAX Z G-FORCE:"); - osdFormatCentiNumber(buff, acc_extremes_min * 100, 0, 2, 0, 4); + osdFormatCentiNumber(buff, acc_extremes_min * 100, 0, 2, 0, 4, false); osdLeftAlignString(buff); strcat(osdFormatTrimWhiteSpace(buff),"/"); multiValueLengthOffset = strlen(buff); displayWrite(osdDisplayPort, statValuesX, top, buff); - osdFormatCentiNumber(buff, acc_extremes_max * 100, 0, 2, 0, 3); + osdFormatCentiNumber(buff, acc_extremes_max * 100, 0, 2, 0, 3, false); osdLeftAlignString(buff); displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); } diff --git a/src/main/io/osd.h b/src/main/io/osd.h index efbee5beda..bf022bf9ab 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -483,7 +483,7 @@ void osdStartedSaveProcess(void); void osdShowEEPROMSavedNotification(void); void osdCrosshairPosition(uint8_t *x, uint8_t *y); -bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length); +bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length, bool leadingZeros); void osdFormatAltitudeSymbol(char *buff, int32_t alt); void osdFormatVelocityStr(char* buff, int32_t vel, bool _3D, bool _max); // Returns a heading angle in degrees normalized to [0, 360). diff --git a/src/main/io/osd_hud.c b/src/main/io/osd_hud.c index 2e209fd282..47cc96f834 100644 --- a/src/main/io/osd_hud.c +++ b/src/main/io/osd_hud.c @@ -256,18 +256,18 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu case OSD_UNIT_IMPERIAL: { if (poiType == 1) { - osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 4, 4); + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 4, 4, false); } else { - osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 3, 3); + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 3, 3, false); } } break; case OSD_UNIT_GA: { if (poiType == 1) { - osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), (uint32_t)FEET_PER_NAUTICALMILE, 0, 4, 4); + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), (uint32_t)FEET_PER_NAUTICALMILE, 0, 4, 4, false); } else { - osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), (uint32_t)FEET_PER_NAUTICALMILE, 0, 3, 3); + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), (uint32_t)FEET_PER_NAUTICALMILE, 0, 3, 3, false); } } break; @@ -278,9 +278,9 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu case OSD_UNIT_METRIC: { if (poiType == 1) { - osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 4, 4); + osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 4, 4, false); } else { - osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 3, 3); + osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 3, 3, false); } } break; diff --git a/src/main/io/osd_utils.c b/src/main/io/osd_utils.c index 194be36f95..6675be8783 100644 --- a/src/main/io/osd_utils.c +++ b/src/main/io/osd_utils.c @@ -38,7 +38,7 @@ int digitCount(int32_t value) } -bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length) +bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length, bool leadingZeros) { char *ptr = buff; char *dec; @@ -86,7 +86,11 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma // Done counting. Time to write the characters. // Write spaces at the start while (remaining > 0) { - *ptr = SYM_BLANK; + if (leadingZeros) + *ptr = '0'; + else + *ptr = SYM_BLANK; + ptr++; remaining--; } @@ -98,7 +102,11 @@ bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int ma // Add any needed remaining leading spaces while(rem_spaces > 0) { - *ptr = SYM_BLANK; + if (leadingZeros) + *ptr = '0'; + else + *ptr = SYM_BLANK; + ptr++; remaining--; rem_spaces--; diff --git a/src/main/io/osd_utils.h b/src/main/io/osd_utils.h index 2f9c61a320..7f10f2bf8f 100644 --- a/src/main/io/osd_utils.h +++ b/src/main/io/osd_utils.h @@ -33,6 +33,6 @@ int digitCount(int32_t value); * of the same length. If the value doesn't fit into the provided length * it will be divided by scale and true will be returned. */ -bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length); +bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length, bool leadingZeros); #endif From 2d2195d841b31ace59b94831595a9e22cd366f25 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Tue, 29 Aug 2023 11:41:39 +0100 Subject: [PATCH 069/175] fix landing detector active state logic --- src/main/fc/fc_core.c | 2 ++ src/main/navigation/navigation.c | 13 +++++++------ src/main/navigation/navigation.h | 1 + 3 files changed, 10 insertions(+), 6 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index a00e797242..92705ab691 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -558,6 +558,8 @@ void tryArm(void) ENABLE_STATE(NAV_EXTRA_ARMING_SAFETY_BYPASSED); } + resetLandingDetectorActiveState(); // reset landing detector after arming to avoid false detection before flight + lastDisarmReason = DISARM_NONE; ENABLE_ARMING_FLAG(ARMED); diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index eba38c68b1..63c5b9884a 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2809,16 +2809,12 @@ void updateLandingStatus(timeMs_t currentTimeMs) DEBUG_SET(DEBUG_LANDING, 1, STATE(LANDING_DETECTED)); if (!ARMING_FLAG(ARMED)) { - if (STATE(LANDING_DETECTED)) { - resetLandingDetector(); - landingDetectorIsActive = false; - } + resetLandingDetector(); + if (!IS_RC_MODE_ACTIVE(BOXARM)) { DISABLE_ARMING_FLAG(ARMING_DISABLED_LANDING_DETECTED); } return; - } else if (getArmTime() < 0.25f && landingDetectorIsActive) { // force reset landing detector immediately after arming - landingDetectorIsActive = false; } if (!landingDetectorIsActive) { @@ -2851,6 +2847,11 @@ void resetLandingDetector(void) posControl.flags.resetLandingDetector = true; } +void resetLandingDetectorActiveState(void) +{ + landingDetectorIsActive = false; +} + bool isFlightDetected(void) { return STATE(AIRPLANE) ? isFixedWingFlying() : isMulticopterFlying(); diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 9ffe532e6c..3fd213a245 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -611,6 +611,7 @@ float calculateAverageSpeed(void); void updateLandingStatus(timeMs_t currentTimeMs); bool isProbablyStillFlying(void); +void resetLandingDetectorActiveState(void); const navigationPIDControllers_t* getNavigationPIDControllers(void); From 89d62544b7b62f0a0e8d2c3679703caea15ff622 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Wed, 30 Aug 2023 18:49:29 +0100 Subject: [PATCH 070/175] More updates - Added use pilot logo option to CLI - Converted osd.h to use tabs --- docs/Settings.md | 10 + src/main/fc/settings.yaml | 6 + src/main/io/osd.c | 1 + src/main/io/osd.h | 687 +++++++++++++++++++------------------- 4 files changed, 360 insertions(+), 344 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 048e8de9d2..bfbb1e7e12 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -4722,6 +4722,16 @@ IMPERIAL, METRIC, UK --- +### osd_use_pilot_logo + +Use custom pilot logo with/instead of the INAV logo. The pilot logo must be characters 473 to 511 + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + ### osd_video_system Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, 'DJIWTF', 'AVATAR' and `BF43COMPAT` diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index b11169b6ac..c63972fefd 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3480,6 +3480,12 @@ groups: max: 6 default_value: 4 + - name: osd_use_pilot_logo + description: Use custom pilot logo with/instead of the INAV logo. The pilot logo must be characters 473 to 511 + field: use_pilot_logo + type: bool + default_value: OFF + - name: osd_switch_indicator_zero_name description: "Character to use for OSD switch incicator 0." field: osd_switch_indicator0_name diff --git a/src/main/io/osd.c b/src/main/io/osd.c index f6289520bc..49cdee582d 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -3673,6 +3673,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .system_msg_display_time = SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_DEFAULT, .units = SETTING_OSD_UNITS_DEFAULT, .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT, + .use_pilot_logo = SETTINGS_OSD_USE_PILOT_LOGO_DEFAULT #ifdef USE_WIND_ESTIMATOR .estimations_wind_compensation = SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT, diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 2dad5ceb81..afe651a8d6 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -32,19 +32,19 @@ // 00vb yyyy yyxx xxxx // (visible)(blink)(yCoord)(xCoord) -#define OSD_VISIBLE_FLAG 0x2000 -#define OSD_VISIBLE(x) ((x) & OSD_VISIBLE_FLAG) +#define OSD_VISIBLE_FLAG 0x2000 +#define OSD_VISIBLE(x) ((x) & OSD_VISIBLE_FLAG) -#define OSD_POS(x,y) (((x) & 0x3F) | (((y) & 0x3F) << 6)) -#define OSD_X(x) ((x) & 0x3F) -#define OSD_Y(x) (((x) >> 6) & 0x3F) -#define OSD_POS_MAX 0xFFF +#define OSD_POS(x,y) (((x) & 0x3F) | (((y) & 0x3F) << 6)) +#define OSD_X(x) ((x) & 0x3F) +#define OSD_Y(x) (((x) >> 6) & 0x3F) +#define OSD_POS_MAX 0xFFF // For DJI compatibility #define OSD_VISIBLE_FLAG_SD 0x0800 -#define OSD_POS_SD(x,y) (((x) & 0x1F) | (((y) & 0x1F) << 5)) +#define OSD_POS_SD(x,y) (((x) & 0x1F) | (((y) & 0x1F) << 5)) -#define OSD_POS_MAX_CLI (OSD_POS_MAX | OSD_VISIBLE_FLAG) +#define OSD_POS_MAX_CLI (OSD_POS_MAX | OSD_VISIBLE_FLAG) #define OSD_HOMING_LIM_H1 6 #define OSD_HOMING_LIM_H2 16 @@ -54,286 +54,286 @@ #define OSD_HOMING_LIM_V3 15 // Message defines to be use in OSD and/or telemetry exports -#define OSD_MSG_RC_RX_LINK_LOST "!RC RX LINK LOST!" -#define OSD_MSG_TURN_ARM_SW_OFF "TURN ARM SWITCH OFF" -#define OSD_MSG_DISABLED_BY_FS "DISABLED BY FAILSAFE" -#define OSD_MSG_AIRCRAFT_UNLEVEL "AIRCRAFT IS NOT LEVEL" -#define OSD_MSG_SENSORS_CAL "SENSORS CALIBRATING" -#define OSD_MSG_SYS_OVERLOADED "SYSTEM OVERLOADED" -#define OSD_MSG_WAITING_GPS_FIX "WAITING FOR GPS FIX" -#define OSD_MSG_DISABLE_NAV_FIRST "DISABLE NAVIGATION FIRST" -#define OSD_MSG_JUMP_WP_MISCONFIG "JUMP WAYPOINT MISCONFIGURED" -#define OSD_MSG_MAG_NOT_CAL "COMPASS NOT CALIBRATED" -#define OSD_MSG_ACC_NOT_CAL "ACCELEROMETER NOT CALIBRATED" -#define OSD_MSG_DISARM_1ST "DISABLE ARM SWITCH FIRST" -#define OSD_MSG_GYRO_FAILURE "GYRO FAILURE" -#define OSD_MSG_ACC_FAIL "ACCELEROMETER FAILURE" -#define OSD_MSG_MAG_FAIL "COMPASS FAILURE" -#define OSD_MSG_BARO_FAIL "BAROMETER FAILURE" -#define OSD_MSG_GPS_FAIL "GPS FAILURE" -#define OSD_MSG_RANGEFINDER_FAIL "RANGE FINDER FAILURE" -#define OSD_MSG_PITOT_FAIL "PITOT METER FAILURE" -#define OSD_MSG_HW_FAIL "HARDWARE FAILURE" -#define OSD_MSG_FS_EN "FAILSAFE MODE ENABLED" -#define OSD_MSG_KILL_SW_EN "KILLSWITCH MODE ENABLED" -#define OSD_MSG_NO_RC_LINK "NO RC LINK" -#define OSD_MSG_THROTTLE_NOT_LOW "THROTTLE IS NOT LOW" -#define OSD_MSG_ROLLPITCH_OFFCENTER "ROLLPITCH NOT CENTERED" -#define OSD_MSG_AUTOTRIM_ACTIVE "AUTOTRIM IS ACTIVE" -#define OSD_MSG_NOT_ENOUGH_MEMORY "NOT ENOUGH MEMORY" -#define OSD_MSG_INVALID_SETTING "INVALID SETTING" -#define OSD_MSG_CLI_ACTIVE "CLI IS ACTIVE" -#define OSD_MSG_PWM_INIT_ERROR "PWM INIT ERROR" -#define OSD_MSG_NO_PREARM "NO PREARM" -#define OSD_MSG_DSHOT_BEEPER "MOTOR BEEPER ACTIVE" -#define OSD_MSG_RTH_FS "(RTH)" -#define OSD_MSG_EMERG_LANDING_FS "(EMERGENCY LANDING)" -#define OSD_MSG_MOVE_EXIT_FS "!MOVE STICKS TO EXIT FS!" -#define OSD_MSG_STARTING_RTH "STARTING RTH" -#define OSD_MSG_RTH_CLIMB "ADJUSTING RTH ALTITUDE" -#define OSD_MSG_RTH_TRACKBACK "RTH BACK TRACKING" -#define OSD_MSG_HEADING_HOME "EN ROUTE TO HOME" -#define OSD_MSG_WP_FINISHED "WP END>HOLDING POSITION" -#define OSD_MSG_WP_LANDED "WP END>LANDED" -#define OSD_MSG_PREPARE_NEXT_WP "PREPARING FOR NEXT WAYPOINT" -#define OSD_MSG_ADJUSTING_WP_ALT "ADJUSTING WP ALTITUDE" -#define OSD_MSG_MISSION_PLANNER "(WP MISSION PLANNER)" -#define OSD_MSG_WP_RTH_CANCEL "CANCEL WP TO EXIT RTH" -#define OSD_MSG_WP_MISSION_LOADED "* MISSION LOADED *" -#define OSD_MSG_EMERG_LANDING "EMERGENCY LANDING" -#define OSD_MSG_LANDING "LANDING" -#define OSD_MSG_LOITERING_HOME "LOITERING AROUND HOME" -#define OSD_MSG_HOVERING "HOVERING" -#define OSD_MSG_LANDED "LANDED" -#define OSD_MSG_PREPARING_LAND "PREPARING TO LAND" -#define OSD_MSG_AUTOLAUNCH "AUTOLAUNCH" -#define OSD_MSG_AUTOLAUNCH_MANUAL "AUTOLAUNCH (MANUAL)" -#define OSD_MSG_ALTITUDE_HOLD "(ALTITUDE HOLD)" -#define OSD_MSG_AUTOTRIM "(AUTOTRIM)" -#define OSD_MSG_AUTOTUNE "(AUTOTUNE)" -#define OSD_MSG_AUTOTUNE_ACRO "SWITCH TO ACRO" -#define OSD_MSG_AUTOLEVEL "(AUTO LEVEL TRIM)" -#define OSD_MSG_HEADFREE "(HEADFREE)" -#define OSD_MSG_NAV_SOARING "(SOARING)" -#define OSD_MSG_UNABLE_ARM "UNABLE TO ARM" -#define OSD_MSG_SAVING_SETTNGS "** SAVING SETTINGS **" -#define OSD_MSG_SETTINGS_SAVED "** SETTINGS SAVED **" +#define OSD_MSG_RC_RX_LINK_LOST "!RC RX LINK LOST!" +#define OSD_MSG_TURN_ARM_SW_OFF "TURN ARM SWITCH OFF" +#define OSD_MSG_DISABLED_BY_FS "DISABLED BY FAILSAFE" +#define OSD_MSG_AIRCRAFT_UNLEVEL "AIRCRAFT IS NOT LEVEL" +#define OSD_MSG_SENSORS_CAL "SENSORS CALIBRATING" +#define OSD_MSG_SYS_OVERLOADED "SYSTEM OVERLOADED" +#define OSD_MSG_WAITING_GPS_FIX "WAITING FOR GPS FIX" +#define OSD_MSG_DISABLE_NAV_FIRST "DISABLE NAVIGATION FIRST" +#define OSD_MSG_JUMP_WP_MISCONFIG "JUMP WAYPOINT MISCONFIGURED" +#define OSD_MSG_MAG_NOT_CAL "COMPASS NOT CALIBRATED" +#define OSD_MSG_ACC_NOT_CAL "ACCELEROMETER NOT CALIBRATED" +#define OSD_MSG_DISARM_1ST "DISABLE ARM SWITCH FIRST" +#define OSD_MSG_GYRO_FAILURE "GYRO FAILURE" +#define OSD_MSG_ACC_FAIL "ACCELEROMETER FAILURE" +#define OSD_MSG_MAG_FAIL "COMPASS FAILURE" +#define OSD_MSG_BARO_FAIL "BAROMETER FAILURE" +#define OSD_MSG_GPS_FAIL "GPS FAILURE" +#define OSD_MSG_RANGEFINDER_FAIL "RANGE FINDER FAILURE" +#define OSD_MSG_PITOT_FAIL "PITOT METER FAILURE" +#define OSD_MSG_HW_FAIL "HARDWARE FAILURE" +#define OSD_MSG_FS_EN "FAILSAFE MODE ENABLED" +#define OSD_MSG_KILL_SW_EN "KILLSWITCH MODE ENABLED" +#define OSD_MSG_NO_RC_LINK "NO RC LINK" +#define OSD_MSG_THROTTLE_NOT_LOW "THROTTLE IS NOT LOW" +#define OSD_MSG_ROLLPITCH_OFFCENTER "ROLLPITCH NOT CENTERED" +#define OSD_MSG_AUTOTRIM_ACTIVE "AUTOTRIM IS ACTIVE" +#define OSD_MSG_NOT_ENOUGH_MEMORY "NOT ENOUGH MEMORY" +#define OSD_MSG_INVALID_SETTING "INVALID SETTING" +#define OSD_MSG_CLI_ACTIVE "CLI IS ACTIVE" +#define OSD_MSG_PWM_INIT_ERROR "PWM INIT ERROR" +#define OSD_MSG_NO_PREARM "NO PREARM" +#define OSD_MSG_DSHOT_BEEPER "MOTOR BEEPER ACTIVE" +#define OSD_MSG_RTH_FS "(RTH)" +#define OSD_MSG_EMERG_LANDING_FS "(EMERGENCY LANDING)" +#define OSD_MSG_MOVE_EXIT_FS "!MOVE STICKS TO EXIT FS!" +#define OSD_MSG_STARTING_RTH "STARTING RTH" +#define OSD_MSG_RTH_CLIMB "ADJUSTING RTH ALTITUDE" +#define OSD_MSG_RTH_TRACKBACK "RTH BACK TRACKING" +#define OSD_MSG_HEADING_HOME "EN ROUTE TO HOME" +#define OSD_MSG_WP_FINISHED "WP END>HOLDING POSITION" +#define OSD_MSG_WP_LANDED "WP END>LANDED" +#define OSD_MSG_PREPARE_NEXT_WP "PREPARING FOR NEXT WAYPOINT" +#define OSD_MSG_ADJUSTING_WP_ALT "ADJUSTING WP ALTITUDE" +#define OSD_MSG_MISSION_PLANNER "(WP MISSION PLANNER)" +#define OSD_MSG_WP_RTH_CANCEL "CANCEL WP TO EXIT RTH" +#define OSD_MSG_WP_MISSION_LOADED "* MISSION LOADED *" +#define OSD_MSG_EMERG_LANDING "EMERGENCY LANDING" +#define OSD_MSG_LANDING "LANDING" +#define OSD_MSG_LOITERING_HOME "LOITERING AROUND HOME" +#define OSD_MSG_HOVERING "HOVERING" +#define OSD_MSG_LANDED "LANDED" +#define OSD_MSG_PREPARING_LAND "PREPARING TO LAND" +#define OSD_MSG_AUTOLAUNCH "AUTOLAUNCH" +#define OSD_MSG_AUTOLAUNCH_MANUAL "AUTOLAUNCH (MANUAL)" +#define OSD_MSG_ALTITUDE_HOLD "(ALTITUDE HOLD)" +#define OSD_MSG_AUTOTRIM "(AUTOTRIM)" +#define OSD_MSG_AUTOTUNE "(AUTOTUNE)" +#define OSD_MSG_AUTOTUNE_ACRO "SWITCH TO ACRO" +#define OSD_MSG_AUTOLEVEL "(AUTO LEVEL TRIM)" +#define OSD_MSG_HEADFREE "(HEADFREE)" +#define OSD_MSG_NAV_SOARING "(SOARING)" +#define OSD_MSG_UNABLE_ARM "UNABLE TO ARM" +#define OSD_MSG_SAVING_SETTNGS "** SAVING SETTINGS **" +#define OSD_MSG_SETTINGS_SAVED "** SETTINGS SAVED **" #ifdef USE_DEV_TOOLS -#define OSD_MSG_GRD_TEST_MODE "GRD TEST > MOTORS DISABLED" +#define OSD_MSG_GRD_TEST_MODE "GRD TEST > MOTORS DISABLED" #endif #if defined(USE_SAFE_HOME) -#define OSD_MSG_DIVERT_SAFEHOME "DIVERTING TO SAFEHOME" -#define OSD_MSG_LOITERING_SAFEHOME "LOITERING AROUND SAFEHOME" +#define OSD_MSG_DIVERT_SAFEHOME "DIVERTING TO SAFEHOME" +#define OSD_MSG_LOITERING_SAFEHOME "LOITERING AROUND SAFEHOME" #endif typedef enum { - OSD_RSSI_VALUE, - OSD_MAIN_BATT_VOLTAGE, - OSD_CROSSHAIRS, - OSD_ARTIFICIAL_HORIZON, - OSD_HORIZON_SIDEBARS, - OSD_ONTIME, - OSD_FLYTIME, - OSD_FLYMODE, - OSD_CRAFT_NAME, - OSD_THROTTLE_POS, - OSD_VTX_CHANNEL, - OSD_CURRENT_DRAW, - OSD_MAH_DRAWN, - OSD_GPS_SPEED, - OSD_GPS_SATS, - OSD_ALTITUDE, - OSD_ROLL_PIDS, - OSD_PITCH_PIDS, - OSD_YAW_PIDS, - OSD_POWER, - OSD_GPS_LON, - OSD_GPS_LAT, - OSD_HOME_DIR, - OSD_HOME_DIST, - OSD_HEADING, - OSD_VARIO, - OSD_VARIO_NUM, - OSD_AIR_SPEED, - OSD_ONTIME_FLYTIME, - OSD_RTC_TIME, - OSD_MESSAGES, - OSD_GPS_HDOP, - OSD_MAIN_BATT_CELL_VOLTAGE, - OSD_SCALED_THROTTLE_POS, - OSD_HEADING_GRAPH, - OSD_EFFICIENCY_MAH_PER_KM, - OSD_WH_DRAWN, - OSD_BATTERY_REMAINING_CAPACITY, - OSD_BATTERY_REMAINING_PERCENT, - OSD_EFFICIENCY_WH_PER_KM, - OSD_TRIP_DIST, - OSD_ATTITUDE_PITCH, - OSD_ATTITUDE_ROLL, - OSD_MAP_NORTH, - OSD_MAP_TAKEOFF, - OSD_RADAR, - OSD_WIND_SPEED_HORIZONTAL, - OSD_WIND_SPEED_VERTICAL, - OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH, - OSD_REMAINING_DISTANCE_BEFORE_RTH, - OSD_HOME_HEADING_ERROR, - OSD_COURSE_HOLD_ERROR, - OSD_COURSE_HOLD_ADJUSTMENT, - OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE, - OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE, - OSD_POWER_SUPPLY_IMPEDANCE, - OSD_LEVEL_PIDS, - OSD_POS_XY_PIDS, - OSD_POS_Z_PIDS, - OSD_VEL_XY_PIDS, - OSD_VEL_Z_PIDS, - OSD_HEADING_P, - OSD_BOARD_ALIGN_ROLL, - OSD_BOARD_ALIGN_PITCH, - OSD_RC_EXPO, - OSD_RC_YAW_EXPO, - OSD_THROTTLE_EXPO, - OSD_PITCH_RATE, - OSD_ROLL_RATE, - OSD_YAW_RATE, - OSD_MANUAL_RC_EXPO, - OSD_MANUAL_RC_YAW_EXPO, - OSD_MANUAL_PITCH_RATE, - OSD_MANUAL_ROLL_RATE, - OSD_MANUAL_YAW_RATE, - OSD_NAV_FW_CRUISE_THR, - OSD_NAV_FW_PITCH2THR, - OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE, - OSD_DEBUG, // Intentionally absent from configurator and CMS. Set it from CLI. - OSD_FW_ALT_PID_OUTPUTS, - OSD_FW_POS_PID_OUTPUTS, - OSD_MC_VEL_X_PID_OUTPUTS, - OSD_MC_VEL_Y_PID_OUTPUTS, - OSD_MC_VEL_Z_PID_OUTPUTS, - OSD_MC_POS_XYZ_P_OUTPUTS, - OSD_3D_SPEED, - OSD_IMU_TEMPERATURE, - OSD_BARO_TEMPERATURE, - OSD_TEMP_SENSOR_0_TEMPERATURE, - OSD_TEMP_SENSOR_1_TEMPERATURE, - OSD_TEMP_SENSOR_2_TEMPERATURE, - OSD_TEMP_SENSOR_3_TEMPERATURE, - OSD_TEMP_SENSOR_4_TEMPERATURE, - OSD_TEMP_SENSOR_5_TEMPERATURE, - OSD_TEMP_SENSOR_6_TEMPERATURE, - OSD_TEMP_SENSOR_7_TEMPERATURE, - OSD_ALTITUDE_MSL, - OSD_PLUS_CODE, - OSD_MAP_SCALE, - OSD_MAP_REFERENCE, - OSD_GFORCE, - OSD_GFORCE_X, - OSD_GFORCE_Y, - OSD_GFORCE_Z, - OSD_RC_SOURCE, - OSD_VTX_POWER, - OSD_ESC_RPM, - OSD_ESC_TEMPERATURE, - OSD_AZIMUTH, - OSD_CRSF_RSSI_DBM, - OSD_CRSF_LQ, - OSD_CRSF_SNR_DB, - OSD_CRSF_TX_POWER, - OSD_GVAR_0, - OSD_GVAR_1, - OSD_GVAR_2, - OSD_GVAR_3, - OSD_TPA, - OSD_NAV_FW_CONTROL_SMOOTHNESS, - OSD_VERSION, - OSD_RANGEFINDER, - OSD_PLIMIT_REMAINING_BURST_TIME, - OSD_PLIMIT_ACTIVE_CURRENT_LIMIT, - OSD_PLIMIT_ACTIVE_POWER_LIMIT, - OSD_GLIDESLOPE, - OSD_GPS_MAX_SPEED, - OSD_3D_MAX_SPEED, - OSD_AIR_MAX_SPEED, - OSD_ACTIVE_PROFILE, - OSD_MISSION, - OSD_SWITCH_INDICATOR_0, - OSD_SWITCH_INDICATOR_1, - OSD_SWITCH_INDICATOR_2, - OSD_SWITCH_INDICATOR_3, - OSD_TPA_TIME_CONSTANT, - OSD_FW_LEVEL_TRIM, - OSD_GLIDE_TIME_REMAINING, - OSD_GLIDE_RANGE, - OSD_CLIMB_EFFICIENCY, - OSD_NAV_WP_MULTI_MISSION_INDEX, - OSD_GROUND_COURSE, // 140 - OSD_CROSS_TRACK_ERROR, - OSD_PILOT_NAME, - OSD_PAN_SERVO_CENTRED, - OSD_ITEM_COUNT // MUST BE LAST + OSD_RSSI_VALUE, + OSD_MAIN_BATT_VOLTAGE, + OSD_CROSSHAIRS, + OSD_ARTIFICIAL_HORIZON, + OSD_HORIZON_SIDEBARS, + OSD_ONTIME, + OSD_FLYTIME, + OSD_FLYMODE, + OSD_CRAFT_NAME, + OSD_THROTTLE_POS, + OSD_VTX_CHANNEL, + OSD_CURRENT_DRAW, + OSD_MAH_DRAWN, + OSD_GPS_SPEED, + OSD_GPS_SATS, + OSD_ALTITUDE, + OSD_ROLL_PIDS, + OSD_PITCH_PIDS, + OSD_YAW_PIDS, + OSD_POWER, + OSD_GPS_LON, + OSD_GPS_LAT, + OSD_HOME_DIR, + OSD_HOME_DIST, + OSD_HEADING, + OSD_VARIO, + OSD_VARIO_NUM, + OSD_AIR_SPEED, + OSD_ONTIME_FLYTIME, + OSD_RTC_TIME, + OSD_MESSAGES, + OSD_GPS_HDOP, + OSD_MAIN_BATT_CELL_VOLTAGE, + OSD_SCALED_THROTTLE_POS, + OSD_HEADING_GRAPH, + OSD_EFFICIENCY_MAH_PER_KM, + OSD_WH_DRAWN, + OSD_BATTERY_REMAINING_CAPACITY, + OSD_BATTERY_REMAINING_PERCENT, + OSD_EFFICIENCY_WH_PER_KM, + OSD_TRIP_DIST, + OSD_ATTITUDE_PITCH, + OSD_ATTITUDE_ROLL, + OSD_MAP_NORTH, + OSD_MAP_TAKEOFF, + OSD_RADAR, + OSD_WIND_SPEED_HORIZONTAL, + OSD_WIND_SPEED_VERTICAL, + OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH, + OSD_REMAINING_DISTANCE_BEFORE_RTH, + OSD_HOME_HEADING_ERROR, + OSD_COURSE_HOLD_ERROR, + OSD_COURSE_HOLD_ADJUSTMENT, + OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE, + OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE, + OSD_POWER_SUPPLY_IMPEDANCE, + OSD_LEVEL_PIDS, + OSD_POS_XY_PIDS, + OSD_POS_Z_PIDS, + OSD_VEL_XY_PIDS, + OSD_VEL_Z_PIDS, + OSD_HEADING_P, + OSD_BOARD_ALIGN_ROLL, + OSD_BOARD_ALIGN_PITCH, + OSD_RC_EXPO, + OSD_RC_YAW_EXPO, + OSD_THROTTLE_EXPO, + OSD_PITCH_RATE, + OSD_ROLL_RATE, + OSD_YAW_RATE, + OSD_MANUAL_RC_EXPO, + OSD_MANUAL_RC_YAW_EXPO, + OSD_MANUAL_PITCH_RATE, + OSD_MANUAL_ROLL_RATE, + OSD_MANUAL_YAW_RATE, + OSD_NAV_FW_CRUISE_THR, + OSD_NAV_FW_PITCH2THR, + OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE, + OSD_DEBUG, // Intentionally absent from configurator and CMS. Set it from CLI. + OSD_FW_ALT_PID_OUTPUTS, + OSD_FW_POS_PID_OUTPUTS, + OSD_MC_VEL_X_PID_OUTPUTS, + OSD_MC_VEL_Y_PID_OUTPUTS, + OSD_MC_VEL_Z_PID_OUTPUTS, + OSD_MC_POS_XYZ_P_OUTPUTS, + OSD_3D_SPEED, + OSD_IMU_TEMPERATURE, + OSD_BARO_TEMPERATURE, + OSD_TEMP_SENSOR_0_TEMPERATURE, + OSD_TEMP_SENSOR_1_TEMPERATURE, + OSD_TEMP_SENSOR_2_TEMPERATURE, + OSD_TEMP_SENSOR_3_TEMPERATURE, + OSD_TEMP_SENSOR_4_TEMPERATURE, + OSD_TEMP_SENSOR_5_TEMPERATURE, + OSD_TEMP_SENSOR_6_TEMPERATURE, + OSD_TEMP_SENSOR_7_TEMPERATURE, + OSD_ALTITUDE_MSL, + OSD_PLUS_CODE, + OSD_MAP_SCALE, + OSD_MAP_REFERENCE, + OSD_GFORCE, + OSD_GFORCE_X, + OSD_GFORCE_Y, + OSD_GFORCE_Z, + OSD_RC_SOURCE, + OSD_VTX_POWER, + OSD_ESC_RPM, + OSD_ESC_TEMPERATURE, + OSD_AZIMUTH, + OSD_CRSF_RSSI_DBM, + OSD_CRSF_LQ, + OSD_CRSF_SNR_DB, + OSD_CRSF_TX_POWER, + OSD_GVAR_0, + OSD_GVAR_1, + OSD_GVAR_2, + OSD_GVAR_3, + OSD_TPA, + OSD_NAV_FW_CONTROL_SMOOTHNESS, + OSD_VERSION, + OSD_RANGEFINDER, + OSD_PLIMIT_REMAINING_BURST_TIME, + OSD_PLIMIT_ACTIVE_CURRENT_LIMIT, + OSD_PLIMIT_ACTIVE_POWER_LIMIT, + OSD_GLIDESLOPE, + OSD_GPS_MAX_SPEED, + OSD_3D_MAX_SPEED, + OSD_AIR_MAX_SPEED, + OSD_ACTIVE_PROFILE, + OSD_MISSION, + OSD_SWITCH_INDICATOR_0, + OSD_SWITCH_INDICATOR_1, + OSD_SWITCH_INDICATOR_2, + OSD_SWITCH_INDICATOR_3, + OSD_TPA_TIME_CONSTANT, + OSD_FW_LEVEL_TRIM, + OSD_GLIDE_TIME_REMAINING, + OSD_GLIDE_RANGE, + OSD_CLIMB_EFFICIENCY, + OSD_NAV_WP_MULTI_MISSION_INDEX, + OSD_GROUND_COURSE, // 140 + OSD_CROSS_TRACK_ERROR, + OSD_PILOT_NAME, + OSD_PAN_SERVO_CENTRED, + OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; typedef enum { - OSD_UNIT_IMPERIAL, - OSD_UNIT_METRIC, - OSD_UNIT_METRIC_MPH, // Old UK units, all metric except speed in mph - OSD_UNIT_UK, // Show everything in imperial, temperature in C - OSD_UNIT_GA, // General Aviation: Knots, Nautical Miles, Feet, Degrees C + OSD_UNIT_IMPERIAL, + OSD_UNIT_METRIC, + OSD_UNIT_METRIC_MPH, // Old UK units, all metric except speed in mph + OSD_UNIT_UK, // Show everything in imperial, temperature in C + OSD_UNIT_GA, // General Aviation: Knots, Nautical Miles, Feet, Degrees C - OSD_UNIT_MAX = OSD_UNIT_GA, + OSD_UNIT_MAX = OSD_UNIT_GA, } osd_unit_e; typedef enum { - OSD_STATS_ENERGY_UNIT_MAH, - OSD_STATS_ENERGY_UNIT_WH, + OSD_STATS_ENERGY_UNIT_MAH, + OSD_STATS_ENERGY_UNIT_WH, } osd_stats_energy_unit_e; typedef enum { - OSD_STATS_MIN_VOLTAGE_UNIT_BATTERY, - OSD_STATS_MIN_VOLTAGE_UNIT_CELL, + OSD_STATS_MIN_VOLTAGE_UNIT_BATTERY, + OSD_STATS_MIN_VOLTAGE_UNIT_CELL, } osd_stats_min_voltage_unit_e; typedef enum { - OSD_CROSSHAIRS_STYLE_DEFAULT, - OSD_CROSSHAIRS_STYLE_AIRCRAFT, - OSD_CROSSHAIRS_STYLE_TYPE3, - OSD_CROSSHAIRS_STYLE_TYPE4, - OSD_CROSSHAIRS_STYLE_TYPE5, - OSD_CROSSHAIRS_STYLE_TYPE6, - OSD_CROSSHAIRS_STYLE_TYPE7, + OSD_CROSSHAIRS_STYLE_DEFAULT, + OSD_CROSSHAIRS_STYLE_AIRCRAFT, + OSD_CROSSHAIRS_STYLE_TYPE3, + OSD_CROSSHAIRS_STYLE_TYPE4, + OSD_CROSSHAIRS_STYLE_TYPE5, + OSD_CROSSHAIRS_STYLE_TYPE6, + OSD_CROSSHAIRS_STYLE_TYPE7, } osd_crosshairs_style_e; typedef enum { - OSD_SIDEBAR_SCROLL_NONE, - OSD_SIDEBAR_SCROLL_ALTITUDE, - OSD_SIDEBAR_SCROLL_SPEED, - OSD_SIDEBAR_SCROLL_HOME_DISTANCE, + OSD_SIDEBAR_SCROLL_NONE, + OSD_SIDEBAR_SCROLL_ALTITUDE, + OSD_SIDEBAR_SCROLL_SPEED, + OSD_SIDEBAR_SCROLL_HOME_DISTANCE, - OSD_SIDEBAR_SCROLL_MAX = OSD_SIDEBAR_SCROLL_HOME_DISTANCE, + OSD_SIDEBAR_SCROLL_MAX = OSD_SIDEBAR_SCROLL_HOME_DISTANCE, } osd_sidebar_scroll_e; typedef enum { - OSD_ALIGN_LEFT, - OSD_ALIGN_RIGHT + OSD_ALIGN_LEFT, + OSD_ALIGN_RIGHT } osd_alignment_e; typedef enum { - OSD_AHI_STYLE_DEFAULT, - OSD_AHI_STYLE_LINE, + OSD_AHI_STYLE_DEFAULT, + OSD_AHI_STYLE_LINE, } osd_ahi_style_e; typedef enum { - OSD_CRSF_LQ_TYPE1, - OSD_CRSF_LQ_TYPE2, - OSD_CRSF_LQ_TYPE3 + OSD_CRSF_LQ_TYPE1, + OSD_CRSF_LQ_TYPE2, + OSD_CRSF_LQ_TYPE3 } osd_crsf_lq_format_e; typedef struct osdLayoutsConfig_s { - // Layouts - uint16_t item_pos[OSD_LAYOUT_COUNT][OSD_ITEM_COUNT]; + // Layouts + uint16_t item_pos[OSD_LAYOUT_COUNT][OSD_ITEM_COUNT]; } osdLayoutsConfig_t; PG_DECLARE(osdLayoutsConfig_t, osdLayoutsConfig); @@ -341,112 +341,111 @@ PG_DECLARE(osdLayoutsConfig_t, osdLayoutsConfig); #define OSD_SWITCH_INDICATOR_NAME_LENGTH 4 typedef struct osdConfig_s { - // Alarms - uint8_t rssi_alarm; // rssi % - uint16_t time_alarm; // fly minutes - uint16_t alt_alarm; // positive altitude in m - uint16_t dist_alarm; // home distance in m - uint16_t neg_alt_alarm; // abs(negative altitude) in m - uint8_t current_alarm; // current consumption in A - int16_t imu_temp_alarm_min; - int16_t imu_temp_alarm_max; - int16_t esc_temp_alarm_min; - int16_t esc_temp_alarm_max; - float gforce_alarm; - float gforce_axis_alarm_min; - float gforce_axis_alarm_max; + // Alarms + uint8_t rssi_alarm; // rssi % + uint16_t time_alarm; // fly minutes + uint16_t alt_alarm; // positive altitude in m + uint16_t dist_alarm; // home distance in m + uint16_t neg_alt_alarm; // abs(negative altitude) in m + uint8_t current_alarm; // current consumption in A + int16_t imu_temp_alarm_min; + int16_t imu_temp_alarm_max; + int16_t esc_temp_alarm_min; + int16_t esc_temp_alarm_max; + float gforce_alarm; + float gforce_axis_alarm_min; + float gforce_axis_alarm_max; #ifdef USE_SERIALRX_CRSF - int8_t snr_alarm; //CRSF SNR alarm in dB - int8_t link_quality_alarm; - int16_t rssi_dbm_alarm; // in dBm - int16_t rssi_dbm_max; // Perfect RSSI. Set to High end of curve. RSSI at 100% - int16_t rssi_dbm_min; // Worst RSSI. Set to low end of curve or RX sensitivity level. RSSI at 0% + int8_t snr_alarm; //CRSF SNR alarm in dB + int8_t link_quality_alarm; + int16_t rssi_dbm_alarm; // in dBm + int16_t rssi_dbm_max; // Perfect RSSI. Set to High end of curve. RSSI at 100% + int16_t rssi_dbm_min; // Worst RSSI. Set to low end of curve or RX sensitivity level. RSSI at 0% #endif #ifdef USE_BARO - int16_t baro_temp_alarm_min; - int16_t baro_temp_alarm_max; + int16_t baro_temp_alarm_min; + int16_t baro_temp_alarm_max; #endif #ifdef USE_TEMPERATURE_SENSOR - osd_alignment_e temp_label_align; + osd_alignment_e temp_label_align; #endif #ifdef USE_PITOT - float airspeed_alarm_min; - float airspeed_alarm_max; + float airspeed_alarm_min; + float airspeed_alarm_max; #endif - videoSystem_e video_system; - uint8_t row_shiftdown; - int16_t msp_displayport_fullframe_interval; + videoSystem_e video_system; + uint8_t row_shiftdown; + int16_t msp_displayport_fullframe_interval; - // Preferences - uint8_t main_voltage_decimals; - uint8_t ahi_reverse_roll; - uint8_t ahi_max_pitch; - uint8_t crosshairs_style; // from osd_crosshairs_style_e - int8_t horizon_offset; - int8_t camera_uptilt; - bool ahi_camera_uptilt_comp; - uint8_t camera_fov_h; - uint8_t camera_fov_v; - uint8_t hud_margin_h; - uint8_t hud_margin_v; - bool hud_homing; - bool hud_homepoint; - uint8_t hud_radar_disp; - uint16_t hud_radar_range_min; - uint16_t hud_radar_range_max; - uint8_t hud_radar_alt_difference_display_time; - uint8_t hud_radar_distance_display_time; - uint8_t hud_wp_disp; + // Preferences + uint8_t main_voltage_decimals; + uint8_t ahi_reverse_roll; + uint8_t ahi_max_pitch; + uint8_t crosshairs_style; // from osd_crosshairs_style_e + int8_t horizon_offset; + int8_t camera_uptilt; + bool ahi_camera_uptilt_comp; + uint8_t camera_fov_h; + uint8_t camera_fov_v; + uint8_t hud_margin_h; + uint8_t hud_margin_v; + bool hud_homing; + bool hud_homepoint; + uint8_t hud_radar_disp; + uint16_t hud_radar_range_min; + uint16_t hud_radar_range_max; + uint8_t hud_radar_alt_difference_display_time; + uint8_t hud_radar_distance_display_time; + uint8_t hud_wp_disp; - uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_e - uint8_t right_sidebar_scroll; // from osd_sidebar_scroll_e - uint8_t sidebar_scroll_arrows; + uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_e + uint8_t right_sidebar_scroll; // from osd_sidebar_scroll_e + uint8_t sidebar_scroll_arrows; - uint8_t units; // from osd_unit_e - uint8_t stats_energy_unit; // from osd_stats_energy_unit_e - uint8_t stats_min_voltage_unit; // from osd_stats_min_voltage_unit_e - uint8_t stats_page_auto_swap_time; // stats page auto swap interval time (seconds) + uint8_t units; // from osd_unit_e + uint8_t stats_energy_unit; // from osd_stats_energy_unit_e + uint8_t stats_min_voltage_unit; // from osd_stats_min_voltage_unit_e + uint8_t stats_page_auto_swap_time; // stats page auto swap interval time (seconds) -#ifdef USE_WIND_ESTIMATOR - bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance -#endif - - uint8_t coordinate_digits; - - bool osd_failsafe_switch_layout; - uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE - uint8_t plus_code_short; - uint8_t ahi_style; - uint8_t force_grid; // Force a pixel based OSD to use grid mode. - uint8_t ahi_bordered; // Only used by the AHI widget - uint8_t ahi_width; // In pixels, only used by the AHI widget - uint8_t ahi_height; // In pixels, only used by the AHI widget - int8_t ahi_vertical_offset; // Offset from center in pixels. Positive moves the AHI down. Widget only. - int8_t sidebar_horizontal_offset; // Horizontal offset from default position. Units are grid slots for grid OSDs, pixels for pixel based OSDs. Positive values move sidebars closer to the edges. - uint8_t left_sidebar_scroll_step; // How many units each sidebar step represents. 0 means the default value for the scroll type. - uint8_t right_sidebar_scroll_step; // Same as left_sidebar_scroll_step, but for the right sidebar. - bool osd_home_position_arm_screen; - uint8_t pan_servo_index; // Index of the pan servo used for home direction offset - int8_t pan_servo_pwm2centideg; // Centidegrees of servo rotation per us pwm - uint8_t pan_servo_offcentre_warning; // Degrees around the centre, that is assumed camera is wanted to be facing forwards, but isn't centred - bool pan_servo_indicator_show_degrees; // Show the degrees of offset for the pan servo - uint8_t crsf_lq_format; - uint8_t sidebar_height; // sidebar height in rows, 0 turns off sidebars leaving only level indicator arrows - uint8_t telemetry; // use telemetry on displayed pixel line 0 - uint8_t esc_rpm_precision; // Number of characters used for the RPM numbers. - uint16_t system_msg_display_time; // system message display time for multiple messages (ms) - uint8_t mAh_used_precision; // Number of numbers used for mAh drawn. Plently of packs now are > 9999 mAh - uint8_t ahi_pitch_interval; // redraws AHI at set pitch interval (Not pixel OSD) - char osd_switch_indicator0_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 0. - uint8_t osd_switch_indicator0_channel; // RC Channel to use for switch indicator 0. - char osd_switch_indicator1_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 1. - uint8_t osd_switch_indicator1_channel; // RC Channel to use for switch indicator 1. - char osd_switch_indicator2_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 2. - uint8_t osd_switch_indicator2_channel; // RC Channel to use for switch indicator 2. - char osd_switch_indicator3_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 3. - uint8_t osd_switch_indicator3_channel; // RC Channel to use for switch indicator 3. - bool osd_switch_indicators_align_left; // Align switch indicator name to left of the switch. +#ifdef USE_WIND_ ESTIMATOR + bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance +#endif + uint8_t coordinate_digits; + bool osd_failsafe_switch_layout; + uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE + uint8_t plus_code_short; + uint8_t ahi_style; + uint8_t force_grid; // Force a pixel based OSD to use grid mode. + uint8_t ahi_bordered; // Only used by the AHI widget + uint8_t ahi_width; // In pixels, only used by the AHI widget + uint8_t ahi_height; // In pixels, only used by the AHI widget + int8_t ahi_vertical_offset; // Offset from center in pixels. Positive moves the AHI down. Widget only. + int8_t sidebar_horizontal_offset; // Horizontal offset from default position. Units are grid slots for grid OSDs, pixels for pixel based OSDs. Positive values move sidebars closer to the edges. + uint8_t left_sidebar_scroll_step; // How many units each sidebar step represents. 0 means the default value for the scroll type. + uint8_t right_sidebar_scroll_step; // Same as left_sidebar_scroll_step, but for the right sidebar. + bool osd_home_position_arm_screen; + uint8_t pan_servo_index; // Index of the pan servo used for home direction offset + int8_t pan_servo_pwm2centideg; // Centidegrees of servo rotation per us pwm + uint8_t pan_servo_offcentre_warning; // Degrees around the centre, that is assumed camera is wanted to be facing forwards, but isn't centred + bool pan_servo_indicator_show_degrees; // Show the degrees of offset for the pan servo + uint8_t crsf_lq_format; + uint8_t sidebar_height; // sidebar height in rows, 0 turns off sidebars leaving only level indicator arrows + uint8_t telemetry; // use telemetry on displayed pixel line 0 + uint8_t esc_rpm_precision; // Number of characters used for the RPM numbers. + uint16_t system_msg_display_time; // system message display time for multiple messages (ms) + uint8_t mAh_used_precision; // Number of numbers used for mAh drawn. Plently of packs now are > 9999 mAh + uint8_t ahi_pitch_interval; // redraws AHI at set pitch interval (Not pixel OSD) + char osd_switch_indicator0_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 0. + uint8_t osd_switch_indicator0_channel; // RC Channel to use for switch indicator 0. + char osd_switch_indicator1_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 1. + uint8_t osd_switch_indicator1_channel; // RC Channel to use for switch indicator 1. + char osd_switch_indicator2_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 2. + uint8_t osd_switch_indicator2_channel; // RC Channel to use for switch indicator 2. + char osd_switch_indicator3_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 3. + uint8_t osd_switch_indicator3_channel; // RC Channel to use for switch indicator 3. + bool osd_switch_indicators_align_left; // Align switch indicator name to left of the switch. + bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with/instead of the INAV logo } osdConfig_t; PG_DECLARE(osdConfig_t, osdConfig); From cd047c06e83a03e740adac556b478227f07a09c4 Mon Sep 17 00:00:00 2001 From: Nick B Date: Wed, 30 Aug 2023 21:43:11 +0200 Subject: [PATCH 071/175] Update CMakeLists.txt --- src/main/target/ATOMRCF405V2/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/ATOMRCF405V2/CMakeLists.txt b/src/main/target/ATOMRCF405V2/CMakeLists.txt index e78fd04a1a..940c2a80fa 100644 --- a/src/main/target/ATOMRCF405V2/CMakeLists.txt +++ b/src/main/target/ATOMRCF405V2/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405xg(ATOMRCF405V2) +target_stm32f405xg(ATOMRCF405V2 SKIP_RELEASES) From f779303a7a2554a873ca72e1b515e72653ec7100 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Thu, 31 Aug 2023 13:53:28 +0100 Subject: [PATCH 072/175] Added small pilot logo - Added small pilot logo initial code - Fixed error from tabs in osd.h --- src/main/io/osd.c | 9 ++++++++- src/main/io/osd.h | 5 +++-- 2 files changed, 11 insertions(+), 3 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 49cdee582d..d24cc63d5b 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2198,6 +2198,12 @@ static bool osdDrawSingleElement(uint8_t item) osdFormatPilotName(buff); break; + case OSD_PILOT_LOGO: + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_PILOT_LOGO_SML_L); + displayWriteChar(osdDisplayPort, elemPosX+1, elemPosY, SYM_PILOT_LOGO_SML_C); + displayWriteChar(osdDisplayPort, elemPosX+2, elemPosY, SYM_PILOT_LOGO_SML_R); + break; + case OSD_THROTTLE_POS: { osdFormatThrottlePosition(buff, false, &elemAttr); @@ -3673,7 +3679,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .system_msg_display_time = SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_DEFAULT, .units = SETTING_OSD_UNITS_DEFAULT, .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT, - .use_pilot_logo = SETTINGS_OSD_USE_PILOT_LOGO_DEFAULT + .use_pilot_logo = SETTING_OSD_USE_PILOT_LOGO_DEFAULT, #ifdef USE_WIND_ESTIMATOR .estimations_wind_compensation = SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT, @@ -3746,6 +3752,7 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) osdLayoutsConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2); osdLayoutsConfig->item_pos[0][OSD_PILOT_NAME] = OSD_POS(20, 3); + osdLayoutsConfig->item_pos[0][OSD_PILOT_LOGO] = OSD_POS(20, 3); osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6); #ifdef USE_SERIALRX_CRSF diff --git a/src/main/io/osd.h b/src/main/io/osd.h index afe651a8d6..d6d0491a83 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -273,6 +273,7 @@ typedef enum { OSD_CROSS_TRACK_ERROR, OSD_PILOT_NAME, OSD_PAN_SERVO_CENTRED, + OSD_PILOT_LOGO, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; @@ -408,8 +409,8 @@ typedef struct osdConfig_s { uint8_t stats_min_voltage_unit; // from osd_stats_min_voltage_unit_e uint8_t stats_page_auto_swap_time; // stats page auto swap interval time (seconds) -#ifdef USE_WIND_ ESTIMATOR - bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance +#ifdef USE_WIND_ESTIMATOR + bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance #endif uint8_t coordinate_digits; bool osd_failsafe_switch_layout; From e0d8917fc782d292c3f3f9df46544a8c87029c23 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 3 Sep 2023 10:17:31 +0100 Subject: [PATCH 073/175] Corrected indexes for actual position in the font --- src/main/drivers/osd_symbols.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index a1b84d52b1..ed68b5f01b 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -258,10 +258,10 @@ #define SYM_SERVO_PAN_IS_OFFSET_L 0x1C7 // 455 Pan servo is offset left #define SYM_SERVO_PAN_IS_OFFSET_R 0x1C8 // 456 Pan servo is offset right -#define SYM_PILOT_LOGO_SML_L 0x1D6 // 470 small Pilot logo Left -#define SYM_PILOT_LOGO_SML_C 0x1D7 // 471 small Pilot logo Centre -#define SYM_PILOT_LOGO_SML_R 0x1D8 // 472 small Pilot logo Right -#define SYM_PILOT_LOGO_LRG_START 0x1D9 // 473 to 511, Pilot logo +#define SYM_PILOT_LOGO_SML_L 0x1D5 // 469 small Pilot logo Left +#define SYM_PILOT_LOGO_SML_C 0x1D6 // 470 small Pilot logo Centre +#define SYM_PILOT_LOGO_SML_R 0x1D7 // 471 small Pilot logo Right +#define SYM_PILOT_LOGO_LRG_START 0x1D8 // 472 to 511, Pilot logo #else From ff6b8a76e8bbeaf91b798bb820a9d3d91cdc8b69 Mon Sep 17 00:00:00 2001 From: Andrey Akimov Date: Mon, 4 Sep 2023 10:30:16 +0300 Subject: [PATCH 074/175] Timer N channel fix --- src/main/drivers/timer_impl_stdperiph.c | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/timer_impl_stdperiph.c b/src/main/drivers/timer_impl_stdperiph.c index 5cb3457c77..620d6f6993 100644 --- a/src/main/drivers/timer_impl_stdperiph.c +++ b/src/main/drivers/timer_impl_stdperiph.c @@ -301,7 +301,12 @@ bool impl_timerPWMConfigChannelDMA(TCH_t * tch, void * dmaBuffer, uint8_t dmaBuf TIM_CtrlPWMOutputs(timer, ENABLE); TIM_ARRPreloadConfig(timer, ENABLE); - TIM_CCxCmd(timer, lookupTIMChannelTable[tch->timHw->channelIndex], TIM_CCx_Enable); + if (tch->timHw->output & TIMER_OUTPUT_N_CHANNEL) { + TIM_CCxNCmd(timer, lookupTIMChannelTable[tch->timHw->channelIndex], TIM_CCxN_Enable); + } else { + TIM_CCxCmd(timer, lookupTIMChannelTable[tch->timHw->channelIndex], TIM_CCx_Enable); + } + TIM_Cmd(timer, ENABLE); dmaInit(tch->dma, OWNER_TIMER, 0); @@ -382,7 +387,12 @@ bool impl_timerPWMConfigDMABurst(burstDmaTimer_t *burstDmaTimer, TCH_t * tch, vo TIM_CtrlPWMOutputs(timer, ENABLE); TIM_ARRPreloadConfig(timer, ENABLE); - TIM_CCxCmd(timer, lookupTIMChannelTable[tch->timHw->channelIndex], TIM_CCx_Enable); + if (tch->timHw->output & TIMER_OUTPUT_N_CHANNEL) { + TIM_CCxNCmd(timer, lookupTIMChannelTable[tch->timHw->channelIndex], TIM_CCxN_Enable); + } else { + TIM_CCxCmd(timer, lookupTIMChannelTable[tch->timHw->channelIndex], TIM_CCx_Enable); + } + TIM_Cmd(timer, ENABLE); if (!tch->timCtx->dmaBurstRef) { From 896478f9ebd0641eb4e52e148875ef205cc0070d Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Mon, 4 Sep 2023 22:46:19 +0100 Subject: [PATCH 075/175] Updates - Added arm screen timeout as CLI settable option. Defaults to current 1.5 seconds. - Fixed boot screen stats. Bug would have existed since 3.0 - Initial code for swapping logos on the boot screen - Replaced pseudo code with actual logic for using pilot logo on HD arming screen - Used already existing logic for detecting if display is HD --- docs/Settings.md | 10 ++++++++++ src/main/fc/settings.yaml | 16 ++++++++++++++++ src/main/io/osd.c | 26 ++++++++++++-------------- src/main/io/osd.h | 5 +++-- 4 files changed, 41 insertions(+), 16 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index bfbb1e7e12..1fd236b8d7 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -3972,6 +3972,16 @@ Value above which to make the OSD relative altitude indicator blink (meters) --- +### osd_arm_screen_display_time + +Amount of time to display the arm screen [ms] + +| Default | Min | Max | +| --- | --- | --- | +| 1500 | 1000 | 5000 | + +--- + ### osd_baro_temp_alarm_max Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index c63972fefd..cb2c5b75e4 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3486,59 +3486,75 @@ groups: type: bool default_value: OFF + - name: osd_arm_screen_display_time + description: Amount of time to display the arm screen [ms] + field: arm_screen_display_time + min: 1000 + max: 5000 + default_value: 1500 + - name: osd_switch_indicator_zero_name description: "Character to use for OSD switch incicator 0." field: osd_switch_indicator0_name type: string max: 5 default_value: "FLAP" + - name: osd_switch_indicator_one_name description: "Character to use for OSD switch incicator 1." field: osd_switch_indicator1_name type: string max: 5 default_value: "GEAR" + - name: osd_switch_indicator_two_name description: "Character to use for OSD switch incicator 2." field: osd_switch_indicator2_name type: string max: 5 default_value: "CAM" + - name: osd_switch_indicator_three_name description: "Character to use for OSD switch incicator 3." field: osd_switch_indicator3_name type: string max: 5 default_value: "LIGT" + - name: osd_switch_indicator_zero_channel description: "RC Channel to use for OSD switch indicator 0." field: osd_switch_indicator0_channel min: 5 max: MAX_SUPPORTED_RC_CHANNEL_COUNT default_value: 5 + - name: osd_switch_indicator_one_channel description: "RC Channel to use for OSD switch indicator 1." field: osd_switch_indicator1_channel min: 5 max: MAX_SUPPORTED_RC_CHANNEL_COUNT default_value: 5 + - name: osd_switch_indicator_two_channel description: "RC Channel to use for OSD switch indicator 2." field: osd_switch_indicator2_channel min: 5 max: MAX_SUPPORTED_RC_CHANNEL_COUNT default_value: 5 + - name: osd_switch_indicator_three_channel description: "RC Channel to use for OSD switch indicator 3." field: osd_switch_indicator3_channel min: 5 max: MAX_SUPPORTED_RC_CHANNEL_COUNT default_value: 5 + - name: osd_switch_indicators_align_left description: "Align text to left of switch indicators" field: osd_switch_indicators_align_left type: bool default_value: ON + - name: osd_system_msg_display_time description: System message display cycle time for multiple messages (milliseconds). field: system_msg_display_time diff --git a/src/main/io/osd.c b/src/main/io/osd.c index d24cc63d5b..8b7a57260f 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -129,7 +129,6 @@ #define STATS_PAGE1 (checkStickPosition(ROL_LO)) #define SPLASH_SCREEN_DISPLAY_TIME 4000 // ms -#define ARMED_SCREEN_DISPLAY_TIME 1500 // ms #define STATS_SCREEN_DISPLAY_TIME 60000 // ms #define EFFICIENCY_UPDATE_INTERVAL (5 * 1000) @@ -3680,6 +3679,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .units = SETTING_OSD_UNITS_DEFAULT, .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT, .use_pilot_logo = SETTING_OSD_USE_PILOT_LOGO_DEFAULT, + .arm_screen_display_time = SETTING_OSD_ARM_SCREEN_DISPLAY_TIME_DEFAULT, #ifdef USE_WIND_ESTIMATOR .estimations_wind_compensation = SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT, @@ -3909,7 +3909,7 @@ static void osdCompleteAsyncInitialization(void) if (fontHasMetadata && metadata.charCount > 256) { hasExtendedFont = true; - unsigned logo_c = SYM_LOGO_START; + unsigned logo_c = (osdConfig()->use_pilot_logo) ? SYM_PILOT_LOGO_LRG_START : SYM_LOGO_START; unsigned logo_x = OSD_CENTER_LEN(SYM_LOGO_WIDTH); for (unsigned ii = 0; ii < SYM_LOGO_HEIGHT; ii++) { for (unsigned jj = 0; jj < SYM_LOGO_WIDTH; jj++) { @@ -3920,8 +3920,7 @@ static void osdCompleteAsyncInitialization(void) y++; } else if (!fontHasMetadata) { const char *m = "INVALID FONT"; - displayWrite(osdDisplayPort, OSD_CENTER_S(m), 3, m); - y = 4; + displayWrite(osdDisplayPort, OSD_CENTER_S(m), y++, m); } if (fontHasMetadata && metadata.version < OSD_MIN_FONT_VERSION) { @@ -3934,13 +3933,12 @@ static void osdCompleteAsyncInitialization(void) uint8_t xPos = osdDisplayIsHD() ? 15 : 5; displayWrite(osdDisplayPort, xPos, y++, string_buffer); #ifdef USE_CMS - displayWrite(osdDisplayPort, xPos+2, y++, CMS_STARTUP_HELP_TEXT1); + displayWrite(osdDisplayPort, xPos+2, y++, CMS_STARTUP_HELP_TEXT1); displayWrite(osdDisplayPort, xPos+6, y++, CMS_STARTUP_HELP_TEXT2); displayWrite(osdDisplayPort, xPos+6, y++, CMS_STARTUP_HELP_TEXT3); #endif + #ifdef USE_STATS - - uint8_t statNameX = osdDisplayIsHD() ? 14 : 4; uint8_t statValueX = osdDisplayIsHD() ? 34 : 24; @@ -3970,15 +3968,15 @@ static void osdCompleteAsyncInitialization(void) displayWrite(osdDisplayPort, statNameX, ++y, "TOTAL TIME:"); uint32_t tot_mins = statsConfig()->stats_total_time / 60; - tfp_sprintf(string_buffer, "%2d:%02dHM", (int)(tot_mins / 60), (int)(tot_mins % 60)); + tfp_sprintf(string_buffer, "%2d:%02dH:M", (int)(tot_mins / 60), (int)(tot_mins % 60)); displayWrite(osdDisplayPort, statValueX-5, y, string_buffer); #ifdef USE_ADC if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) { displayWrite(osdDisplayPort, statNameX, ++y, "TOTAL ENERGY:"); osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4); - strcat(string_buffer, "\xAB"); // SYM_WH displayWrite(osdDisplayPort, statValueX-4, y, string_buffer); + displayWriteChar(osdDisplayPort, statValueX, y, SYM_WH); displayWrite(osdDisplayPort, statNameX, ++y, "AVG EFFICIENCY:"); if (statsConfig()->stats_total_dist) { @@ -4014,7 +4012,7 @@ static void osdCompleteAsyncInitialization(void) displayCommitTransaction(osdDisplayPort); displayResync(osdDisplayPort); - osdSetNextRefreshIn(SPLASH_SCREEN_DISPLAY_TIME); + osdSetNextRefreshIn(10000);//SPLASH_SCREEN_DISPLAY_TIME); // TEMPORARY - PUT BACK ONCE TESTING IS FINISHED! } void osdInit(displayPort_t *osdDisplayPortToUse) @@ -4390,7 +4388,7 @@ static void osdShowHDArmScreen(void) logoRow++; } - // if (using pilot logo) { + if (osdConfig()->use_pilot_logo) { logo_c = SYM_PILOT_LOGO_LRG_START; logo_x = (logoColOffset * 2) + ((osdDisplayPort->cols % 2 == 0) ? 0 : 1); // Add extra 1 px space between logos, if the OSD has an odd number of columns logoRow = armScreenRow; @@ -4400,7 +4398,7 @@ static void osdShowHDArmScreen(void) } logoRow++; } - // } // using pilot logo + } armScreenRow = logoRow + 2; @@ -4556,7 +4554,7 @@ static void osdShowArmed(void) { displayClearScreen(osdDisplayPort); - if (osdDisplayPort->rows >= OSD_STATS_SINGLE_PAGE_MIN_ROWS) { + if (osdDisplayIsHD()) { osdShowHDArmScreen(); } else { osdShowSDArmScreen(); @@ -4661,7 +4659,7 @@ static void osdRefresh(timeUs_t currentTimeUs) statsDisplayed = false; osdResetStats(); osdShowArmed(); - uint32_t delay = ARMED_SCREEN_DISPLAY_TIME; + uint32_t delay = osdConfig()->arm_screen_display_time; #if defined(USE_SAFE_HOME) if (safehome_distance) delay *= 3; diff --git a/src/main/io/osd.h b/src/main/io/osd.h index d6d0491a83..08b74cfe23 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -273,7 +273,7 @@ typedef enum { OSD_CROSS_TRACK_ERROR, OSD_PILOT_NAME, OSD_PAN_SERVO_CENTRED, - OSD_PILOT_LOGO, + OSD_PILOT_LOGO, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; @@ -446,7 +446,8 @@ typedef struct osdConfig_s { char osd_switch_indicator3_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 3. uint8_t osd_switch_indicator3_channel; // RC Channel to use for switch indicator 3. bool osd_switch_indicators_align_left; // Align switch indicator name to left of the switch. - bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with/instead of the INAV logo + bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with/instead of the INAV logo + uint16_t arm_screen_display_time; // Length of time the arm screen is displayed } osdConfig_t; PG_DECLARE(osdConfig_t, osdConfig); From 46b1ece7b6b36a18c20be7ee9186496f0f4a0846 Mon Sep 17 00:00:00 2001 From: Andrey Akimov Date: Tue, 5 Sep 2023 12:35:53 +0300 Subject: [PATCH 076/175] use dma burst for MATEKF405TE --- src/main/target/MATEKF405TE/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/MATEKF405TE/target.h b/src/main/target/MATEKF405TE/target.h index 93ab3345de..b00b77299e 100644 --- a/src/main/target/MATEKF405TE/target.h +++ b/src/main/target/MATEKF405TE/target.h @@ -178,5 +178,5 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_DSHOT +#define USE_DSHOT_DMAR #define USE_ESC_SENSOR - From d0d13af8210f7edfdfa16d241ce56bfc99e8bb86 Mon Sep 17 00:00:00 2001 From: Andrey Akimov Date: Tue, 5 Sep 2023 13:50:16 +0300 Subject: [PATCH 077/175] Revert "use dma burst for MATEKF405TE" This reverts commit 46b1ece7b6b36a18c20be7ee9186496f0f4a0846. --- src/main/target/MATEKF405TE/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/MATEKF405TE/target.h b/src/main/target/MATEKF405TE/target.h index b00b77299e..93ab3345de 100644 --- a/src/main/target/MATEKF405TE/target.h +++ b/src/main/target/MATEKF405TE/target.h @@ -178,5 +178,5 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_DSHOT -#define USE_DSHOT_DMAR #define USE_ESC_SENSOR + From fa60cfda81a4d50591bea9d74a85378f75844e81 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Wed, 6 Sep 2023 23:25:13 +0100 Subject: [PATCH 078/175] fixes --- src/main/fc/fc_core.c | 10 +++++----- src/main/navigation/navigation.c | 3 +++ 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 92705ab691..19015989ca 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -512,11 +512,11 @@ bool emergInflightRearmEnabled(void) return false; } - if (isProbablyStillFlying()) { - emergRearmStabiliseTimeout = currentTimeMs + 5000; // activate Angle mode for 5s after rearm to help stabilise craft - return true; - } else if (STATE(MULTIROTOR) && (currentTimeMs > US2MS(lastDisarmTimeUs) + 1500) && fabsf(getEstimatedActualVelocity(Z)) > 100.0f) { - // allow emergency rearm if MR has vertical speed at least 1.5 sec after disarm indicating still flying + // allow emergency rearm if MR has vertical speed at least 1.5 sec after disarm indicating still flying + bool mcDisarmVertVelCheck = STATE(MULTIROTOR) && (currentTimeMs > US2MS(lastDisarmTimeUs) + 1500) && fabsf(getEstimatedActualVelocity(Z)) > 100.0f; + + if (isProbablyStillFlying() || mcDisarmVertVelCheck) { + emergRearmStabiliseTimeout = currentTimeMs + 5000; // activate Angle mode for 5s after rearm to help stabilise craft return true; } diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 63c5b9884a..5b3f17bb2a 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2809,6 +2809,9 @@ void updateLandingStatus(timeMs_t currentTimeMs) DEBUG_SET(DEBUG_LANDING, 1, STATE(LANDING_DETECTED)); if (!ARMING_FLAG(ARMED)) { + if (STATE(LANDING_DETECTED)) { + landingDetectorIsActive = false; + } resetLandingDetector(); if (!IS_RC_MODE_ACTIVE(BOXARM)) { From c26a583fa0e08ef6ea8d0609e1a782b700dbadb4 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Tue, 12 Sep 2023 22:55:52 +0100 Subject: [PATCH 079/175] Update Unfortunately the large pilot logo can't be available on SD. There seems to be an issue with the storage on the MAX7456 chip. The last 33 characters of page 2 seem to corrupt on power loss. After uploading the font, all looks fine. After a reboot, the logo looks fine. But after a power cycle, the last 33 characters are corrupted. Changes: - cms.h now back to tabs - moved logo and stats drawing to own functions, to save repetition. - Made large pilot logo HD only - Disabled large pilot logo support with BFCOMPAT mode. - Stats and logos will self centre, no matter the column width. - All arm screen times will be increased by 3 seconds with a safehome failure message. --- src/main/cms/cms.h | 22 ++-- src/main/io/osd.c | 250 +++++++++++++++++++++++++-------------------- 2 files changed, 152 insertions(+), 120 deletions(-) diff --git a/src/main/cms/cms.h b/src/main/cms/cms.h index f1f8d8017c..69620f354c 100644 --- a/src/main/cms/cms.h +++ b/src/main/cms/cms.h @@ -7,14 +7,14 @@ #include "cms/cms_types.h" typedef enum { - CMS_KEY_NONE, - CMS_KEY_UP, - CMS_KEY_DOWN, - CMS_KEY_LEFT, - CMS_KEY_RIGHT, - CMS_KEY_ESC, - CMS_KEY_MENU, - CMS_KEY_SAVEMENU + CMS_KEY_NONE, + CMS_KEY_UP, + CMS_KEY_DOWN, + CMS_KEY_LEFT, + CMS_KEY_RIGHT, + CMS_KEY_ESC, + CMS_KEY_MENU, + CMS_KEY_SAVEMENU } cms_key_e; @@ -37,9 +37,9 @@ void cmsYieldDisplay(displayPort_t *pPort, timeMs_t duration); void cmsUpdate(uint32_t currentTimeUs); void cmsSetExternKey(cms_key_e extKey); -#define CMS_STARTUP_HELP_TEXT1 "MENU: THR MID" -#define CMS_STARTUP_HELP_TEXT2 "+ YAW LEFT" -#define CMS_STARTUP_HELP_TEXT3 "+ PITCH UP" +#define CMS_STARTUP_HELP_TEXT1 "MENU: THR MID" +#define CMS_STARTUP_HELP_TEXT2 "+ YAW LEFT" +#define CMS_STARTUP_HELP_TEXT3 "+ PITCH UP" // cmsMenuExit special ptr values #define CMS_EXIT (0) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 8b7a57260f..e02949936f 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -3873,6 +3873,133 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) } } +uint8_t drawLogos(bool singular, uint8_t row) { + uint8_t logoRow = row; + uint8_t logoColOffset = 0; + bool usePilotLogo = (osdConfig()->use_pilot_logo && osdDisplayIsHD()); + +#ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is in use, the pilot logo cannot be used, due to font issues. + if (isBfCompatibleVideoSystem(osdConfig())) + usePilotLogo = false; +#endif + + // Draw Logo(s) + if (usePilotLogo && !singular) { + logoColOffset = floor((osdDisplayPort->cols - (SYM_LOGO_WIDTH * 2)) / 3.0f); + } else { + logoColOffset = floor((osdDisplayPort->cols - SYM_LOGO_WIDTH) / 2.0f); + } + + // Draw INAV logo + if ((singular && !usePilotLogo) || !singular) { + unsigned logo_c = SYM_LOGO_START; + uint8_t logo_x = logoColOffset; + for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) { + for (uint8_t lCol = 0; lCol < SYM_LOGO_WIDTH; lCol++) { + displayWriteChar(osdDisplayPort, logo_x + lCol, logoRow, logo_c++); + } + logoRow++; + } + } + + // Draw the pilot logo + if (usePilotLogo) { + unsigned logo_c = SYM_PILOT_LOGO_LRG_START; + uint8_t logo_x = 0; + logoRow = row; + if (singular) { + logo_x = logoColOffset; + } else { + logo_x = (logoColOffset * 2) + SYM_LOGO_WIDTH + ((osdDisplayPort->cols % 2 == 0) ? 0 : 1); // Add extra 1 px space between logos, if the OSD has an odd number of columns + } + + for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) { + for (uint8_t lCol = 0; lCol < SYM_LOGO_WIDTH; lCol++) { + displayWriteChar(osdDisplayPort, logo_x + lCol, logoRow, logo_c++); + } + logoRow++; + } + } + + return logoRow; +} + +uint8_t drawStats(uint8_t row) { +#ifdef USE_STATS + char string_buffer[30]; + uint8_t statNameX = (osdDisplayPort->cols - 22) / 2; + uint8_t statValueX = statNameX + 21; + + if (statsConfig()->stats_enabled) { + displayWrite(osdDisplayPort, statNameX, row, "ODOMETER:"); + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_MILE)); + string_buffer[5] = SYM_MI; + break; + default: + case OSD_UNIT_GA: + tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_NAUTICALMILE)); + string_buffer[5] = SYM_NM; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_KILOMETER)); + string_buffer[5] = SYM_KM; + break; + } + string_buffer[6] = '\0'; + displayWrite(osdDisplayPort, statValueX-5, row, string_buffer); + + displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL TIME:"); + uint32_t tot_mins = statsConfig()->stats_total_time / 60; + tfp_sprintf(string_buffer, "%2d:%02dH:M", (int)(tot_mins / 60), (int)(tot_mins % 60)); + displayWrite(osdDisplayPort, statValueX-7, row, string_buffer); + +#ifdef USE_ADC + if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) { + displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL ENERGY:"); + osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4); + displayWrite(osdDisplayPort, statValueX-4, row, string_buffer); + displayWriteChar(osdDisplayPort, statValueX, row, SYM_WH); + + displayWrite(osdDisplayPort, statNameX, ++row, "AVG EFFICIENCY:"); + if (statsConfig()->stats_total_dist) { + uint32_t avg_efficiency = statsConfig()->stats_total_energy / (statsConfig()->stats_total_dist / METERS_PER_KILOMETER); // mWh/km + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); + string_buffer[3] = SYM_WH_MI; + break; + case OSD_UNIT_GA: + osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); + string_buffer[3] = SYM_WH_NM; + break; + default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3); + string_buffer[3] = SYM_WH_KM; + break; + } + } else { + string_buffer[0] = string_buffer[1] = string_buffer[2] = '-'; + } + string_buffer[4] = '\0'; + displayWrite(osdDisplayPort, statValueX-3, row++, string_buffer); + } +#endif // USE_ADC + } +#endif // USE_STATS + return row; +} + static void osdSetNextRefreshIn(uint32_t timeMs) { resumeRefreshAt = micros() + timeMs * 1000; refreshWaitForResumeCmdRelease = true; @@ -3909,14 +4036,8 @@ static void osdCompleteAsyncInitialization(void) if (fontHasMetadata && metadata.charCount > 256) { hasExtendedFont = true; - unsigned logo_c = (osdConfig()->use_pilot_logo) ? SYM_PILOT_LOGO_LRG_START : SYM_LOGO_START; - unsigned logo_x = OSD_CENTER_LEN(SYM_LOGO_WIDTH); - for (unsigned ii = 0; ii < SYM_LOGO_HEIGHT; ii++) { - for (unsigned jj = 0; jj < SYM_LOGO_WIDTH; jj++) { - displayWriteChar(osdDisplayPort, logo_x + jj, y, logo_c++); - } - y++; - } + + y = drawLogos(true, y); y++; } else if (!fontHasMetadata) { const char *m = "INVALID FONT"; @@ -3930,7 +4051,7 @@ static void osdCompleteAsyncInitialization(void) char string_buffer[30]; tfp_sprintf(string_buffer, "INAV VERSION: %s", FC_VERSION_STRING); - uint8_t xPos = osdDisplayIsHD() ? 15 : 5; + uint8_t xPos = (osdDisplayPort->cols - 19) / 2; // Automatically centre, regardless of resolution. In the case of odd number screens, bias to the left. displayWrite(osdDisplayPort, xPos, y++, string_buffer); #ifdef USE_CMS displayWrite(osdDisplayPort, xPos+2, y++, CMS_STARTUP_HELP_TEXT1); @@ -3939,80 +4060,12 @@ static void osdCompleteAsyncInitialization(void) #endif #ifdef USE_STATS - uint8_t statNameX = osdDisplayIsHD() ? 14 : 4; - uint8_t statValueX = osdDisplayIsHD() ? 34 : 24; - - if (statsConfig()->stats_enabled) { - displayWrite(osdDisplayPort, statNameX, ++y, "ODOMETER:"); - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_MILE)); - string_buffer[5] = SYM_MI; - break; - default: - case OSD_UNIT_GA: - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_NAUTICALMILE)); - string_buffer[5] = SYM_NM; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_KILOMETER)); - string_buffer[5] = SYM_KM; - break; - } - string_buffer[6] = '\0'; - displayWrite(osdDisplayPort, statValueX-5, y, string_buffer); - - displayWrite(osdDisplayPort, statNameX, ++y, "TOTAL TIME:"); - uint32_t tot_mins = statsConfig()->stats_total_time / 60; - tfp_sprintf(string_buffer, "%2d:%02dH:M", (int)(tot_mins / 60), (int)(tot_mins % 60)); - displayWrite(osdDisplayPort, statValueX-5, y, string_buffer); - -#ifdef USE_ADC - if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) { - displayWrite(osdDisplayPort, statNameX, ++y, "TOTAL ENERGY:"); - osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4); - displayWrite(osdDisplayPort, statValueX-4, y, string_buffer); - displayWriteChar(osdDisplayPort, statValueX, y, SYM_WH); - - displayWrite(osdDisplayPort, statNameX, ++y, "AVG EFFICIENCY:"); - if (statsConfig()->stats_total_dist) { - uint32_t avg_efficiency = statsConfig()->stats_total_energy / (statsConfig()->stats_total_dist / METERS_PER_KILOMETER); // mWh/km - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); - string_buffer[3] = SYM_WH_MI; - break; - case OSD_UNIT_GA: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); - string_buffer[3] = SYM_WH_NM; - break; - default: - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3); - string_buffer[3] = SYM_WH_KM; - break; - } - } else { - string_buffer[0] = string_buffer[1] = string_buffer[2] = '-'; - } - string_buffer[4] = '\0'; - displayWrite(osdDisplayPort, statValueX-3, y, string_buffer); - } -#endif // USE_ADC - } + y = drawStats(++y); #endif displayCommitTransaction(osdDisplayPort); displayResync(osdDisplayPort); - osdSetNextRefreshIn(10000);//SPLASH_SCREEN_DISPLAY_TIME); // TEMPORARY - PUT BACK ONCE TESTING IS FINISHED! + osdSetNextRefreshIn(SPLASH_SCREEN_DISPLAY_TIME); } void osdInit(displayPort_t *osdDisplayPortToUse) @@ -4372,35 +4425,10 @@ static void osdShowHDArmScreen(void) char *time; uint8_t armScreenRow = 2; // Start at row 2 - - // Draw Logo(s) - uint8_t logoColOffset = floor((osdDisplayPort->cols - SYM_LOGO_WIDTH) / 2.0f); - // uint8_t logoColOffset = floor((osdDisplayPort->cols - ((using pilot logo) ? (SYM_LOGO_WIDTH * 2) : SYM_LOGO_WIDTH)) / 2.0f); - - // Draw INAV logo - unsigned logo_c = SYM_LOGO_START; - uint8_t logo_x = logoColOffset; - uint8_t logoRow = armScreenRow; - for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) { - for (uint8_t lCol = 0; lCol < SYM_LOGO_WIDTH; lCol++) { - displayWriteChar(osdDisplayPort, logo_x + lCol, logoRow, logo_c++); - } - logoRow++; - } - - if (osdConfig()->use_pilot_logo) { - logo_c = SYM_PILOT_LOGO_LRG_START; - logo_x = (logoColOffset * 2) + ((osdDisplayPort->cols % 2 == 0) ? 0 : 1); // Add extra 1 px space between logos, if the OSD has an odd number of columns - logoRow = armScreenRow; - for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) { - for (uint8_t lCol = 0; lCol < SYM_LOGO_WIDTH; lCol++) { - displayWriteChar(osdDisplayPort, logo_x + lCol, logoRow, logo_c++); - } - logoRow++; - } - } - armScreenRow = logoRow + 2; + + armScreenRow = drawLogos(false, armScreenRow); + armScreenRow++; strcpy(buf, "ARMED"); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow, buf); @@ -4467,7 +4495,11 @@ static void osdShowHDArmScreen(void) } tfp_sprintf(versionBuf, "INAV VERSION: %s", FC_VERSION_STRING); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, armScreenRow, versionBuf); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, armScreenRow++, versionBuf); + +#ifdef USE_STATS + armScreenRow = drawStats(++armScreenRow); +#endif // USE_STATS } static void osdShowSDArmScreen(void) @@ -4662,7 +4694,7 @@ static void osdRefresh(timeUs_t currentTimeUs) uint32_t delay = osdConfig()->arm_screen_display_time; #if defined(USE_SAFE_HOME) if (safehome_distance) - delay *= 3; + delay+= 3000; #endif osdSetNextRefreshIn(delay); } else { From 8feb087730727b3999a72d4293e41d410e4e4d67 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Fri, 15 Sep 2023 08:06:02 +0100 Subject: [PATCH 080/175] Updates (not tested) - Added the ability to specify the gap between the logos - Matched arm screen and boot screen logo displays --- docs/Settings.md | 10 ++++++++++ src/main/fc/settings.yaml | 7 +++++++ src/main/io/osd.c | 20 +++++++++++++++++--- src/main/io/osd.h | 3 ++- 4 files changed, 36 insertions(+), 4 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 1fd236b8d7..51091fd55b 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -4312,6 +4312,16 @@ Temperature under which the IMU temperature OSD element will start blinking (dec --- +### osd_inav_to_pilot_logo_spacing + +The space between the INAV and pilot logos, if `osd_use_pilot_logo` is `ON`. This number may be adjusted so that it fits the odd/even col width displays. For example, if using an odd column width display, such as Walksnail, and this is set to 4. 1 will be added so that the logos are equally spaced from the centre of the screen. + +| Default | Min | Max | +| --- | --- | --- | +| 8 | 0 | 20 | + +--- + ### osd_left_sidebar_scroll _// TODO_ diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index cb2c5b75e4..eff96ffdcf 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3486,6 +3486,13 @@ groups: type: bool default_value: OFF + - name: osd_inav_to_pilot_logo_spacing + description: The space between the INAV and pilot logos, if `osd_use_pilot_logo` is `ON`. This number may be adjusted so that it fits the odd/even col width displays. For example, if using an odd column width display, such as Walksnail, and this is set to 4. 1 will be added so that the logos are equally spaced from the centre of the screen. + field: inav_to_pilot_logo_spacing + min: 0 + max: 20 + default_value: 8 + - name: osd_arm_screen_display_time description: Amount of time to display the arm screen [ms] field: arm_screen_display_time diff --git a/src/main/io/osd.c b/src/main/io/osd.c index e02949936f..52a1a7dcb5 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -3679,6 +3679,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .units = SETTING_OSD_UNITS_DEFAULT, .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT, .use_pilot_logo = SETTING_OSD_USE_PILOT_LOGO_DEFAULT, + .inav_to_pilot_logo_spacing = SETTING_OSD_INAV_TO_PILOT_LOGO_SPACING_DEFAULT, .arm_screen_display_time = SETTING_OSD_ARM_SCREEN_DISPLAY_TIME_DEFAULT, #ifdef USE_WIND_ESTIMATOR @@ -3873,6 +3874,13 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) } } +/** + * @brief Draws the INAV and/or pilot logos on the display + * + * @param singular If true, only one logo will be drawn. If false, both logos will be drawn, separated by osdConfig()->inav_to_pilot_logo_spacing characters + * @param row The row number to start drawing the logos. If not singular, both logos are drawn on the same rows. + * @return uint8_t The row number after the logo(s). + */ uint8_t drawLogos(bool singular, uint8_t row) { uint8_t logoRow = row; uint8_t logoColOffset = 0; @@ -3883,9 +3891,15 @@ uint8_t drawLogos(bool singular, uint8_t row) { usePilotLogo = false; #endif + uint8_t logoSpacing = osdConfig()->inav_to_pilot_logo_spacing; + + if (logoSpacing > 0 && ((osdDisplayPort->cols % 2) != (logoSpacing % 2))) { + logoSpacing++; // Add extra 1 character space between logos, if the odd/even of the OSD cols doesn't match the odd/even of the logo spacing + } + // Draw Logo(s) if (usePilotLogo && !singular) { - logoColOffset = floor((osdDisplayPort->cols - (SYM_LOGO_WIDTH * 2)) / 3.0f); + logoColOffset = ((osdDisplayPort->cols - (SYM_LOGO_WIDTH * 2)) - logoSpacing) / 2; } else { logoColOffset = floor((osdDisplayPort->cols - SYM_LOGO_WIDTH) / 2.0f); } @@ -3910,7 +3924,7 @@ uint8_t drawLogos(bool singular, uint8_t row) { if (singular) { logo_x = logoColOffset; } else { - logo_x = (logoColOffset * 2) + SYM_LOGO_WIDTH + ((osdDisplayPort->cols % 2 == 0) ? 0 : 1); // Add extra 1 px space between logos, if the OSD has an odd number of columns + logo_x = logoColOffset + SYM_LOGO_WIDTH + logoSpacing; } for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) { @@ -4037,7 +4051,7 @@ static void osdCompleteAsyncInitialization(void) if (fontHasMetadata && metadata.charCount > 256) { hasExtendedFont = true; - y = drawLogos(true, y); + y = drawLogos(false, y); y++; } else if (!fontHasMetadata) { const char *m = "INVALID FONT"; diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 08b74cfe23..0d3e3ba976 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -446,7 +446,8 @@ typedef struct osdConfig_s { char osd_switch_indicator3_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 3. uint8_t osd_switch_indicator3_channel; // RC Channel to use for switch indicator 3. bool osd_switch_indicators_align_left; // Align switch indicator name to left of the switch. - bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with/instead of the INAV logo + bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with the INAV logo. + uint8_t inav_to_pilot_logo_spacing; // The space between the INAV and pilot logos, if pilot logo is used. This number may be adjusted so that it fits the odd/even col width. uint16_t arm_screen_display_time; // Length of time the arm screen is displayed } osdConfig_t; From 11029ba947e5eb2506a3c9efbb94cb04243cbacd Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 16 Sep 2023 09:06:52 +0100 Subject: [PATCH 081/175] Update Changes to HD arming screen - Explicitly select safehome row - temporarily removed stats due to space - combined craft name and armed to a single row. - put lon and lat on single row. - changed time format (need to test), as tenths of seconds is a bit pointless. date would be more useful. --- src/main/io/osd.c | 74 +++++++++++++++++++++++++++++------------------ 1 file changed, 46 insertions(+), 28 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 52a1a7dcb5..0bdf997a31 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -3679,7 +3679,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .units = SETTING_OSD_UNITS_DEFAULT, .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT, .use_pilot_logo = SETTING_OSD_USE_PILOT_LOGO_DEFAULT, - .inav_to_pilot_logo_spacing = SETTING_OSD_INAV_TO_PILOT_LOGO_SPACING_DEFAULT, + .inav_to_pilot_logo_spacing = SETTING_OSD_INAV_TO_PILOT_LOGO_SPACING_DEFAULT, .arm_screen_display_time = SETTING_OSD_ARM_SCREEN_DISPLAY_TIME_DEFAULT, #ifdef USE_WIND_ESTIMATOR @@ -3891,11 +3891,11 @@ uint8_t drawLogos(bool singular, uint8_t row) { usePilotLogo = false; #endif - uint8_t logoSpacing = osdConfig()->inav_to_pilot_logo_spacing; + uint8_t logoSpacing = osdConfig()->inav_to_pilot_logo_spacing; - if (logoSpacing > 0 && ((osdDisplayPort->cols % 2) != (logoSpacing % 2))) { - logoSpacing++; // Add extra 1 character space between logos, if the odd/even of the OSD cols doesn't match the odd/even of the logo spacing - } + if (logoSpacing > 0 && ((osdDisplayPort->cols % 2) != (logoSpacing % 2))) { + logoSpacing++; // Add extra 1 character space between logos, if the odd/even of the OSD cols doesn't match the odd/even of the logo spacing + } // Draw Logo(s) if (usePilotLogo && !singular) { @@ -4433,26 +4433,29 @@ static void osdShowHDArmScreen(void) { dateTime_t dt; char buf[MAX(32, FORMATTED_DATE_TIME_BUFSIZE)]; + char buf2[MAX(32, FORMATTED_DATE_TIME_BUFSIZE)]; char craftNameBuf[MAX_NAME_LENGTH]; char versionBuf[30]; char *date; char *time; - + uint8_t safehomeRow = 0; uint8_t armScreenRow = 2; // Start at row 2 - - + armScreenRow = drawLogos(false, armScreenRow); armScreenRow++; - strcpy(buf, "ARMED"); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow, buf); - armScreenRow += 2; - if (strlen(systemConfig()->craftName) > 0) { osdFormatCraftName(craftNameBuf); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(systemConfig()->craftName)) / 2, armScreenRow++, craftNameBuf ); + strcpy(buf2, "ARMED!"); + tfp_sprintf(buf, "%s - %s", craftNameBuf, buf2); + } else { + strcpy(buf, "ARMED!"); } + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + safehomeRow = armScreenRow; + armScreenRow++; + if (posControl.waypointListValid && posControl.waypointCount > 0) { #ifdef USE_MULTI_MISSION tfp_sprintf(buf, "MISSION %u/%u (%u WP)", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); @@ -4469,26 +4472,37 @@ static void osdShowHDArmScreen(void) if (STATE(GPS_FIX_HOME)) { if (osdConfig()->osd_home_position_arm_screen){ osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); - osdFormatCoordinate(buf, SYM_LON, GPS_home.lon); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + osdFormatCoordinate(buf2, SYM_LON, GPS_home.lon); + uint8_t gap = 1; + uint8_t col = strlen(buf) + strlen(buf2) + gap; + + if ((osdDisplayPort->cols %2) != (col %2)) { + gap++; + col++; + } + + col = (osdDisplayPort->cols - col) / 2; + + displayWrite(osdDisplayPort, col, armScreenRow, buf); + displayWrite(osdDisplayPort, col + strlen(buf) + gap, armScreenRow++, buf2); + int digits = osdConfig()->plus_code_digits; olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); } armScreenRow++; + #if defined (USE_SAFE_HOME) if (safehome_distance) { // safehome found during arming if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) { strcpy(buf, "SAFEHOME FOUND; MODE OFF"); } else { - char buf2[12]; // format the distance first osdFormatDistanceStr(buf2, safehome_distance); tfp_sprintf(buf, "%c - %s -> SAFEHOME %u", SYM_HOME, buf2, safehome_index); } textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT; - // write this message above the ARMED message to make it obvious (3rd parameter - row 7) - displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, 7, buf, elemAttr); + // write this message below the ARMED message to make it obvious + displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, safehomeRow, buf, elemAttr); } #endif } else { @@ -4499,21 +4513,25 @@ static void osdShowHDArmScreen(void) } #endif - if (rtcGetDateTime(&dt)) { - dateTimeFormatLocal(buf, &dt); - dateTimeSplitFormatted(buf, &date, &time); + if (rtcGetDateTimeLocal(&dt)) { + tfp_sprintf(buf, "%04u-%02u-%02u %02u:%02u:%02u", dt.year, dt.month, dt.day, dt.hours, dt.minutes, dt.seconds); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + armScreenRow++; - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(date)) / 2, armScreenRow, date); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(time)) / 2, armScreenRow++, time); - armScreenRow += 2; + //dateTimeFormatLocal(buf2, &dt); + //dateTimeSplitFormatted(buf2, &date, &time); + + //displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(date)) / 2, armScreenRow, date); + //displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(time)) / 2, armScreenRow++, time); + //armScreenRow += 2; } tfp_sprintf(versionBuf, "INAV VERSION: %s", FC_VERSION_STRING); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, armScreenRow++, versionBuf); -#ifdef USE_STATS - armScreenRow = drawStats(++armScreenRow); -#endif // USE_STATS +// #ifdef USE_STATS +// armScreenRow = drawStats(++armScreenRow); +// #endif // USE_STATS } static void osdShowSDArmScreen(void) From 09c0f302f95aa2bf401838ed656c47b25dc82d23 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 17 Sep 2023 09:06:44 +0100 Subject: [PATCH 082/175] Tidying up - Removed unneeded code after testing new date time format on HD arm screen. I needed to use actual aircraft as HITL doesn't support date/time over GPS. - Updated date time format on SD arm screen - Remove extra row if safehomes is not used - Switched around format of safehome display for readability - Arm screens will show stats if there is enough space to neatly do so - Single row for long lat on SD, as there is plenty of space - Tidied up all the `y + x` instances on SD arm screen, and made the variable name more explicit --- src/main/io/osd.c | 128 ++++++++++++++++++++++++---------------------- 1 file changed, 66 insertions(+), 62 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 0bdf997a31..7d2e2ed9a0 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -4431,15 +4431,13 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) // HD arming screen. based on the minimum HD OSD grid size of 50 x 18 static void osdShowHDArmScreen(void) { - dateTime_t dt; - char buf[MAX(32, FORMATTED_DATE_TIME_BUFSIZE)]; - char buf2[MAX(32, FORMATTED_DATE_TIME_BUFSIZE)]; - char craftNameBuf[MAX_NAME_LENGTH]; - char versionBuf[30]; - char *date; - char *time; - uint8_t safehomeRow = 0; - uint8_t armScreenRow = 2; // Start at row 2 + dateTime_t dt; + char buf[MAX(osdDisplayPort->cols, FORMATTED_DATE_TIME_BUFSIZE)]; + char buf2[MAX(osdDisplayPort->cols, FORMATTED_DATE_TIME_BUFSIZE)]; + char craftNameBuf[MAX_NAME_LENGTH]; + char versionBuf[osdDisplayPort->cols]; + uint8_t safehomeRow = 0; + uint8_t armScreenRow = 2; // Start at row 2 armScreenRow = drawLogos(false, armScreenRow); armScreenRow++; @@ -4451,10 +4449,16 @@ static void osdShowHDArmScreen(void) } else { strcpy(buf, "ARMED!"); } - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); - safehomeRow = armScreenRow; - armScreenRow++; +#if defined(USE_GPS) +#if defined (USE_SAFE_HOME) + if (safehome_distance) { + safehomeRow = armScreenRow; + armScreenRow++; + } +#endif // USE_SAFE_HOME +#endif // USE_GPS + armScreenRow++; if (posControl.waypointListValid && posControl.waypointCount > 0) { #ifdef USE_MULTI_MISSION @@ -4470,7 +4474,7 @@ static void osdShowHDArmScreen(void) #if defined(USE_GPS) if (feature(FEATURE_GPS)) { if (STATE(GPS_FIX_HOME)) { - if (osdConfig()->osd_home_position_arm_screen){ + if (osdConfig()->osd_home_position_arm_screen) { osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat); osdFormatCoordinate(buf2, SYM_LON, GPS_home.lon); uint8_t gap = 1; @@ -4490,7 +4494,6 @@ static void osdShowHDArmScreen(void) olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); } - armScreenRow++; #if defined (USE_SAFE_HOME) if (safehome_distance) { // safehome found during arming @@ -4498,7 +4501,7 @@ static void osdShowHDArmScreen(void) strcpy(buf, "SAFEHOME FOUND; MODE OFF"); } else { osdFormatDistanceStr(buf2, safehome_distance); - tfp_sprintf(buf, "%c - %s -> SAFEHOME %u", SYM_HOME, buf2, safehome_index); + tfp_sprintf(buf, "%c SAFEHOME %u @ %s", SYM_HOME, safehome_index, buf2); } textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT; // write this message below the ARMED message to make it obvious @@ -4508,8 +4511,8 @@ static void osdShowHDArmScreen(void) } else { strcpy(buf, "!NO HOME POSITION!"); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); - armScreenRow++; } + armScreenRow++; } #endif @@ -4517,100 +4520,101 @@ static void osdShowHDArmScreen(void) tfp_sprintf(buf, "%04u-%02u-%02u %02u:%02u:%02u", dt.year, dt.month, dt.day, dt.hours, dt.minutes, dt.seconds); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); armScreenRow++; - - //dateTimeFormatLocal(buf2, &dt); - //dateTimeSplitFormatted(buf2, &date, &time); - - //displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(date)) / 2, armScreenRow, date); - //displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(time)) / 2, armScreenRow++, time); - //armScreenRow += 2; } tfp_sprintf(versionBuf, "INAV VERSION: %s", FC_VERSION_STRING); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, armScreenRow++, versionBuf); + armScreenRow++; -// #ifdef USE_STATS -// armScreenRow = drawStats(++armScreenRow); -// #endif // USE_STATS +#ifdef USE_STATS + if (armScreenRow < (osdDisplayPort->rows - 4)) + armScreenRow = drawStats(armScreenRow); +#endif // USE_STATS } static void osdShowSDArmScreen(void) { - dateTime_t dt; - char buf[MAX(32, FORMATTED_DATE_TIME_BUFSIZE)]; - char craftNameBuf[MAX_NAME_LENGTH]; - char versionBuf[30]; - char *date; - char *time; + dateTime_t dt; + char buf[MAX(osdDisplayPort->cols, FORMATTED_DATE_TIME_BUFSIZE)]; + char buf2[MAX(osdDisplayPort->cols, FORMATTED_DATE_TIME_BUFSIZE)]; + char craftNameBuf[MAX_NAME_LENGTH]; + char versionBuf[osdDisplayPort->cols]; // We need 12 visible rows, start row never < first fully visible row 1 - uint8_t y = osdDisplayPort->rows > 13 ? (osdDisplayPort->rows - 12) / 2 : 1; + uint8_t armScreenRow = osdDisplayPort->rows > 13 ? (osdDisplayPort->rows - 12) / 2 : 1; + uint8_t safehomeRow = 0; - strcpy(buf, "ARMED"); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); - y += 2; + strcpy(buf, "ARMED!"); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + safehomeRow = armScreenRow; + armScreenRow++; if (strlen(systemConfig()->craftName) > 0) { osdFormatCraftName(craftNameBuf); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(systemConfig()->craftName)) / 2, y, craftNameBuf ); - y += 1; + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(systemConfig()->craftName)) / 2, armScreenRow++, craftNameBuf ); } + if (posControl.waypointListValid && posControl.waypointCount > 0) { #ifdef USE_MULTI_MISSION tfp_sprintf(buf, "MISSION %u/%u (%u WP)", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow, buf); #else strcpy(buf, "*MISSION LOADED*"); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow, buf); #endif } - y += 1; + armScreenRow++; #if defined(USE_GPS) if (feature(FEATURE_GPS)) { if (STATE(GPS_FIX_HOME)) { - if (osdConfig()->osd_home_position_arm_screen){ + if (osdConfig()->osd_home_position_arm_screen) { osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); - osdFormatCoordinate(buf, SYM_LON, GPS_home.lon); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y + 1, buf); - int digits = osdConfig()->plus_code_digits; + osdFormatCoordinate(buf2, SYM_LON, GPS_home.lon); + + uint8_t gpsStartCol = (osdDisplayPort->cols - (strlen(buf) + strlen(buf2) + 2)) / 2; + displayWrite(osdDisplayPort, gpsStartCol, armScreenRow, buf); + displayWrite(osdDisplayPort, gpsStartCol + strlen(buf) + 2, armScreenRow++, buf2); + + int digits = osdConfig()->plus_code_digits; olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y + 2, buf); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); } - y += 4; + #if defined (USE_SAFE_HOME) if (safehome_distance) { // safehome found during arming if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) { strcpy(buf, "SAFEHOME FOUND; MODE OFF"); } else { - char buf2[12]; // format the distance first osdFormatDistanceStr(buf2, safehome_distance); - tfp_sprintf(buf, "%c - %s -> SAFEHOME %u", SYM_HOME, buf2, safehome_index); + tfp_sprintf(buf, "%c SAFEHOME %u @ %s", SYM_HOME, safehome_index, buf2); } textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT; - // write this message above the ARMED message to make it obvious - displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y - 8, buf, elemAttr); + // write this message below the ARMED message to make it obvious + displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, safehomeRow, buf, elemAttr); } #endif } else { strcpy(buf, "!NO HOME POSITION!"); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); - y += 1; + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); } + armScreenRow++; } #endif - if (rtcGetDateTime(&dt)) { - dateTimeFormatLocal(buf, &dt); - dateTimeSplitFormatted(buf, &date, &time); - - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(date)) / 2, y, date); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(time)) / 2, y + 1, time); - y += 3; + if (rtcGetDateTimeLocal(&dt)) { + tfp_sprintf(buf, "%04u-%02u-%02u %02u:%02u:%02u", dt.year, dt.month, dt.day, dt.hours, dt.minutes, dt.seconds); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + armScreenRow++; } tfp_sprintf(versionBuf, "INAV VERSION: %s", FC_VERSION_STRING); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, y, versionBuf); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, armScreenRow++, versionBuf); + armScreenRow++; + +#ifdef USE_STATS + if (armScreenRow < (osdDisplayPort->rows - 4)) + armScreenRow = drawStats(armScreenRow); +#endif // USE_STATS } // called when motors armed From d92538de21d0fe89744f820f78e8a54141c79455 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Mon, 18 Sep 2023 08:35:29 +0100 Subject: [PATCH 083/175] Converted tabs to 4 spaces --- src/main/cms/cms.h | 16 +- src/main/io/osd.c | 7796 ++++++++++++++++++++++---------------------- src/main/io/osd.h | 538 +-- 3 files changed, 4175 insertions(+), 4175 deletions(-) diff --git a/src/main/cms/cms.h b/src/main/cms/cms.h index 69620f354c..812975e3b4 100644 --- a/src/main/cms/cms.h +++ b/src/main/cms/cms.h @@ -7,14 +7,14 @@ #include "cms/cms_types.h" typedef enum { - CMS_KEY_NONE, - CMS_KEY_UP, - CMS_KEY_DOWN, - CMS_KEY_LEFT, - CMS_KEY_RIGHT, - CMS_KEY_ESC, - CMS_KEY_MENU, - CMS_KEY_SAVEMENU + CMS_KEY_NONE, + CMS_KEY_UP, + CMS_KEY_DOWN, + CMS_KEY_LEFT, + CMS_KEY_RIGHT, + CMS_KEY_ESC, + CMS_KEY_MENU, + CMS_KEY_SAVEMENU } cms_key_e; diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 7d2e2ed9a0..4191c670b0 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -141,8 +141,8 @@ // Wrap all string constants intenteded for display as messages with // this macro to ensure compile time length validation. #define OSD_MESSAGE_STR(x) ({ \ - STATIC_ASSERT(_CONST_STR_SIZE(x) <= OSD_MESSAGE_LENGTH, message_string_ ## __COUNTER__ ## _too_long); \ - x; \ + STATIC_ASSERT(_CONST_STR_SIZE(x) <= OSD_MESSAGE_LENGTH, message_string_ ## __COUNTER__ ## _too_long); \ + x; \ }) #define OSD_CHR_IS_NUM(c) (c >= '0' && c <= '9') @@ -163,17 +163,17 @@ static pt1Filter_t GForceFilter, GForceFilterAxis[XYZ_AXIS_COUNT]; static float GForce, GForceAxis[XYZ_AXIS_COUNT]; typedef struct statistic_s { - uint16_t max_speed; - uint16_t max_3D_speed; - uint16_t max_air_speed; - uint16_t min_voltage; // /100 - int16_t max_current; - int32_t max_power; - int16_t min_rssi; - int16_t min_lq; // for CRSF - int16_t min_rssi_dbm; // for CRSF - int32_t max_altitude; - uint32_t max_distance; + uint16_t max_speed; + uint16_t max_3D_speed; + uint16_t max_air_speed; + uint16_t min_voltage; // /100 + int16_t max_current; + int32_t max_power; + int16_t min_rssi; + int16_t min_lq; // for CRSF + int16_t min_rssi_dbm; // for CRSF + int32_t max_altitude; + uint32_t max_distance; } statistic_t; static statistic_t stats; @@ -186,8 +186,8 @@ static bool fullRedraw = false; static uint8_t armState; typedef struct osdMapData_s { - uint32_t scale; - char referenceSymbol; + uint32_t scale; + char referenceSymbol; } osdMapData_t; static osdMapData_t osdMapData; @@ -207,28 +207,28 @@ PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 8); PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 1); void osdStartedSaveProcess(void) { - savingSettings = true; + savingSettings = true; } void osdShowEEPROMSavedNotification(void) { - savingSettings = false; - notify_settings_saved = millis() + 5000; + savingSettings = false; + notify_settings_saved = millis() + 5000; } bool osdDisplayIsPAL(void) { - return displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL; + return displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL; } bool osdDisplayIsHD(void) { - if (displayScreenSize(osdDisplayPort) >= VIDEO_BUFFER_CHARS_HDZERO) - { - return true; - } - return false; + if (displayScreenSize(osdDisplayPort) >= VIDEO_BUFFER_CHARS_HDZERO) + { + return true; + } + return false; } @@ -238,11 +238,11 @@ bool osdDisplayIsHD(void) */ static void osdLeftAlignString(char *buff) { - uint8_t sp = 0, ch = 0; - uint8_t len = strlen(buff); - while (buff[sp] == ' ') sp++; - for (ch = 0; ch < (len - sp); ch++) buff[ch] = buff[ch + sp]; - for (sp = ch; sp < len; sp++) buff[sp] = ' '; + uint8_t sp = 0, ch = 0; + uint8_t len = strlen(buff); + while (buff[sp] == ' ') sp++; + for (ch = 0; ch < (len - sp); ch++) buff[ch] = buff[ch + sp]; + for (sp = ch; sp < len; sp++) buff[sp] = ' '; } /* @@ -252,29 +252,29 @@ static void osdLeftAlignString(char *buff) */ /* void osdSimpleDistanceSymbol(char *buff, int32_t dist) { - int32_t convertedDistance; - char suffix; + int32_t convertedDistance; + char suffix; - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_GA: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - convertedDistance = CENTIMETERS_TO_FEET(dist); - suffix = SYM_ALT_FT; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - convertedDistance = CENTIMETERS_TO_METERS(dist); - suffix = SYM_ALT_M; // Intentionally use the altitude symbol, as the distance symbol is not defined in BFCOMPAT mode - break; - } + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + convertedDistance = CENTIMETERS_TO_FEET(dist); + suffix = SYM_ALT_FT; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + convertedDistance = CENTIMETERS_TO_METERS(dist); + suffix = SYM_ALT_M; // Intentionally use the altitude symbol, as the distance symbol is not defined in BFCOMPAT mode + break; + } - tfp_sprintf(buff, "%5d", (int) convertedDistance); // 5 digits, allowing up to 99999 meters/feet, which should be plenty for 99.9% of use cases - buff[5] = suffix; - buff[6] = '\0'; + tfp_sprintf(buff, "%5d", (int) convertedDistance); // 5 digits, allowing up to 99999 meters/feet, which should be plenty for 99.9% of use cases + buff[5] = suffix; + buff[6] = '\0'; } */ /** @@ -284,58 +284,58 @@ static void osdLeftAlignString(char *buff) */ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) { - uint8_t digits = 3U; // Total number of digits (including decimal point) - uint8_t sym_index = 3U; // Position (index) at buffer of units symbol - uint8_t symbol_m = SYM_DIST_M; - uint8_t symbol_km = SYM_DIST_KM; - uint8_t symbol_ft = SYM_DIST_FT; - uint8_t symbol_mi = SYM_DIST_MI; - uint8_t symbol_nm = SYM_DIST_NM; + uint8_t digits = 3U; // Total number of digits (including decimal point) + uint8_t sym_index = 3U; // Position (index) at buffer of units symbol + uint8_t symbol_m = SYM_DIST_M; + uint8_t symbol_km = SYM_DIST_KM; + uint8_t symbol_ft = SYM_DIST_FT; + uint8_t symbol_mi = SYM_DIST_MI; + uint8_t symbol_nm = SYM_DIST_NM; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values - if (isBfCompatibleVideoSystem(osdConfig())) { - // Add one digit so up no switch to scaled decimal occurs above 99 - digits = 4U; - sym_index = 4U; - // Use altitude symbols on purpose, as it seems distance symbols are not defined in BFCOMPAT mode - symbol_m = SYM_ALT_M; - symbol_km = SYM_ALT_KM; - symbol_ft = SYM_ALT_FT; - symbol_mi = SYM_MI; - symbol_nm = SYM_MI; - } + if (isBfCompatibleVideoSystem(osdConfig())) { + // Add one digit so up no switch to scaled decimal occurs above 99 + digits = 4U; + sym_index = 4U; + // Use altitude symbols on purpose, as it seems distance symbols are not defined in BFCOMPAT mode + symbol_m = SYM_ALT_M; + symbol_km = SYM_ALT_KM; + symbol_ft = SYM_ALT_FT; + symbol_mi = SYM_MI; + symbol_nm = SYM_MI; + } #endif - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_MILE, decimals, 3, digits)) { - buff[sym_index] = symbol_mi; - } else { - buff[sym_index] = symbol_ft; - } - buff[sym_index + 1] = '\0'; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - if (osdFormatCentiNumber(buff, dist, METERS_PER_KILOMETER, decimals, 3, digits)) { - buff[sym_index] = symbol_km; - } else { - buff[sym_index] = symbol_m; - } - buff[sym_index + 1] = '\0'; - break; - case OSD_UNIT_GA: - if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), (uint32_t)FEET_PER_NAUTICALMILE, decimals, 3, digits)) { - buff[sym_index] = symbol_nm; - } else { - buff[sym_index] = symbol_ft; - } - buff[sym_index + 1] = '\0'; - break; - } + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), FEET_PER_MILE, decimals, 3, digits)) { + buff[sym_index] = symbol_mi; + } else { + buff[sym_index] = symbol_ft; + } + buff[sym_index + 1] = '\0'; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + if (osdFormatCentiNumber(buff, dist, METERS_PER_KILOMETER, decimals, 3, digits)) { + buff[sym_index] = symbol_km; + } else { + buff[sym_index] = symbol_m; + } + buff[sym_index + 1] = '\0'; + break; + case OSD_UNIT_GA: + if (osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(dist), (uint32_t)FEET_PER_NAUTICALMILE, decimals, 3, digits)) { + buff[sym_index] = symbol_nm; + } else { + buff[sym_index] = symbol_ft; + } + buff[sym_index + 1] = '\0'; + break; + } } /** @@ -344,45 +344,45 @@ static void osdFormatDistanceSymbol(char *buff, int32_t dist, uint8_t decimals) */ static void osdFormatDistanceStr(char *buff, int32_t dist) { - int32_t centifeet; - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - centifeet = CENTIMETERS_TO_CENTIFEET(dist); - if (abs(centifeet) < FEET_PER_MILE * 100 / 2) { - // Show feet when dist < 0.5mi - tfp_sprintf(buff, "%d%c", (int)(centifeet / 100), SYM_FT); - } else { - // Show miles when dist >= 0.5mi - tfp_sprintf(buff, "%d.%02d%c", (int)(centifeet / (100*FEET_PER_MILE)), - (abs(centifeet) % (100 * FEET_PER_MILE)) / FEET_PER_MILE, SYM_MI); - } - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - if (abs(dist) < METERS_PER_KILOMETER * 100) { - // Show meters when dist < 1km - tfp_sprintf(buff, "%d%c", (int)(dist / 100), SYM_M); - } else { - // Show kilometers when dist >= 1km - tfp_sprintf(buff, "%d.%02d%c", (int)(dist / (100*METERS_PER_KILOMETER)), - (abs(dist) % (100 * METERS_PER_KILOMETER)) / METERS_PER_KILOMETER, SYM_KM); - } - break; - case OSD_UNIT_GA: - centifeet = CENTIMETERS_TO_CENTIFEET(dist); - if (abs(centifeet) < 100000) { - // Show feet when dist < 1000ft - tfp_sprintf(buff, "%d%c", (int)(centifeet / 100), SYM_FT); - } else { - // Show nautical miles when dist >= 1000ft - tfp_sprintf(buff, "%d.%02d%c", (int)(centifeet / (100 * FEET_PER_NAUTICALMILE)), - (int)((abs(centifeet) % (int)(100 * FEET_PER_NAUTICALMILE)) / FEET_PER_NAUTICALMILE), SYM_NM); - } - break; - } + int32_t centifeet; + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + centifeet = CENTIMETERS_TO_CENTIFEET(dist); + if (abs(centifeet) < FEET_PER_MILE * 100 / 2) { + // Show feet when dist < 0.5mi + tfp_sprintf(buff, "%d%c", (int)(centifeet / 100), SYM_FT); + } else { + // Show miles when dist >= 0.5mi + tfp_sprintf(buff, "%d.%02d%c", (int)(centifeet / (100*FEET_PER_MILE)), + (abs(centifeet) % (100 * FEET_PER_MILE)) / FEET_PER_MILE, SYM_MI); + } + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + if (abs(dist) < METERS_PER_KILOMETER * 100) { + // Show meters when dist < 1km + tfp_sprintf(buff, "%d%c", (int)(dist / 100), SYM_M); + } else { + // Show kilometers when dist >= 1km + tfp_sprintf(buff, "%d.%02d%c", (int)(dist / (100*METERS_PER_KILOMETER)), + (abs(dist) % (100 * METERS_PER_KILOMETER)) / METERS_PER_KILOMETER, SYM_KM); + } + break; + case OSD_UNIT_GA: + centifeet = CENTIMETERS_TO_CENTIFEET(dist); + if (abs(centifeet) < 100000) { + // Show feet when dist < 1000ft + tfp_sprintf(buff, "%d%c", (int)(centifeet / 100), SYM_FT); + } else { + // Show nautical miles when dist >= 1000ft + tfp_sprintf(buff, "%d.%02d%c", (int)(centifeet / (100 * FEET_PER_NAUTICALMILE)), + (int)((abs(centifeet) % (int)(100 * FEET_PER_NAUTICALMILE)) / FEET_PER_NAUTICALMILE), SYM_NM); + } + break; + } } /** @@ -391,20 +391,20 @@ static void osdFormatDistanceStr(char *buff, int32_t dist) */ static int32_t osdConvertVelocityToUnit(int32_t vel) { - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - return CMSEC_TO_CENTIMPH(vel) / 100; // Convert to mph - case OSD_UNIT_METRIC: - return CMSEC_TO_CENTIKPH(vel) / 100; // Convert to kmh - case OSD_UNIT_GA: - return CMSEC_TO_CENTIKNOTS(vel) / 100; // Convert to Knots - } - // Unreachable - return -1; + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + return CMSEC_TO_CENTIMPH(vel) / 100; // Convert to mph + case OSD_UNIT_METRIC: + return CMSEC_TO_CENTIKPH(vel) / 100; // Convert to kmh + case OSD_UNIT_GA: + return CMSEC_TO_CENTIKNOTS(vel) / 100; // Convert to Knots + } + // Unreachable + return -1; } /** @@ -415,41 +415,41 @@ static int32_t osdConvertVelocityToUnit(int32_t vel) */ void osdFormatVelocityStr(char* buff, int32_t vel, bool _3D, bool _max) { - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - if (_max) { - tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_MPH : SYM_MPH)); - } else { - tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_MPH : SYM_MPH)); - } - break; - case OSD_UNIT_METRIC: - if (_max) { - tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KMH : SYM_KMH)); - } else { - tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KMH : SYM_KMH)); - } - break; - case OSD_UNIT_GA: - if (_max) { - tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KT : SYM_KT)); - } else { - tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KT : SYM_KT)); - } - break; - } + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + if (_max) { + tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_MPH : SYM_MPH)); + } else { + tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_MPH : SYM_MPH)); + } + break; + case OSD_UNIT_METRIC: + if (_max) { + tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KMH : SYM_KMH)); + } else { + tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KMH : SYM_KMH)); + } + break; + case OSD_UNIT_GA: + if (_max) { + tfp_sprintf(buff, "%c%3d%c", SYM_MAX, (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KT : SYM_KT)); + } else { + tfp_sprintf(buff, "%3d%c", (int)osdConvertVelocityToUnit(vel), (_3D ? SYM_3D_KT : SYM_KT)); + } + break; + } } /** * Returns the average velocity. This always uses stats, so can be called as an OSD element later if wanted, to show a real time average */ static void osdGenerateAverageVelocityStr(char* buff) { - uint32_t cmPerSec = getTotalTravelDistance() / getFlightTime(); - osdFormatVelocityStr(buff, cmPerSec, false, false); + uint32_t cmPerSec = getTotalTravelDistance() / getFlightTime(); + osdFormatVelocityStr(buff, cmPerSec, false, false); } /** @@ -461,35 +461,35 @@ static void osdGenerateAverageVelocityStr(char* buff) { #ifdef USE_WIND_ESTIMATOR static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) { - int32_t centivalue; - char suffix; - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - centivalue = CMSEC_TO_CENTIMPH(ws); - suffix = SYM_MPH; - break; - case OSD_UNIT_GA: - centivalue = CMSEC_TO_CENTIKNOTS(ws); - suffix = SYM_KT; - break; - default: - case OSD_UNIT_METRIC: - centivalue = CMSEC_TO_CENTIKPH(ws); - suffix = SYM_KMH; - break; - } + int32_t centivalue; + char suffix; + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + centivalue = CMSEC_TO_CENTIMPH(ws); + suffix = SYM_MPH; + break; + case OSD_UNIT_GA: + centivalue = CMSEC_TO_CENTIKNOTS(ws); + suffix = SYM_KT; + break; + default: + case OSD_UNIT_METRIC: + centivalue = CMSEC_TO_CENTIKPH(ws); + suffix = SYM_KMH; + break; + } - osdFormatCentiNumber(buff, centivalue, 0, 2, 0, 3); + osdFormatCentiNumber(buff, centivalue, 0, 2, 0, 3); - if (!isValid && ((millis() / 1000) % 4 < 2)) - suffix = '*'; + if (!isValid && ((millis() / 1000) % 4 < 2)) + suffix = '*'; - buff[3] = suffix; - buff[4] = '\0'; + buff[3] = suffix; + buff[4] = '\0'; } #endif @@ -499,29 +499,29 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) */ /* void osdSimpleAltitudeSymbol(char *buff, int32_t alt) { - int32_t convertedAltutude = 0; - char suffix = '\0'; + int32_t convertedAltutude = 0; + char suffix = '\0'; - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_GA: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - convertedAltutude = CENTIMETERS_TO_FEET(alt); - suffix = SYM_ALT_FT; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - convertedAltutude = CENTIMETERS_TO_METERS(alt); - suffix = SYM_ALT_M; - break; - } + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + convertedAltutude = CENTIMETERS_TO_FEET(alt); + suffix = SYM_ALT_FT; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + convertedAltutude = CENTIMETERS_TO_METERS(alt); + suffix = SYM_ALT_M; + break; + } - tfp_sprintf(buff, "%4d", (int) convertedAltutude); - buff[4] = suffix; - buff[5] = '\0'; + tfp_sprintf(buff, "%4d", (int) convertedAltutude); + buff[4] = suffix; + buff[5] = '\0'; } */ /** @@ -531,54 +531,54 @@ static void osdFormatWindSpeedStr(char *buff, int32_t ws, bool isValid) */ void osdFormatAltitudeSymbol(char *buff, int32_t alt) { - uint8_t totalDigits = 4U; - uint8_t digits = 4U; - uint8_t symbolIndex = 4U; - uint8_t symbolKFt = SYM_ALT_KFT; + uint8_t totalDigits = 4U; + uint8_t digits = 4U; + uint8_t symbolIndex = 4U; + uint8_t symbolKFt = SYM_ALT_KFT; - if (alt >= 0) { - digits = 3U; - buff[0] = ' '; - } + if (alt >= 0) { + digits = 3U; + buff[0] = ' '; + } #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values - if (isBfCompatibleVideoSystem(osdConfig())) { - totalDigits++; - digits++; - symbolIndex++; - symbolKFt = SYM_ALT_FT; - } + if (isBfCompatibleVideoSystem(osdConfig())) { + totalDigits++; + digits++; + symbolIndex++; + symbolKFt = SYM_ALT_FT; + } #endif - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_GA: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - if (osdFormatCentiNumber(buff + totalDigits - digits, CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, digits)) { - // Scaled to kft - buff[symbolIndex++] = symbolKFt; - } else { - // Formatted in feet - buff[symbolIndex++] = SYM_ALT_FT; - } - buff[symbolIndex] = '\0'; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - // alt is alredy in cm - if (osdFormatCentiNumber(buff + totalDigits - digits, alt, 1000, 0, 2, digits)) { - // Scaled to km - buff[symbolIndex++] = SYM_ALT_KM; - } else { - // Formatted in m - buff[symbolIndex++] = SYM_ALT_M; - } - buff[symbolIndex] = '\0'; - break; - } + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + if (osdFormatCentiNumber(buff + totalDigits - digits, CENTIMETERS_TO_CENTIFEET(alt), 1000, 0, 2, digits)) { + // Scaled to kft + buff[symbolIndex++] = symbolKFt; + } else { + // Formatted in feet + buff[symbolIndex++] = SYM_ALT_FT; + } + buff[symbolIndex] = '\0'; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + // alt is alredy in cm + if (osdFormatCentiNumber(buff + totalDigits - digits, alt, 1000, 0, 2, digits)) { + // Scaled to km + buff[symbolIndex++] = SYM_ALT_KM; + } else { + // Formatted in m + buff[symbolIndex++] = SYM_ALT_M; + } + buff[symbolIndex] = '\0'; + break; + } } /** @@ -587,52 +587,52 @@ void osdFormatAltitudeSymbol(char *buff, int32_t alt) */ static void osdFormatAltitudeStr(char *buff, int32_t alt) { - int32_t value; - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_GA: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - value = CENTIMETERS_TO_FEET(alt); - tfp_sprintf(buff, "%d%c", (int)value, SYM_FT); - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - value = CENTIMETERS_TO_METERS(alt); - tfp_sprintf(buff, "%d%c", (int)value, SYM_M); - break; - } + int32_t value; + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + value = CENTIMETERS_TO_FEET(alt); + tfp_sprintf(buff, "%d%c", (int)value, SYM_FT); + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + value = CENTIMETERS_TO_METERS(alt); + tfp_sprintf(buff, "%d%c", (int)value, SYM_M); + break; + } } static void osdFormatTime(char *buff, uint32_t seconds, char sym_m, char sym_h) { - uint32_t value = seconds; - char sym = sym_m; - // Maximum value we can show in minutes is 99 minutes and 59 seconds - if (seconds > (99 * 60) + 59) { - sym = sym_h; - value = seconds / 60; - } - buff[0] = sym; - tfp_sprintf(buff + 1, "%02d:%02d", (int)(value / 60), (int)(value % 60)); + uint32_t value = seconds; + char sym = sym_m; + // Maximum value we can show in minutes is 99 minutes and 59 seconds + if (seconds > (99 * 60) + 59) { + sym = sym_h; + value = seconds / 60; + } + buff[0] = sym; + tfp_sprintf(buff + 1, "%02d:%02d", (int)(value / 60), (int)(value % 60)); } static inline void osdFormatOnTime(char *buff) { - osdFormatTime(buff, micros() / 1000000, SYM_ON_M, SYM_ON_H); + osdFormatTime(buff, micros() / 1000000, SYM_ON_M, SYM_ON_H); } static inline void osdFormatFlyTime(char *buff, textAttributes_t *attr) { - uint32_t seconds = getFlightTime(); - osdFormatTime(buff, seconds, SYM_FLY_M, SYM_FLY_H); - if (attr && osdConfig()->time_alarm > 0) { - if (seconds / 60 >= osdConfig()->time_alarm && ARMING_FLAG(ARMED)) { - TEXT_ATTRIBUTES_ADD_BLINK(*attr); - } - } + uint32_t seconds = getFlightTime(); + osdFormatTime(buff, seconds, SYM_FLY_M, SYM_FLY_H); + if (attr && osdConfig()->time_alarm > 0) { + if (seconds / 60 >= osdConfig()->time_alarm && ARMING_FLAG(ARMED)) { + TEXT_ATTRIBUTES_ADD_BLINK(*attr); + } + } } /** @@ -641,23 +641,23 @@ static inline void osdFormatFlyTime(char *buff, textAttributes_t *attr) */ char *osdFormatTrimWhiteSpace(char *buff) { - char *end; + char *end; - // Trim leading spaces - while(isspace((unsigned char)*buff)) buff++; + // Trim leading spaces + while(isspace((unsigned char)*buff)) buff++; - // All spaces? - if(*buff == 0) - return buff; + // All spaces? + if(*buff == 0) + return buff; - // Trim trailing spaces - end = buff + strlen(buff) - 1; - while(end > buff && isspace((unsigned char)*end)) end--; + // Trim trailing spaces + end = buff + strlen(buff) - 1; + while(end > buff && isspace((unsigned char)*end)) end--; - // Write new null terminator character - end[1] = '\0'; + // Write new null terminator character + end[1] = '\0'; - return buff; + return buff; } /** @@ -665,32 +665,32 @@ char *osdFormatTrimWhiteSpace(char *buff) */ static uint16_t osdConvertRSSI(void) { - // change range to [0, 99] - return constrain(getRSSI() * 100 / RSSI_MAX_VALUE, 0, 99); + // change range to [0, 99] + return constrain(getRSSI() * 100 / RSSI_MAX_VALUE, 0, 99); } static uint16_t osdGetCrsfLQ(void) { - int16_t statsLQ = rxLinkStatistics.uplinkLQ; - int16_t scaledLQ = scaleRange(constrain(statsLQ, 0, 100), 0, 100, 170, 300); - int16_t displayedLQ = 0; - switch (osdConfig()->crsf_lq_format) { - case OSD_CRSF_LQ_TYPE1: - displayedLQ = statsLQ; - break; - case OSD_CRSF_LQ_TYPE2: - displayedLQ = statsLQ; - break; - case OSD_CRSF_LQ_TYPE3: - displayedLQ = rxLinkStatistics.rfMode >= 2 ? scaledLQ : statsLQ; - break; - } - return displayedLQ; + int16_t statsLQ = rxLinkStatistics.uplinkLQ; + int16_t scaledLQ = scaleRange(constrain(statsLQ, 0, 100), 0, 100, 170, 300); + int16_t displayedLQ = 0; + switch (osdConfig()->crsf_lq_format) { + case OSD_CRSF_LQ_TYPE1: + displayedLQ = statsLQ; + break; + case OSD_CRSF_LQ_TYPE2: + displayedLQ = statsLQ; + break; + case OSD_CRSF_LQ_TYPE3: + displayedLQ = rxLinkStatistics.rfMode >= 2 ? scaledLQ : statsLQ; + break; + } + return displayedLQ; } static int16_t osdGetCrsfdBm(void) { - return rxLinkStatistics.uplinkRSSI; + return rxLinkStatistics.uplinkRSSI; } /** * Displays a temperature postfixed with a symbol depending on the current unit system @@ -700,366 +700,366 @@ static int16_t osdGetCrsfdBm(void) */ static void osdDisplayTemperature(uint8_t elemPosX, uint8_t elemPosY, uint16_t symbol, const char *label, bool valid, int16_t temperature, int16_t alarm_min, int16_t alarm_max) { - char buff[TEMPERATURE_LABEL_LEN + 2 < 6 ? 6 : TEMPERATURE_LABEL_LEN + 2]; - textAttributes_t elemAttr = valid ? TEXT_ATTRIBUTES_NONE : _TEXT_ATTRIBUTES_BLINK_BIT; - uint8_t valueXOffset = 0; + char buff[TEMPERATURE_LABEL_LEN + 2 < 6 ? 6 : TEMPERATURE_LABEL_LEN + 2]; + textAttributes_t elemAttr = valid ? TEXT_ATTRIBUTES_NONE : _TEXT_ATTRIBUTES_BLINK_BIT; + uint8_t valueXOffset = 0; - if (symbol) { - buff[0] = symbol; - buff[1] = '\0'; - displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); - valueXOffset = 1; - } + if (symbol) { + buff[0] = symbol; + buff[1] = '\0'; + displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); + valueXOffset = 1; + } #ifdef USE_TEMPERATURE_SENSOR - else if (label[0] != '\0') { - uint8_t label_len = strnlen(label, TEMPERATURE_LABEL_LEN); - memcpy(buff, label, label_len); - memset(buff + label_len, ' ', TEMPERATURE_LABEL_LEN + 1 - label_len); - buff[5] = '\0'; - displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); - valueXOffset = osdConfig()->temp_label_align == OSD_ALIGN_LEFT ? 5 : label_len + 1; - } + else if (label[0] != '\0') { + uint8_t label_len = strnlen(label, TEMPERATURE_LABEL_LEN); + memcpy(buff, label, label_len); + memset(buff + label_len, ' ', TEMPERATURE_LABEL_LEN + 1 - label_len); + buff[5] = '\0'; + displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); + valueXOffset = osdConfig()->temp_label_align == OSD_ALIGN_LEFT ? 5 : label_len + 1; + } #else - UNUSED(label); + UNUSED(label); #endif - if (valid) { + if (valid) { - if ((temperature <= alarm_min) || (temperature >= alarm_max)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - if (osdConfig()->units == OSD_UNIT_IMPERIAL) temperature = temperature * 9 / 5.0f + 320; - tfp_sprintf(buff, "%3d", temperature / 10); + if ((temperature <= alarm_min) || (temperature >= alarm_max)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + if (osdConfig()->units == OSD_UNIT_IMPERIAL) temperature = temperature * 9 / 5.0f + 320; + tfp_sprintf(buff, "%3d", temperature / 10); - } else - strcpy(buff, "---"); + } else + strcpy(buff, "---"); - buff[3] = osdConfig()->units == OSD_UNIT_IMPERIAL ? SYM_TEMP_F : SYM_TEMP_C; - buff[4] = '\0'; + buff[3] = osdConfig()->units == OSD_UNIT_IMPERIAL ? SYM_TEMP_F : SYM_TEMP_C; + buff[4] = '\0'; - displayWriteWithAttr(osdDisplayPort, elemPosX + valueXOffset, elemPosY, buff, elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + valueXOffset, elemPosY, buff, elemAttr); } #ifdef USE_TEMPERATURE_SENSOR static void osdDisplayTemperatureSensor(uint8_t elemPosX, uint8_t elemPosY, uint8_t sensorIndex) { - int16_t temperature; - const bool valid = getSensorTemperature(sensorIndex, &temperature); - const tempSensorConfig_t *sensorConfig = tempSensorConfig(sensorIndex); - uint16_t symbol = sensorConfig->osdSymbol ? SYM_TEMP_SENSOR_FIRST + sensorConfig->osdSymbol - 1 : 0; - osdDisplayTemperature(elemPosX, elemPosY, symbol, sensorConfig->label, valid, temperature, sensorConfig->alarm_min, sensorConfig->alarm_max); + int16_t temperature; + const bool valid = getSensorTemperature(sensorIndex, &temperature); + const tempSensorConfig_t *sensorConfig = tempSensorConfig(sensorIndex); + uint16_t symbol = sensorConfig->osdSymbol ? SYM_TEMP_SENSOR_FIRST + sensorConfig->osdSymbol - 1 : 0; + osdDisplayTemperature(elemPosX, elemPosY, symbol, sensorConfig->label, valid, temperature, sensorConfig->alarm_min, sensorConfig->alarm_max); } #endif static void osdFormatCoordinate(char *buff, char sym, int32_t val) { - // up to 4 for number + 1 for the symbol + null terminator + fill the rest with decimals - const int coordinateLength = osdConfig()->coordinate_digits + 1; + // up to 4 for number + 1 for the symbol + null terminator + fill the rest with decimals + const int coordinateLength = osdConfig()->coordinate_digits + 1; - buff[0] = sym; - int32_t integerPart = val / GPS_DEGREES_DIVIDER; - // Latitude maximum integer width is 3 (-90) while - // longitude maximum integer width is 4 (-180). - int integerDigits = tfp_sprintf(buff + 1, (integerPart == 0 && val < 0) ? "-%d" : "%d", (int)integerPart); - // We can show up to 7 digits in decimalPart. - int32_t decimalPart = abs(val % (int)GPS_DEGREES_DIVIDER); - STATIC_ASSERT(GPS_DEGREES_DIVIDER == 1e7, adjust_max_decimal_digits); - int decimalDigits; - bool bfcompat = false; // Assume BFCOMPAT mode is no enabled + buff[0] = sym; + int32_t integerPart = val / GPS_DEGREES_DIVIDER; + // Latitude maximum integer width is 3 (-90) while + // longitude maximum integer width is 4 (-180). + int integerDigits = tfp_sprintf(buff + 1, (integerPart == 0 && val < 0) ? "-%d" : "%d", (int)integerPart); + // We can show up to 7 digits in decimalPart. + int32_t decimalPart = abs(val % (int)GPS_DEGREES_DIVIDER); + STATIC_ASSERT(GPS_DEGREES_DIVIDER == 1e7, adjust_max_decimal_digits); + int decimalDigits; + bool bfcompat = false; // Assume BFCOMPAT mode is no enabled #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if(isBfCompatibleVideoSystem(osdConfig())) { - bfcompat = true; - } + if(isBfCompatibleVideoSystem(osdConfig())) { + bfcompat = true; + } #endif - if (!bfcompat) { - decimalDigits = tfp_sprintf(buff + 1 + integerDigits, "%07d", (int)decimalPart); - // Embbed the decimal separator - buff[1 + integerDigits - 1] += SYM_ZERO_HALF_TRAILING_DOT - '0'; - buff[1 + integerDigits] += SYM_ZERO_HALF_LEADING_DOT - '0'; - } else { - // BFCOMPAT mode enabled - decimalDigits = tfp_sprintf(buff + 1 + integerDigits, ".%06d", (int)decimalPart); - } - // Fill up to coordinateLength with zeros - int total = 1 + integerDigits + decimalDigits; - while(total < coordinateLength) { - buff[total] = '0'; - total++; - } - buff[coordinateLength] = '\0'; + if (!bfcompat) { + decimalDigits = tfp_sprintf(buff + 1 + integerDigits, "%07d", (int)decimalPart); + // Embbed the decimal separator + buff[1 + integerDigits - 1] += SYM_ZERO_HALF_TRAILING_DOT - '0'; + buff[1 + integerDigits] += SYM_ZERO_HALF_LEADING_DOT - '0'; + } else { + // BFCOMPAT mode enabled + decimalDigits = tfp_sprintf(buff + 1 + integerDigits, ".%06d", (int)decimalPart); + } + // Fill up to coordinateLength with zeros + int total = 1 + integerDigits + decimalDigits; + while(total < coordinateLength) { + buff[total] = '0'; + total++; + } + buff[coordinateLength] = '\0'; } static void osdFormatCraftName(char *buff) { - if (strlen(systemConfig()->craftName) == 0) - strcpy(buff, "CRAFT_NAME"); - else { - for (int i = 0; i < MAX_NAME_LENGTH; i++) { - buff[i] = sl_toupper((unsigned char)systemConfig()->craftName[i]); - if (systemConfig()->craftName[i] == 0) - break; - } - } + if (strlen(systemConfig()->craftName) == 0) + strcpy(buff, "CRAFT_NAME"); + else { + for (int i = 0; i < MAX_NAME_LENGTH; i++) { + buff[i] = sl_toupper((unsigned char)systemConfig()->craftName[i]); + if (systemConfig()->craftName[i] == 0) + break; + } + } } void osdFormatPilotName(char *buff) { - if (strlen(systemConfig()->pilotName) == 0) - strcpy(buff, "PILOT_NAME"); - else { - for (int i = 0; i < MAX_NAME_LENGTH; i++) { - buff[i] = sl_toupper((unsigned char)systemConfig()->pilotName[i]); - if (systemConfig()->pilotName[i] == 0) - break; - } - } + if (strlen(systemConfig()->pilotName) == 0) + strcpy(buff, "PILOT_NAME"); + else { + for (int i = 0; i < MAX_NAME_LENGTH; i++) { + buff[i] = sl_toupper((unsigned char)systemConfig()->pilotName[i]); + if (systemConfig()->pilotName[i] == 0) + break; + } + } } static const char * osdArmingDisabledReasonMessage(void) { - const char *message = NULL; - char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; + const char *message = NULL; + char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; - switch (isArmingDisabledReason()) { - case ARMING_DISABLED_FAILSAFE_SYSTEM: - // See handling of FAILSAFE_RX_LOSS_MONITORING in failsafe.c - if (failsafePhase() == FAILSAFE_RX_LOSS_MONITORING) { - if (failsafeIsReceivingRxData()) { - // If we're not using sticks, it means the ARM switch - // hasn't been off since entering FAILSAFE_RX_LOSS_MONITORING - // yet - return OSD_MESSAGE_STR(OSD_MSG_TURN_ARM_SW_OFF); - } - // Not receiving RX data - return OSD_MESSAGE_STR(OSD_MSG_RC_RX_LINK_LOST); - } - return OSD_MESSAGE_STR(OSD_MSG_DISABLED_BY_FS); - case ARMING_DISABLED_NOT_LEVEL: - return OSD_MESSAGE_STR(OSD_MSG_AIRCRAFT_UNLEVEL); - case ARMING_DISABLED_SENSORS_CALIBRATING: - return OSD_MESSAGE_STR(OSD_MSG_SENSORS_CAL); - case ARMING_DISABLED_SYSTEM_OVERLOADED: - return OSD_MESSAGE_STR(OSD_MSG_SYS_OVERLOADED); - case ARMING_DISABLED_NAVIGATION_UNSAFE: - // Check the exact reason - switch (navigationIsBlockingArming(NULL)) { - char buf[6]; - case NAV_ARMING_BLOCKER_NONE: - break; - case NAV_ARMING_BLOCKER_MISSING_GPS_FIX: - return OSD_MESSAGE_STR(OSD_MSG_WAITING_GPS_FIX); - case NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE: - return OSD_MESSAGE_STR(OSD_MSG_DISABLE_NAV_FIRST); - case NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR: - osdFormatDistanceSymbol(buf, distanceToFirstWP(), 0); - tfp_sprintf(messageBuf, "FIRST WP TOO FAR (%s)", buf); - return message = messageBuf; - case NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR: - return OSD_MESSAGE_STR(OSD_MSG_JUMP_WP_MISCONFIG); - } - break; - case ARMING_DISABLED_COMPASS_NOT_CALIBRATED: - return OSD_MESSAGE_STR(OSD_MSG_MAG_NOT_CAL); - case ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED: - return OSD_MESSAGE_STR(OSD_MSG_ACC_NOT_CAL); - case ARMING_DISABLED_ARM_SWITCH: - return OSD_MESSAGE_STR(OSD_MSG_DISARM_1ST); - case ARMING_DISABLED_HARDWARE_FAILURE: - { - if (!HW_SENSOR_IS_HEALTHY(getHwGyroStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_GYRO_FAILURE); - } - if (!HW_SENSOR_IS_HEALTHY(getHwAccelerometerStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_ACC_FAIL); - } - if (!HW_SENSOR_IS_HEALTHY(getHwCompassStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_MAG_FAIL); - } - if (!HW_SENSOR_IS_HEALTHY(getHwBarometerStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_BARO_FAIL); - } - if (!HW_SENSOR_IS_HEALTHY(getHwGPSStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_GPS_FAIL); - } - if (!HW_SENSOR_IS_HEALTHY(getHwRangefinderStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_RANGEFINDER_FAIL); - } - if (!HW_SENSOR_IS_HEALTHY(getHwPitotmeterStatus())) { - return OSD_MESSAGE_STR(OSD_MSG_PITOT_FAIL); - } - } - return OSD_MESSAGE_STR(OSD_MSG_HW_FAIL); - case ARMING_DISABLED_BOXFAILSAFE: - return OSD_MESSAGE_STR(OSD_MSG_FS_EN); - case ARMING_DISABLED_BOXKILLSWITCH: - return OSD_MESSAGE_STR(OSD_MSG_KILL_SW_EN); - case ARMING_DISABLED_RC_LINK: - return OSD_MESSAGE_STR(OSD_MSG_NO_RC_LINK); - case ARMING_DISABLED_THROTTLE: - return OSD_MESSAGE_STR(OSD_MSG_THROTTLE_NOT_LOW); - case ARMING_DISABLED_ROLLPITCH_NOT_CENTERED: - return OSD_MESSAGE_STR(OSD_MSG_ROLLPITCH_OFFCENTER); - case ARMING_DISABLED_SERVO_AUTOTRIM: - return OSD_MESSAGE_STR(OSD_MSG_AUTOTRIM_ACTIVE); - case ARMING_DISABLED_OOM: - return OSD_MESSAGE_STR(OSD_MSG_NOT_ENOUGH_MEMORY); - case ARMING_DISABLED_INVALID_SETTING: - return OSD_MESSAGE_STR(OSD_MSG_INVALID_SETTING); - case ARMING_DISABLED_CLI: - return OSD_MESSAGE_STR(OSD_MSG_CLI_ACTIVE); - case ARMING_DISABLED_PWM_OUTPUT_ERROR: - return OSD_MESSAGE_STR(OSD_MSG_PWM_INIT_ERROR); - case ARMING_DISABLED_NO_PREARM: - return OSD_MESSAGE_STR(OSD_MSG_NO_PREARM); - case ARMING_DISABLED_DSHOT_BEEPER: - return OSD_MESSAGE_STR(OSD_MSG_DSHOT_BEEPER); - // Cases without message - case ARMING_DISABLED_LANDING_DETECTED: - FALLTHROUGH; - case ARMING_DISABLED_CMS_MENU: - FALLTHROUGH; - case ARMING_DISABLED_OSD_MENU: - FALLTHROUGH; - case ARMING_DISABLED_ALL_FLAGS: - FALLTHROUGH; - case ARMED: - FALLTHROUGH; - case SIMULATOR_MODE_HITL: - FALLTHROUGH; - case SIMULATOR_MODE_SITL: - FALLTHROUGH; - case WAS_EVER_ARMED: - break; - } - return NULL; + switch (isArmingDisabledReason()) { + case ARMING_DISABLED_FAILSAFE_SYSTEM: + // See handling of FAILSAFE_RX_LOSS_MONITORING in failsafe.c + if (failsafePhase() == FAILSAFE_RX_LOSS_MONITORING) { + if (failsafeIsReceivingRxData()) { + // If we're not using sticks, it means the ARM switch + // hasn't been off since entering FAILSAFE_RX_LOSS_MONITORING + // yet + return OSD_MESSAGE_STR(OSD_MSG_TURN_ARM_SW_OFF); + } + // Not receiving RX data + return OSD_MESSAGE_STR(OSD_MSG_RC_RX_LINK_LOST); + } + return OSD_MESSAGE_STR(OSD_MSG_DISABLED_BY_FS); + case ARMING_DISABLED_NOT_LEVEL: + return OSD_MESSAGE_STR(OSD_MSG_AIRCRAFT_UNLEVEL); + case ARMING_DISABLED_SENSORS_CALIBRATING: + return OSD_MESSAGE_STR(OSD_MSG_SENSORS_CAL); + case ARMING_DISABLED_SYSTEM_OVERLOADED: + return OSD_MESSAGE_STR(OSD_MSG_SYS_OVERLOADED); + case ARMING_DISABLED_NAVIGATION_UNSAFE: + // Check the exact reason + switch (navigationIsBlockingArming(NULL)) { + char buf[6]; + case NAV_ARMING_BLOCKER_NONE: + break; + case NAV_ARMING_BLOCKER_MISSING_GPS_FIX: + return OSD_MESSAGE_STR(OSD_MSG_WAITING_GPS_FIX); + case NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE: + return OSD_MESSAGE_STR(OSD_MSG_DISABLE_NAV_FIRST); + case NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR: + osdFormatDistanceSymbol(buf, distanceToFirstWP(), 0); + tfp_sprintf(messageBuf, "FIRST WP TOO FAR (%s)", buf); + return message = messageBuf; + case NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR: + return OSD_MESSAGE_STR(OSD_MSG_JUMP_WP_MISCONFIG); + } + break; + case ARMING_DISABLED_COMPASS_NOT_CALIBRATED: + return OSD_MESSAGE_STR(OSD_MSG_MAG_NOT_CAL); + case ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED: + return OSD_MESSAGE_STR(OSD_MSG_ACC_NOT_CAL); + case ARMING_DISABLED_ARM_SWITCH: + return OSD_MESSAGE_STR(OSD_MSG_DISARM_1ST); + case ARMING_DISABLED_HARDWARE_FAILURE: + { + if (!HW_SENSOR_IS_HEALTHY(getHwGyroStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_GYRO_FAILURE); + } + if (!HW_SENSOR_IS_HEALTHY(getHwAccelerometerStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_ACC_FAIL); + } + if (!HW_SENSOR_IS_HEALTHY(getHwCompassStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_MAG_FAIL); + } + if (!HW_SENSOR_IS_HEALTHY(getHwBarometerStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_BARO_FAIL); + } + if (!HW_SENSOR_IS_HEALTHY(getHwGPSStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_GPS_FAIL); + } + if (!HW_SENSOR_IS_HEALTHY(getHwRangefinderStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_RANGEFINDER_FAIL); + } + if (!HW_SENSOR_IS_HEALTHY(getHwPitotmeterStatus())) { + return OSD_MESSAGE_STR(OSD_MSG_PITOT_FAIL); + } + } + return OSD_MESSAGE_STR(OSD_MSG_HW_FAIL); + case ARMING_DISABLED_BOXFAILSAFE: + return OSD_MESSAGE_STR(OSD_MSG_FS_EN); + case ARMING_DISABLED_BOXKILLSWITCH: + return OSD_MESSAGE_STR(OSD_MSG_KILL_SW_EN); + case ARMING_DISABLED_RC_LINK: + return OSD_MESSAGE_STR(OSD_MSG_NO_RC_LINK); + case ARMING_DISABLED_THROTTLE: + return OSD_MESSAGE_STR(OSD_MSG_THROTTLE_NOT_LOW); + case ARMING_DISABLED_ROLLPITCH_NOT_CENTERED: + return OSD_MESSAGE_STR(OSD_MSG_ROLLPITCH_OFFCENTER); + case ARMING_DISABLED_SERVO_AUTOTRIM: + return OSD_MESSAGE_STR(OSD_MSG_AUTOTRIM_ACTIVE); + case ARMING_DISABLED_OOM: + return OSD_MESSAGE_STR(OSD_MSG_NOT_ENOUGH_MEMORY); + case ARMING_DISABLED_INVALID_SETTING: + return OSD_MESSAGE_STR(OSD_MSG_INVALID_SETTING); + case ARMING_DISABLED_CLI: + return OSD_MESSAGE_STR(OSD_MSG_CLI_ACTIVE); + case ARMING_DISABLED_PWM_OUTPUT_ERROR: + return OSD_MESSAGE_STR(OSD_MSG_PWM_INIT_ERROR); + case ARMING_DISABLED_NO_PREARM: + return OSD_MESSAGE_STR(OSD_MSG_NO_PREARM); + case ARMING_DISABLED_DSHOT_BEEPER: + return OSD_MESSAGE_STR(OSD_MSG_DSHOT_BEEPER); + // Cases without message + case ARMING_DISABLED_LANDING_DETECTED: + FALLTHROUGH; + case ARMING_DISABLED_CMS_MENU: + FALLTHROUGH; + case ARMING_DISABLED_OSD_MENU: + FALLTHROUGH; + case ARMING_DISABLED_ALL_FLAGS: + FALLTHROUGH; + case ARMED: + FALLTHROUGH; + case SIMULATOR_MODE_HITL: + FALLTHROUGH; + case SIMULATOR_MODE_SITL: + FALLTHROUGH; + case WAS_EVER_ARMED: + break; + } + return NULL; } static const char * osdFailsafePhaseMessage(void) { - // See failsafe.h for each phase explanation - switch (failsafePhase()) { - case FAILSAFE_RETURN_TO_HOME: - // XXX: Keep this in sync with OSD_FLYMODE. - return OSD_MESSAGE_STR(OSD_MSG_RTH_FS); - case FAILSAFE_LANDING: - // This should be considered an emergengy landing - return OSD_MESSAGE_STR(OSD_MSG_EMERG_LANDING_FS); - case FAILSAFE_RX_LOSS_MONITORING: - // Only reachable from FAILSAFE_LANDED, which performs - // a disarm. Since aircraft has been disarmed, we no - // longer show failsafe details. - FALLTHROUGH; - case FAILSAFE_LANDED: - // Very brief, disarms and transitions into - // FAILSAFE_RX_LOSS_MONITORING. Note that it prevents - // further rearming via ARMING_DISABLED_FAILSAFE_SYSTEM, - // so we'll show the user how to re-arm in when - // that flag is the reason to prevent arming. - FALLTHROUGH; - case FAILSAFE_RX_LOSS_IDLE: - // This only happens when user has chosen NONE as FS - // procedure. The recovery messages should be enough. - FALLTHROUGH; - case FAILSAFE_IDLE: - // Failsafe not active - FALLTHROUGH; - case FAILSAFE_RX_LOSS_DETECTED: - // Very brief, changes to FAILSAFE_RX_LOSS_RECOVERED - // or the FS procedure immediately. - FALLTHROUGH; - case FAILSAFE_RX_LOSS_RECOVERED: - // Exiting failsafe - break; - } - return NULL; + // See failsafe.h for each phase explanation + switch (failsafePhase()) { + case FAILSAFE_RETURN_TO_HOME: + // XXX: Keep this in sync with OSD_FLYMODE. + return OSD_MESSAGE_STR(OSD_MSG_RTH_FS); + case FAILSAFE_LANDING: + // This should be considered an emergengy landing + return OSD_MESSAGE_STR(OSD_MSG_EMERG_LANDING_FS); + case FAILSAFE_RX_LOSS_MONITORING: + // Only reachable from FAILSAFE_LANDED, which performs + // a disarm. Since aircraft has been disarmed, we no + // longer show failsafe details. + FALLTHROUGH; + case FAILSAFE_LANDED: + // Very brief, disarms and transitions into + // FAILSAFE_RX_LOSS_MONITORING. Note that it prevents + // further rearming via ARMING_DISABLED_FAILSAFE_SYSTEM, + // so we'll show the user how to re-arm in when + // that flag is the reason to prevent arming. + FALLTHROUGH; + case FAILSAFE_RX_LOSS_IDLE: + // This only happens when user has chosen NONE as FS + // procedure. The recovery messages should be enough. + FALLTHROUGH; + case FAILSAFE_IDLE: + // Failsafe not active + FALLTHROUGH; + case FAILSAFE_RX_LOSS_DETECTED: + // Very brief, changes to FAILSAFE_RX_LOSS_RECOVERED + // or the FS procedure immediately. + FALLTHROUGH; + case FAILSAFE_RX_LOSS_RECOVERED: + // Exiting failsafe + break; + } + return NULL; } static const char * osdFailsafeInfoMessage(void) { - if (failsafeIsReceivingRxData()) { - // User must move sticks to exit FS mode - return OSD_MESSAGE_STR(OSD_MSG_MOVE_EXIT_FS); - } - return OSD_MESSAGE_STR(OSD_MSG_RC_RX_LINK_LOST); + if (failsafeIsReceivingRxData()) { + // User must move sticks to exit FS mode + return OSD_MESSAGE_STR(OSD_MSG_MOVE_EXIT_FS); + } + return OSD_MESSAGE_STR(OSD_MSG_RC_RX_LINK_LOST); } #if defined(USE_SAFE_HOME) static const char * divertingToSafehomeMessage(void) { - if (NAV_Status.state != MW_NAV_STATE_HOVER_ABOVE_HOME && safehome_applied) { - return OSD_MESSAGE_STR(OSD_MSG_DIVERT_SAFEHOME); - } - return NULL; + if (NAV_Status.state != MW_NAV_STATE_HOVER_ABOVE_HOME && safehome_applied) { + return OSD_MESSAGE_STR(OSD_MSG_DIVERT_SAFEHOME); + } + return NULL; } #endif static const char * navigationStateMessage(void) { - switch (NAV_Status.state) { - case MW_NAV_STATE_NONE: - break; - case MW_NAV_STATE_RTH_START: - return OSD_MESSAGE_STR(OSD_MSG_STARTING_RTH); - case MW_NAV_STATE_RTH_CLIMB: - return OSD_MESSAGE_STR(OSD_MSG_RTH_CLIMB); - case MW_NAV_STATE_RTH_ENROUTE: - if (posControl.flags.rthTrackbackActive) { - return OSD_MESSAGE_STR(OSD_MSG_RTH_TRACKBACK); - } else { - return OSD_MESSAGE_STR(OSD_MSG_HEADING_HOME); - } - case MW_NAV_STATE_HOLD_INFINIT: - // Used by HOLD flight modes. No information to add. - break; - case MW_NAV_STATE_HOLD_TIMED: - // "HOLDING WP FOR xx S" Countdown added in osdGetSystemMessage - break; - case MW_NAV_STATE_WP_ENROUTE: - // "TO WP" + WP countdown added in osdGetSystemMessage - break; - case MW_NAV_STATE_PROCESS_NEXT: - return OSD_MESSAGE_STR(OSD_MSG_PREPARE_NEXT_WP); - case MW_NAV_STATE_DO_JUMP: - // Not used - break; - case MW_NAV_STATE_LAND_START: - // Not used - break; - case MW_NAV_STATE_EMERGENCY_LANDING: - return OSD_MESSAGE_STR(OSD_MSG_EMERG_LANDING); - case MW_NAV_STATE_LAND_IN_PROGRESS: - return OSD_MESSAGE_STR(OSD_MSG_LANDING); - case MW_NAV_STATE_HOVER_ABOVE_HOME: - if (STATE(FIXED_WING_LEGACY)) { + switch (NAV_Status.state) { + case MW_NAV_STATE_NONE: + break; + case MW_NAV_STATE_RTH_START: + return OSD_MESSAGE_STR(OSD_MSG_STARTING_RTH); + case MW_NAV_STATE_RTH_CLIMB: + return OSD_MESSAGE_STR(OSD_MSG_RTH_CLIMB); + case MW_NAV_STATE_RTH_ENROUTE: + if (posControl.flags.rthTrackbackActive) { + return OSD_MESSAGE_STR(OSD_MSG_RTH_TRACKBACK); + } else { + return OSD_MESSAGE_STR(OSD_MSG_HEADING_HOME); + } + case MW_NAV_STATE_HOLD_INFINIT: + // Used by HOLD flight modes. No information to add. + break; + case MW_NAV_STATE_HOLD_TIMED: + // "HOLDING WP FOR xx S" Countdown added in osdGetSystemMessage + break; + case MW_NAV_STATE_WP_ENROUTE: + // "TO WP" + WP countdown added in osdGetSystemMessage + break; + case MW_NAV_STATE_PROCESS_NEXT: + return OSD_MESSAGE_STR(OSD_MSG_PREPARE_NEXT_WP); + case MW_NAV_STATE_DO_JUMP: + // Not used + break; + case MW_NAV_STATE_LAND_START: + // Not used + break; + case MW_NAV_STATE_EMERGENCY_LANDING: + return OSD_MESSAGE_STR(OSD_MSG_EMERG_LANDING); + case MW_NAV_STATE_LAND_IN_PROGRESS: + return OSD_MESSAGE_STR(OSD_MSG_LANDING); + case MW_NAV_STATE_HOVER_ABOVE_HOME: + if (STATE(FIXED_WING_LEGACY)) { #if defined(USE_SAFE_HOME) - if (safehome_applied) { - return OSD_MESSAGE_STR(OSD_MSG_LOITERING_SAFEHOME); - } + if (safehome_applied) { + return OSD_MESSAGE_STR(OSD_MSG_LOITERING_SAFEHOME); + } #endif - return OSD_MESSAGE_STR(OSD_MSG_LOITERING_HOME); - } - return OSD_MESSAGE_STR(OSD_MSG_HOVERING); - case MW_NAV_STATE_LANDED: - return OSD_MESSAGE_STR(OSD_MSG_LANDED); - case MW_NAV_STATE_LAND_SETTLE: - return OSD_MESSAGE_STR(OSD_MSG_PREPARING_LAND); - case MW_NAV_STATE_LAND_START_DESCENT: - // Not used - break; - } - return NULL; + return OSD_MESSAGE_STR(OSD_MSG_LOITERING_HOME); + } + return OSD_MESSAGE_STR(OSD_MSG_HOVERING); + case MW_NAV_STATE_LANDED: + return OSD_MESSAGE_STR(OSD_MSG_LANDED); + case MW_NAV_STATE_LAND_SETTLE: + return OSD_MESSAGE_STR(OSD_MSG_PREPARING_LAND); + case MW_NAV_STATE_LAND_START_DESCENT: + // Not used + break; + } + return NULL; } static void osdFormatMessage(char *buff, size_t size, const char *message, bool isCenteredText) { - // String is always filled with Blanks - memset(buff, SYM_BLANK, size); - if (message) { - size_t messageLength = strlen(message); - int rem = isCenteredText ? MAX(0, (int)size - (int)messageLength) : 0; - strncpy(buff + rem / 2, message, MIN((int)size - rem / 2, (int)messageLength)); - } - // Ensure buff is zero terminated - buff[size] = '\0'; + // String is always filled with Blanks + memset(buff, SYM_BLANK, size); + if (message) { + size_t messageLength = strlen(message); + int rem = isCenteredText ? MAX(0, (int)size - (int)messageLength) : 0; + strncpy(buff + rem / 2, message, MIN((int)size - rem / 2, (int)messageLength)); + } + // Ensure buff is zero terminated + buff[size] = '\0'; } /** @@ -1068,25 +1068,25 @@ static void osdFormatMessage(char *buff, size_t size, const char *message, bool **/ static void osdFormatBatteryChargeSymbol(char *buff) { - uint8_t p = calculateBatteryPercentage(); - p = (100 - p) / 16.6; - buff[0] = SYM_BATT_FULL + p; + uint8_t p = calculateBatteryPercentage(); + p = (100 - p) / 16.6; + buff[0] = SYM_BATT_FULL + p; } static void osdUpdateBatteryCapacityOrVoltageTextAttributes(textAttributes_t *attr) { - const batteryState_e batteryState = getBatteryState(); + const batteryState_e batteryState = getBatteryState(); - if (batteryState == BATTERY_WARNING || batteryState == BATTERY_CRITICAL) { - TEXT_ATTRIBUTES_ADD_BLINK(*attr); - } + if (batteryState == BATTERY_WARNING || batteryState == BATTERY_CRITICAL) { + TEXT_ATTRIBUTES_ADD_BLINK(*attr); + } } void osdCrosshairPosition(uint8_t *x, uint8_t *y) { - *x = osdDisplayPort->cols / 2; - *y = osdDisplayPort->rows / 2; - *y -= osdConfig()->horizon_offset; // positive horizon_offset moves the HUD up, negative moves down + *x = osdDisplayPort->cols / 2; + *y = osdDisplayPort->rows / 2; + *y -= osdConfig()->horizon_offset; // positive horizon_offset moves the HUD up, negative moves down } /** @@ -1095,13 +1095,13 @@ void osdCrosshairPosition(uint8_t *x, uint8_t *y) */ bool osdUsingScaledThrottle(void) { - bool usingScaledThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_SCALED_THROTTLE_POS]); - bool usingRCThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_THROTTLE_POS]); + bool usingScaledThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_SCALED_THROTTLE_POS]); + bool usingRCThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_THROTTLE_POS]); - if (!usingScaledThrottle && !usingRCThrottle) - usingScaledThrottle = true; + if (!usingScaledThrottle && !usingRCThrottle) + usingScaledThrottle = true; - return usingScaledThrottle; + return usingScaledThrottle; } /** @@ -1110,26 +1110,26 @@ bool osdUsingScaledThrottle(void) **/ static void osdFormatThrottlePosition(char *buff, bool useScaled, textAttributes_t *elemAttr) { - if (useScaled) { - buff[0] = SYM_SCALE; - } else { - buff[0] = SYM_BLANK; - } - buff[1] = SYM_THR; - if (navigationIsControllingThrottle()) { - buff[0] = SYM_AUTO_THR0; - buff[1] = SYM_AUTO_THR1; - if (isFixedWingAutoThrottleManuallyIncreased()) { - TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr); - } - useScaled = true; - } + if (useScaled) { + buff[0] = SYM_SCALE; + } else { + buff[0] = SYM_BLANK; + } + buff[1] = SYM_THR; + if (navigationIsControllingThrottle()) { + buff[0] = SYM_AUTO_THR0; + buff[1] = SYM_AUTO_THR1; + if (isFixedWingAutoThrottleManuallyIncreased()) { + TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr); + } + useScaled = true; + } #ifdef USE_POWER_LIMITS - if (powerLimiterIsLimiting()) { - TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr); - } + if (powerLimiterIsLimiting()) { + TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr); + } #endif - tfp_sprintf(buff + 2, "%3d", getThrottlePercent(useScaled)); + tfp_sprintf(buff + 2, "%3d", getThrottlePercent(useScaled)); } /** @@ -1137,110 +1137,110 @@ static void osdFormatThrottlePosition(char *buff, bool useScaled, textAttributes **/ static void osdFormatGVar(char *buff, uint8_t index) { - buff[0] = 'G'; - buff[1] = '0'+index; - buff[2] = ':'; - #ifdef USE_PROGRAMMING_FRAMEWORK - osdFormatCentiNumber(buff + 3, (int32_t)gvGet(index)*(int32_t)100, 1, 0, 0, 5); - #endif + buff[0] = 'G'; + buff[1] = '0'+index; + buff[2] = ':'; + #ifdef USE_PROGRAMMING_FRAMEWORK + osdFormatCentiNumber(buff + 3, (int32_t)gvGet(index)*(int32_t)100, 1, 0, 0, 5); + #endif } #if defined(USE_ESC_SENSOR) static void osdFormatRpm(char *buff, uint32_t rpm) { - buff[0] = SYM_RPM; - if (rpm) { - if ( digitCount(rpm) > osdConfig()->esc_rpm_precision) { - uint8_t rpmMaxDecimals = (osdConfig()->esc_rpm_precision - 3); - osdFormatCentiNumber(buff + 1, rpm / 10, 0, rpmMaxDecimals, rpmMaxDecimals, osdConfig()->esc_rpm_precision-1); - buff[osdConfig()->esc_rpm_precision] = 'K'; - buff[osdConfig()->esc_rpm_precision+1] = '\0'; - } - else { - switch(osdConfig()->esc_rpm_precision) { - case 6: - tfp_sprintf(buff + 1, "%6lu", rpm); - break; - case 5: - tfp_sprintf(buff + 1, "%5lu", rpm); - break; - case 4: - tfp_sprintf(buff + 1, "%4lu", rpm); - break; - case 3: - default: - tfp_sprintf(buff + 1, "%3lu", rpm); - break; - } + buff[0] = SYM_RPM; + if (rpm) { + if ( digitCount(rpm) > osdConfig()->esc_rpm_precision) { + uint8_t rpmMaxDecimals = (osdConfig()->esc_rpm_precision - 3); + osdFormatCentiNumber(buff + 1, rpm / 10, 0, rpmMaxDecimals, rpmMaxDecimals, osdConfig()->esc_rpm_precision-1); + buff[osdConfig()->esc_rpm_precision] = 'K'; + buff[osdConfig()->esc_rpm_precision+1] = '\0'; + } + else { + switch(osdConfig()->esc_rpm_precision) { + case 6: + tfp_sprintf(buff + 1, "%6lu", rpm); + break; + case 5: + tfp_sprintf(buff + 1, "%5lu", rpm); + break; + case 4: + tfp_sprintf(buff + 1, "%4lu", rpm); + break; + case 3: + default: + tfp_sprintf(buff + 1, "%3lu", rpm); + break; + } - } - } - else { - uint8_t buffPos = 1; - while (buffPos <=( osdConfig()->esc_rpm_precision)) { - strcpy(buff + buffPos++, "-"); - } - } + } + } + else { + uint8_t buffPos = 1; + while (buffPos <=( osdConfig()->esc_rpm_precision)) { + strcpy(buff + buffPos++, "-"); + } + } } #endif int32_t osdGetAltitude(void) { - return getEstimatedActualPosition(Z); + return getEstimatedActualPosition(Z); } static inline int32_t osdGetAltitudeMsl(void) { - return getEstimatedActualPosition(Z)+GPS_home.alt; + return getEstimatedActualPosition(Z)+GPS_home.alt; } uint16_t osdGetRemainingGlideTime(void) { - float value = getEstimatedActualVelocity(Z); - static pt1Filter_t glideTimeFilterState; - const timeMs_t curTimeMs = millis(); - static timeMs_t glideTimeUpdatedMs; + float value = getEstimatedActualVelocity(Z); + static pt1Filter_t glideTimeFilterState; + const timeMs_t curTimeMs = millis(); + static timeMs_t glideTimeUpdatedMs; - value = pt1FilterApply4(&glideTimeFilterState, isnormal(value) ? value : 0, 0.5, MS2S(curTimeMs - glideTimeUpdatedMs)); - glideTimeUpdatedMs = curTimeMs; + value = pt1FilterApply4(&glideTimeFilterState, isnormal(value) ? value : 0, 0.5, MS2S(curTimeMs - glideTimeUpdatedMs)); + glideTimeUpdatedMs = curTimeMs; - if (value < 0) { - value = osdGetAltitude() / abs((int)value); - } else { - value = 0; - } + if (value < 0) { + value = osdGetAltitude() / abs((int)value); + } else { + value = 0; + } - return (uint16_t)roundf(value); + return (uint16_t)roundf(value); } static bool osdIsHeadingValid(void) { - return isImuHeadingValid(); + return isImuHeadingValid(); } int16_t osdGetHeading(void) { - return attitude.values.yaw; + return attitude.values.yaw; } int16_t osdGetPanServoOffset(void) { - int8_t servoIndex = osdConfig()->pan_servo_index; - int16_t servoPosition = servo[servoIndex]; - int16_t servoMiddle = servoParams(servoIndex)->middle; - return (int16_t)CENTIDEGREES_TO_DEGREES((servoPosition - servoMiddle) * osdConfig()->pan_servo_pwm2centideg); + int8_t servoIndex = osdConfig()->pan_servo_index; + int16_t servoPosition = servo[servoIndex]; + int16_t servoMiddle = servoParams(servoIndex)->middle; + return (int16_t)CENTIDEGREES_TO_DEGREES((servoPosition - servoMiddle) * osdConfig()->pan_servo_pwm2centideg); } // Returns a heading angle in degrees normalized to [0, 360). int osdGetHeadingAngle(int angle) { - while (angle < 0) { - angle += 360; - } - while (angle >= 360) { - angle -= 360; - } - return angle; + while (angle < 0) { + angle += 360; + } + while (angle >= 360) { + angle -= 360; + } + return angle; } #if defined(USE_GPS) @@ -1254,141 +1254,141 @@ int osdGetHeadingAngle(int angle) * erasing all screen on each redraw. */ static void osdDrawMap(int referenceHeading, uint16_t referenceSym, uint16_t centerSym, - uint32_t poiDistance, int16_t poiDirection, uint16_t poiSymbol, - uint16_t *drawn, uint32_t *usedScale) + uint32_t poiDistance, int16_t poiDirection, uint16_t poiSymbol, + uint16_t *drawn, uint32_t *usedScale) { - // TODO: These need to be tested with several setups. We might - // need to make them configurable. - const int hMargin = 5; - const int vMargin = 3; + // TODO: These need to be tested with several setups. We might + // need to make them configurable. + const int hMargin = 5; + const int vMargin = 3; - // TODO: Get this from the display driver? - const int charWidth = 12; - const int charHeight = 18; + // TODO: Get this from the display driver? + const int charWidth = 12; + const int charHeight = 18; - uint8_t minX = hMargin; - uint8_t maxX = osdDisplayPort->cols - 1 - hMargin; - uint8_t minY = vMargin; - uint8_t maxY = osdDisplayPort->rows - 1 - vMargin; - uint8_t midX = osdDisplayPort->cols / 2; - uint8_t midY = osdDisplayPort->rows / 2; + uint8_t minX = hMargin; + uint8_t maxX = osdDisplayPort->cols - 1 - hMargin; + uint8_t minY = vMargin; + uint8_t maxY = osdDisplayPort->rows - 1 - vMargin; + uint8_t midX = osdDisplayPort->cols / 2; + uint8_t midY = osdDisplayPort->rows / 2; - // Fixed marks - displayWriteChar(osdDisplayPort, midX, midY, centerSym); + // Fixed marks + displayWriteChar(osdDisplayPort, midX, midY, centerSym); - // First, erase the previous drawing. - if (OSD_VISIBLE(*drawn)) { - displayWriteChar(osdDisplayPort, OSD_X(*drawn), OSD_Y(*drawn), SYM_BLANK); - *drawn = 0; - } + // First, erase the previous drawing. + if (OSD_VISIBLE(*drawn)) { + displayWriteChar(osdDisplayPort, OSD_X(*drawn), OSD_Y(*drawn), SYM_BLANK); + *drawn = 0; + } - uint32_t initialScale; - const unsigned scaleMultiplier = 2; - // We try to reduce the scale when the POI will be around half the distance - // between the center and the closers map edge, to avoid too much jumping - const int scaleReductionMultiplier = MIN(midX - hMargin, midY - vMargin) / 2; + uint32_t initialScale; + const unsigned scaleMultiplier = 2; + // We try to reduce the scale when the POI will be around half the distance + // between the center and the closers map edge, to avoid too much jumping + const int scaleReductionMultiplier = MIN(midX - hMargin, midY - vMargin) / 2; - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - initialScale = 16; // 16m ~= 0.01miles - break; - case OSD_UNIT_GA: - initialScale = 18; // 18m ~= 0.01 nautical miles - break; - default: - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - initialScale = 10; // 10m as initial scale - break; - } + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + initialScale = 16; // 16m ~= 0.01miles + break; + case OSD_UNIT_GA: + initialScale = 18; // 18m ~= 0.01 nautical miles + break; + default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + initialScale = 10; // 10m as initial scale + break; + } - // Try to keep the same scale when getting closer until we draw over the center point - uint32_t scale = initialScale; - if (*usedScale) { - scale = *usedScale; - if (scale > initialScale && poiDistance < *usedScale * scaleReductionMultiplier) { - scale /= scaleMultiplier; - } - } + // Try to keep the same scale when getting closer until we draw over the center point + uint32_t scale = initialScale; + if (*usedScale) { + scale = *usedScale; + if (scale > initialScale && poiDistance < *usedScale * scaleReductionMultiplier) { + scale /= scaleMultiplier; + } + } - if (STATE(GPS_FIX)) { + if (STATE(GPS_FIX)) { - int directionToPoi = osdGetHeadingAngle(poiDirection - referenceHeading); - float poiAngle = DEGREES_TO_RADIANS(directionToPoi); - float poiSin = sin_approx(poiAngle); - float poiCos = cos_approx(poiAngle); + int directionToPoi = osdGetHeadingAngle(poiDirection - referenceHeading); + float poiAngle = DEGREES_TO_RADIANS(directionToPoi); + float poiSin = sin_approx(poiAngle); + float poiCos = cos_approx(poiAngle); - // Now start looking for a valid scale that lets us draw everything - int ii; - for (ii = 0; ii < 50; ii++) { - // Calculate location of the aircraft in map - int points = poiDistance / ((float)scale / charHeight); + // Now start looking for a valid scale that lets us draw everything + int ii; + for (ii = 0; ii < 50; ii++) { + // Calculate location of the aircraft in map + int points = poiDistance / ((float)scale / charHeight); - float pointsX = points * poiSin; - int poiX = midX - roundf(pointsX / charWidth); - if (poiX < minX || poiX > maxX) { - scale *= scaleMultiplier; - continue; - } + float pointsX = points * poiSin; + int poiX = midX - roundf(pointsX / charWidth); + if (poiX < minX || poiX > maxX) { + scale *= scaleMultiplier; + continue; + } - float pointsY = points * poiCos; - int poiY = midY + roundf(pointsY / charHeight); - if (poiY < minY || poiY > maxY) { - scale *= scaleMultiplier; - continue; - } + float pointsY = points * poiCos; + int poiY = midY + roundf(pointsY / charHeight); + if (poiY < minY || poiY > maxY) { + scale *= scaleMultiplier; + continue; + } - if (poiX == midX && poiY == midY) { - // We're over the map center symbol, so we would be drawing - // over it even if we increased the scale. Alternate between - // drawing the center symbol or drawing the POI. - if (centerSym != SYM_BLANK && OSD_ALTERNATING_CHOICES(1000, 2) == 0) { - break; - } - } else { + if (poiX == midX && poiY == midY) { + // We're over the map center symbol, so we would be drawing + // over it even if we increased the scale. Alternate between + // drawing the center symbol or drawing the POI. + if (centerSym != SYM_BLANK && OSD_ALTERNATING_CHOICES(1000, 2) == 0) { + break; + } + } else { - uint16_t c; - if (displayReadCharWithAttr(osdDisplayPort, poiX, poiY, &c, NULL) && c != SYM_BLANK) { - // Something else written here, increase scale. If the display doesn't support reading - // back characters, we assume there's nothing. - // - // If we're close to the center, decrease scale. Otherwise increase it. - uint8_t centerDeltaX = (maxX - minX) / (scaleMultiplier * 2); - uint8_t centerDeltaY = (maxY - minY) / (scaleMultiplier * 2); - if (poiX >= midX - centerDeltaX && poiX <= midX + centerDeltaX && - poiY >= midY - centerDeltaY && poiY <= midY + centerDeltaY && - scale > scaleMultiplier) { + uint16_t c; + if (displayReadCharWithAttr(osdDisplayPort, poiX, poiY, &c, NULL) && c != SYM_BLANK) { + // Something else written here, increase scale. If the display doesn't support reading + // back characters, we assume there's nothing. + // + // If we're close to the center, decrease scale. Otherwise increase it. + uint8_t centerDeltaX = (maxX - minX) / (scaleMultiplier * 2); + uint8_t centerDeltaY = (maxY - minY) / (scaleMultiplier * 2); + if (poiX >= midX - centerDeltaX && poiX <= midX + centerDeltaX && + poiY >= midY - centerDeltaY && poiY <= midY + centerDeltaY && + scale > scaleMultiplier) { - scale /= scaleMultiplier; - } else { - scale *= scaleMultiplier; - } - continue; - } - } + scale /= scaleMultiplier; + } else { + scale *= scaleMultiplier; + } + continue; + } + } - // Draw the point on the map - if (poiSymbol == SYM_ARROW_UP) { - // Drawing aircraft, rotate - int mapHeading = osdGetHeadingAngle(DECIDEGREES_TO_DEGREES(osdGetHeading()) - referenceHeading); - poiSymbol += mapHeading * 2 / 45; - } - displayWriteChar(osdDisplayPort, poiX, poiY, poiSymbol); + // Draw the point on the map + if (poiSymbol == SYM_ARROW_UP) { + // Drawing aircraft, rotate + int mapHeading = osdGetHeadingAngle(DECIDEGREES_TO_DEGREES(osdGetHeading()) - referenceHeading); + poiSymbol += mapHeading * 2 / 45; + } + displayWriteChar(osdDisplayPort, poiX, poiY, poiSymbol); - // Update saved location - *drawn = OSD_POS(poiX, poiY) | OSD_VISIBLE_FLAG; - break; - } - } + // Update saved location + *drawn = OSD_POS(poiX, poiY) | OSD_VISIBLE_FLAG; + break; + } + } - *usedScale = scale; + *usedScale = scale; - // Update global map data for scale and reference - osdMapData.scale = scale; - osdMapData.referenceSymbol = referenceSym; + // Update global map data for scale and reference + osdMapData.scale = scale; + osdMapData.referenceSymbol = referenceSym; } /* Draws a map with the home in the center and the craft moving around. @@ -1396,7 +1396,7 @@ static void osdDrawMap(int referenceHeading, uint16_t referenceSym, uint16_t cen */ static void osdDrawHomeMap(int referenceHeading, uint8_t referenceSym, uint16_t *drawn, uint32_t *usedScale) { - osdDrawMap(referenceHeading, referenceSym, SYM_HOME, GPS_distanceToHome, GPS_directionToHome, SYM_ARROW_UP, drawn, usedScale); + osdDrawMap(referenceHeading, referenceSym, SYM_HOME, GPS_distanceToHome, GPS_directionToHome, SYM_ARROW_UP, drawn, usedScale); } /* Draws a map with the aircraft in the center and the home moving around. @@ -1404,2474 +1404,2474 @@ static void osdDrawHomeMap(int referenceHeading, uint8_t referenceSym, uint16_t */ static void osdDrawRadar(uint16_t *drawn, uint32_t *usedScale) { - int16_t reference = DECIDEGREES_TO_DEGREES(osdGetHeading()); - int16_t poiDirection = osdGetHeadingAngle(GPS_directionToHome + 180); - osdDrawMap(reference, 0, SYM_ARROW_UP, GPS_distanceToHome, poiDirection, SYM_HOME, drawn, usedScale); + int16_t reference = DECIDEGREES_TO_DEGREES(osdGetHeading()); + int16_t poiDirection = osdGetHeadingAngle(GPS_directionToHome + 180); + osdDrawMap(reference, 0, SYM_ARROW_UP, GPS_distanceToHome, poiDirection, SYM_HOME, drawn, usedScale); } static uint16_t crc_accumulate(uint8_t data, uint16_t crcAccum) { - uint8_t tmp; - tmp = data ^ (uint8_t)(crcAccum & 0xff); - tmp ^= (tmp << 4); - crcAccum = (crcAccum >> 8) ^ (tmp << 8) ^ (tmp << 3) ^ (tmp >> 4); - return crcAccum; + uint8_t tmp; + tmp = data ^ (uint8_t)(crcAccum & 0xff); + tmp ^= (tmp << 4); + crcAccum = (crcAccum >> 8) ^ (tmp << 8) ^ (tmp << 3) ^ (tmp >> 4); + return crcAccum; } static void osdDisplayTelemetry(void) { - uint32_t trk_data; - uint16_t trk_crc = 0; - char trk_buffer[31]; - static int16_t trk_elevation = 127; - static uint16_t trk_bearing = 0; + uint32_t trk_data; + uint16_t trk_crc = 0; + char trk_buffer[31]; + static int16_t trk_elevation = 127; + static uint16_t trk_bearing = 0; - if (ARMING_FLAG(ARMED)) { - if (STATE(GPS_FIX)){ - if (GPS_distanceToHome > 5) { - trk_bearing = GPS_directionToHome; - trk_bearing += 360 + 180; - trk_bearing %= 360; - int32_t alt = CENTIMETERS_TO_METERS(osdGetAltitude()); - float at = atan2(alt, GPS_distanceToHome); - trk_elevation = at * 57.2957795f; // 57.2957795 = 1 rad - trk_elevation += 37; // because elevation in telemetry should be from -37 to 90 - if (trk_elevation < 0) { - trk_elevation = 0; - } - } - } - } - else{ - trk_elevation = 127; - trk_bearing = 0; - } + if (ARMING_FLAG(ARMED)) { + if (STATE(GPS_FIX)){ + if (GPS_distanceToHome > 5) { + trk_bearing = GPS_directionToHome; + trk_bearing += 360 + 180; + trk_bearing %= 360; + int32_t alt = CENTIMETERS_TO_METERS(osdGetAltitude()); + float at = atan2(alt, GPS_distanceToHome); + trk_elevation = at * 57.2957795f; // 57.2957795 = 1 rad + trk_elevation += 37; // because elevation in telemetry should be from -37 to 90 + if (trk_elevation < 0) { + trk_elevation = 0; + } + } + } + } + else{ + trk_elevation = 127; + trk_bearing = 0; + } - trk_data = 0; // bit 0 - packet type 0 = bearing/elevation, 1 = 2 byte data packet - trk_data = trk_data | (uint32_t)(0x7F & trk_elevation) << 1; // bits 1-7 - elevation angle to target. NOTE number is abused. constrained value of -37 to 90 sent as 0 to 127. - trk_data = trk_data | (uint32_t)trk_bearing << 8; // bits 8-17 - bearing angle to target. 0 = true north. 0 to 360 - trk_crc = crc_accumulate(0xFF & trk_data, trk_crc); // CRC First Byte bits 0-7 - trk_crc = crc_accumulate(0xFF & trk_bearing, trk_crc); // CRC Second Byte bits 8-15 - trk_crc = crc_accumulate(trk_bearing >> 8, trk_crc); // CRC Third Byte bits 16-17 - trk_data = trk_data | (uint32_t)trk_crc << 17; // bits 18-29 CRC & 0x3FFFF + trk_data = 0; // bit 0 - packet type 0 = bearing/elevation, 1 = 2 byte data packet + trk_data = trk_data | (uint32_t)(0x7F & trk_elevation) << 1; // bits 1-7 - elevation angle to target. NOTE number is abused. constrained value of -37 to 90 sent as 0 to 127. + trk_data = trk_data | (uint32_t)trk_bearing << 8; // bits 8-17 - bearing angle to target. 0 = true north. 0 to 360 + trk_crc = crc_accumulate(0xFF & trk_data, trk_crc); // CRC First Byte bits 0-7 + trk_crc = crc_accumulate(0xFF & trk_bearing, trk_crc); // CRC Second Byte bits 8-15 + trk_crc = crc_accumulate(trk_bearing >> 8, trk_crc); // CRC Third Byte bits 16-17 + trk_data = trk_data | (uint32_t)trk_crc << 17; // bits 18-29 CRC & 0x3FFFF - for (uint8_t t_ctr = 0; t_ctr < 30; t_ctr++) { // Prepare screen buffer and write data line. - if (trk_data & (uint32_t)1 << t_ctr){ - trk_buffer[29 - t_ctr] = SYM_TELEMETRY_0; - } - else{ - trk_buffer[29 - t_ctr] = SYM_TELEMETRY_1; - } - } - trk_buffer[30] = 0; - displayWrite(osdDisplayPort, 0, 0, trk_buffer); - if (osdConfig()->telemetry>1){ - displayWrite(osdDisplayPort, 0, 3, trk_buffer); // Test display because normal telemetry line is not visible - } + for (uint8_t t_ctr = 0; t_ctr < 30; t_ctr++) { // Prepare screen buffer and write data line. + if (trk_data & (uint32_t)1 << t_ctr){ + trk_buffer[29 - t_ctr] = SYM_TELEMETRY_0; + } + else{ + trk_buffer[29 - t_ctr] = SYM_TELEMETRY_1; + } + } + trk_buffer[30] = 0; + displayWrite(osdDisplayPort, 0, 0, trk_buffer); + if (osdConfig()->telemetry>1){ + displayWrite(osdDisplayPort, 0, 3, trk_buffer); // Test display because normal telemetry line is not visible + } } #endif static void osdFormatPidControllerOutput(char *buff, const char *label, const pidController_t *pidController, uint8_t scale, bool showDecimal) { - strcpy(buff, label); - for (uint8_t i = strlen(label); i < 5; ++i) buff[i] = ' '; - uint8_t decimals = showDecimal ? 1 : 0; - osdFormatCentiNumber(buff + 5, pidController->proportional * scale, 0, decimals, 0, 4); - buff[9] = ' '; - osdFormatCentiNumber(buff + 10, pidController->integrator * scale, 0, decimals, 0, 4); - buff[14] = ' '; - osdFormatCentiNumber(buff + 15, pidController->derivative * scale, 0, decimals, 0, 4); - buff[19] = ' '; - osdFormatCentiNumber(buff + 20, pidController->output_constrained * scale, 0, decimals, 0, 4); - buff[24] = '\0'; + strcpy(buff, label); + for (uint8_t i = strlen(label); i < 5; ++i) buff[i] = ' '; + uint8_t decimals = showDecimal ? 1 : 0; + osdFormatCentiNumber(buff + 5, pidController->proportional * scale, 0, decimals, 0, 4); + buff[9] = ' '; + osdFormatCentiNumber(buff + 10, pidController->integrator * scale, 0, decimals, 0, 4); + buff[14] = ' '; + osdFormatCentiNumber(buff + 15, pidController->derivative * scale, 0, decimals, 0, 4); + buff[19] = ' '; + osdFormatCentiNumber(buff + 20, pidController->output_constrained * scale, 0, decimals, 0, 4); + buff[24] = '\0'; } static void osdDisplayBatteryVoltage(uint8_t elemPosX, uint8_t elemPosY, uint16_t voltage, uint8_t digits, uint8_t decimals) { - char buff[7]; - textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; + char buff[7]; + textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; - osdFormatBatteryChargeSymbol(buff); - buff[1] = '\0'; - osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); + osdFormatBatteryChargeSymbol(buff); + buff[1] = '\0'; + osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); - elemAttr = TEXT_ATTRIBUTES_NONE; - digits = MIN(digits, 5); - osdFormatCentiNumber(buff, voltage, 0, decimals, 0, digits); - buff[digits] = SYM_VOLT; - buff[digits+1] = '\0'; - const batteryState_e batteryVoltageState = checkBatteryVoltageState(); - if (batteryVoltageState == BATTERY_CRITICAL || batteryVoltageState == BATTERY_WARNING) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - displayWriteWithAttr(osdDisplayPort, elemPosX + 1, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + digits = MIN(digits, 5); + osdFormatCentiNumber(buff, voltage, 0, decimals, 0, digits); + buff[digits] = SYM_VOLT; + buff[digits+1] = '\0'; + const batteryState_e batteryVoltageState = checkBatteryVoltageState(); + if (batteryVoltageState == BATTERY_CRITICAL || batteryVoltageState == BATTERY_WARNING) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + displayWriteWithAttr(osdDisplayPort, elemPosX + 1, elemPosY, buff, elemAttr); } static void osdDisplayFlightPIDValues(uint8_t elemPosX, uint8_t elemPosY, const char *str, pidIndex_e pidIndex, adjustmentFunction_e adjFuncP, adjustmentFunction_e adjFuncI, adjustmentFunction_e adjFuncD, adjustmentFunction_e adjFuncFF) { - textAttributes_t elemAttr; - char buff[4]; + textAttributes_t elemAttr; + char buff[4]; - const pid8_t *pid = &pidBank()->pid[pidIndex]; - pidType_e pidType = pidIndexGetType(pidIndex); + const pid8_t *pid = &pidBank()->pid[pidIndex]; + pidType_e pidType = pidIndexGetType(pidIndex); - displayWrite(osdDisplayPort, elemPosX, elemPosY, str); + displayWrite(osdDisplayPort, elemPosX, elemPosY, str); - if (pidType == PID_TYPE_NONE) { - // PID is not used in this configuration. Draw dashes. - // XXX: Keep this in sync with the %3d format and spacing used below - displayWrite(osdDisplayPort, elemPosX + 6, elemPosY, "- - - -"); - return; - } + if (pidType == PID_TYPE_NONE) { + // PID is not used in this configuration. Draw dashes. + // XXX: Keep this in sync with the %3d format and spacing used below + displayWrite(osdDisplayPort, elemPosX + 6, elemPosY, "- - - -"); + return; + } - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pid->P); - if ((isAdjustmentFunctionSelected(adjFuncP)) || (((adjFuncP == ADJUSTMENT_ROLL_P) || (adjFuncP == ADJUSTMENT_PITCH_P)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_P)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pid->P); + if ((isAdjustmentFunctionSelected(adjFuncP)) || (((adjFuncP == ADJUSTMENT_ROLL_P) || (adjFuncP == ADJUSTMENT_PITCH_P)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_P)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pid->I); - if ((isAdjustmentFunctionSelected(adjFuncI)) || (((adjFuncI == ADJUSTMENT_ROLL_I) || (adjFuncI == ADJUSTMENT_PITCH_I)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_I)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 8, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pid->I); + if ((isAdjustmentFunctionSelected(adjFuncI)) || (((adjFuncI == ADJUSTMENT_ROLL_I) || (adjFuncI == ADJUSTMENT_PITCH_I)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_I)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 8, elemPosY, buff, elemAttr); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pid->D); - if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D) || (adjFuncD == ADJUSTMENT_PITCH_D)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 12, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pid->D); + if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D) || (adjFuncD == ADJUSTMENT_PITCH_D)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 12, elemPosY, buff, elemAttr); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pid->FF); - if ((isAdjustmentFunctionSelected(adjFuncFF)) || (((adjFuncFF == ADJUSTMENT_ROLL_FF) || (adjFuncFF == ADJUSTMENT_PITCH_FF)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_FF)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 16, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pid->FF); + if ((isAdjustmentFunctionSelected(adjFuncFF)) || (((adjFuncFF == ADJUSTMENT_ROLL_FF) || (adjFuncFF == ADJUSTMENT_PITCH_FF)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_FF)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 16, elemPosY, buff, elemAttr); } static void osdDisplayNavPIDValues(uint8_t elemPosX, uint8_t elemPosY, const char *str, pidIndex_e pidIndex, adjustmentFunction_e adjFuncP, adjustmentFunction_e adjFuncI, adjustmentFunction_e adjFuncD) { - textAttributes_t elemAttr; - char buff[4]; + textAttributes_t elemAttr; + char buff[4]; - const pid8_t *pid = &pidBank()->pid[pidIndex]; - pidType_e pidType = pidIndexGetType(pidIndex); + const pid8_t *pid = &pidBank()->pid[pidIndex]; + pidType_e pidType = pidIndexGetType(pidIndex); - displayWrite(osdDisplayPort, elemPosX, elemPosY, str); + displayWrite(osdDisplayPort, elemPosX, elemPosY, str); - if (pidType == PID_TYPE_NONE) { - // PID is not used in this configuration. Draw dashes. - // XXX: Keep this in sync with the %3d format and spacing used below - displayWrite(osdDisplayPort, elemPosX + 6, elemPosY, "- - -"); - return; - } + if (pidType == PID_TYPE_NONE) { + // PID is not used in this configuration. Draw dashes. + // XXX: Keep this in sync with the %3d format and spacing used below + displayWrite(osdDisplayPort, elemPosX + 6, elemPosY, "- - -"); + return; + } - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pid->P); - if ((isAdjustmentFunctionSelected(adjFuncP)) || (((adjFuncP == ADJUSTMENT_ROLL_P) || (adjFuncP == ADJUSTMENT_PITCH_P)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_P)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pid->P); + if ((isAdjustmentFunctionSelected(adjFuncP)) || (((adjFuncP == ADJUSTMENT_ROLL_P) || (adjFuncP == ADJUSTMENT_PITCH_P)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_P)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pid->I); - if ((isAdjustmentFunctionSelected(adjFuncI)) || (((adjFuncI == ADJUSTMENT_ROLL_I) || (adjFuncI == ADJUSTMENT_PITCH_I)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_I)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 8, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pid->I); + if ((isAdjustmentFunctionSelected(adjFuncI)) || (((adjFuncI == ADJUSTMENT_ROLL_I) || (adjFuncI == ADJUSTMENT_PITCH_I)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_I)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 8, elemPosY, buff, elemAttr); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", pidType == PID_TYPE_PIFF ? pid->FF : pid->D); - if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D) || (adjFuncD == ADJUSTMENT_PITCH_D)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D)))) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 12, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", pidType == PID_TYPE_PIFF ? pid->FF : pid->D); + if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D) || (adjFuncD == ADJUSTMENT_PITCH_D)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D)))) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 12, elemPosY, buff, elemAttr); } static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY, const char *str, const uint8_t valueOffset, const float value, const uint8_t valueLength, const uint8_t maxDecimals, adjustmentFunction_e adjFunc) { - char buff[8]; - textAttributes_t elemAttr; - displayWrite(osdDisplayPort, elemPosX, elemPosY, str); + char buff[8]; + textAttributes_t elemAttr; + displayWrite(osdDisplayPort, elemPosX, elemPosY, str); - elemAttr = TEXT_ATTRIBUTES_NONE; - osdFormatCentiNumber(buff, value * 100, 0, maxDecimals, 0, MIN(valueLength, 8)); - if (isAdjustmentFunctionSelected(adjFunc)) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + strlen(str) + 1 + valueOffset, elemPosY, buff, elemAttr); + elemAttr = TEXT_ATTRIBUTES_NONE; + osdFormatCentiNumber(buff, value * 100, 0, maxDecimals, 0, MIN(valueLength, 8)); + if (isAdjustmentFunctionSelected(adjFunc)) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + strlen(str) + 1 + valueOffset, elemPosY, buff, elemAttr); } int8_t getGeoWaypointNumber(int8_t waypointIndex) { - static int8_t lastWaypointIndex = 1; - static int8_t geoWaypointIndex; + static int8_t lastWaypointIndex = 1; + static int8_t geoWaypointIndex; - if (waypointIndex != lastWaypointIndex) { - lastWaypointIndex = geoWaypointIndex = waypointIndex; - for (uint8_t i = posControl.startWpIndex; i <= waypointIndex; i++) { - if (posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || - posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD || - posControl.waypointList[i].action == NAV_WP_ACTION_JUMP) { - geoWaypointIndex -= 1; - } - } - } + if (waypointIndex != lastWaypointIndex) { + lastWaypointIndex = geoWaypointIndex = waypointIndex; + for (uint8_t i = posControl.startWpIndex; i <= waypointIndex; i++) { + if (posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || + posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD || + posControl.waypointList[i].action == NAV_WP_ACTION_JUMP) { + geoWaypointIndex -= 1; + } + } + } - return geoWaypointIndex - posControl.startWpIndex + 1; + return geoWaypointIndex - posControl.startWpIndex + 1; } void osdDisplaySwitchIndicator(const char *swName, int rcValue, char *buff) { - int8_t ptr = 0; + int8_t ptr = 0; - if (osdConfig()->osd_switch_indicators_align_left) { - for (ptr = 0; ptr < constrain(strlen(swName), 0, OSD_SWITCH_INDICATOR_NAME_LENGTH); ptr++) { - buff[ptr] = swName[ptr]; - } + if (osdConfig()->osd_switch_indicators_align_left) { + for (ptr = 0; ptr < constrain(strlen(swName), 0, OSD_SWITCH_INDICATOR_NAME_LENGTH); ptr++) { + buff[ptr] = swName[ptr]; + } - if ( rcValue < 1333) { - buff[ptr++] = SYM_SWITCH_INDICATOR_LOW; - } else if ( rcValue > 1666) { - buff[ptr++] = SYM_SWITCH_INDICATOR_HIGH; - } else { - buff[ptr++] = SYM_SWITCH_INDICATOR_MID; - } - } else { - if ( rcValue < 1333) { - buff[ptr++] = SYM_SWITCH_INDICATOR_LOW; - } else if ( rcValue > 1666) { - buff[ptr++] = SYM_SWITCH_INDICATOR_HIGH; - } else { - buff[ptr++] = SYM_SWITCH_INDICATOR_MID; - } + if ( rcValue < 1333) { + buff[ptr++] = SYM_SWITCH_INDICATOR_LOW; + } else if ( rcValue > 1666) { + buff[ptr++] = SYM_SWITCH_INDICATOR_HIGH; + } else { + buff[ptr++] = SYM_SWITCH_INDICATOR_MID; + } + } else { + if ( rcValue < 1333) { + buff[ptr++] = SYM_SWITCH_INDICATOR_LOW; + } else if ( rcValue > 1666) { + buff[ptr++] = SYM_SWITCH_INDICATOR_HIGH; + } else { + buff[ptr++] = SYM_SWITCH_INDICATOR_MID; + } - for (ptr = 1; ptr < constrain(strlen(swName), 0, OSD_SWITCH_INDICATOR_NAME_LENGTH) + 1; ptr++) { - buff[ptr] = swName[ptr-1]; - } + for (ptr = 1; ptr < constrain(strlen(swName), 0, OSD_SWITCH_INDICATOR_NAME_LENGTH) + 1; ptr++) { + buff[ptr] = swName[ptr-1]; + } - ptr++; - } + ptr++; + } - buff[ptr] = '\0'; + buff[ptr] = '\0'; } static bool osdDrawSingleElement(uint8_t item) { - uint16_t pos = osdLayoutsConfig()->item_pos[currentLayout][item]; - if (!OSD_VISIBLE(pos)) { - return false; - } - uint8_t elemPosX = OSD_X(pos); - uint8_t elemPosY = OSD_Y(pos); - textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; - char buff[32] = {0}; + uint16_t pos = osdLayoutsConfig()->item_pos[currentLayout][item]; + if (!OSD_VISIBLE(pos)) { + return false; + } + uint8_t elemPosX = OSD_X(pos); + uint8_t elemPosY = OSD_Y(pos); + textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; + char buff[32] = {0}; - switch (item) { - case OSD_RSSI_VALUE: - { - uint16_t osdRssi = osdConvertRSSI(); - buff[0] = SYM_RSSI; - tfp_sprintf(buff + 1, "%2d", osdRssi); - if (osdRssi < osdConfig()->rssi_alarm) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } + switch (item) { + case OSD_RSSI_VALUE: + { + uint16_t osdRssi = osdConvertRSSI(); + buff[0] = SYM_RSSI; + tfp_sprintf(buff + 1, "%2d", osdRssi); + if (osdRssi < osdConfig()->rssi_alarm) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } - case OSD_MAIN_BATT_VOLTAGE: { - uint8_t base_digits = 2U; + case OSD_MAIN_BATT_VOLTAGE: { + uint8_t base_digits = 2U; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if(isBfCompatibleVideoSystem(osdConfig())) { - base_digits = 3U; // Add extra digit to account for decimal point taking an extra character space - } + if(isBfCompatibleVideoSystem(osdConfig())) { + base_digits = 3U; // Add extra digit to account for decimal point taking an extra character space + } #endif - osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawVoltage(), base_digits + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals); - return true; - } + osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawVoltage(), base_digits + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals); + return true; + } - case OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE: { - uint8_t base_digits = 2U; + case OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE: { + uint8_t base_digits = 2U; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if(isBfCompatibleVideoSystem(osdConfig())) { - base_digits = 3U; // Add extra digit to account for decimal point taking an extra character space - } + if(isBfCompatibleVideoSystem(osdConfig())) { + base_digits = 3U; // Add extra digit to account for decimal point taking an extra character space + } #endif - osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedVoltage(), base_digits + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals); - return true; - } + osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedVoltage(), base_digits + osdConfig()->main_voltage_decimals, osdConfig()->main_voltage_decimals); + return true; + } - case OSD_CURRENT_DRAW: { - osdFormatCentiNumber(buff, getAmperage(), 0, 2, 0, 3); - buff[3] = SYM_AMP; - buff[4] = '\0'; + case OSD_CURRENT_DRAW: { + osdFormatCentiNumber(buff, getAmperage(), 0, 2, 0, 3); + buff[3] = SYM_AMP; + buff[4] = '\0'; - uint8_t current_alarm = osdConfig()->current_alarm; - if ((current_alarm > 0) && ((getAmperage() / 100.0f) > current_alarm)) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } + uint8_t current_alarm = osdConfig()->current_alarm; + if ((current_alarm > 0) && ((getAmperage() / 100.0f) > current_alarm)) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } - case OSD_MAH_DRAWN: { - uint8_t mah_digits = osdConfig()->mAh_used_precision; // Initialize to config value - bool bfcompat = false; // Assume BFCOMPAT is off + case OSD_MAH_DRAWN: { + uint8_t mah_digits = osdConfig()->mAh_used_precision; // Initialize to config value + bool bfcompat = false; // Assume BFCOMPAT is off #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if (isBfCompatibleVideoSystem(osdConfig())) { - bfcompat = true; - } + if (isBfCompatibleVideoSystem(osdConfig())) { + bfcompat = true; + } #endif - if (bfcompat) { - //BFcompat is unable to work with scaled values and it only has mAh symbol to work with - tfp_sprintf(buff, "%5d", (int)getMAhDrawn()); // Use 5 digits to allow 10Ah+ packs - buff[5] = SYM_MAH; - buff[6] = '\0'; - } else { - if (osdFormatCentiNumber(buff, getMAhDrawn() * 100, 1000, 0, (mah_digits - 2), mah_digits)) { - // Shown in Ah - buff[mah_digits] = SYM_AH; - } else { - // Shown in mAh - buff[mah_digits] = SYM_MAH; - } - buff[mah_digits + 1] = '\0'; - } + if (bfcompat) { + //BFcompat is unable to work with scaled values and it only has mAh symbol to work with + tfp_sprintf(buff, "%5d", (int)getMAhDrawn()); // Use 5 digits to allow 10Ah+ packs + buff[5] = SYM_MAH; + buff[6] = '\0'; + } else { + if (osdFormatCentiNumber(buff, getMAhDrawn() * 100, 1000, 0, (mah_digits - 2), mah_digits)) { + // Shown in Ah + buff[mah_digits] = SYM_AH; + } else { + // Shown in mAh + buff[mah_digits] = SYM_MAH; + } + buff[mah_digits + 1] = '\0'; + } - osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); - break; - } + osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); + break; + } - case OSD_WH_DRAWN: - osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3); - osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); - buff[3] = SYM_WH; - buff[4] = '\0'; - break; + case OSD_WH_DRAWN: + osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3); + osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); + buff[3] = SYM_WH; + buff[4] = '\0'; + break; - case OSD_BATTERY_REMAINING_CAPACITY: + case OSD_BATTERY_REMAINING_CAPACITY: - if (currentBatteryProfile->capacity.value == 0) - tfp_sprintf(buff, " NA"); - else if (!batteryWasFullWhenPluggedIn()) - tfp_sprintf(buff, " NF"); - else if (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH) - tfp_sprintf(buff, "%4lu", (unsigned long)getBatteryRemainingCapacity()); - else // currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH - osdFormatCentiNumber(buff + 1, getBatteryRemainingCapacity() / 10, 0, 2, 0, 3); + if (currentBatteryProfile->capacity.value == 0) + tfp_sprintf(buff, " NA"); + else if (!batteryWasFullWhenPluggedIn()) + tfp_sprintf(buff, " NF"); + else if (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH) + tfp_sprintf(buff, "%4lu", (unsigned long)getBatteryRemainingCapacity()); + else // currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH + osdFormatCentiNumber(buff + 1, getBatteryRemainingCapacity() / 10, 0, 2, 0, 3); - buff[4] = currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH ? SYM_MAH : SYM_WH; - buff[5] = '\0'; + buff[4] = currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MAH ? SYM_MAH : SYM_WH; + buff[5] = '\0'; - if (batteryUsesCapacityThresholds()) { - osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); - } + if (batteryUsesCapacityThresholds()) { + osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); + } - break; + break; - case OSD_BATTERY_REMAINING_PERCENT: - osdFormatBatteryChargeSymbol(buff); - tfp_sprintf(buff + 1, "%3d%%", calculateBatteryPercentage()); - osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); - break; + case OSD_BATTERY_REMAINING_PERCENT: + osdFormatBatteryChargeSymbol(buff); + tfp_sprintf(buff + 1, "%3d%%", calculateBatteryPercentage()); + osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); + break; - case OSD_POWER_SUPPLY_IMPEDANCE: - if (isPowerSupplyImpedanceValid()) - tfp_sprintf(buff, "%3d", getPowerSupplyImpedance()); - else - strcpy(buff, "---"); - buff[3] = SYM_MILLIOHM; - buff[4] = '\0'; - break; + case OSD_POWER_SUPPLY_IMPEDANCE: + if (isPowerSupplyImpedanceValid()) + tfp_sprintf(buff, "%3d", getPowerSupplyImpedance()); + else + strcpy(buff, "---"); + buff[3] = SYM_MILLIOHM; + buff[4] = '\0'; + break; #ifdef USE_GPS - case OSD_GPS_SATS: - buff[0] = SYM_SAT_L; - buff[1] = SYM_SAT_R; - tfp_sprintf(buff + 2, "%2d", gpsSol.numSat); - if (!STATE(GPS_FIX)) { - if (getHwGPSStatus() == HW_SENSOR_UNAVAILABLE || getHwGPSStatus() == HW_SENSOR_UNHEALTHY) { - strcpy(buff + 2, "X!"); - } - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; + case OSD_GPS_SATS: + buff[0] = SYM_SAT_L; + buff[1] = SYM_SAT_R; + tfp_sprintf(buff + 2, "%2d", gpsSol.numSat); + if (!STATE(GPS_FIX)) { + if (getHwGPSStatus() == HW_SENSOR_UNAVAILABLE || getHwGPSStatus() == HW_SENSOR_UNHEALTHY) { + strcpy(buff + 2, "X!"); + } + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; - case OSD_GPS_SPEED: - osdFormatVelocityStr(buff, gpsSol.groundSpeed, false, false); - break; + case OSD_GPS_SPEED: + osdFormatVelocityStr(buff, gpsSol.groundSpeed, false, false); + break; - case OSD_GPS_MAX_SPEED: - osdFormatVelocityStr(buff, stats.max_speed, false, true); - break; + case OSD_GPS_MAX_SPEED: + osdFormatVelocityStr(buff, stats.max_speed, false, true); + break; - case OSD_3D_SPEED: - osdFormatVelocityStr(buff, osdGet3DSpeed(), true, false); - break; + case OSD_3D_SPEED: + osdFormatVelocityStr(buff, osdGet3DSpeed(), true, false); + break; - case OSD_3D_MAX_SPEED: - osdFormatVelocityStr(buff, stats.max_3D_speed, true, true); - break; + case OSD_3D_MAX_SPEED: + osdFormatVelocityStr(buff, stats.max_3D_speed, true, true); + break; - case OSD_GLIDESLOPE: - { - float horizontalSpeed = gpsSol.groundSpeed; - float sinkRate = -getEstimatedActualVelocity(Z); - static pt1Filter_t gsFilterState; - const timeMs_t currentTimeMs = millis(); - static timeMs_t gsUpdatedTimeMs; - float glideSlope = horizontalSpeed / sinkRate; - glideSlope = pt1FilterApply4(&gsFilterState, isnormal(glideSlope) ? glideSlope : 200, 0.5, MS2S(currentTimeMs - gsUpdatedTimeMs)); - gsUpdatedTimeMs = currentTimeMs; + case OSD_GLIDESLOPE: + { + float horizontalSpeed = gpsSol.groundSpeed; + float sinkRate = -getEstimatedActualVelocity(Z); + static pt1Filter_t gsFilterState; + const timeMs_t currentTimeMs = millis(); + static timeMs_t gsUpdatedTimeMs; + float glideSlope = horizontalSpeed / sinkRate; + glideSlope = pt1FilterApply4(&gsFilterState, isnormal(glideSlope) ? glideSlope : 200, 0.5, MS2S(currentTimeMs - gsUpdatedTimeMs)); + gsUpdatedTimeMs = currentTimeMs; - buff[0] = SYM_GLIDESLOPE; - if (glideSlope > 0.0f && glideSlope < 100.0f) { - osdFormatCentiNumber(buff + 1, glideSlope * 100.0f, 0, 2, 0, 3); - } else { - buff[1] = buff[2] = buff[3] = '-'; - } - buff[4] = '\0'; - break; - } + buff[0] = SYM_GLIDESLOPE; + if (glideSlope > 0.0f && glideSlope < 100.0f) { + osdFormatCentiNumber(buff + 1, glideSlope * 100.0f, 0, 2, 0, 3); + } else { + buff[1] = buff[2] = buff[3] = '-'; + } + buff[4] = '\0'; + break; + } - case OSD_GPS_LAT: - osdFormatCoordinate(buff, SYM_LAT, gpsSol.llh.lat); - break; + case OSD_GPS_LAT: + osdFormatCoordinate(buff, SYM_LAT, gpsSol.llh.lat); + break; - case OSD_GPS_LON: - osdFormatCoordinate(buff, SYM_LON, gpsSol.llh.lon); - break; + case OSD_GPS_LON: + osdFormatCoordinate(buff, SYM_LON, gpsSol.llh.lon); + break; - case OSD_HOME_DIR: - { - if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && isImuHeadingValid()) { - if (GPS_distanceToHome < (navConfig()->general.min_rth_distance / 100) ) { - displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_HOME_NEAR); - } - else - { - int16_t panHomeDirOffset = 0; - if (!(osdConfig()->pan_servo_pwm2centideg == 0)){ - panHomeDirOffset = osdGetPanServoOffset(); - } - int16_t flightDirection = STATE(AIRPLANE) ? CENTIDEGREES_TO_DEGREES(posControl.actualState.cog) : DECIDEGREES_TO_DEGREES(osdGetHeading()); - int homeDirection = GPS_directionToHome - flightDirection + panHomeDirOffset; - osdDrawDirArrow(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), homeDirection); - } - } else { - // No home or no fix or unknown heading, blink. - // If we're unarmed, show the arrow pointing up so users can see the arrow - // while configuring the OSD. If we're armed, show a '-' indicating that - // we don't know the direction to home. - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, ARMING_FLAG(ARMED) ? '-' : SYM_ARROW_UP, elemAttr); - } - return true; - } + case OSD_HOME_DIR: + { + if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && isImuHeadingValid()) { + if (GPS_distanceToHome < (navConfig()->general.min_rth_distance / 100) ) { + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_HOME_NEAR); + } + else + { + int16_t panHomeDirOffset = 0; + if (!(osdConfig()->pan_servo_pwm2centideg == 0)){ + panHomeDirOffset = osdGetPanServoOffset(); + } + int16_t flightDirection = STATE(AIRPLANE) ? CENTIDEGREES_TO_DEGREES(posControl.actualState.cog) : DECIDEGREES_TO_DEGREES(osdGetHeading()); + int homeDirection = GPS_directionToHome - flightDirection + panHomeDirOffset; + osdDrawDirArrow(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), homeDirection); + } + } else { + // No home or no fix or unknown heading, blink. + // If we're unarmed, show the arrow pointing up so users can see the arrow + // while configuring the OSD. If we're armed, show a '-' indicating that + // we don't know the direction to home. + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, ARMING_FLAG(ARMED) ? '-' : SYM_ARROW_UP, elemAttr); + } + return true; + } - case OSD_HOME_HEADING_ERROR: - { - buff[0] = SYM_HOME; - buff[1] = SYM_HEADING; + case OSD_HOME_HEADING_ERROR: + { + buff[0] = SYM_HOME; + buff[1] = SYM_HEADING; - if (isImuHeadingValid() && navigationPositionEstimateIsHealthy()) { - int16_t h = lrintf(CENTIDEGREES_TO_DEGREES((float)wrap_18000(DEGREES_TO_CENTIDEGREES((int32_t)GPS_directionToHome) - (STATE(AIRPLANE) ? posControl.actualState.cog : DECIDEGREES_TO_CENTIDEGREES((int32_t)osdGetHeading()))))); - tfp_sprintf(buff + 2, "%4d", h); - } else { - strcpy(buff + 2, "----"); - } + if (isImuHeadingValid() && navigationPositionEstimateIsHealthy()) { + int16_t h = lrintf(CENTIDEGREES_TO_DEGREES((float)wrap_18000(DEGREES_TO_CENTIDEGREES((int32_t)GPS_directionToHome) - (STATE(AIRPLANE) ? posControl.actualState.cog : DECIDEGREES_TO_CENTIDEGREES((int32_t)osdGetHeading()))))); + tfp_sprintf(buff + 2, "%4d", h); + } else { + strcpy(buff + 2, "----"); + } - buff[6] = SYM_DEGREES; - buff[7] = '\0'; - break; - } + buff[6] = SYM_DEGREES; + buff[7] = '\0'; + break; + } - case OSD_HOME_DIST: - { - buff[0] = SYM_HOME; - uint32_t distance_to_home_cm = GPS_distanceToHome * 100; - osdFormatDistanceSymbol(&buff[1], distance_to_home_cm, 0); + case OSD_HOME_DIST: + { + buff[0] = SYM_HOME; + uint32_t distance_to_home_cm = GPS_distanceToHome * 100; + osdFormatDistanceSymbol(&buff[1], distance_to_home_cm, 0); - uint16_t dist_alarm = osdConfig()->dist_alarm; - if (dist_alarm > 0 && GPS_distanceToHome > dist_alarm) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } - break; + uint16_t dist_alarm = osdConfig()->dist_alarm; + if (dist_alarm > 0 && GPS_distanceToHome > dist_alarm) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + break; - case OSD_TRIP_DIST: - buff[0] = SYM_TOTAL; - osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); - break; + case OSD_TRIP_DIST: + buff[0] = SYM_TOTAL; + osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); + break; - case OSD_GROUND_COURSE: - { - buff[0] = SYM_GROUND_COURSE; - if (osdIsHeadingValid()) { - tfp_sprintf(&buff[1], "%3d", (int16_t)CENTIDEGREES_TO_DEGREES(posControl.actualState.cog)); - } else { - buff[1] = buff[2] = buff[3] = '-'; - } - buff[4] = SYM_DEGREES; - buff[5] = '\0'; - break; - } + case OSD_GROUND_COURSE: + { + buff[0] = SYM_GROUND_COURSE; + if (osdIsHeadingValid()) { + tfp_sprintf(&buff[1], "%3d", (int16_t)CENTIDEGREES_TO_DEGREES(posControl.actualState.cog)); + } else { + buff[1] = buff[2] = buff[3] = '-'; + } + buff[4] = SYM_DEGREES; + buff[5] = '\0'; + break; + } - case OSD_COURSE_HOLD_ERROR: - { - if (ARMING_FLAG(ARMED) && !FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { - displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); - return true; - } + case OSD_COURSE_HOLD_ERROR: + { + if (ARMING_FLAG(ARMED) && !FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { + displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); + return true; + } - buff[0] = SYM_HEADING; + buff[0] = SYM_HEADING; - if ((!ARMING_FLAG(ARMED)) || (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && isAdjustingPosition())) { - buff[1] = buff[2] = buff[3] = '-'; - } else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { - int16_t herr = lrintf(CENTIDEGREES_TO_DEGREES((float)navigationGetHeadingError())); - if (ABS(herr) > 99) - strcpy(buff + 1, ">99"); - else - tfp_sprintf(buff + 1, "%3d", herr); - } + if ((!ARMING_FLAG(ARMED)) || (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && isAdjustingPosition())) { + buff[1] = buff[2] = buff[3] = '-'; + } else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { + int16_t herr = lrintf(CENTIDEGREES_TO_DEGREES((float)navigationGetHeadingError())); + if (ABS(herr) > 99) + strcpy(buff + 1, ">99"); + else + tfp_sprintf(buff + 1, "%3d", herr); + } - buff[4] = SYM_DEGREES; - buff[5] = '\0'; - break; - } + buff[4] = SYM_DEGREES; + buff[5] = '\0'; + break; + } - case OSD_COURSE_HOLD_ADJUSTMENT: - { - int16_t heading_adjust = lrintf(CENTIDEGREES_TO_DEGREES((float)getCruiseHeadingAdjustment())); + case OSD_COURSE_HOLD_ADJUSTMENT: + { + int16_t heading_adjust = lrintf(CENTIDEGREES_TO_DEGREES((float)getCruiseHeadingAdjustment())); - if (ARMING_FLAG(ARMED) && ((!FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) || !(isAdjustingPosition() || isAdjustingHeading() || (heading_adjust != 0)))) { - displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); - return true; - } + if (ARMING_FLAG(ARMED) && ((!FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) || !(isAdjustingPosition() || isAdjustingHeading() || (heading_adjust != 0)))) { + displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); + return true; + } - buff[0] = SYM_HEADING; + buff[0] = SYM_HEADING; - if (!ARMING_FLAG(ARMED)) { - buff[1] = buff[2] = buff[3] = buff[4] = '-'; - } else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { - tfp_sprintf(buff + 1, "%4d", heading_adjust); - } + if (!ARMING_FLAG(ARMED)) { + buff[1] = buff[2] = buff[3] = buff[4] = '-'; + } else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { + tfp_sprintf(buff + 1, "%4d", heading_adjust); + } - buff[5] = SYM_DEGREES; - buff[6] = '\0'; - break; - } + buff[5] = SYM_DEGREES; + buff[6] = '\0'; + break; + } - case OSD_CROSS_TRACK_ERROR: - { - if (isWaypointNavTrackingActive()) { - buff[0] = SYM_CROSS_TRACK_ERROR; - osdFormatDistanceSymbol(buff + 1, navigationGetCrossTrackError(), 0); - } else { - displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); - return true; - } - break; - } + case OSD_CROSS_TRACK_ERROR: + { + if (isWaypointNavTrackingActive()) { + buff[0] = SYM_CROSS_TRACK_ERROR; + osdFormatDistanceSymbol(buff + 1, navigationGetCrossTrackError(), 0); + } else { + displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); + return true; + } + break; + } - case OSD_GPS_HDOP: - { - buff[0] = SYM_HDP_L; - buff[1] = SYM_HDP_R; - int32_t centiHDOP = 100 * gpsSol.hdop / HDOP_SCALE; - uint8_t digits = 2U; + case OSD_GPS_HDOP: + { + buff[0] = SYM_HDP_L; + buff[1] = SYM_HDP_R; + int32_t centiHDOP = 100 * gpsSol.hdop / HDOP_SCALE; + uint8_t digits = 2U; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values - if (isBfCompatibleVideoSystem(osdConfig())) { - digits = 3U; - } + if (isBfCompatibleVideoSystem(osdConfig())) { + digits = 3U; + } #endif - osdFormatCentiNumber(&buff[2], centiHDOP, 0, 1, 0, digits); - break; - } + osdFormatCentiNumber(&buff[2], centiHDOP, 0, 1, 0, digits); + break; + } - case OSD_MAP_NORTH: - { - static uint16_t drawn = 0; - static uint32_t scale = 0; - osdDrawHomeMap(0, 'N', &drawn, &scale); - return true; - } - case OSD_MAP_TAKEOFF: - { - static uint16_t drawn = 0; - static uint32_t scale = 0; - osdDrawHomeMap(CENTIDEGREES_TO_DEGREES(navigationGetHomeHeading()), 'T', &drawn, &scale); - return true; - } - case OSD_RADAR: - { - static uint16_t drawn = 0; - static uint32_t scale = 0; - osdDrawRadar(&drawn, &scale); - return true; - } + case OSD_MAP_NORTH: + { + static uint16_t drawn = 0; + static uint32_t scale = 0; + osdDrawHomeMap(0, 'N', &drawn, &scale); + return true; + } + case OSD_MAP_TAKEOFF: + { + static uint16_t drawn = 0; + static uint32_t scale = 0; + osdDrawHomeMap(CENTIDEGREES_TO_DEGREES(navigationGetHomeHeading()), 'T', &drawn, &scale); + return true; + } + case OSD_RADAR: + { + static uint16_t drawn = 0; + static uint32_t scale = 0; + osdDrawRadar(&drawn, &scale); + return true; + } #endif // GPS - case OSD_ALTITUDE: - { - int32_t alt = osdGetAltitude(); - osdFormatAltitudeSymbol(buff, alt); + case OSD_ALTITUDE: + { + int32_t alt = osdGetAltitude(); + osdFormatAltitudeSymbol(buff, alt); - uint16_t alt_alarm = osdConfig()->alt_alarm; - uint16_t neg_alt_alarm = osdConfig()->neg_alt_alarm; - if ((alt_alarm > 0 && CENTIMETERS_TO_METERS(alt) > alt_alarm) || - (neg_alt_alarm > 0 && alt < 0 && -CENTIMETERS_TO_METERS(alt) > neg_alt_alarm)) { + uint16_t alt_alarm = osdConfig()->alt_alarm; + uint16_t neg_alt_alarm = osdConfig()->neg_alt_alarm; + if ((alt_alarm > 0 && CENTIMETERS_TO_METERS(alt) > alt_alarm) || + (neg_alt_alarm > 0 && alt < 0 && -CENTIMETERS_TO_METERS(alt) > neg_alt_alarm)) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } - case OSD_ALTITUDE_MSL: - { - int32_t alt = osdGetAltitudeMsl(); - osdFormatAltitudeSymbol(buff, alt); - break; - } + case OSD_ALTITUDE_MSL: + { + int32_t alt = osdGetAltitudeMsl(); + osdFormatAltitudeSymbol(buff, alt); + break; + } #ifdef USE_RANGEFINDER - case OSD_RANGEFINDER: - { - int32_t range = rangefinderGetLatestRawAltitude(); - if (range < 0) { - buff[0] = '-'; - buff[1] = '-'; - buff[2] = '-'; - } else { - osdFormatDistanceSymbol(buff, range, 1); - } - } - break; + case OSD_RANGEFINDER: + { + int32_t range = rangefinderGetLatestRawAltitude(); + if (range < 0) { + buff[0] = '-'; + buff[1] = '-'; + buff[2] = '-'; + } else { + osdFormatDistanceSymbol(buff, range, 1); + } + } + break; #endif - case OSD_ONTIME: - { - osdFormatOnTime(buff); - break; - } + case OSD_ONTIME: + { + osdFormatOnTime(buff); + break; + } - case OSD_FLYTIME: - { - osdFormatFlyTime(buff, &elemAttr); - break; - } + case OSD_FLYTIME: + { + osdFormatFlyTime(buff, &elemAttr); + break; + } - case OSD_ONTIME_FLYTIME: - { - if (ARMING_FLAG(ARMED)) { - osdFormatFlyTime(buff, &elemAttr); - } else { - osdFormatOnTime(buff); - } - break; - } + case OSD_ONTIME_FLYTIME: + { + if (ARMING_FLAG(ARMED)) { + osdFormatFlyTime(buff, &elemAttr); + } else { + osdFormatOnTime(buff); + } + break; + } - case OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH: - { - /*static int32_t updatedTimeSeconds = 0;*/ - static int32_t timeSeconds = -1; + case OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH: + { + /*static int32_t updatedTimeSeconds = 0;*/ + static int32_t timeSeconds = -1; #if defined(USE_ADC) && defined(USE_GPS) - static timeUs_t updatedTimestamp = 0; - timeUs_t currentTimeUs = micros(); - if (cmpTimeUs(currentTimeUs, updatedTimestamp) >= MS2US(1000)) { + static timeUs_t updatedTimestamp = 0; + timeUs_t currentTimeUs = micros(); + if (cmpTimeUs(currentTimeUs, updatedTimestamp) >= MS2US(1000)) { #ifdef USE_WIND_ESTIMATOR - timeSeconds = calculateRemainingFlightTimeBeforeRTH(osdConfig()->estimations_wind_compensation); + timeSeconds = calculateRemainingFlightTimeBeforeRTH(osdConfig()->estimations_wind_compensation); #else - timeSeconds = calculateRemainingFlightTimeBeforeRTH(false); + timeSeconds = calculateRemainingFlightTimeBeforeRTH(false); #endif - updatedTimestamp = currentTimeUs; - } + updatedTimestamp = currentTimeUs; + } #endif - if ((!ARMING_FLAG(ARMED)) || (timeSeconds == -1)) { - buff[0] = SYM_FLIGHT_MINS_REMAINING; - strcpy(buff + 1, "--:--"); + if ((!ARMING_FLAG(ARMED)) || (timeSeconds == -1)) { + buff[0] = SYM_FLIGHT_MINS_REMAINING; + strcpy(buff + 1, "--:--"); #if defined(USE_ADC) && defined(USE_GPS) - updatedTimestamp = 0; + updatedTimestamp = 0; #endif - } else if (timeSeconds == -2) { - // Wind is too strong to come back with cruise throttle - buff[0] = SYM_FLIGHT_MINS_REMAINING; - buff[1] = buff[2] = buff[4] = buff[5] = SYM_WIND_HORIZONTAL; - buff[3] = ':'; - buff[6] = '\0'; - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } else { - osdFormatTime(buff, timeSeconds, SYM_FLIGHT_MINS_REMAINING, SYM_FLIGHT_HOURS_REMAINING); - if (timeSeconds == 0) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } - break; + } else if (timeSeconds == -2) { + // Wind is too strong to come back with cruise throttle + buff[0] = SYM_FLIGHT_MINS_REMAINING; + buff[1] = buff[2] = buff[4] = buff[5] = SYM_WIND_HORIZONTAL; + buff[3] = ':'; + buff[6] = '\0'; + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } else { + osdFormatTime(buff, timeSeconds, SYM_FLIGHT_MINS_REMAINING, SYM_FLIGHT_HOURS_REMAINING); + if (timeSeconds == 0) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + break; - case OSD_REMAINING_DISTANCE_BEFORE_RTH:; - static int32_t distanceMeters = -1; + case OSD_REMAINING_DISTANCE_BEFORE_RTH:; + static int32_t distanceMeters = -1; #if defined(USE_ADC) && defined(USE_GPS) - static timeUs_t updatedTimestamp = 0; - timeUs_t currentTimeUs = micros(); - if (cmpTimeUs(currentTimeUs, updatedTimestamp) >= MS2US(1000)) { + static timeUs_t updatedTimestamp = 0; + timeUs_t currentTimeUs = micros(); + if (cmpTimeUs(currentTimeUs, updatedTimestamp) >= MS2US(1000)) { #ifdef USE_WIND_ESTIMATOR - distanceMeters = calculateRemainingDistanceBeforeRTH(osdConfig()->estimations_wind_compensation); + distanceMeters = calculateRemainingDistanceBeforeRTH(osdConfig()->estimations_wind_compensation); #else - distanceMeters = calculateRemainingDistanceBeforeRTH(false); + distanceMeters = calculateRemainingDistanceBeforeRTH(false); #endif - updatedTimestamp = currentTimeUs; - } + updatedTimestamp = currentTimeUs; + } #endif - //buff[0] = SYM_TRIP_DIST; - displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_FLIGHT_DIST_REMAINING); - if ((!ARMING_FLAG(ARMED)) || (distanceMeters == -1)) { - buff[4] = SYM_BLANK; - buff[5] = '\0'; - strcpy(buff + 1, "---"); - } else if (distanceMeters == -2) { - // Wind is too strong to come back with cruise throttle - buff[1] = buff[2] = buff[3] = SYM_WIND_HORIZONTAL; - switch ((osd_unit_e)osdConfig()->units){ - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - buff[4] = SYM_DIST_MI; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - buff[4] = SYM_DIST_KM; - break; - case OSD_UNIT_GA: - buff[4] = SYM_DIST_NM; - break; - } - buff[5] = '\0'; - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } else { - osdFormatDistanceSymbol(buff + 1, distanceMeters * 100, 0); - if (distanceMeters == 0) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; + //buff[0] = SYM_TRIP_DIST; + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_FLIGHT_DIST_REMAINING); + if ((!ARMING_FLAG(ARMED)) || (distanceMeters == -1)) { + buff[4] = SYM_BLANK; + buff[5] = '\0'; + strcpy(buff + 1, "---"); + } else if (distanceMeters == -2) { + // Wind is too strong to come back with cruise throttle + buff[1] = buff[2] = buff[3] = SYM_WIND_HORIZONTAL; + switch ((osd_unit_e)osdConfig()->units){ + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + buff[4] = SYM_DIST_MI; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + buff[4] = SYM_DIST_KM; + break; + case OSD_UNIT_GA: + buff[4] = SYM_DIST_NM; + break; + } + buff[5] = '\0'; + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } else { + osdFormatDistanceSymbol(buff + 1, distanceMeters * 100, 0); + if (distanceMeters == 0) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; - case OSD_FLYMODE: - { - char *p = "ACRO"; + case OSD_FLYMODE: + { + char *p = "ACRO"; - if (FLIGHT_MODE(FAILSAFE_MODE)) - p = "!FS!"; - else if (FLIGHT_MODE(MANUAL_MODE)) - p = "MANU"; - else if (FLIGHT_MODE(TURTLE_MODE)) - p = "TURT"; - else if (FLIGHT_MODE(NAV_RTH_MODE)) - p = isWaypointMissionRTHActive() ? "WRTH" : "RTH "; - else if (FLIGHT_MODE(NAV_POSHOLD_MODE) && STATE(AIRPLANE)) - p = "LOTR"; - else if (FLIGHT_MODE(NAV_POSHOLD_MODE)) - p = "HOLD"; - else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)) - p = "CRUZ"; - else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) - p = "CRSH"; - else if (FLIGHT_MODE(NAV_WP_MODE)) - p = " WP "; - else if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && navigationRequiresAngleMode()) { - // If navigationRequiresAngleMode() returns false when ALTHOLD is active, - // it means it can be combined with ANGLE, HORIZON, ACRO, etc... - // and its display is handled by OSD_MESSAGES rather than OSD_FLYMODE. - p = " AH "; - } - else if (FLIGHT_MODE(ANGLE_MODE)) - p = "ANGL"; - else if (FLIGHT_MODE(HORIZON_MODE)) - p = "HOR "; + if (FLIGHT_MODE(FAILSAFE_MODE)) + p = "!FS!"; + else if (FLIGHT_MODE(MANUAL_MODE)) + p = "MANU"; + else if (FLIGHT_MODE(TURTLE_MODE)) + p = "TURT"; + else if (FLIGHT_MODE(NAV_RTH_MODE)) + p = isWaypointMissionRTHActive() ? "WRTH" : "RTH "; + else if (FLIGHT_MODE(NAV_POSHOLD_MODE) && STATE(AIRPLANE)) + p = "LOTR"; + else if (FLIGHT_MODE(NAV_POSHOLD_MODE)) + p = "HOLD"; + else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)) + p = "CRUZ"; + else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) + p = "CRSH"; + else if (FLIGHT_MODE(NAV_WP_MODE)) + p = " WP "; + else if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && navigationRequiresAngleMode()) { + // If navigationRequiresAngleMode() returns false when ALTHOLD is active, + // it means it can be combined with ANGLE, HORIZON, ACRO, etc... + // and its display is handled by OSD_MESSAGES rather than OSD_FLYMODE. + p = " AH "; + } + else if (FLIGHT_MODE(ANGLE_MODE)) + p = "ANGL"; + else if (FLIGHT_MODE(HORIZON_MODE)) + p = "HOR "; - displayWrite(osdDisplayPort, elemPosX, elemPosY, p); - return true; - } + displayWrite(osdDisplayPort, elemPosX, elemPosY, p); + return true; + } - case OSD_CRAFT_NAME: - osdFormatCraftName(buff); - break; + case OSD_CRAFT_NAME: + osdFormatCraftName(buff); + break; - case OSD_PILOT_NAME: - osdFormatPilotName(buff); - break; + case OSD_PILOT_NAME: + osdFormatPilotName(buff); + break; - case OSD_PILOT_LOGO: - displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_PILOT_LOGO_SML_L); - displayWriteChar(osdDisplayPort, elemPosX+1, elemPosY, SYM_PILOT_LOGO_SML_C); - displayWriteChar(osdDisplayPort, elemPosX+2, elemPosY, SYM_PILOT_LOGO_SML_R); - break; + case OSD_PILOT_LOGO: + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_PILOT_LOGO_SML_L); + displayWriteChar(osdDisplayPort, elemPosX+1, elemPosY, SYM_PILOT_LOGO_SML_C); + displayWriteChar(osdDisplayPort, elemPosX+2, elemPosY, SYM_PILOT_LOGO_SML_R); + break; - case OSD_THROTTLE_POS: - { - osdFormatThrottlePosition(buff, false, &elemAttr); - break; - } + case OSD_THROTTLE_POS: + { + osdFormatThrottlePosition(buff, false, &elemAttr); + break; + } - case OSD_VTX_CHANNEL: - { - vtxDeviceOsdInfo_t osdInfo; - vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo); + case OSD_VTX_CHANNEL: + { + vtxDeviceOsdInfo_t osdInfo; + vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo); - tfp_sprintf(buff, "CH:%c%s:", osdInfo.bandLetter, osdInfo.channelName); - displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); + tfp_sprintf(buff, "CH:%c%s:", osdInfo.bandLetter, osdInfo.channelName); + displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); - tfp_sprintf(buff, "%c", osdInfo.powerIndexLetter); - if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 6, elemPosY, buff, elemAttr); - return true; - } - break; + tfp_sprintf(buff, "%c", osdInfo.powerIndexLetter); + if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 6, elemPosY, buff, elemAttr); + return true; + } + break; - case OSD_VTX_POWER: - { - vtxDeviceOsdInfo_t osdInfo; - vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo); + case OSD_VTX_POWER: + { + vtxDeviceOsdInfo_t osdInfo; + vtxCommonGetOsdInfo(vtxCommonDevice(), &osdInfo); - tfp_sprintf(buff, "%c", SYM_VTX_POWER); - displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); + tfp_sprintf(buff, "%c", SYM_VTX_POWER); + displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); - tfp_sprintf(buff, "%c", osdInfo.powerIndexLetter); - if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); - return true; - } + tfp_sprintf(buff, "%c", osdInfo.powerIndexLetter); + if (isAdjustmentFunctionSelected(ADJUSTMENT_VTX_POWER_LEVEL)) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); + return true; + } #if defined(USE_SERIALRX_CRSF) - case OSD_CRSF_RSSI_DBM: - { - int16_t rssi = rxLinkStatistics.uplinkRSSI; - buff[0] = (rxLinkStatistics.activeAntenna == 0) ? SYM_RSSI : SYM_2RSS; // Separate symbols for each antenna - if (rssi <= -100) { - tfp_sprintf(buff + 1, "%4d%c", rssi, SYM_DBM); - } else { - tfp_sprintf(buff + 1, "%3d%c%c", rssi, SYM_DBM, ' '); - } - if (!failsafeIsReceivingRxData()){ - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } else if (osdConfig()->rssi_dbm_alarm && rssi < osdConfig()->rssi_dbm_alarm) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } - case OSD_CRSF_LQ: - { - buff[0] = SYM_LQ; - int16_t statsLQ = rxLinkStatistics.uplinkLQ; - int16_t scaledLQ = scaleRange(constrain(statsLQ, 0, 100), 0, 100, 170, 300); - switch (osdConfig()->crsf_lq_format) { - case OSD_CRSF_LQ_TYPE1: - if (!failsafeIsReceivingRxData()) { - tfp_sprintf(buff+1, "%3d", 0); - } else { - tfp_sprintf(buff+1, "%3d", rxLinkStatistics.uplinkLQ); - } - break; - case OSD_CRSF_LQ_TYPE2: - if (!failsafeIsReceivingRxData()) { - tfp_sprintf(buff+1, "%s:%3d", " ", 0); - } else { - tfp_sprintf(buff+1, "%d:%3d", rxLinkStatistics.rfMode, rxLinkStatistics.uplinkLQ); - } - break; - case OSD_CRSF_LQ_TYPE3: - if (!failsafeIsReceivingRxData()) { - tfp_sprintf(buff+1, "%3d", 0); - } else { - tfp_sprintf(buff+1, "%3d", rxLinkStatistics.rfMode >= 2 ? scaledLQ : rxLinkStatistics.uplinkLQ); - } - break; - } - if (!failsafeIsReceivingRxData()) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } else if (rxLinkStatistics.uplinkLQ < osdConfig()->link_quality_alarm) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } + case OSD_CRSF_RSSI_DBM: + { + int16_t rssi = rxLinkStatistics.uplinkRSSI; + buff[0] = (rxLinkStatistics.activeAntenna == 0) ? SYM_RSSI : SYM_2RSS; // Separate symbols for each antenna + if (rssi <= -100) { + tfp_sprintf(buff + 1, "%4d%c", rssi, SYM_DBM); + } else { + tfp_sprintf(buff + 1, "%3d%c%c", rssi, SYM_DBM, ' '); + } + if (!failsafeIsReceivingRxData()){ + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } else if (osdConfig()->rssi_dbm_alarm && rssi < osdConfig()->rssi_dbm_alarm) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } + case OSD_CRSF_LQ: + { + buff[0] = SYM_LQ; + int16_t statsLQ = rxLinkStatistics.uplinkLQ; + int16_t scaledLQ = scaleRange(constrain(statsLQ, 0, 100), 0, 100, 170, 300); + switch (osdConfig()->crsf_lq_format) { + case OSD_CRSF_LQ_TYPE1: + if (!failsafeIsReceivingRxData()) { + tfp_sprintf(buff+1, "%3d", 0); + } else { + tfp_sprintf(buff+1, "%3d", rxLinkStatistics.uplinkLQ); + } + break; + case OSD_CRSF_LQ_TYPE2: + if (!failsafeIsReceivingRxData()) { + tfp_sprintf(buff+1, "%s:%3d", " ", 0); + } else { + tfp_sprintf(buff+1, "%d:%3d", rxLinkStatistics.rfMode, rxLinkStatistics.uplinkLQ); + } + break; + case OSD_CRSF_LQ_TYPE3: + if (!failsafeIsReceivingRxData()) { + tfp_sprintf(buff+1, "%3d", 0); + } else { + tfp_sprintf(buff+1, "%3d", rxLinkStatistics.rfMode >= 2 ? scaledLQ : rxLinkStatistics.uplinkLQ); + } + break; + } + if (!failsafeIsReceivingRxData()) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } else if (rxLinkStatistics.uplinkLQ < osdConfig()->link_quality_alarm) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } - case OSD_CRSF_SNR_DB: - { - static pt1Filter_t snrFilterState; - static timeMs_t snrUpdated = 0; - int8_t snrFiltered = pt1FilterApply4(&snrFilterState, rxLinkStatistics.uplinkSNR, 0.5f, MS2S(millis() - snrUpdated)); - snrUpdated = millis(); + case OSD_CRSF_SNR_DB: + { + static pt1Filter_t snrFilterState; + static timeMs_t snrUpdated = 0; + int8_t snrFiltered = pt1FilterApply4(&snrFilterState, rxLinkStatistics.uplinkSNR, 0.5f, MS2S(millis() - snrUpdated)); + snrUpdated = millis(); - const char* showsnr = "-20"; - const char* hidesnr = " "; - if (snrFiltered > osdConfig()->snr_alarm) { - if (cmsInMenu) { - buff[0] = SYM_SNR; - tfp_sprintf(buff + 1, "%s%c", showsnr, SYM_DB); - } else { - buff[0] = SYM_BLANK; - tfp_sprintf(buff + 1, "%s%c", hidesnr, SYM_BLANK); - } - } else if (snrFiltered <= osdConfig()->snr_alarm) { - buff[0] = SYM_SNR; - if (snrFiltered <= -10) { - tfp_sprintf(buff + 1, "%3d%c", snrFiltered, SYM_DB); - } else { - tfp_sprintf(buff + 1, "%2d%c%c", snrFiltered, SYM_DB, ' '); - } - } - break; - } + const char* showsnr = "-20"; + const char* hidesnr = " "; + if (snrFiltered > osdConfig()->snr_alarm) { + if (cmsInMenu) { + buff[0] = SYM_SNR; + tfp_sprintf(buff + 1, "%s%c", showsnr, SYM_DB); + } else { + buff[0] = SYM_BLANK; + tfp_sprintf(buff + 1, "%s%c", hidesnr, SYM_BLANK); + } + } else if (snrFiltered <= osdConfig()->snr_alarm) { + buff[0] = SYM_SNR; + if (snrFiltered <= -10) { + tfp_sprintf(buff + 1, "%3d%c", snrFiltered, SYM_DB); + } else { + tfp_sprintf(buff + 1, "%2d%c%c", snrFiltered, SYM_DB, ' '); + } + } + break; + } - case OSD_CRSF_TX_POWER: - { - if (!failsafeIsReceivingRxData()) - tfp_sprintf(buff, "%s%c", " ", SYM_BLANK); - else - tfp_sprintf(buff, "%4d%c", rxLinkStatistics.uplinkTXPower, SYM_MW); - break; - } + case OSD_CRSF_TX_POWER: + { + if (!failsafeIsReceivingRxData()) + tfp_sprintf(buff, "%s%c", " ", SYM_BLANK); + else + tfp_sprintf(buff, "%4d%c", rxLinkStatistics.uplinkTXPower, SYM_MW); + break; + } #endif - case OSD_CROSSHAIRS: // Hud is a sub-element of the crosshair + case OSD_CROSSHAIRS: // Hud is a sub-element of the crosshair - osdCrosshairPosition(&elemPosX, &elemPosY); - osdHudDrawCrosshair(osdGetDisplayPortCanvas(), elemPosX, elemPosY); + osdCrosshairPosition(&elemPosX, &elemPosY); + osdHudDrawCrosshair(osdGetDisplayPortCanvas(), elemPosX, elemPosY); - if (osdConfig()->hud_homing && STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && isImuHeadingValid()) { - osdHudDrawHoming(elemPosX, elemPosY); - } + if (osdConfig()->hud_homing && STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && isImuHeadingValid()) { + osdHudDrawHoming(elemPosX, elemPosY); + } - if (STATE(GPS_FIX) && isImuHeadingValid()) { + if (STATE(GPS_FIX) && isImuHeadingValid()) { - if (osdConfig()->hud_homepoint || osdConfig()->hud_radar_disp > 0 || osdConfig()->hud_wp_disp > 0) { - osdHudClear(); - } + if (osdConfig()->hud_homepoint || osdConfig()->hud_radar_disp > 0 || osdConfig()->hud_wp_disp > 0) { + osdHudClear(); + } - // -------- POI : Home point + // -------- POI : Home point - if (osdConfig()->hud_homepoint) { // Display the home point (H) - osdHudDrawPoi(GPS_distanceToHome, GPS_directionToHome, -osdGetAltitude() / 100, 0, SYM_HOME, 0 , 0); - } + if (osdConfig()->hud_homepoint) { // Display the home point (H) + osdHudDrawPoi(GPS_distanceToHome, GPS_directionToHome, -osdGetAltitude() / 100, 0, SYM_HOME, 0 , 0); + } - // -------- POI : Nearby aircrafts from ESP32 radar + // -------- POI : Nearby aircrafts from ESP32 radar - if (osdConfig()->hud_radar_disp > 0) { // Display the POI from the radar - for (uint8_t i = 0; i < osdConfig()->hud_radar_disp; i++) { - if (radar_pois[i].gps.lat != 0 && radar_pois[i].gps.lon != 0 && radar_pois[i].state < 2) { // state 2 means POI has been lost and must be skipped - fpVector3_t poi; - geoConvertGeodeticToLocal(&poi, &posControl.gpsOrigin, &radar_pois[i].gps, GEO_ALT_RELATIVE); - radar_pois[i].distance = calculateDistanceToDestination(&poi) / 100; // In meters + if (osdConfig()->hud_radar_disp > 0) { // Display the POI from the radar + for (uint8_t i = 0; i < osdConfig()->hud_radar_disp; i++) { + if (radar_pois[i].gps.lat != 0 && radar_pois[i].gps.lon != 0 && radar_pois[i].state < 2) { // state 2 means POI has been lost and must be skipped + fpVector3_t poi; + geoConvertGeodeticToLocal(&poi, &posControl.gpsOrigin, &radar_pois[i].gps, GEO_ALT_RELATIVE); + radar_pois[i].distance = calculateDistanceToDestination(&poi) / 100; // In meters - if (radar_pois[i].distance >= osdConfig()->hud_radar_range_min && radar_pois[i].distance <= osdConfig()->hud_radar_range_max) { - radar_pois[i].direction = calculateBearingToDestination(&poi) / 100; // In ° - radar_pois[i].altitude = (radar_pois[i].gps.alt - osdGetAltitudeMsl()) / 100; - osdHudDrawPoi(radar_pois[i].distance, osdGetHeadingAngle(radar_pois[i].direction), radar_pois[i].altitude, 1, 65 + i, radar_pois[i].heading, radar_pois[i].lq); - } - } - } - } + if (radar_pois[i].distance >= osdConfig()->hud_radar_range_min && radar_pois[i].distance <= osdConfig()->hud_radar_range_max) { + radar_pois[i].direction = calculateBearingToDestination(&poi) / 100; // In ° + radar_pois[i].altitude = (radar_pois[i].gps.alt - osdGetAltitudeMsl()) / 100; + osdHudDrawPoi(radar_pois[i].distance, osdGetHeadingAngle(radar_pois[i].direction), radar_pois[i].altitude, 1, 65 + i, radar_pois[i].heading, radar_pois[i].lq); + } + } + } + } - // -------- POI : Next waypoints from navigation + // -------- POI : Next waypoints from navigation - if (osdConfig()->hud_wp_disp > 0 && posControl.waypointListValid && posControl.waypointCount > 0) { // Display the next waypoints - gpsLocation_t wp2; - int j; + if (osdConfig()->hud_wp_disp > 0 && posControl.waypointListValid && posControl.waypointCount > 0) { // Display the next waypoints + gpsLocation_t wp2; + int j; - for (int i = osdConfig()->hud_wp_disp - 1; i >= 0 ; i--) { // Display in reverse order so the next WP is always written on top - j = posControl.activeWaypointIndex + i; - if (j > posControl.startWpIndex + posControl.waypointCount - 1) { // limit to max WP index for mission - break; - } - if (posControl.waypointList[j].lat != 0 && posControl.waypointList[j].lon != 0) { - wp2.lat = posControl.waypointList[j].lat; - wp2.lon = posControl.waypointList[j].lon; - wp2.alt = posControl.waypointList[j].alt; - fpVector3_t poi; - geoConvertGeodeticToLocal(&poi, &posControl.gpsOrigin, &wp2, waypointMissionAltConvMode(posControl.waypointList[j].p3)); - int32_t altConvModeAltitude = waypointMissionAltConvMode(posControl.waypointList[j].p3) == GEO_ALT_ABSOLUTE ? osdGetAltitudeMsl() : osdGetAltitude(); - j = getGeoWaypointNumber(j); - while (j > 9) j -= 10; // Only the last digit displayed if WP>=10, no room for more (48 = ascii 0) - osdHudDrawPoi(calculateDistanceToDestination(&poi) / 100, osdGetHeadingAngle(calculateBearingToDestination(&poi) / 100), (posControl.waypointList[j].alt - altConvModeAltitude)/ 100, 2, SYM_WAYPOINT, 48 + j, i); - } - } - } - } + for (int i = osdConfig()->hud_wp_disp - 1; i >= 0 ; i--) { // Display in reverse order so the next WP is always written on top + j = posControl.activeWaypointIndex + i; + if (j > posControl.startWpIndex + posControl.waypointCount - 1) { // limit to max WP index for mission + break; + } + if (posControl.waypointList[j].lat != 0 && posControl.waypointList[j].lon != 0) { + wp2.lat = posControl.waypointList[j].lat; + wp2.lon = posControl.waypointList[j].lon; + wp2.alt = posControl.waypointList[j].alt; + fpVector3_t poi; + geoConvertGeodeticToLocal(&poi, &posControl.gpsOrigin, &wp2, waypointMissionAltConvMode(posControl.waypointList[j].p3)); + int32_t altConvModeAltitude = waypointMissionAltConvMode(posControl.waypointList[j].p3) == GEO_ALT_ABSOLUTE ? osdGetAltitudeMsl() : osdGetAltitude(); + j = getGeoWaypointNumber(j); + while (j > 9) j -= 10; // Only the last digit displayed if WP>=10, no room for more (48 = ascii 0) + osdHudDrawPoi(calculateDistanceToDestination(&poi) / 100, osdGetHeadingAngle(calculateBearingToDestination(&poi) / 100), (posControl.waypointList[j].alt - altConvModeAltitude)/ 100, 2, SYM_WAYPOINT, 48 + j, i); + } + } + } + } - return true; - break; + return true; + break; - case OSD_ATTITUDE_ROLL: - buff[0] = SYM_ROLL_LEVEL; - if (ABS(attitude.values.roll) >= 1) - buff[0] += (attitude.values.roll < 0 ? -1 : 1); - osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.roll)), 0, 1, 0, 3); - break; + case OSD_ATTITUDE_ROLL: + buff[0] = SYM_ROLL_LEVEL; + if (ABS(attitude.values.roll) >= 1) + buff[0] += (attitude.values.roll < 0 ? -1 : 1); + osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.roll)), 0, 1, 0, 3); + break; - case OSD_ATTITUDE_PITCH: - if (ABS(attitude.values.pitch) < 1) - buff[0] = 'P'; - else if (attitude.values.pitch > 0) - buff[0] = SYM_PITCH_DOWN; - else if (attitude.values.pitch < 0) - buff[0] = SYM_PITCH_UP; - osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.pitch)), 0, 1, 0, 3); - break; + case OSD_ATTITUDE_PITCH: + if (ABS(attitude.values.pitch) < 1) + buff[0] = 'P'; + else if (attitude.values.pitch > 0) + buff[0] = SYM_PITCH_DOWN; + else if (attitude.values.pitch < 0) + buff[0] = SYM_PITCH_UP; + osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.pitch)), 0, 1, 0, 3); + break; - case OSD_ARTIFICIAL_HORIZON: - { - float rollAngle = DECIDEGREES_TO_RADIANS(attitude.values.roll); - float pitchAngle = DECIDEGREES_TO_RADIANS(attitude.values.pitch); + case OSD_ARTIFICIAL_HORIZON: + { + float rollAngle = DECIDEGREES_TO_RADIANS(attitude.values.roll); + float pitchAngle = DECIDEGREES_TO_RADIANS(attitude.values.pitch); - pitchAngle -= osdConfig()->ahi_camera_uptilt_comp ? DEGREES_TO_RADIANS(osdConfig()->camera_uptilt) : 0; - pitchAngle += DEGREES_TO_RADIANS(getFixedWingLevelTrim()); - if (osdConfig()->ahi_reverse_roll) { - rollAngle = -rollAngle; - } - osdDrawArtificialHorizon(osdDisplayPort, osdGetDisplayPortCanvas(), - OSD_DRAW_POINT_GRID(elemPosX, elemPosY), rollAngle, pitchAngle); - osdDrawSingleElement(OSD_HORIZON_SIDEBARS); - osdDrawSingleElement(OSD_CROSSHAIRS); + pitchAngle -= osdConfig()->ahi_camera_uptilt_comp ? DEGREES_TO_RADIANS(osdConfig()->camera_uptilt) : 0; + pitchAngle += DEGREES_TO_RADIANS(getFixedWingLevelTrim()); + if (osdConfig()->ahi_reverse_roll) { + rollAngle = -rollAngle; + } + osdDrawArtificialHorizon(osdDisplayPort, osdGetDisplayPortCanvas(), + OSD_DRAW_POINT_GRID(elemPosX, elemPosY), rollAngle, pitchAngle); + osdDrawSingleElement(OSD_HORIZON_SIDEBARS); + osdDrawSingleElement(OSD_CROSSHAIRS); - return true; - } + return true; + } - case OSD_HORIZON_SIDEBARS: - { - osdDrawSidebars(osdDisplayPort, osdGetDisplayPortCanvas()); - return true; - } + case OSD_HORIZON_SIDEBARS: + { + osdDrawSidebars(osdDisplayPort, osdGetDisplayPortCanvas()); + return true; + } #if defined(USE_BARO) || defined(USE_GPS) - case OSD_VARIO: - { - float zvel = getEstimatedActualVelocity(Z); - osdDrawVario(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), zvel); - return true; - } + case OSD_VARIO: + { + float zvel = getEstimatedActualVelocity(Z); + osdDrawVario(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), zvel); + return true; + } - case OSD_VARIO_NUM: - { - int16_t value = getEstimatedActualVelocity(Z); - char sym; - switch ((osd_unit_e)osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - // Convert to centifeet/s - value = CENTIMETERS_TO_CENTIFEET(value); - sym = SYM_FTS; - break; - case OSD_UNIT_GA: - // Convert to centi-100feet/min - value = CENTIMETERS_TO_FEET(value * 60); - sym = SYM_100FTM; - break; - default: - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - // Already in cm/s - sym = SYM_MS; - break; - } + case OSD_VARIO_NUM: + { + int16_t value = getEstimatedActualVelocity(Z); + char sym; + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + // Convert to centifeet/s + value = CENTIMETERS_TO_CENTIFEET(value); + sym = SYM_FTS; + break; + case OSD_UNIT_GA: + // Convert to centi-100feet/min + value = CENTIMETERS_TO_FEET(value * 60); + sym = SYM_100FTM; + break; + default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + // Already in cm/s + sym = SYM_MS; + break; + } - osdFormatCentiNumber(buff, value, 0, 1, 0, 3); - buff[3] = sym; - buff[4] = '\0'; - break; - } - case OSD_CLIMB_EFFICIENCY: - { - // amperage is in centi amps (10mA), vertical speed is in cms/s. We want - // Ah/dist only to show when vertical speed > 1m/s. - static pt1Filter_t veFilterState; - static timeUs_t vEfficiencyUpdated = 0; - int32_t value = 0; - timeUs_t currentTimeUs = micros(); - timeDelta_t vEfficiencyTimeDelta = cmpTimeUs(currentTimeUs, vEfficiencyUpdated); - if (getEstimatedActualVelocity(Z) > 0) { - if (vEfficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { - // Centiamps (kept for osdFormatCentiNumber) / m/s - Will appear as A / m/s in OSD - value = pt1FilterApply4(&veFilterState, (float)getAmperage() / (getEstimatedActualVelocity(Z) / 100.0f), 1, US2S(vEfficiencyTimeDelta)); + osdFormatCentiNumber(buff, value, 0, 1, 0, 3); + buff[3] = sym; + buff[4] = '\0'; + break; + } + case OSD_CLIMB_EFFICIENCY: + { + // amperage is in centi amps (10mA), vertical speed is in cms/s. We want + // Ah/dist only to show when vertical speed > 1m/s. + static pt1Filter_t veFilterState; + static timeUs_t vEfficiencyUpdated = 0; + int32_t value = 0; + timeUs_t currentTimeUs = micros(); + timeDelta_t vEfficiencyTimeDelta = cmpTimeUs(currentTimeUs, vEfficiencyUpdated); + if (getEstimatedActualVelocity(Z) > 0) { + if (vEfficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { + // Centiamps (kept for osdFormatCentiNumber) / m/s - Will appear as A / m/s in OSD + value = pt1FilterApply4(&veFilterState, (float)getAmperage() / (getEstimatedActualVelocity(Z) / 100.0f), 1, US2S(vEfficiencyTimeDelta)); - vEfficiencyUpdated = currentTimeUs; - } else { - value = veFilterState.state; - } - } - bool efficiencyValid = (value > 0) && (getEstimatedActualVelocity(Z) > 100); - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_GA: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - // mAh/foot - if (efficiencyValid) { - osdFormatCentiNumber(buff, (value * METERS_PER_FOOT), 1, 2, 2, 3); - tfp_sprintf(buff, "%s%c%c", buff, SYM_AH_V_FT_0, SYM_AH_V_FT_1); - } else { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_AH_V_FT_0; - buff[4] = SYM_AH_V_FT_1; - buff[5] = '\0'; - } - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - // mAh/metre - if (efficiencyValid) { - osdFormatCentiNumber(buff, value, 1, 2, 2, 3); - tfp_sprintf(buff, "%s%c%c", buff, SYM_AH_V_M_0, SYM_AH_V_M_1); - } else { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_AH_V_M_0; - buff[4] = SYM_AH_V_M_1; - buff[5] = '\0'; - } - break; - } - break; - } - case OSD_GLIDE_TIME_REMAINING: - { - uint16_t glideTime = osdGetRemainingGlideTime(); - buff[0] = SYM_GLIDE_MINS; - if (glideTime > 0) { - // Maximum value we can show in minutes is 99 minutes and 59 seconds. It is extremely unlikely that glide - // time will be longer than 99 minutes. If it is, it will show 99:^^ - if (glideTime > (99 * 60) + 59) { - tfp_sprintf(buff + 1, "%02d:", (int)(glideTime / 60)); - buff[4] = SYM_DIRECTION; - buff[5] = SYM_DIRECTION; - } else { - tfp_sprintf(buff + 1, "%02d:%02d", (int)(glideTime / 60), (int)(glideTime % 60)); - } - } else { - tfp_sprintf(buff + 1, "%s", "--:--"); - } - buff[6] = '\0'; - break; - } - case OSD_GLIDE_RANGE: - { - uint16_t glideSeconds = osdGetRemainingGlideTime(); - buff[0] = SYM_GLIDE_DIST; - if (glideSeconds > 0) { - uint32_t glideRangeCM = glideSeconds * gpsSol.groundSpeed; - osdFormatDistanceSymbol(buff + 1, glideRangeCM, 0); - } else { - tfp_sprintf(buff + 1, "%s%c", "---", SYM_BLANK); - buff[5] = '\0'; - } - break; - } + vEfficiencyUpdated = currentTimeUs; + } else { + value = veFilterState.state; + } + } + bool efficiencyValid = (value > 0) && (getEstimatedActualVelocity(Z) > 100); + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + // mAh/foot + if (efficiencyValid) { + osdFormatCentiNumber(buff, (value * METERS_PER_FOOT), 1, 2, 2, 3); + tfp_sprintf(buff, "%s%c%c", buff, SYM_AH_V_FT_0, SYM_AH_V_FT_1); + } else { + buff[0] = buff[1] = buff[2] = '-'; + buff[3] = SYM_AH_V_FT_0; + buff[4] = SYM_AH_V_FT_1; + buff[5] = '\0'; + } + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + // mAh/metre + if (efficiencyValid) { + osdFormatCentiNumber(buff, value, 1, 2, 2, 3); + tfp_sprintf(buff, "%s%c%c", buff, SYM_AH_V_M_0, SYM_AH_V_M_1); + } else { + buff[0] = buff[1] = buff[2] = '-'; + buff[3] = SYM_AH_V_M_0; + buff[4] = SYM_AH_V_M_1; + buff[5] = '\0'; + } + break; + } + break; + } + case OSD_GLIDE_TIME_REMAINING: + { + uint16_t glideTime = osdGetRemainingGlideTime(); + buff[0] = SYM_GLIDE_MINS; + if (glideTime > 0) { + // Maximum value we can show in minutes is 99 minutes and 59 seconds. It is extremely unlikely that glide + // time will be longer than 99 minutes. If it is, it will show 99:^^ + if (glideTime > (99 * 60) + 59) { + tfp_sprintf(buff + 1, "%02d:", (int)(glideTime / 60)); + buff[4] = SYM_DIRECTION; + buff[5] = SYM_DIRECTION; + } else { + tfp_sprintf(buff + 1, "%02d:%02d", (int)(glideTime / 60), (int)(glideTime % 60)); + } + } else { + tfp_sprintf(buff + 1, "%s", "--:--"); + } + buff[6] = '\0'; + break; + } + case OSD_GLIDE_RANGE: + { + uint16_t glideSeconds = osdGetRemainingGlideTime(); + buff[0] = SYM_GLIDE_DIST; + if (glideSeconds > 0) { + uint32_t glideRangeCM = glideSeconds * gpsSol.groundSpeed; + osdFormatDistanceSymbol(buff + 1, glideRangeCM, 0); + } else { + tfp_sprintf(buff + 1, "%s%c", "---", SYM_BLANK); + buff[5] = '\0'; + } + break; + } #endif - case OSD_SWITCH_INDICATOR_0: - osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator0_name, rxGetChannelValue(osdConfig()->osd_switch_indicator0_channel - 1), buff); - break; + case OSD_SWITCH_INDICATOR_0: + osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator0_name, rxGetChannelValue(osdConfig()->osd_switch_indicator0_channel - 1), buff); + break; - case OSD_SWITCH_INDICATOR_1: - osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator1_name, rxGetChannelValue(osdConfig()->osd_switch_indicator1_channel - 1), buff); - break; + case OSD_SWITCH_INDICATOR_1: + osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator1_name, rxGetChannelValue(osdConfig()->osd_switch_indicator1_channel - 1), buff); + break; - case OSD_SWITCH_INDICATOR_2: - osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator2_name, rxGetChannelValue(osdConfig()->osd_switch_indicator2_channel - 1), buff); - break; + case OSD_SWITCH_INDICATOR_2: + osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator2_name, rxGetChannelValue(osdConfig()->osd_switch_indicator2_channel - 1), buff); + break; - case OSD_SWITCH_INDICATOR_3: - osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator3_name, rxGetChannelValue(osdConfig()->osd_switch_indicator3_channel - 1), buff); - break; + case OSD_SWITCH_INDICATOR_3: + osdDisplaySwitchIndicator(osdConfig()->osd_switch_indicator3_name, rxGetChannelValue(osdConfig()->osd_switch_indicator3_channel - 1), buff); + break; - case OSD_PAN_SERVO_CENTRED: - { - int16_t panOffset = osdGetPanServoOffset(); - const timeMs_t panServoTimeNow = millis(); - static timeMs_t panServoTimeOffCentre = 0; + case OSD_PAN_SERVO_CENTRED: + { + int16_t panOffset = osdGetPanServoOffset(); + const timeMs_t panServoTimeNow = millis(); + static timeMs_t panServoTimeOffCentre = 0; - if (panOffset < 0) { - if (osdConfig()->pan_servo_offcentre_warning != 0 && panOffset >= -osdConfig()->pan_servo_offcentre_warning) { - if (panServoTimeOffCentre == 0) { - panServoTimeOffCentre = panServoTimeNow; - } else if (panServoTimeNow >= (panServoTimeOffCentre + 10000 )) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } else { - panServoTimeOffCentre = 0; - } + if (panOffset < 0) { + if (osdConfig()->pan_servo_offcentre_warning != 0 && panOffset >= -osdConfig()->pan_servo_offcentre_warning) { + if (panServoTimeOffCentre == 0) { + panServoTimeOffCentre = panServoTimeNow; + } else if (panServoTimeNow >= (panServoTimeOffCentre + 10000 )) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } else { + panServoTimeOffCentre = 0; + } - if (osdConfig()->pan_servo_indicator_show_degrees) { - tfp_sprintf(buff, "%3d%c", -panOffset, SYM_DEGREES); - displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); - } - displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_R, elemAttr); - } else if (panOffset > 0) { - if (osdConfig()->pan_servo_offcentre_warning != 0 && panOffset <= osdConfig()->pan_servo_offcentre_warning) { - if (panServoTimeOffCentre == 0) { - panServoTimeOffCentre = panServoTimeNow; - } else if (panServoTimeNow >= (panServoTimeOffCentre + 10000 )) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } else { - panServoTimeOffCentre = 0; - } + if (osdConfig()->pan_servo_indicator_show_degrees) { + tfp_sprintf(buff, "%3d%c", -panOffset, SYM_DEGREES); + displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); + } + displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_R, elemAttr); + } else if (panOffset > 0) { + if (osdConfig()->pan_servo_offcentre_warning != 0 && panOffset <= osdConfig()->pan_servo_offcentre_warning) { + if (panServoTimeOffCentre == 0) { + panServoTimeOffCentre = panServoTimeNow; + } else if (panServoTimeNow >= (panServoTimeOffCentre + 10000 )) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } else { + panServoTimeOffCentre = 0; + } - if (osdConfig()->pan_servo_indicator_show_degrees) { - tfp_sprintf(buff, "%3d%c", panOffset, SYM_DEGREES); - displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); - } - displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_L, elemAttr); - } else { - panServoTimeOffCentre = 0; + if (osdConfig()->pan_servo_indicator_show_degrees) { + tfp_sprintf(buff, "%3d%c", panOffset, SYM_DEGREES); + displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); + } + displayWriteCharWithAttr(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_OFFSET_L, elemAttr); + } else { + panServoTimeOffCentre = 0; - if (osdConfig()->pan_servo_indicator_show_degrees) { - tfp_sprintf(buff, "%3d%c", panOffset, SYM_DEGREES); - displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); - } - displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_CENTRED); - } + if (osdConfig()->pan_servo_indicator_show_degrees) { + tfp_sprintf(buff, "%3d%c", panOffset, SYM_DEGREES); + displayWriteWithAttr(osdDisplayPort, elemPosX+1, elemPosY, buff, elemAttr); + } + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_SERVO_PAN_IS_CENTRED); + } - return true; - } - break; + return true; + } + break; - case OSD_ACTIVE_PROFILE: - tfp_sprintf(buff, "%c%u", SYM_PROFILE, (getConfigProfile() + 1)); - displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); - break; + case OSD_ACTIVE_PROFILE: + tfp_sprintf(buff, "%c%u", SYM_PROFILE, (getConfigProfile() + 1)); + displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); + break; - case OSD_ROLL_PIDS: - osdDisplayFlightPIDValues(elemPosX, elemPosY, "ROL", PID_ROLL, ADJUSTMENT_ROLL_P, ADJUSTMENT_ROLL_I, ADJUSTMENT_ROLL_D, ADJUSTMENT_ROLL_FF); - return true; + case OSD_ROLL_PIDS: + osdDisplayFlightPIDValues(elemPosX, elemPosY, "ROL", PID_ROLL, ADJUSTMENT_ROLL_P, ADJUSTMENT_ROLL_I, ADJUSTMENT_ROLL_D, ADJUSTMENT_ROLL_FF); + return true; - case OSD_PITCH_PIDS: - osdDisplayFlightPIDValues(elemPosX, elemPosY, "PIT", PID_PITCH, ADJUSTMENT_PITCH_P, ADJUSTMENT_PITCH_I, ADJUSTMENT_PITCH_D, ADJUSTMENT_PITCH_FF); - return true; + case OSD_PITCH_PIDS: + osdDisplayFlightPIDValues(elemPosX, elemPosY, "PIT", PID_PITCH, ADJUSTMENT_PITCH_P, ADJUSTMENT_PITCH_I, ADJUSTMENT_PITCH_D, ADJUSTMENT_PITCH_FF); + return true; - case OSD_YAW_PIDS: - osdDisplayFlightPIDValues(elemPosX, elemPosY, "YAW", PID_YAW, ADJUSTMENT_YAW_P, ADJUSTMENT_YAW_I, ADJUSTMENT_YAW_D, ADJUSTMENT_YAW_FF); - return true; + case OSD_YAW_PIDS: + osdDisplayFlightPIDValues(elemPosX, elemPosY, "YAW", PID_YAW, ADJUSTMENT_YAW_P, ADJUSTMENT_YAW_I, ADJUSTMENT_YAW_D, ADJUSTMENT_YAW_FF); + return true; - case OSD_LEVEL_PIDS: - osdDisplayNavPIDValues(elemPosX, elemPosY, "LEV", PID_LEVEL, ADJUSTMENT_LEVEL_P, ADJUSTMENT_LEVEL_I, ADJUSTMENT_LEVEL_D); - return true; + case OSD_LEVEL_PIDS: + osdDisplayNavPIDValues(elemPosX, elemPosY, "LEV", PID_LEVEL, ADJUSTMENT_LEVEL_P, ADJUSTMENT_LEVEL_I, ADJUSTMENT_LEVEL_D); + return true; - case OSD_POS_XY_PIDS: - osdDisplayNavPIDValues(elemPosX, elemPosY, "PXY", PID_POS_XY, ADJUSTMENT_POS_XY_P, ADJUSTMENT_POS_XY_I, ADJUSTMENT_POS_XY_D); - return true; + case OSD_POS_XY_PIDS: + osdDisplayNavPIDValues(elemPosX, elemPosY, "PXY", PID_POS_XY, ADJUSTMENT_POS_XY_P, ADJUSTMENT_POS_XY_I, ADJUSTMENT_POS_XY_D); + return true; - case OSD_POS_Z_PIDS: - osdDisplayNavPIDValues(elemPosX, elemPosY, "PZ", PID_POS_Z, ADJUSTMENT_POS_Z_P, ADJUSTMENT_POS_Z_I, ADJUSTMENT_POS_Z_D); - return true; + case OSD_POS_Z_PIDS: + osdDisplayNavPIDValues(elemPosX, elemPosY, "PZ", PID_POS_Z, ADJUSTMENT_POS_Z_P, ADJUSTMENT_POS_Z_I, ADJUSTMENT_POS_Z_D); + return true; - case OSD_VEL_XY_PIDS: - osdDisplayNavPIDValues(elemPosX, elemPosY, "VXY", PID_VEL_XY, ADJUSTMENT_VEL_XY_P, ADJUSTMENT_VEL_XY_I, ADJUSTMENT_VEL_XY_D); - return true; + case OSD_VEL_XY_PIDS: + osdDisplayNavPIDValues(elemPosX, elemPosY, "VXY", PID_VEL_XY, ADJUSTMENT_VEL_XY_P, ADJUSTMENT_VEL_XY_I, ADJUSTMENT_VEL_XY_D); + return true; - case OSD_VEL_Z_PIDS: - osdDisplayNavPIDValues(elemPosX, elemPosY, "VZ", PID_VEL_Z, ADJUSTMENT_VEL_Z_P, ADJUSTMENT_VEL_Z_I, ADJUSTMENT_VEL_Z_D); - return true; + case OSD_VEL_Z_PIDS: + osdDisplayNavPIDValues(elemPosX, elemPosY, "VZ", PID_VEL_Z, ADJUSTMENT_VEL_Z_P, ADJUSTMENT_VEL_Z_I, ADJUSTMENT_VEL_Z_D); + return true; - case OSD_HEADING_P: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "HP", 0, pidBank()->pid[PID_HEADING].P, 3, 0, ADJUSTMENT_HEADING_P); - return true; + case OSD_HEADING_P: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "HP", 0, pidBank()->pid[PID_HEADING].P, 3, 0, ADJUSTMENT_HEADING_P); + return true; - case OSD_BOARD_ALIGN_ROLL: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "AR", 0, DECIDEGREES_TO_DEGREES((float)boardAlignment()->rollDeciDegrees), 4, 1, ADJUSTMENT_ROLL_BOARD_ALIGNMENT); - return true; + case OSD_BOARD_ALIGN_ROLL: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "AR", 0, DECIDEGREES_TO_DEGREES((float)boardAlignment()->rollDeciDegrees), 4, 1, ADJUSTMENT_ROLL_BOARD_ALIGNMENT); + return true; - case OSD_BOARD_ALIGN_PITCH: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "AP", 0, DECIDEGREES_TO_DEGREES((float)boardAlignment()->pitchDeciDegrees), 4, 1, ADJUSTMENT_PITCH_BOARD_ALIGNMENT); - return true; + case OSD_BOARD_ALIGN_PITCH: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "AP", 0, DECIDEGREES_TO_DEGREES((float)boardAlignment()->pitchDeciDegrees), 4, 1, ADJUSTMENT_PITCH_BOARD_ALIGNMENT); + return true; - case OSD_RC_EXPO: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "EXP", 0, currentControlRateProfile->stabilized.rcExpo8, 3, 0, ADJUSTMENT_RC_EXPO); - return true; + case OSD_RC_EXPO: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "EXP", 0, currentControlRateProfile->stabilized.rcExpo8, 3, 0, ADJUSTMENT_RC_EXPO); + return true; - case OSD_RC_YAW_EXPO: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "YEX", 0, currentControlRateProfile->stabilized.rcYawExpo8, 3, 0, ADJUSTMENT_RC_YAW_EXPO); - return true; + case OSD_RC_YAW_EXPO: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "YEX", 0, currentControlRateProfile->stabilized.rcYawExpo8, 3, 0, ADJUSTMENT_RC_YAW_EXPO); + return true; - case OSD_THROTTLE_EXPO: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "TEX", 0, currentControlRateProfile->throttle.rcExpo8, 3, 0, ADJUSTMENT_THROTTLE_EXPO); - return true; + case OSD_THROTTLE_EXPO: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "TEX", 0, currentControlRateProfile->throttle.rcExpo8, 3, 0, ADJUSTMENT_THROTTLE_EXPO); + return true; - case OSD_PITCH_RATE: - displayWrite(osdDisplayPort, elemPosX, elemPosY, "SPR"); + case OSD_PITCH_RATE: + displayWrite(osdDisplayPort, elemPosX, elemPosY, "SPR"); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", currentControlRateProfile->stabilized.rates[FD_PITCH]); - if (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_RATE)) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); - return true; + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", currentControlRateProfile->stabilized.rates[FD_PITCH]); + if (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_RATE)) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); + return true; - case OSD_ROLL_RATE: - displayWrite(osdDisplayPort, elemPosX, elemPosY, "SRR"); + case OSD_ROLL_RATE: + displayWrite(osdDisplayPort, elemPosX, elemPosY, "SRR"); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", currentControlRateProfile->stabilized.rates[FD_ROLL]); - if (isAdjustmentFunctionSelected(ADJUSTMENT_ROLL_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_RATE)) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); - return true; + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", currentControlRateProfile->stabilized.rates[FD_ROLL]); + if (isAdjustmentFunctionSelected(ADJUSTMENT_ROLL_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_RATE)) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); + return true; - case OSD_YAW_RATE: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "SYR", 0, currentControlRateProfile->stabilized.rates[FD_YAW], 3, 0, ADJUSTMENT_YAW_RATE); - return true; + case OSD_YAW_RATE: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "SYR", 0, currentControlRateProfile->stabilized.rates[FD_YAW], 3, 0, ADJUSTMENT_YAW_RATE); + return true; - case OSD_MANUAL_RC_EXPO: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "MEX", 0, currentControlRateProfile->manual.rcExpo8, 3, 0, ADJUSTMENT_MANUAL_RC_EXPO); - return true; + case OSD_MANUAL_RC_EXPO: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "MEX", 0, currentControlRateProfile->manual.rcExpo8, 3, 0, ADJUSTMENT_MANUAL_RC_EXPO); + return true; - case OSD_MANUAL_RC_YAW_EXPO: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "MYX", 0, currentControlRateProfile->manual.rcYawExpo8, 3, 0, ADJUSTMENT_MANUAL_RC_YAW_EXPO); - return true; + case OSD_MANUAL_RC_YAW_EXPO: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "MYX", 0, currentControlRateProfile->manual.rcYawExpo8, 3, 0, ADJUSTMENT_MANUAL_RC_YAW_EXPO); + return true; - case OSD_MANUAL_PITCH_RATE: - displayWrite(osdDisplayPort, elemPosX, elemPosY, "MPR"); + case OSD_MANUAL_PITCH_RATE: + displayWrite(osdDisplayPort, elemPosX, elemPosY, "MPR"); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", currentControlRateProfile->manual.rates[FD_PITCH]); - if (isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_PITCH_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_PITCH_ROLL_RATE)) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); - return true; + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", currentControlRateProfile->manual.rates[FD_PITCH]); + if (isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_PITCH_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_PITCH_ROLL_RATE)) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); + return true; - case OSD_MANUAL_ROLL_RATE: - displayWrite(osdDisplayPort, elemPosX, elemPosY, "MRR"); + case OSD_MANUAL_ROLL_RATE: + displayWrite(osdDisplayPort, elemPosX, elemPosY, "MRR"); - elemAttr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", currentControlRateProfile->manual.rates[FD_ROLL]); - if (isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_ROLL_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_PITCH_ROLL_RATE)) - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); - return true; + elemAttr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", currentControlRateProfile->manual.rates[FD_ROLL]); + if (isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_ROLL_RATE) || isAdjustmentFunctionSelected(ADJUSTMENT_MANUAL_PITCH_ROLL_RATE)) + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY, buff, elemAttr); + return true; - case OSD_MANUAL_YAW_RATE: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "MYR", 0, currentControlRateProfile->stabilized.rates[FD_YAW], 3, 0, ADJUSTMENT_YAW_RATE); - return true; + case OSD_MANUAL_YAW_RATE: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "MYR", 0, currentControlRateProfile->stabilized.rates[FD_YAW], 3, 0, ADJUSTMENT_YAW_RATE); + return true; - case OSD_NAV_FW_CRUISE_THR: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CRZ", 0, currentBatteryProfile->nav.fw.cruise_throttle, 4, 0, ADJUSTMENT_NAV_FW_CRUISE_THR); - return true; + case OSD_NAV_FW_CRUISE_THR: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CRZ", 0, currentBatteryProfile->nav.fw.cruise_throttle, 4, 0, ADJUSTMENT_NAV_FW_CRUISE_THR); + return true; - case OSD_NAV_FW_PITCH2THR: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "P2T", 0, currentBatteryProfile->nav.fw.pitch_to_throttle, 3, 0, ADJUSTMENT_NAV_FW_PITCH2THR); - return true; + case OSD_NAV_FW_PITCH2THR: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "P2T", 0, currentBatteryProfile->nav.fw.pitch_to_throttle, 3, 0, ADJUSTMENT_NAV_FW_PITCH2THR); + return true; - case OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "0TP", 0, (float)navConfig()->fw.minThrottleDownPitchAngle / 10, 3, 1, ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE); - return true; + case OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE: + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "0TP", 0, (float)navConfig()->fw.minThrottleDownPitchAngle / 10, 3, 1, ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE); + return true; - case OSD_FW_ALT_PID_OUTPUTS: - { - const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); - osdFormatPidControllerOutput(buff, "PZO", &nav_pids->fw_alt, 10, true); // display requested pitch degrees - break; - } + case OSD_FW_ALT_PID_OUTPUTS: + { + const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); + osdFormatPidControllerOutput(buff, "PZO", &nav_pids->fw_alt, 10, true); // display requested pitch degrees + break; + } - case OSD_FW_POS_PID_OUTPUTS: - { - const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); // display requested roll degrees - osdFormatPidControllerOutput(buff, "PXYO", &nav_pids->fw_nav, 1, true); - break; - } + case OSD_FW_POS_PID_OUTPUTS: + { + const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); // display requested roll degrees + osdFormatPidControllerOutput(buff, "PXYO", &nav_pids->fw_nav, 1, true); + break; + } - case OSD_MC_VEL_Z_PID_OUTPUTS: - { - const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); - osdFormatPidControllerOutput(buff, "VZO", &nav_pids->vel[Z], 100, false); // display throttle adjustment µs - break; - } + case OSD_MC_VEL_Z_PID_OUTPUTS: + { + const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); + osdFormatPidControllerOutput(buff, "VZO", &nav_pids->vel[Z], 100, false); // display throttle adjustment µs + break; + } - case OSD_MC_VEL_X_PID_OUTPUTS: - { - const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); - osdFormatPidControllerOutput(buff, "VXO", &nav_pids->vel[X], 100, false); // display requested acceleration cm/s^2 - break; - } + case OSD_MC_VEL_X_PID_OUTPUTS: + { + const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); + osdFormatPidControllerOutput(buff, "VXO", &nav_pids->vel[X], 100, false); // display requested acceleration cm/s^2 + break; + } - case OSD_MC_VEL_Y_PID_OUTPUTS: - { - const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); - osdFormatPidControllerOutput(buff, "VYO", &nav_pids->vel[Y], 100, false); // display requested acceleration cm/s^2 - break; - } + case OSD_MC_VEL_Y_PID_OUTPUTS: + { + const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); + osdFormatPidControllerOutput(buff, "VYO", &nav_pids->vel[Y], 100, false); // display requested acceleration cm/s^2 + break; + } - case OSD_MC_POS_XYZ_P_OUTPUTS: - { - const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); - strcpy(buff, "POSO "); - // display requested velocity cm/s - tfp_sprintf(buff + 5, "%4d", (int)lrintf(nav_pids->pos[X].output_constrained * 100)); - buff[9] = ' '; - tfp_sprintf(buff + 10, "%4d", (int)lrintf(nav_pids->pos[Y].output_constrained * 100)); - buff[14] = ' '; - tfp_sprintf(buff + 15, "%4d", (int)lrintf(nav_pids->pos[Z].output_constrained * 100)); - buff[19] = '\0'; - break; - } + case OSD_MC_POS_XYZ_P_OUTPUTS: + { + const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); + strcpy(buff, "POSO "); + // display requested velocity cm/s + tfp_sprintf(buff + 5, "%4d", (int)lrintf(nav_pids->pos[X].output_constrained * 100)); + buff[9] = ' '; + tfp_sprintf(buff + 10, "%4d", (int)lrintf(nav_pids->pos[Y].output_constrained * 100)); + buff[14] = ' '; + tfp_sprintf(buff + 15, "%4d", (int)lrintf(nav_pids->pos[Z].output_constrained * 100)); + buff[19] = '\0'; + break; + } - case OSD_POWER: - { - bool kiloWatt = osdFormatCentiNumber(buff, getPower(), 1000, 2, 2, 3); - buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; - buff[4] = '\0'; + case OSD_POWER: + { + bool kiloWatt = osdFormatCentiNumber(buff, getPower(), 1000, 2, 2, 3); + buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; + buff[4] = '\0'; - uint8_t current_alarm = osdConfig()->current_alarm; - if ((current_alarm > 0) && ((getAmperage() / 100.0f) > current_alarm)) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } + uint8_t current_alarm = osdConfig()->current_alarm; + if ((current_alarm > 0) && ((getAmperage() / 100.0f) > current_alarm)) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } - case OSD_AIR_SPEED: - { - #ifdef USE_PITOT - buff[0] = SYM_AIR; + case OSD_AIR_SPEED: + { + #ifdef USE_PITOT + buff[0] = SYM_AIR; - if (pitotIsHealthy()) - { - const float airspeed_estimate = getAirspeedEstimate(); - osdFormatVelocityStr(buff + 1, airspeed_estimate, false, false); - if ((osdConfig()->airspeed_alarm_min != 0 && airspeed_estimate < osdConfig()->airspeed_alarm_min) || - (osdConfig()->airspeed_alarm_max != 0 && airspeed_estimate > osdConfig()->airspeed_alarm_max)) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } - else - { - strcpy(buff + 1, " X!"); - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - #else - return false; - #endif - break; - } + if (pitotIsHealthy()) + { + const float airspeed_estimate = getAirspeedEstimate(); + osdFormatVelocityStr(buff + 1, airspeed_estimate, false, false); + if ((osdConfig()->airspeed_alarm_min != 0 && airspeed_estimate < osdConfig()->airspeed_alarm_min) || + (osdConfig()->airspeed_alarm_max != 0 && airspeed_estimate > osdConfig()->airspeed_alarm_max)) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + else + { + strcpy(buff + 1, " X!"); + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + #else + return false; + #endif + break; + } - case OSD_AIR_MAX_SPEED: - { - #ifdef USE_PITOT - buff[0] = SYM_MAX; - buff[1] = SYM_AIR; - osdFormatVelocityStr(buff + 2, stats.max_air_speed, false, false); - #else - return false; - #endif - break; - } + case OSD_AIR_MAX_SPEED: + { + #ifdef USE_PITOT + buff[0] = SYM_MAX; + buff[1] = SYM_AIR; + osdFormatVelocityStr(buff + 2, stats.max_air_speed, false, false); + #else + return false; + #endif + break; + } - case OSD_RTC_TIME: - { - // RTC not configured will show 00:00 - dateTime_t dateTime; - rtcGetDateTimeLocal(&dateTime); - buff[0] = SYM_CLOCK; - tfp_sprintf(buff + 1, "%02u:%02u:%02u", dateTime.hours, dateTime.minutes, dateTime.seconds); - break; - } + case OSD_RTC_TIME: + { + // RTC not configured will show 00:00 + dateTime_t dateTime; + rtcGetDateTimeLocal(&dateTime); + buff[0] = SYM_CLOCK; + tfp_sprintf(buff + 1, "%02u:%02u:%02u", dateTime.hours, dateTime.minutes, dateTime.seconds); + break; + } - case OSD_MESSAGES: - { - elemAttr = osdGetSystemMessage(buff, OSD_MESSAGE_LENGTH, true); - break; - } + case OSD_MESSAGES: + { + elemAttr = osdGetSystemMessage(buff, OSD_MESSAGE_LENGTH, true); + break; + } - case OSD_VERSION: - { - tfp_sprintf(buff, "INAV %s", FC_VERSION_STRING); - displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); - break; - } + case OSD_VERSION: + { + tfp_sprintf(buff, "INAV %s", FC_VERSION_STRING); + displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); + break; + } - case OSD_MAIN_BATT_CELL_VOLTAGE: - { - uint8_t base_digits = 3U; + case OSD_MAIN_BATT_CELL_VOLTAGE: + { + uint8_t base_digits = 3U; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if(isBfCompatibleVideoSystem(osdConfig())) { - base_digits = 4U; // Add extra digit to account for decimal point taking an extra character space - } + if(isBfCompatibleVideoSystem(osdConfig())) { + base_digits = 4U; // Add extra digit to account for decimal point taking an extra character space + } #endif - osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawAverageCellVoltage(), base_digits, 2); - return true; - } + osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatteryRawAverageCellVoltage(), base_digits, 2); + return true; + } - case OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE: - { - uint8_t base_digits = 3U; + case OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE: + { + uint8_t base_digits = 3U; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it - if(isBfCompatibleVideoSystem(osdConfig())) { - base_digits = 4U; // Add extra digit to account for decimal point taking an extra character space - } + if(isBfCompatibleVideoSystem(osdConfig())) { + base_digits = 4U; // Add extra digit to account for decimal point taking an extra character space + } #endif - osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedAverageCellVoltage(), base_digits, 2); - return true; - } + osdDisplayBatteryVoltage(elemPosX, elemPosY, getBatterySagCompensatedAverageCellVoltage(), base_digits, 2); + return true; + } - case OSD_SCALED_THROTTLE_POS: - { - osdFormatThrottlePosition(buff, true, &elemAttr); - break; - } + case OSD_SCALED_THROTTLE_POS: + { + osdFormatThrottlePosition(buff, true, &elemAttr); + break; + } - case OSD_HEADING: - { - buff[0] = SYM_HEADING; - if (osdIsHeadingValid()) { - int16_t h = DECIDEGREES_TO_DEGREES(osdGetHeading()); - if (h < 0) { - h += 360; - } - tfp_sprintf(&buff[1], "%3d", h); - } else { - buff[1] = buff[2] = buff[3] = '-'; - } - buff[4] = SYM_DEGREES; - buff[5] = '\0'; - break; - } + case OSD_HEADING: + { + buff[0] = SYM_HEADING; + if (osdIsHeadingValid()) { + int16_t h = DECIDEGREES_TO_DEGREES(osdGetHeading()); + if (h < 0) { + h += 360; + } + tfp_sprintf(&buff[1], "%3d", h); + } else { + buff[1] = buff[2] = buff[3] = '-'; + } + buff[4] = SYM_DEGREES; + buff[5] = '\0'; + break; + } - case OSD_HEADING_GRAPH: - { - if (osdIsHeadingValid()) { - osdDrawHeadingGraph(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), osdGetHeading()); - return true; - } else { - buff[0] = buff[2] = buff[4] = buff[6] = buff[8] = SYM_HEADING_LINE; - buff[1] = buff[3] = buff[5] = buff[7] = SYM_HEADING_DIVIDED_LINE; - buff[OSD_HEADING_GRAPH_WIDTH] = '\0'; - } - break; - } + case OSD_HEADING_GRAPH: + { + if (osdIsHeadingValid()) { + osdDrawHeadingGraph(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), osdGetHeading()); + return true; + } else { + buff[0] = buff[2] = buff[4] = buff[6] = buff[8] = SYM_HEADING_LINE; + buff[1] = buff[3] = buff[5] = buff[7] = SYM_HEADING_DIVIDED_LINE; + buff[OSD_HEADING_GRAPH_WIDTH] = '\0'; + } + break; + } - case OSD_EFFICIENCY_MAH_PER_KM: - { - // amperage is in centi amps, speed is in cms/s. We want - // mah/km. Only show when ground speed > 1m/s. - static pt1Filter_t eFilterState; - static timeUs_t efficiencyUpdated = 0; - int32_t value = 0; - bool moreThanAh = false; - timeUs_t currentTimeUs = micros(); - timeDelta_t efficiencyTimeDelta = cmpTimeUs(currentTimeUs, efficiencyUpdated); - uint8_t digits = 3U; + case OSD_EFFICIENCY_MAH_PER_KM: + { + // amperage is in centi amps, speed is in cms/s. We want + // mah/km. Only show when ground speed > 1m/s. + static pt1Filter_t eFilterState; + static timeUs_t efficiencyUpdated = 0; + int32_t value = 0; + bool moreThanAh = false; + timeUs_t currentTimeUs = micros(); + timeDelta_t efficiencyTimeDelta = cmpTimeUs(currentTimeUs, efficiencyUpdated); + uint8_t digits = 3U; #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values - if (isBfCompatibleVideoSystem(osdConfig())) { - // Increase number of digits so values above 99 don't get scaled by osdFormatCentiNumber - digits = 4U; - } + if (isBfCompatibleVideoSystem(osdConfig())) { + // Increase number of digits so values above 99 don't get scaled by osdFormatCentiNumber + digits = 4U; + } #endif - if (STATE(GPS_FIX) && gpsSol.groundSpeed > 0) { - if (efficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { - value = pt1FilterApply4(&eFilterState, ((float)getAmperage() / gpsSol.groundSpeed) / 0.0036f, - 1, US2S(efficiencyTimeDelta)); + if (STATE(GPS_FIX) && gpsSol.groundSpeed > 0) { + if (efficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { + value = pt1FilterApply4(&eFilterState, ((float)getAmperage() / gpsSol.groundSpeed) / 0.0036f, + 1, US2S(efficiencyTimeDelta)); - efficiencyUpdated = currentTimeUs; - } else { - value = eFilterState.state; - } - } - bool efficiencyValid = (value > 0) && (gpsSol.groundSpeed > 100); - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10, 1000, 0, 2, digits); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_MI); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = buff[3] = '-'; - buff[digits] = SYM_MAH_MI_0; // This will overwrite the "-" at buff[3] if not in BFCOMPAT mode - buff[digits + 1] = SYM_MAH_MI_1; - buff[digits + 2] = '\0'; - } - break; - case OSD_UNIT_GA: - moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10, 1000, 0, 2, digits); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = buff[3] = '-'; - buff[digits] = SYM_MAH_NM_0; - buff[digits + 1] = SYM_MAH_NM_1; - buff[digits + 2] = '\0'; - } - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - moreThanAh = osdFormatCentiNumber(buff, value * 100, 1000, 0, 2, digits); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_KM); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = buff[3] = '-'; - buff[digits] = SYM_MAH_KM_0; - buff[digits + 1] = SYM_MAH_KM_1; - buff[digits + 2] = '\0'; - } - break; - } - break; - } + efficiencyUpdated = currentTimeUs; + } else { + value = eFilterState.state; + } + } + bool efficiencyValid = (value > 0) && (gpsSol.groundSpeed > 100); + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10, 1000, 0, 2, digits); + if (!moreThanAh) { + tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); + } else { + tfp_sprintf(buff, "%s%c", buff, SYM_AH_MI); + } + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = buff[3] = '-'; + buff[digits] = SYM_MAH_MI_0; // This will overwrite the "-" at buff[3] if not in BFCOMPAT mode + buff[digits + 1] = SYM_MAH_MI_1; + buff[digits + 2] = '\0'; + } + break; + case OSD_UNIT_GA: + moreThanAh = osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10, 1000, 0, 2, digits); + if (!moreThanAh) { + tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); + } else { + tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM); + } + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = buff[3] = '-'; + buff[digits] = SYM_MAH_NM_0; + buff[digits + 1] = SYM_MAH_NM_1; + buff[digits + 2] = '\0'; + } + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + moreThanAh = osdFormatCentiNumber(buff, value * 100, 1000, 0, 2, digits); + if (!moreThanAh) { + tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); + } else { + tfp_sprintf(buff, "%s%c", buff, SYM_AH_KM); + } + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = buff[3] = '-'; + buff[digits] = SYM_MAH_KM_0; + buff[digits + 1] = SYM_MAH_KM_1; + buff[digits + 2] = '\0'; + } + break; + } + break; + } - case OSD_EFFICIENCY_WH_PER_KM: - { - // amperage is in centi amps, speed is in cms/s. We want - // mWh/km. Only show when ground speed > 1m/s. - static pt1Filter_t eFilterState; - static timeUs_t efficiencyUpdated = 0; - int32_t value = 0; - timeUs_t currentTimeUs = micros(); - timeDelta_t efficiencyTimeDelta = cmpTimeUs(currentTimeUs, efficiencyUpdated); - if (STATE(GPS_FIX) && gpsSol.groundSpeed > 0) { - if (efficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { - value = pt1FilterApply4(&eFilterState, ((float)getPower() / gpsSol.groundSpeed) / 0.0036f, - 1, US2S(efficiencyTimeDelta)); + case OSD_EFFICIENCY_WH_PER_KM: + { + // amperage is in centi amps, speed is in cms/s. We want + // mWh/km. Only show when ground speed > 1m/s. + static pt1Filter_t eFilterState; + static timeUs_t efficiencyUpdated = 0; + int32_t value = 0; + timeUs_t currentTimeUs = micros(); + timeDelta_t efficiencyTimeDelta = cmpTimeUs(currentTimeUs, efficiencyUpdated); + if (STATE(GPS_FIX) && gpsSol.groundSpeed > 0) { + if (efficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) { + value = pt1FilterApply4(&eFilterState, ((float)getPower() / gpsSol.groundSpeed) / 0.0036f, + 1, US2S(efficiencyTimeDelta)); - efficiencyUpdated = currentTimeUs; - } else { - value = eFilterState.state; - } - } - bool efficiencyValid = (value > 0) && (gpsSol.groundSpeed > 100); - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10000, 0, 2, 0, 3); - buff[3] = SYM_WH_MI; - break; - case OSD_UNIT_GA: - osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10000, 0, 2, 0, 3); - buff[3] = SYM_WH_NM; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - osdFormatCentiNumber(buff, value / 10, 0, 2, 0, 3); - buff[3] = SYM_WH_KM; - break; - } - buff[4] = '\0'; - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - } - break; - } + efficiencyUpdated = currentTimeUs; + } else { + value = eFilterState.state; + } + } + bool efficiencyValid = (value > 0) && (gpsSol.groundSpeed > 100); + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + osdFormatCentiNumber(buff, value * METERS_PER_MILE / 10000, 0, 2, 0, 3); + buff[3] = SYM_WH_MI; + break; + case OSD_UNIT_GA: + osdFormatCentiNumber(buff, value * METERS_PER_NAUTICALMILE / 10000, 0, 2, 0, 3); + buff[3] = SYM_WH_NM; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + osdFormatCentiNumber(buff, value / 10, 0, 2, 0, 3); + buff[3] = SYM_WH_KM; + break; + } + buff[4] = '\0'; + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + } + break; + } - case OSD_GFORCE: - { - buff[0] = SYM_GFORCE; - osdFormatCentiNumber(buff + 1, GForce, 0, 2, 0, 3); - if (GForce > osdConfig()->gforce_alarm * 100) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } + case OSD_GFORCE: + { + buff[0] = SYM_GFORCE; + osdFormatCentiNumber(buff + 1, GForce, 0, 2, 0, 3); + if (GForce > osdConfig()->gforce_alarm * 100) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } - case OSD_GFORCE_X: - case OSD_GFORCE_Y: - case OSD_GFORCE_Z: - { - float GForceValue = GForceAxis[item - OSD_GFORCE_X]; - buff[0] = SYM_GFORCE_X + item - OSD_GFORCE_X; - osdFormatCentiNumber(buff + 1, GForceValue, 0, 2, 0, 4); - if ((GForceValue < osdConfig()->gforce_axis_alarm_min * 100) || (GForceValue > osdConfig()->gforce_axis_alarm_max * 100)) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - break; - } - case OSD_DEBUG: - { - /* - * Longest representable string is -2147483648 does not fit in the screen. - * Only 7 digits for negative and 8 digits for positive values allowed - */ - for (uint8_t bufferIndex = 0; bufferIndex < DEBUG32_VALUE_COUNT; ++elemPosY, bufferIndex += 2) { - tfp_sprintf( - buff, - "[%u]=%8ld [%u]=%8ld", - bufferIndex, - (long)constrain(debug[bufferIndex], -9999999, 99999999), - bufferIndex+1, - (long)constrain(debug[bufferIndex+1], -9999999, 99999999) - ); - displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); - } - break; - } + case OSD_GFORCE_X: + case OSD_GFORCE_Y: + case OSD_GFORCE_Z: + { + float GForceValue = GForceAxis[item - OSD_GFORCE_X]; + buff[0] = SYM_GFORCE_X + item - OSD_GFORCE_X; + osdFormatCentiNumber(buff + 1, GForceValue, 0, 2, 0, 4); + if ((GForceValue < osdConfig()->gforce_axis_alarm_min * 100) || (GForceValue > osdConfig()->gforce_axis_alarm_max * 100)) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + break; + } + case OSD_DEBUG: + { + /* + * Longest representable string is -2147483648 does not fit in the screen. + * Only 7 digits for negative and 8 digits for positive values allowed + */ + for (uint8_t bufferIndex = 0; bufferIndex < DEBUG32_VALUE_COUNT; ++elemPosY, bufferIndex += 2) { + tfp_sprintf( + buff, + "[%u]=%8ld [%u]=%8ld", + bufferIndex, + (long)constrain(debug[bufferIndex], -9999999, 99999999), + bufferIndex+1, + (long)constrain(debug[bufferIndex+1], -9999999, 99999999) + ); + displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); + } + break; + } - case OSD_IMU_TEMPERATURE: - { - int16_t temperature; - const bool valid = getIMUTemperature(&temperature); - osdDisplayTemperature(elemPosX, elemPosY, SYM_IMU_TEMP, NULL, valid, temperature, osdConfig()->imu_temp_alarm_min, osdConfig()->imu_temp_alarm_max); - return true; - } + case OSD_IMU_TEMPERATURE: + { + int16_t temperature; + const bool valid = getIMUTemperature(&temperature); + osdDisplayTemperature(elemPosX, elemPosY, SYM_IMU_TEMP, NULL, valid, temperature, osdConfig()->imu_temp_alarm_min, osdConfig()->imu_temp_alarm_max); + return true; + } - case OSD_BARO_TEMPERATURE: - { - int16_t temperature; - const bool valid = getBaroTemperature(&temperature); - osdDisplayTemperature(elemPosX, elemPosY, SYM_BARO_TEMP, NULL, valid, temperature, osdConfig()->imu_temp_alarm_min, osdConfig()->imu_temp_alarm_max); - return true; - } + case OSD_BARO_TEMPERATURE: + { + int16_t temperature; + const bool valid = getBaroTemperature(&temperature); + osdDisplayTemperature(elemPosX, elemPosY, SYM_BARO_TEMP, NULL, valid, temperature, osdConfig()->imu_temp_alarm_min, osdConfig()->imu_temp_alarm_max); + return true; + } #ifdef USE_TEMPERATURE_SENSOR - case OSD_TEMP_SENSOR_0_TEMPERATURE: - case OSD_TEMP_SENSOR_1_TEMPERATURE: - case OSD_TEMP_SENSOR_2_TEMPERATURE: - case OSD_TEMP_SENSOR_3_TEMPERATURE: - case OSD_TEMP_SENSOR_4_TEMPERATURE: - case OSD_TEMP_SENSOR_5_TEMPERATURE: - case OSD_TEMP_SENSOR_6_TEMPERATURE: - case OSD_TEMP_SENSOR_7_TEMPERATURE: - { - osdDisplayTemperatureSensor(elemPosX, elemPosY, item - OSD_TEMP_SENSOR_0_TEMPERATURE); - return true; - } + case OSD_TEMP_SENSOR_0_TEMPERATURE: + case OSD_TEMP_SENSOR_1_TEMPERATURE: + case OSD_TEMP_SENSOR_2_TEMPERATURE: + case OSD_TEMP_SENSOR_3_TEMPERATURE: + case OSD_TEMP_SENSOR_4_TEMPERATURE: + case OSD_TEMP_SENSOR_5_TEMPERATURE: + case OSD_TEMP_SENSOR_6_TEMPERATURE: + case OSD_TEMP_SENSOR_7_TEMPERATURE: + { + osdDisplayTemperatureSensor(elemPosX, elemPosY, item - OSD_TEMP_SENSOR_0_TEMPERATURE); + return true; + } #endif /* ifdef USE_TEMPERATURE_SENSOR */ - case OSD_WIND_SPEED_HORIZONTAL: + case OSD_WIND_SPEED_HORIZONTAL: #ifdef USE_WIND_ESTIMATOR - { - bool valid = isEstimatedWindSpeedValid(); - float horizontalWindSpeed; - uint16_t angle; - horizontalWindSpeed = getEstimatedHorizontalWindSpeed(&angle); - int16_t windDirection = osdGetHeadingAngle( CENTIDEGREES_TO_DEGREES((int)angle) - DECIDEGREES_TO_DEGREES(attitude.values.yaw) + 22); - buff[0] = SYM_WIND_HORIZONTAL; - buff[1] = SYM_DIRECTION + (windDirection*2 / 90); - osdFormatWindSpeedStr(buff + 2, horizontalWindSpeed, valid); - break; - } + { + bool valid = isEstimatedWindSpeedValid(); + float horizontalWindSpeed; + uint16_t angle; + horizontalWindSpeed = getEstimatedHorizontalWindSpeed(&angle); + int16_t windDirection = osdGetHeadingAngle( CENTIDEGREES_TO_DEGREES((int)angle) - DECIDEGREES_TO_DEGREES(attitude.values.yaw) + 22); + buff[0] = SYM_WIND_HORIZONTAL; + buff[1] = SYM_DIRECTION + (windDirection*2 / 90); + osdFormatWindSpeedStr(buff + 2, horizontalWindSpeed, valid); + break; + } #else - return false; + return false; #endif - case OSD_WIND_SPEED_VERTICAL: + case OSD_WIND_SPEED_VERTICAL: #ifdef USE_WIND_ESTIMATOR - { - buff[0] = SYM_WIND_VERTICAL; - buff[1] = SYM_BLANK; - bool valid = isEstimatedWindSpeedValid(); - float verticalWindSpeed; - verticalWindSpeed = -getEstimatedWindSpeed(Z); //from NED to NEU - if (verticalWindSpeed < 0) { - buff[1] = SYM_AH_DIRECTION_DOWN; - verticalWindSpeed = -verticalWindSpeed; - } else { - buff[1] = SYM_AH_DIRECTION_UP; - } - osdFormatWindSpeedStr(buff + 2, verticalWindSpeed, valid); - break; - } + { + buff[0] = SYM_WIND_VERTICAL; + buff[1] = SYM_BLANK; + bool valid = isEstimatedWindSpeedValid(); + float verticalWindSpeed; + verticalWindSpeed = -getEstimatedWindSpeed(Z); //from NED to NEU + if (verticalWindSpeed < 0) { + buff[1] = SYM_AH_DIRECTION_DOWN; + verticalWindSpeed = -verticalWindSpeed; + } else { + buff[1] = SYM_AH_DIRECTION_UP; + } + osdFormatWindSpeedStr(buff + 2, verticalWindSpeed, valid); + break; + } #else - return false; + return false; #endif - case OSD_PLUS_CODE: - { - STATIC_ASSERT(GPS_DEGREES_DIVIDER == OLC_DEG_MULTIPLIER, invalid_olc_deg_multiplier); - int digits = osdConfig()->plus_code_digits; - int digitsRemoved = osdConfig()->plus_code_short * 2; - if (STATE(GPS_FIX)) { - olc_encode(gpsSol.llh.lat, gpsSol.llh.lon, digits, buff, sizeof(buff)); - } else { - // +codes with > 8 digits have a + at the 9th digit - // and we only support 10 and up. - memset(buff, '-', digits + 1); - buff[8] = '+'; - buff[digits + 1] = '\0'; - } - // Optionally trim digits from the left - memmove(buff, buff+digitsRemoved, strlen(buff) + digitsRemoved); - buff[digits + 1 - digitsRemoved] = '\0'; - break; - } + case OSD_PLUS_CODE: + { + STATIC_ASSERT(GPS_DEGREES_DIVIDER == OLC_DEG_MULTIPLIER, invalid_olc_deg_multiplier); + int digits = osdConfig()->plus_code_digits; + int digitsRemoved = osdConfig()->plus_code_short * 2; + if (STATE(GPS_FIX)) { + olc_encode(gpsSol.llh.lat, gpsSol.llh.lon, digits, buff, sizeof(buff)); + } else { + // +codes with > 8 digits have a + at the 9th digit + // and we only support 10 and up. + memset(buff, '-', digits + 1); + buff[8] = '+'; + buff[digits + 1] = '\0'; + } + // Optionally trim digits from the left + memmove(buff, buff+digitsRemoved, strlen(buff) + digitsRemoved); + buff[digits + 1 - digitsRemoved] = '\0'; + break; + } - case OSD_AZIMUTH: - { + case OSD_AZIMUTH: + { - buff[0] = SYM_AZIMUTH; - if (osdIsHeadingValid()) { - int16_t h = GPS_directionToHome; - if (h < 0) { - h += 360; - } - if (h >= 180) - h = h - 180; - else - h = h + 180; + buff[0] = SYM_AZIMUTH; + if (osdIsHeadingValid()) { + int16_t h = GPS_directionToHome; + if (h < 0) { + h += 360; + } + if (h >= 180) + h = h - 180; + else + h = h + 180; - tfp_sprintf(&buff[1], "%3d", h); - } else { - buff[1] = buff[2] = buff[3] = '-'; - } - buff[4] = SYM_DEGREES; - buff[5] = '\0'; - break; - } + tfp_sprintf(&buff[1], "%3d", h); + } else { + buff[1] = buff[2] = buff[3] = '-'; + } + buff[4] = SYM_DEGREES; + buff[5] = '\0'; + break; + } - case OSD_MAP_SCALE: - { - float scaleToUnit; - int scaleUnitDivisor; - char symUnscaled; - char symScaled; - int maxDecimals; + case OSD_MAP_SCALE: + { + float scaleToUnit; + int scaleUnitDivisor; + char symUnscaled; + char symScaled; + int maxDecimals; - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - scaleToUnit = 100 / 1609.3440f; // scale to 0.01mi for osdFormatCentiNumber() - scaleUnitDivisor = 0; - symUnscaled = SYM_MI; - symScaled = SYM_MI; - maxDecimals = 2; - break; - case OSD_UNIT_GA: - scaleToUnit = 100 / 1852.0010f; // scale to 0.01mi for osdFormatCentiNumber() - scaleUnitDivisor = 0; - symUnscaled = SYM_NM; - symScaled = SYM_NM; - maxDecimals = 2; - break; - default: - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - scaleToUnit = 100; // scale to cm for osdFormatCentiNumber() - scaleUnitDivisor = 1000; // Convert to km when scale gets bigger than 999m - symUnscaled = SYM_M; - symScaled = SYM_KM; - maxDecimals = 0; - break; - } - buff[0] = SYM_SCALE; - if (osdMapData.scale > 0) { - bool scaled = osdFormatCentiNumber(&buff[1], osdMapData.scale * scaleToUnit, scaleUnitDivisor, maxDecimals, 2, 3); - buff[4] = scaled ? symScaled : symUnscaled; - // Make sure this is cleared if the map stops being drawn - osdMapData.scale = 0; - } else { - memset(&buff[1], '-', 4); - } - buff[5] = '\0'; - break; - } - case OSD_MAP_REFERENCE: - { - char referenceSymbol; - if (osdMapData.referenceSymbol) { - referenceSymbol = osdMapData.referenceSymbol; - // Make sure this is cleared if the map stops being drawn - osdMapData.referenceSymbol = 0; - } else { - referenceSymbol = '-'; - } - displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_DIRECTION); - displayWriteChar(osdDisplayPort, elemPosX, elemPosY + 1, referenceSymbol); - return true; - } + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + scaleToUnit = 100 / 1609.3440f; // scale to 0.01mi for osdFormatCentiNumber() + scaleUnitDivisor = 0; + symUnscaled = SYM_MI; + symScaled = SYM_MI; + maxDecimals = 2; + break; + case OSD_UNIT_GA: + scaleToUnit = 100 / 1852.0010f; // scale to 0.01mi for osdFormatCentiNumber() + scaleUnitDivisor = 0; + symUnscaled = SYM_NM; + symScaled = SYM_NM; + maxDecimals = 2; + break; + default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + scaleToUnit = 100; // scale to cm for osdFormatCentiNumber() + scaleUnitDivisor = 1000; // Convert to km when scale gets bigger than 999m + symUnscaled = SYM_M; + symScaled = SYM_KM; + maxDecimals = 0; + break; + } + buff[0] = SYM_SCALE; + if (osdMapData.scale > 0) { + bool scaled = osdFormatCentiNumber(&buff[1], osdMapData.scale * scaleToUnit, scaleUnitDivisor, maxDecimals, 2, 3); + buff[4] = scaled ? symScaled : symUnscaled; + // Make sure this is cleared if the map stops being drawn + osdMapData.scale = 0; + } else { + memset(&buff[1], '-', 4); + } + buff[5] = '\0'; + break; + } + case OSD_MAP_REFERENCE: + { + char referenceSymbol; + if (osdMapData.referenceSymbol) { + referenceSymbol = osdMapData.referenceSymbol; + // Make sure this is cleared if the map stops being drawn + osdMapData.referenceSymbol = 0; + } else { + referenceSymbol = '-'; + } + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_DIRECTION); + displayWriteChar(osdDisplayPort, elemPosX, elemPosY + 1, referenceSymbol); + return true; + } - case OSD_GVAR_0: - { - osdFormatGVar(buff, 0); - break; - } - case OSD_GVAR_1: - { - osdFormatGVar(buff, 1); - break; - } - case OSD_GVAR_2: - { - osdFormatGVar(buff, 2); - break; - } - case OSD_GVAR_3: - { - osdFormatGVar(buff, 3); - break; - } + case OSD_GVAR_0: + { + osdFormatGVar(buff, 0); + break; + } + case OSD_GVAR_1: + { + osdFormatGVar(buff, 1); + break; + } + case OSD_GVAR_2: + { + osdFormatGVar(buff, 2); + break; + } + case OSD_GVAR_3: + { + osdFormatGVar(buff, 3); + break; + } #if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE) - case OSD_RC_SOURCE: - { - const char *source_text = IS_RC_MODE_ACTIVE(BOXMSPRCOVERRIDE) && !mspOverrideIsInFailsafe() ? "MSP" : "STD"; - if (IS_RC_MODE_ACTIVE(BOXMSPRCOVERRIDE) && mspOverrideIsInFailsafe()) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, source_text, elemAttr); - return true; - } + case OSD_RC_SOURCE: + { + const char *source_text = IS_RC_MODE_ACTIVE(BOXMSPRCOVERRIDE) && !mspOverrideIsInFailsafe() ? "MSP" : "STD"; + if (IS_RC_MODE_ACTIVE(BOXMSPRCOVERRIDE) && mspOverrideIsInFailsafe()) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, source_text, elemAttr); + return true; + } #endif #if defined(USE_ESC_SENSOR) - case OSD_ESC_RPM: - { - escSensorData_t * escSensor = escSensorGetData(); - if (escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE) { - osdFormatRpm(buff, escSensor->rpm); - } - else { - osdFormatRpm(buff, 0); - } - break; - } - case OSD_ESC_TEMPERATURE: - { - escSensorData_t * escSensor = escSensorGetData(); - bool escTemperatureValid = escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE; - osdDisplayTemperature(elemPosX, elemPosY, SYM_ESC_TEMP, NULL, escTemperatureValid, (escSensor->temperature)*10, osdConfig()->esc_temp_alarm_min, osdConfig()->esc_temp_alarm_max); - return true; - } + case OSD_ESC_RPM: + { + escSensorData_t * escSensor = escSensorGetData(); + if (escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE) { + osdFormatRpm(buff, escSensor->rpm); + } + else { + osdFormatRpm(buff, 0); + } + break; + } + case OSD_ESC_TEMPERATURE: + { + escSensorData_t * escSensor = escSensorGetData(); + bool escTemperatureValid = escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE; + osdDisplayTemperature(elemPosX, elemPosY, SYM_ESC_TEMP, NULL, escTemperatureValid, (escSensor->temperature)*10, osdConfig()->esc_temp_alarm_min, osdConfig()->esc_temp_alarm_max); + return true; + } #endif - case OSD_TPA: - { - char buff[4]; - textAttributes_t attr; + case OSD_TPA: + { + char buff[4]; + textAttributes_t attr; - displayWrite(osdDisplayPort, elemPosX, elemPosY, "TPA"); - attr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%3d", currentControlRateProfile->throttle.dynPID); - if (isAdjustmentFunctionSelected(ADJUSTMENT_TPA)) { - TEXT_ATTRIBUTES_ADD_BLINK(attr); - } - displayWriteWithAttr(osdDisplayPort, elemPosX + 5, elemPosY, buff, attr); + displayWrite(osdDisplayPort, elemPosX, elemPosY, "TPA"); + attr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%3d", currentControlRateProfile->throttle.dynPID); + if (isAdjustmentFunctionSelected(ADJUSTMENT_TPA)) { + TEXT_ATTRIBUTES_ADD_BLINK(attr); + } + displayWriteWithAttr(osdDisplayPort, elemPosX + 5, elemPosY, buff, attr); - displayWrite(osdDisplayPort, elemPosX, elemPosY + 1, "BP"); - attr = TEXT_ATTRIBUTES_NONE; - tfp_sprintf(buff, "%4d", currentControlRateProfile->throttle.pa_breakpoint); - if (isAdjustmentFunctionSelected(ADJUSTMENT_TPA_BREAKPOINT)) { - TEXT_ATTRIBUTES_ADD_BLINK(attr); - } - displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY + 1, buff, attr); + displayWrite(osdDisplayPort, elemPosX, elemPosY + 1, "BP"); + attr = TEXT_ATTRIBUTES_NONE; + tfp_sprintf(buff, "%4d", currentControlRateProfile->throttle.pa_breakpoint); + if (isAdjustmentFunctionSelected(ADJUSTMENT_TPA_BREAKPOINT)) { + TEXT_ATTRIBUTES_ADD_BLINK(attr); + } + displayWriteWithAttr(osdDisplayPort, elemPosX + 4, elemPosY + 1, buff, attr); - return true; - } - case OSD_TPA_TIME_CONSTANT: - { - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "TPA TC", 0, currentControlRateProfile->throttle.fixedWingTauMs, 4, 0, ADJUSTMENT_FW_TPA_TIME_CONSTANT); - return true; - } - case OSD_FW_LEVEL_TRIM: - { - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "LEVEL", 0, getFixedWingLevelTrim(), 3, 1, ADJUSTMENT_FW_LEVEL_TRIM); - return true; - } + return true; + } + case OSD_TPA_TIME_CONSTANT: + { + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "TPA TC", 0, currentControlRateProfile->throttle.fixedWingTauMs, 4, 0, ADJUSTMENT_FW_TPA_TIME_CONSTANT); + return true; + } + case OSD_FW_LEVEL_TRIM: + { + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "LEVEL", 0, getFixedWingLevelTrim(), 3, 1, ADJUSTMENT_FW_LEVEL_TRIM); + return true; + } - case OSD_NAV_FW_CONTROL_SMOOTHNESS: - { - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CTL S", 0, navConfig()->fw.control_smoothness, 1, 0, ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS); - return true; - } + case OSD_NAV_FW_CONTROL_SMOOTHNESS: + { + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CTL S", 0, navConfig()->fw.control_smoothness, 1, 0, ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS); + return true; + } #ifdef USE_MULTI_MISSION - case OSD_NAV_WP_MULTI_MISSION_INDEX: - { - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "WP NO", 0, navConfig()->general.waypoint_multi_mission_index, 1, 0, ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX); - return true; - } + case OSD_NAV_WP_MULTI_MISSION_INDEX: + { + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "WP NO", 0, navConfig()->general.waypoint_multi_mission_index, 1, 0, ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX); + return true; + } #endif - case OSD_MISSION: - { - if (IS_RC_MODE_ACTIVE(BOXPLANWPMISSION)) { - char buf[5]; - switch (posControl.wpMissionPlannerStatus) { - case WP_PLAN_WAIT: - strcpy(buf, "WAIT"); - break; - case WP_PLAN_SAVE: - strcpy(buf, "SAVE"); - break; - case WP_PLAN_OK: - strcpy(buf, " OK "); - break; - case WP_PLAN_FULL: - strcpy(buf, "FULL"); - } - tfp_sprintf(buff, "%s>%2uWP", buf, posControl.wpPlannerActiveWPIndex); - } else if (posControl.wpPlannerActiveWPIndex){ - tfp_sprintf(buff, "PLAN>%2uWP", posControl.waypointCount); // mission planner mision active - } + case OSD_MISSION: + { + if (IS_RC_MODE_ACTIVE(BOXPLANWPMISSION)) { + char buf[5]; + switch (posControl.wpMissionPlannerStatus) { + case WP_PLAN_WAIT: + strcpy(buf, "WAIT"); + break; + case WP_PLAN_SAVE: + strcpy(buf, "SAVE"); + break; + case WP_PLAN_OK: + strcpy(buf, " OK "); + break; + case WP_PLAN_FULL: + strcpy(buf, "FULL"); + } + tfp_sprintf(buff, "%s>%2uWP", buf, posControl.wpPlannerActiveWPIndex); + } else if (posControl.wpPlannerActiveWPIndex){ + tfp_sprintf(buff, "PLAN>%2uWP", posControl.waypointCount); // mission planner mision active + } #ifdef USE_MULTI_MISSION - else { - if (ARMING_FLAG(ARMED) && !(IS_RC_MODE_ACTIVE(BOXCHANGEMISSION) && posControl.multiMissionCount > 1)){ - // Limit field size when Armed, only show selected mission - tfp_sprintf(buff, "M%u ", posControl.loadedMultiMissionIndex); - } else if (posControl.multiMissionCount) { - if (navConfig()->general.waypoint_multi_mission_index != posControl.loadedMultiMissionIndex) { - tfp_sprintf(buff, "M%u/%u>LOAD", navConfig()->general.waypoint_multi_mission_index, posControl.multiMissionCount); - } else { - if (posControl.waypointListValid && posControl.waypointCount > 0) { - tfp_sprintf(buff, "M%u/%u>%2uWP", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); - } else { - tfp_sprintf(buff, "M0/%u> 0WP", posControl.multiMissionCount); - } - } - } else { // no multi mission loaded - show active WP count from other source - tfp_sprintf(buff, "WP CNT>%2u", posControl.waypointCount); - } - } + else { + if (ARMING_FLAG(ARMED) && !(IS_RC_MODE_ACTIVE(BOXCHANGEMISSION) && posControl.multiMissionCount > 1)){ + // Limit field size when Armed, only show selected mission + tfp_sprintf(buff, "M%u ", posControl.loadedMultiMissionIndex); + } else if (posControl.multiMissionCount) { + if (navConfig()->general.waypoint_multi_mission_index != posControl.loadedMultiMissionIndex) { + tfp_sprintf(buff, "M%u/%u>LOAD", navConfig()->general.waypoint_multi_mission_index, posControl.multiMissionCount); + } else { + if (posControl.waypointListValid && posControl.waypointCount > 0) { + tfp_sprintf(buff, "M%u/%u>%2uWP", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); + } else { + tfp_sprintf(buff, "M0/%u> 0WP", posControl.multiMissionCount); + } + } + } else { // no multi mission loaded - show active WP count from other source + tfp_sprintf(buff, "WP CNT>%2u", posControl.waypointCount); + } + } #endif - displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); - return true; - } + displayWrite(osdDisplayPort, elemPosX, elemPosY, buff); + return true; + } #ifdef USE_POWER_LIMITS - case OSD_PLIMIT_REMAINING_BURST_TIME: - osdFormatCentiNumber(buff, powerLimiterGetRemainingBurstTime() * 100, 0, 1, 0, 3); - buff[3] = 'S'; - buff[4] = '\0'; - break; + case OSD_PLIMIT_REMAINING_BURST_TIME: + osdFormatCentiNumber(buff, powerLimiterGetRemainingBurstTime() * 100, 0, 1, 0, 3); + buff[3] = 'S'; + buff[4] = '\0'; + break; - case OSD_PLIMIT_ACTIVE_CURRENT_LIMIT: - if (currentBatteryProfile->powerLimits.continuousCurrent) { - osdFormatCentiNumber(buff, powerLimiterGetActiveCurrentLimit(), 0, 2, 0, 3); - buff[3] = SYM_AMP; - buff[4] = '\0'; + case OSD_PLIMIT_ACTIVE_CURRENT_LIMIT: + if (currentBatteryProfile->powerLimits.continuousCurrent) { + osdFormatCentiNumber(buff, powerLimiterGetActiveCurrentLimit(), 0, 2, 0, 3); + buff[3] = SYM_AMP; + buff[4] = '\0'; - if (powerLimiterIsLimitingCurrent()) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } - break; + if (powerLimiterIsLimitingCurrent()) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + break; #ifdef USE_ADC - case OSD_PLIMIT_ACTIVE_POWER_LIMIT: - { - if (currentBatteryProfile->powerLimits.continuousPower) { - bool kiloWatt = osdFormatCentiNumber(buff, powerLimiterGetActivePowerLimit(), 1000, 2, 2, 3); - buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; - buff[4] = '\0'; + case OSD_PLIMIT_ACTIVE_POWER_LIMIT: + { + if (currentBatteryProfile->powerLimits.continuousPower) { + bool kiloWatt = osdFormatCentiNumber(buff, powerLimiterGetActivePowerLimit(), 1000, 2, 2, 3); + buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; + buff[4] = '\0'; - if (powerLimiterIsLimitingPower()) { - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } - break; - } + if (powerLimiterIsLimitingPower()) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + break; + } #endif // USE_ADC #endif // USE_POWER_LIMITS - default: - return false; - } + default: + return false; + } - displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); - return true; + displayWriteWithAttr(osdDisplayPort, elemPosX, elemPosY, buff, elemAttr); + return true; } uint8_t osdIncElementIndex(uint8_t elementIndex) { - ++elementIndex; + ++elementIndex; - if (elementIndex == OSD_ARTIFICIAL_HORIZON) { // always drawn last so skip - elementIndex++; - } + if (elementIndex == OSD_ARTIFICIAL_HORIZON) { // always drawn last so skip + elementIndex++; + } #ifndef USE_TEMPERATURE_SENSOR - if (elementIndex == OSD_TEMP_SENSOR_0_TEMPERATURE) { - elementIndex = OSD_ALTITUDE_MSL; - } + if (elementIndex == OSD_TEMP_SENSOR_0_TEMPERATURE) { + elementIndex = OSD_ALTITUDE_MSL; + } #endif - if (!(feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER))) { - if (elementIndex == OSD_POWER) { - elementIndex = OSD_GPS_LON; - } - if (elementIndex == OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE) { - elementIndex = OSD_LEVEL_PIDS; - } + if (!(feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER))) { + if (elementIndex == OSD_POWER) { + elementIndex = OSD_GPS_LON; + } + if (elementIndex == OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE) { + elementIndex = OSD_LEVEL_PIDS; + } #ifdef USE_POWER_LIMITS - if (elementIndex == OSD_PLIMIT_REMAINING_BURST_TIME) { - elementIndex = OSD_GLIDESLOPE; - } + if (elementIndex == OSD_PLIMIT_REMAINING_BURST_TIME) { + elementIndex = OSD_GLIDESLOPE; + } #endif - } + } #ifndef USE_POWER_LIMITS - if (elementIndex == OSD_PLIMIT_REMAINING_BURST_TIME) { - elementIndex = OSD_GLIDESLOPE; - } + if (elementIndex == OSD_PLIMIT_REMAINING_BURST_TIME) { + elementIndex = OSD_GLIDESLOPE; + } #endif - if (!feature(FEATURE_CURRENT_METER)) { - if (elementIndex == OSD_CURRENT_DRAW) { - elementIndex = OSD_GPS_SPEED; - } - if (elementIndex == OSD_EFFICIENCY_MAH_PER_KM) { - elementIndex = OSD_BATTERY_REMAINING_PERCENT; - } - if (elementIndex == OSD_EFFICIENCY_WH_PER_KM) { - elementIndex = OSD_TRIP_DIST; - } - if (elementIndex == OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH) { - elementIndex = OSD_HOME_HEADING_ERROR; - } - if (elementIndex == OSD_CLIMB_EFFICIENCY) { - elementIndex = OSD_NAV_WP_MULTI_MISSION_INDEX; - } - } + if (!feature(FEATURE_CURRENT_METER)) { + if (elementIndex == OSD_CURRENT_DRAW) { + elementIndex = OSD_GPS_SPEED; + } + if (elementIndex == OSD_EFFICIENCY_MAH_PER_KM) { + elementIndex = OSD_BATTERY_REMAINING_PERCENT; + } + if (elementIndex == OSD_EFFICIENCY_WH_PER_KM) { + elementIndex = OSD_TRIP_DIST; + } + if (elementIndex == OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH) { + elementIndex = OSD_HOME_HEADING_ERROR; + } + if (elementIndex == OSD_CLIMB_EFFICIENCY) { + elementIndex = OSD_NAV_WP_MULTI_MISSION_INDEX; + } + } - if (!STATE(ESC_SENSOR_ENABLED)) { - if (elementIndex == OSD_ESC_RPM) { - elementIndex = OSD_AZIMUTH; - } - } + if (!STATE(ESC_SENSOR_ENABLED)) { + if (elementIndex == OSD_ESC_RPM) { + elementIndex = OSD_AZIMUTH; + } + } - if (!feature(FEATURE_GPS)) { - if (elementIndex == OSD_GPS_HDOP || elementIndex == OSD_TRIP_DIST || elementIndex == OSD_3D_SPEED || elementIndex == OSD_MISSION || - elementIndex == OSD_AZIMUTH || elementIndex == OSD_BATTERY_REMAINING_CAPACITY || elementIndex == OSD_EFFICIENCY_MAH_PER_KM) { - elementIndex++; - } - if (elementIndex == OSD_HEADING_GRAPH && !sensors(SENSOR_MAG)) { - elementIndex = feature(FEATURE_CURRENT_METER) ? OSD_WH_DRAWN : OSD_BATTERY_REMAINING_PERCENT; - } - if (elementIndex == OSD_EFFICIENCY_WH_PER_KM) { - elementIndex = OSD_ATTITUDE_PITCH; - } - if (elementIndex == OSD_GPS_SPEED) { - elementIndex = OSD_ALTITUDE; - } - if (elementIndex == OSD_GPS_LON) { - elementIndex = sensors(SENSOR_MAG) ? OSD_HEADING : OSD_VARIO; - } - if (elementIndex == OSD_MAP_NORTH) { - elementIndex = feature(FEATURE_CURRENT_METER) ? OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE : OSD_LEVEL_PIDS; - } - if (elementIndex == OSD_PLUS_CODE) { - elementIndex = OSD_GFORCE; - } - if (elementIndex == OSD_GLIDESLOPE) { - elementIndex = OSD_AIR_MAX_SPEED; - } - if (elementIndex == OSD_GLIDE_RANGE) { - elementIndex = feature(FEATURE_CURRENT_METER) ? OSD_CLIMB_EFFICIENCY : OSD_PILOT_NAME; - } - if (elementIndex == OSD_NAV_WP_MULTI_MISSION_INDEX) { - elementIndex = OSD_PILOT_NAME; - } - } + if (!feature(FEATURE_GPS)) { + if (elementIndex == OSD_GPS_HDOP || elementIndex == OSD_TRIP_DIST || elementIndex == OSD_3D_SPEED || elementIndex == OSD_MISSION || + elementIndex == OSD_AZIMUTH || elementIndex == OSD_BATTERY_REMAINING_CAPACITY || elementIndex == OSD_EFFICIENCY_MAH_PER_KM) { + elementIndex++; + } + if (elementIndex == OSD_HEADING_GRAPH && !sensors(SENSOR_MAG)) { + elementIndex = feature(FEATURE_CURRENT_METER) ? OSD_WH_DRAWN : OSD_BATTERY_REMAINING_PERCENT; + } + if (elementIndex == OSD_EFFICIENCY_WH_PER_KM) { + elementIndex = OSD_ATTITUDE_PITCH; + } + if (elementIndex == OSD_GPS_SPEED) { + elementIndex = OSD_ALTITUDE; + } + if (elementIndex == OSD_GPS_LON) { + elementIndex = sensors(SENSOR_MAG) ? OSD_HEADING : OSD_VARIO; + } + if (elementIndex == OSD_MAP_NORTH) { + elementIndex = feature(FEATURE_CURRENT_METER) ? OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE : OSD_LEVEL_PIDS; + } + if (elementIndex == OSD_PLUS_CODE) { + elementIndex = OSD_GFORCE; + } + if (elementIndex == OSD_GLIDESLOPE) { + elementIndex = OSD_AIR_MAX_SPEED; + } + if (elementIndex == OSD_GLIDE_RANGE) { + elementIndex = feature(FEATURE_CURRENT_METER) ? OSD_CLIMB_EFFICIENCY : OSD_PILOT_NAME; + } + if (elementIndex == OSD_NAV_WP_MULTI_MISSION_INDEX) { + elementIndex = OSD_PILOT_NAME; + } + } - if (!sensors(SENSOR_ACC)) { - if (elementIndex == OSD_CROSSHAIRS) { - elementIndex = OSD_ONTIME; - } - if (elementIndex == OSD_GFORCE) { - elementIndex = OSD_RC_SOURCE; - } - } + if (!sensors(SENSOR_ACC)) { + if (elementIndex == OSD_CROSSHAIRS) { + elementIndex = OSD_ONTIME; + } + if (elementIndex == OSD_GFORCE) { + elementIndex = OSD_RC_SOURCE; + } + } - if (elementIndex == OSD_ITEM_COUNT) { - elementIndex = 0; - } - return elementIndex; + if (elementIndex == OSD_ITEM_COUNT) { + elementIndex = 0; + } + return elementIndex; } void osdDrawNextElement(void) { - static uint8_t elementIndex = 0; - // Flag for end of loop, also prevents infinite loop when no elements are enabled - uint8_t index = elementIndex; - do { - elementIndex = osdIncElementIndex(elementIndex); - } while (!osdDrawSingleElement(elementIndex) && index != elementIndex); + static uint8_t elementIndex = 0; + // Flag for end of loop, also prevents infinite loop when no elements are enabled + uint8_t index = elementIndex; + do { + elementIndex = osdIncElementIndex(elementIndex); + } while (!osdDrawSingleElement(elementIndex) && index != elementIndex); - // Draw artificial horizon + tracking telemtry last - osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON); - if (osdConfig()->telemetry>0){ - osdDisplayTelemetry(); - } + // Draw artificial horizon + tracking telemtry last + osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON); + if (osdConfig()->telemetry>0){ + osdDisplayTelemetry(); + } } PG_RESET_TEMPLATE(osdConfig_t, osdConfig, - .rssi_alarm = SETTING_OSD_RSSI_ALARM_DEFAULT, - .time_alarm = SETTING_OSD_TIME_ALARM_DEFAULT, - .alt_alarm = SETTING_OSD_ALT_ALARM_DEFAULT, - .dist_alarm = SETTING_OSD_DIST_ALARM_DEFAULT, - .neg_alt_alarm = SETTING_OSD_NEG_ALT_ALARM_DEFAULT, - .current_alarm = SETTING_OSD_CURRENT_ALARM_DEFAULT, - .imu_temp_alarm_min = SETTING_OSD_IMU_TEMP_ALARM_MIN_DEFAULT, - .imu_temp_alarm_max = SETTING_OSD_IMU_TEMP_ALARM_MAX_DEFAULT, - .esc_temp_alarm_min = SETTING_OSD_ESC_TEMP_ALARM_MIN_DEFAULT, - .esc_temp_alarm_max = SETTING_OSD_ESC_TEMP_ALARM_MAX_DEFAULT, - .gforce_alarm = SETTING_OSD_GFORCE_ALARM_DEFAULT, - .gforce_axis_alarm_min = SETTING_OSD_GFORCE_AXIS_ALARM_MIN_DEFAULT, - .gforce_axis_alarm_max = SETTING_OSD_GFORCE_AXIS_ALARM_MAX_DEFAULT, + .rssi_alarm = SETTING_OSD_RSSI_ALARM_DEFAULT, + .time_alarm = SETTING_OSD_TIME_ALARM_DEFAULT, + .alt_alarm = SETTING_OSD_ALT_ALARM_DEFAULT, + .dist_alarm = SETTING_OSD_DIST_ALARM_DEFAULT, + .neg_alt_alarm = SETTING_OSD_NEG_ALT_ALARM_DEFAULT, + .current_alarm = SETTING_OSD_CURRENT_ALARM_DEFAULT, + .imu_temp_alarm_min = SETTING_OSD_IMU_TEMP_ALARM_MIN_DEFAULT, + .imu_temp_alarm_max = SETTING_OSD_IMU_TEMP_ALARM_MAX_DEFAULT, + .esc_temp_alarm_min = SETTING_OSD_ESC_TEMP_ALARM_MIN_DEFAULT, + .esc_temp_alarm_max = SETTING_OSD_ESC_TEMP_ALARM_MAX_DEFAULT, + .gforce_alarm = SETTING_OSD_GFORCE_ALARM_DEFAULT, + .gforce_axis_alarm_min = SETTING_OSD_GFORCE_AXIS_ALARM_MIN_DEFAULT, + .gforce_axis_alarm_max = SETTING_OSD_GFORCE_AXIS_ALARM_MAX_DEFAULT, #ifdef USE_BARO - .baro_temp_alarm_min = SETTING_OSD_BARO_TEMP_ALARM_MIN_DEFAULT, - .baro_temp_alarm_max = SETTING_OSD_BARO_TEMP_ALARM_MAX_DEFAULT, + .baro_temp_alarm_min = SETTING_OSD_BARO_TEMP_ALARM_MIN_DEFAULT, + .baro_temp_alarm_max = SETTING_OSD_BARO_TEMP_ALARM_MAX_DEFAULT, #endif #ifdef USE_SERIALRX_CRSF - .snr_alarm = SETTING_OSD_SNR_ALARM_DEFAULT, - .crsf_lq_format = SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT, - .link_quality_alarm = SETTING_OSD_LINK_QUALITY_ALARM_DEFAULT, - .rssi_dbm_alarm = SETTING_OSD_RSSI_DBM_ALARM_DEFAULT, - .rssi_dbm_max = SETTING_OSD_RSSI_DBM_MAX_DEFAULT, - .rssi_dbm_min = SETTING_OSD_RSSI_DBM_MIN_DEFAULT, + .snr_alarm = SETTING_OSD_SNR_ALARM_DEFAULT, + .crsf_lq_format = SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT, + .link_quality_alarm = SETTING_OSD_LINK_QUALITY_ALARM_DEFAULT, + .rssi_dbm_alarm = SETTING_OSD_RSSI_DBM_ALARM_DEFAULT, + .rssi_dbm_max = SETTING_OSD_RSSI_DBM_MAX_DEFAULT, + .rssi_dbm_min = SETTING_OSD_RSSI_DBM_MIN_DEFAULT, #endif #ifdef USE_TEMPERATURE_SENSOR - .temp_label_align = SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT, + .temp_label_align = SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT, #endif #ifdef USE_PITOT - .airspeed_alarm_min = SETTING_OSD_AIRSPEED_ALARM_MIN_DEFAULT, - .airspeed_alarm_max = SETTING_OSD_AIRSPEED_ALARM_MAX_DEFAULT, + .airspeed_alarm_min = SETTING_OSD_AIRSPEED_ALARM_MIN_DEFAULT, + .airspeed_alarm_max = SETTING_OSD_AIRSPEED_ALARM_MAX_DEFAULT, #endif - .video_system = SETTING_OSD_VIDEO_SYSTEM_DEFAULT, - .row_shiftdown = SETTING_OSD_ROW_SHIFTDOWN_DEFAULT, - .msp_displayport_fullframe_interval = SETTING_OSD_MSP_DISPLAYPORT_FULLFRAME_INTERVAL_DEFAULT, + .video_system = SETTING_OSD_VIDEO_SYSTEM_DEFAULT, + .row_shiftdown = SETTING_OSD_ROW_SHIFTDOWN_DEFAULT, + .msp_displayport_fullframe_interval = SETTING_OSD_MSP_DISPLAYPORT_FULLFRAME_INTERVAL_DEFAULT, - .ahi_reverse_roll = SETTING_OSD_AHI_REVERSE_ROLL_DEFAULT, - .ahi_max_pitch = SETTING_OSD_AHI_MAX_PITCH_DEFAULT, - .crosshairs_style = SETTING_OSD_CROSSHAIRS_STYLE_DEFAULT, - .horizon_offset = SETTING_OSD_HORIZON_OFFSET_DEFAULT, - .camera_uptilt = SETTING_OSD_CAMERA_UPTILT_DEFAULT, - .ahi_camera_uptilt_comp = SETTING_OSD_AHI_CAMERA_UPTILT_COMP_DEFAULT, - .camera_fov_h = SETTING_OSD_CAMERA_FOV_H_DEFAULT, - .camera_fov_v = SETTING_OSD_CAMERA_FOV_V_DEFAULT, - .hud_margin_h = SETTING_OSD_HUD_MARGIN_H_DEFAULT, - .hud_margin_v = SETTING_OSD_HUD_MARGIN_V_DEFAULT, - .hud_homing = SETTING_OSD_HUD_HOMING_DEFAULT, - .hud_homepoint = SETTING_OSD_HUD_HOMEPOINT_DEFAULT, - .hud_radar_disp = SETTING_OSD_HUD_RADAR_DISP_DEFAULT, - .hud_radar_range_min = SETTING_OSD_HUD_RADAR_RANGE_MIN_DEFAULT, - .hud_radar_range_max = SETTING_OSD_HUD_RADAR_RANGE_MAX_DEFAULT, - .hud_radar_alt_difference_display_time = SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_DEFAULT, - .hud_radar_distance_display_time = SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_DEFAULT, - .hud_wp_disp = SETTING_OSD_HUD_WP_DISP_DEFAULT, - .left_sidebar_scroll = SETTING_OSD_LEFT_SIDEBAR_SCROLL_DEFAULT, - .right_sidebar_scroll = SETTING_OSD_RIGHT_SIDEBAR_SCROLL_DEFAULT, - .sidebar_scroll_arrows = SETTING_OSD_SIDEBAR_SCROLL_ARROWS_DEFAULT, - .sidebar_horizontal_offset = SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_DEFAULT, - .left_sidebar_scroll_step = SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_DEFAULT, - .right_sidebar_scroll_step = SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_DEFAULT, - .sidebar_height = SETTING_OSD_SIDEBAR_HEIGHT_DEFAULT, - .ahi_pitch_interval = SETTING_OSD_AHI_PITCH_INTERVAL_DEFAULT, - .osd_home_position_arm_screen = SETTING_OSD_HOME_POSITION_ARM_SCREEN_DEFAULT, - .pan_servo_index = SETTING_OSD_PAN_SERVO_INDEX_DEFAULT, - .pan_servo_pwm2centideg = SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_DEFAULT, - .pan_servo_offcentre_warning = SETTING_OSD_PAN_SERVO_OFFCENTRE_WARNING_DEFAULT, - .pan_servo_indicator_show_degrees = SETTING_OSD_PAN_SERVO_INDICATOR_SHOW_DEGREES_DEFAULT, - .esc_rpm_precision = SETTING_OSD_ESC_RPM_PRECISION_DEFAULT, - .mAh_used_precision = SETTING_OSD_MAH_USED_PRECISION_DEFAULT, - .osd_switch_indicator0_name = SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_DEFAULT, - .osd_switch_indicator0_channel = SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_DEFAULT, - .osd_switch_indicator1_name = SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_DEFAULT, - .osd_switch_indicator1_channel = SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_DEFAULT, - .osd_switch_indicator2_name = SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_DEFAULT, - .osd_switch_indicator2_channel = SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_DEFAULT, - .osd_switch_indicator3_name = SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_DEFAULT, - .osd_switch_indicator3_channel = SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_DEFAULT, - .osd_switch_indicators_align_left = SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_DEFAULT, - .system_msg_display_time = SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_DEFAULT, - .units = SETTING_OSD_UNITS_DEFAULT, - .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT, - .use_pilot_logo = SETTING_OSD_USE_PILOT_LOGO_DEFAULT, - .inav_to_pilot_logo_spacing = SETTING_OSD_INAV_TO_PILOT_LOGO_SPACING_DEFAULT, - .arm_screen_display_time = SETTING_OSD_ARM_SCREEN_DISPLAY_TIME_DEFAULT, + .ahi_reverse_roll = SETTING_OSD_AHI_REVERSE_ROLL_DEFAULT, + .ahi_max_pitch = SETTING_OSD_AHI_MAX_PITCH_DEFAULT, + .crosshairs_style = SETTING_OSD_CROSSHAIRS_STYLE_DEFAULT, + .horizon_offset = SETTING_OSD_HORIZON_OFFSET_DEFAULT, + .camera_uptilt = SETTING_OSD_CAMERA_UPTILT_DEFAULT, + .ahi_camera_uptilt_comp = SETTING_OSD_AHI_CAMERA_UPTILT_COMP_DEFAULT, + .camera_fov_h = SETTING_OSD_CAMERA_FOV_H_DEFAULT, + .camera_fov_v = SETTING_OSD_CAMERA_FOV_V_DEFAULT, + .hud_margin_h = SETTING_OSD_HUD_MARGIN_H_DEFAULT, + .hud_margin_v = SETTING_OSD_HUD_MARGIN_V_DEFAULT, + .hud_homing = SETTING_OSD_HUD_HOMING_DEFAULT, + .hud_homepoint = SETTING_OSD_HUD_HOMEPOINT_DEFAULT, + .hud_radar_disp = SETTING_OSD_HUD_RADAR_DISP_DEFAULT, + .hud_radar_range_min = SETTING_OSD_HUD_RADAR_RANGE_MIN_DEFAULT, + .hud_radar_range_max = SETTING_OSD_HUD_RADAR_RANGE_MAX_DEFAULT, + .hud_radar_alt_difference_display_time = SETTING_OSD_HUD_RADAR_ALT_DIFFERENCE_DISPLAY_TIME_DEFAULT, + .hud_radar_distance_display_time = SETTING_OSD_HUD_RADAR_DISTANCE_DISPLAY_TIME_DEFAULT, + .hud_wp_disp = SETTING_OSD_HUD_WP_DISP_DEFAULT, + .left_sidebar_scroll = SETTING_OSD_LEFT_SIDEBAR_SCROLL_DEFAULT, + .right_sidebar_scroll = SETTING_OSD_RIGHT_SIDEBAR_SCROLL_DEFAULT, + .sidebar_scroll_arrows = SETTING_OSD_SIDEBAR_SCROLL_ARROWS_DEFAULT, + .sidebar_horizontal_offset = SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_DEFAULT, + .left_sidebar_scroll_step = SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_DEFAULT, + .right_sidebar_scroll_step = SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_DEFAULT, + .sidebar_height = SETTING_OSD_SIDEBAR_HEIGHT_DEFAULT, + .ahi_pitch_interval = SETTING_OSD_AHI_PITCH_INTERVAL_DEFAULT, + .osd_home_position_arm_screen = SETTING_OSD_HOME_POSITION_ARM_SCREEN_DEFAULT, + .pan_servo_index = SETTING_OSD_PAN_SERVO_INDEX_DEFAULT, + .pan_servo_pwm2centideg = SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_DEFAULT, + .pan_servo_offcentre_warning = SETTING_OSD_PAN_SERVO_OFFCENTRE_WARNING_DEFAULT, + .pan_servo_indicator_show_degrees = SETTING_OSD_PAN_SERVO_INDICATOR_SHOW_DEGREES_DEFAULT, + .esc_rpm_precision = SETTING_OSD_ESC_RPM_PRECISION_DEFAULT, + .mAh_used_precision = SETTING_OSD_MAH_USED_PRECISION_DEFAULT, + .osd_switch_indicator0_name = SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_DEFAULT, + .osd_switch_indicator0_channel = SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNEL_DEFAULT, + .osd_switch_indicator1_name = SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_DEFAULT, + .osd_switch_indicator1_channel = SETTING_OSD_SWITCH_INDICATOR_ONE_CHANNEL_DEFAULT, + .osd_switch_indicator2_name = SETTING_OSD_SWITCH_INDICATOR_TWO_NAME_DEFAULT, + .osd_switch_indicator2_channel = SETTING_OSD_SWITCH_INDICATOR_TWO_CHANNEL_DEFAULT, + .osd_switch_indicator3_name = SETTING_OSD_SWITCH_INDICATOR_THREE_NAME_DEFAULT, + .osd_switch_indicator3_channel = SETTING_OSD_SWITCH_INDICATOR_THREE_CHANNEL_DEFAULT, + .osd_switch_indicators_align_left = SETTING_OSD_SWITCH_INDICATORS_ALIGN_LEFT_DEFAULT, + .system_msg_display_time = SETTING_OSD_SYSTEM_MSG_DISPLAY_TIME_DEFAULT, + .units = SETTING_OSD_UNITS_DEFAULT, + .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT, + .use_pilot_logo = SETTING_OSD_USE_PILOT_LOGO_DEFAULT, + .inav_to_pilot_logo_spacing = SETTING_OSD_INAV_TO_PILOT_LOGO_SPACING_DEFAULT, + .arm_screen_display_time = SETTING_OSD_ARM_SCREEN_DISPLAY_TIME_DEFAULT, #ifdef USE_WIND_ESTIMATOR - .estimations_wind_compensation = SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT, + .estimations_wind_compensation = SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT, #endif - .coordinate_digits = SETTING_OSD_COORDINATE_DIGITS_DEFAULT, + .coordinate_digits = SETTING_OSD_COORDINATE_DIGITS_DEFAULT, - .osd_failsafe_switch_layout = SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_DEFAULT, + .osd_failsafe_switch_layout = SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_DEFAULT, - .plus_code_digits = SETTING_OSD_PLUS_CODE_DIGITS_DEFAULT, - .plus_code_short = SETTING_OSD_PLUS_CODE_SHORT_DEFAULT, + .plus_code_digits = SETTING_OSD_PLUS_CODE_DIGITS_DEFAULT, + .plus_code_short = SETTING_OSD_PLUS_CODE_SHORT_DEFAULT, - .ahi_width = SETTING_OSD_AHI_WIDTH_DEFAULT, - .ahi_height = SETTING_OSD_AHI_HEIGHT_DEFAULT, - .ahi_vertical_offset = SETTING_OSD_AHI_VERTICAL_OFFSET_DEFAULT, - .ahi_bordered = SETTING_OSD_AHI_BORDERED_DEFAULT, - .ahi_style = SETTING_OSD_AHI_STYLE_DEFAULT, + .ahi_width = SETTING_OSD_AHI_WIDTH_DEFAULT, + .ahi_height = SETTING_OSD_AHI_HEIGHT_DEFAULT, + .ahi_vertical_offset = SETTING_OSD_AHI_VERTICAL_OFFSET_DEFAULT, + .ahi_bordered = SETTING_OSD_AHI_BORDERED_DEFAULT, + .ahi_style = SETTING_OSD_AHI_STYLE_DEFAULT, - .force_grid = SETTING_OSD_FORCE_GRID_DEFAULT, + .force_grid = SETTING_OSD_FORCE_GRID_DEFAULT, - .stats_energy_unit = SETTING_OSD_STATS_ENERGY_UNIT_DEFAULT, - .stats_min_voltage_unit = SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_DEFAULT, - .stats_page_auto_swap_time = SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_DEFAULT + .stats_energy_unit = SETTING_OSD_STATS_ENERGY_UNIT_DEFAULT, + .stats_min_voltage_unit = SETTING_OSD_STATS_MIN_VOLTAGE_UNIT_DEFAULT, + .stats_page_auto_swap_time = SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_DEFAULT ); void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) { - osdLayoutsConfig->item_pos[0][OSD_ALTITUDE] = OSD_POS(1, 0) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 0) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1); + osdLayoutsConfig->item_pos[0][OSD_ALTITUDE] = OSD_POS(1, 0) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 0) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1); - osdLayoutsConfig->item_pos[0][OSD_RSSI_VALUE] = OSD_POS(23, 0) | OSD_VISIBLE_FLAG; - //line 2 - osdLayoutsConfig->item_pos[0][OSD_HOME_DIST] = OSD_POS(1, 1); - osdLayoutsConfig->item_pos[0][OSD_TRIP_DIST] = OSD_POS(1, 2); - osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_CELL_VOLTAGE] = OSD_POS(12, 1); - osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1); - osdLayoutsConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1); - osdLayoutsConfig->item_pos[0][OSD_3D_SPEED] = OSD_POS(23, 1); - osdLayoutsConfig->item_pos[0][OSD_GLIDESLOPE] = OSD_POS(23, 2); + osdLayoutsConfig->item_pos[0][OSD_RSSI_VALUE] = OSD_POS(23, 0) | OSD_VISIBLE_FLAG; + //line 2 + osdLayoutsConfig->item_pos[0][OSD_HOME_DIST] = OSD_POS(1, 1); + osdLayoutsConfig->item_pos[0][OSD_TRIP_DIST] = OSD_POS(1, 2); + osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_CELL_VOLTAGE] = OSD_POS(12, 1); + osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1); + osdLayoutsConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1); + osdLayoutsConfig->item_pos[0][OSD_3D_SPEED] = OSD_POS(23, 1); + osdLayoutsConfig->item_pos[0][OSD_GLIDESLOPE] = OSD_POS(23, 2); - osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_SCALED_THROTTLE_POS] = OSD_POS(6, 2); - osdLayoutsConfig->item_pos[0][OSD_HEADING] = OSD_POS(12, 2); - osdLayoutsConfig->item_pos[0][OSD_GROUND_COURSE] = OSD_POS(12, 3); - osdLayoutsConfig->item_pos[0][OSD_COURSE_HOLD_ERROR] = OSD_POS(12, 2); - osdLayoutsConfig->item_pos[0][OSD_COURSE_HOLD_ADJUSTMENT] = OSD_POS(12, 2); - osdLayoutsConfig->item_pos[0][OSD_CROSS_TRACK_ERROR] = OSD_POS(12, 3); - osdLayoutsConfig->item_pos[0][OSD_HEADING_GRAPH] = OSD_POS(18, 2); - osdLayoutsConfig->item_pos[0][OSD_CURRENT_DRAW] = OSD_POS(2, 3) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_MAH_DRAWN] = OSD_POS(1, 4) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_WH_DRAWN] = OSD_POS(1, 5); - osdLayoutsConfig->item_pos[0][OSD_BATTERY_REMAINING_CAPACITY] = OSD_POS(1, 6); - osdLayoutsConfig->item_pos[0][OSD_BATTERY_REMAINING_PERCENT] = OSD_POS(1, 7); - osdLayoutsConfig->item_pos[0][OSD_POWER_SUPPLY_IMPEDANCE] = OSD_POS(1, 8); + osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_SCALED_THROTTLE_POS] = OSD_POS(6, 2); + osdLayoutsConfig->item_pos[0][OSD_HEADING] = OSD_POS(12, 2); + osdLayoutsConfig->item_pos[0][OSD_GROUND_COURSE] = OSD_POS(12, 3); + osdLayoutsConfig->item_pos[0][OSD_COURSE_HOLD_ERROR] = OSD_POS(12, 2); + osdLayoutsConfig->item_pos[0][OSD_COURSE_HOLD_ADJUSTMENT] = OSD_POS(12, 2); + osdLayoutsConfig->item_pos[0][OSD_CROSS_TRACK_ERROR] = OSD_POS(12, 3); + osdLayoutsConfig->item_pos[0][OSD_HEADING_GRAPH] = OSD_POS(18, 2); + osdLayoutsConfig->item_pos[0][OSD_CURRENT_DRAW] = OSD_POS(2, 3) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_MAH_DRAWN] = OSD_POS(1, 4) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_WH_DRAWN] = OSD_POS(1, 5); + osdLayoutsConfig->item_pos[0][OSD_BATTERY_REMAINING_CAPACITY] = OSD_POS(1, 6); + osdLayoutsConfig->item_pos[0][OSD_BATTERY_REMAINING_PERCENT] = OSD_POS(1, 7); + osdLayoutsConfig->item_pos[0][OSD_POWER_SUPPLY_IMPEDANCE] = OSD_POS(1, 8); - osdLayoutsConfig->item_pos[0][OSD_EFFICIENCY_MAH_PER_KM] = OSD_POS(1, 5); - osdLayoutsConfig->item_pos[0][OSD_EFFICIENCY_WH_PER_KM] = OSD_POS(1, 5); + osdLayoutsConfig->item_pos[0][OSD_EFFICIENCY_MAH_PER_KM] = OSD_POS(1, 5); + osdLayoutsConfig->item_pos[0][OSD_EFFICIENCY_WH_PER_KM] = OSD_POS(1, 5); - osdLayoutsConfig->item_pos[0][OSD_ATTITUDE_ROLL] = OSD_POS(1, 7); - osdLayoutsConfig->item_pos[0][OSD_ATTITUDE_PITCH] = OSD_POS(1, 8); + osdLayoutsConfig->item_pos[0][OSD_ATTITUDE_ROLL] = OSD_POS(1, 7); + osdLayoutsConfig->item_pos[0][OSD_ATTITUDE_PITCH] = OSD_POS(1, 8); - // avoid OSD_VARIO under OSD_CROSSHAIRS - osdLayoutsConfig->item_pos[0][OSD_VARIO] = OSD_POS(23, 5); - // OSD_VARIO_NUM at the right of OSD_VARIO - osdLayoutsConfig->item_pos[0][OSD_VARIO_NUM] = OSD_POS(24, 7); - osdLayoutsConfig->item_pos[0][OSD_HOME_DIR] = OSD_POS(14, 11); - osdLayoutsConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6); - osdLayoutsConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6); + // avoid OSD_VARIO under OSD_CROSSHAIRS + osdLayoutsConfig->item_pos[0][OSD_VARIO] = OSD_POS(23, 5); + // OSD_VARIO_NUM at the right of OSD_VARIO + osdLayoutsConfig->item_pos[0][OSD_VARIO_NUM] = OSD_POS(24, 7); + osdLayoutsConfig->item_pos[0][OSD_HOME_DIR] = OSD_POS(14, 11); + osdLayoutsConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6); + osdLayoutsConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6); - osdLayoutsConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2); - osdLayoutsConfig->item_pos[0][OSD_PILOT_NAME] = OSD_POS(20, 3); - osdLayoutsConfig->item_pos[0][OSD_PILOT_LOGO] = OSD_POS(20, 3); - osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6); + osdLayoutsConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2); + osdLayoutsConfig->item_pos[0][OSD_PILOT_NAME] = OSD_POS(20, 3); + osdLayoutsConfig->item_pos[0][OSD_PILOT_LOGO] = OSD_POS(20, 3); + osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6); #ifdef USE_SERIALRX_CRSF - osdLayoutsConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(23, 12); - osdLayoutsConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(23, 11); - osdLayoutsConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(24, 9); - osdLayoutsConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(24, 10); + osdLayoutsConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(23, 12); + osdLayoutsConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(23, 11); + osdLayoutsConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(24, 9); + osdLayoutsConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(24, 10); #endif - osdLayoutsConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8); - osdLayoutsConfig->item_pos[0][OSD_FLYTIME] = OSD_POS(23, 9); - osdLayoutsConfig->item_pos[0][OSD_ONTIME_FLYTIME] = OSD_POS(23, 11) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_RTC_TIME] = OSD_POS(23, 12); - osdLayoutsConfig->item_pos[0][OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH] = OSD_POS(23, 7); - osdLayoutsConfig->item_pos[0][OSD_REMAINING_DISTANCE_BEFORE_RTH] = OSD_POS(23, 6); + osdLayoutsConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8); + osdLayoutsConfig->item_pos[0][OSD_FLYTIME] = OSD_POS(23, 9); + osdLayoutsConfig->item_pos[0][OSD_ONTIME_FLYTIME] = OSD_POS(23, 11) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_RTC_TIME] = OSD_POS(23, 12); + osdLayoutsConfig->item_pos[0][OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH] = OSD_POS(23, 7); + osdLayoutsConfig->item_pos[0][OSD_REMAINING_DISTANCE_BEFORE_RTH] = OSD_POS(23, 6); - osdLayoutsConfig->item_pos[0][OSD_MISSION] = OSD_POS(0, 10); - osdLayoutsConfig->item_pos[0][OSD_GPS_SATS] = OSD_POS(0, 11) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_GPS_HDOP] = OSD_POS(0, 10); + osdLayoutsConfig->item_pos[0][OSD_MISSION] = OSD_POS(0, 10); + osdLayoutsConfig->item_pos[0][OSD_GPS_SATS] = OSD_POS(0, 11) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_GPS_HDOP] = OSD_POS(0, 10); - osdLayoutsConfig->item_pos[0][OSD_GPS_LAT] = OSD_POS(0, 12); - // Put this on top of the latitude, since it's very unlikely - // that users will want to use both at the same time. - osdLayoutsConfig->item_pos[0][OSD_PLUS_CODE] = OSD_POS(0, 12); - osdLayoutsConfig->item_pos[0][OSD_FLYMODE] = OSD_POS(13, 12) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_GPS_LON] = OSD_POS(18, 12); + osdLayoutsConfig->item_pos[0][OSD_GPS_LAT] = OSD_POS(0, 12); + // Put this on top of the latitude, since it's very unlikely + // that users will want to use both at the same time. + osdLayoutsConfig->item_pos[0][OSD_PLUS_CODE] = OSD_POS(0, 12); + osdLayoutsConfig->item_pos[0][OSD_FLYMODE] = OSD_POS(13, 12) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_GPS_LON] = OSD_POS(18, 12); - osdLayoutsConfig->item_pos[0][OSD_AZIMUTH] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_AZIMUTH] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_ROLL_PIDS] = OSD_POS(2, 10); - osdLayoutsConfig->item_pos[0][OSD_PITCH_PIDS] = OSD_POS(2, 11); - osdLayoutsConfig->item_pos[0][OSD_YAW_PIDS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_LEVEL_PIDS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_POS_XY_PIDS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_POS_Z_PIDS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_VEL_XY_PIDS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_VEL_Z_PIDS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_HEADING_P] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_BOARD_ALIGN_ROLL] = OSD_POS(2, 10); - osdLayoutsConfig->item_pos[0][OSD_BOARD_ALIGN_PITCH] = OSD_POS(2, 11); - osdLayoutsConfig->item_pos[0][OSD_RC_EXPO] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_RC_YAW_EXPO] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_THROTTLE_EXPO] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_PITCH_RATE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_ROLL_RATE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_YAW_RATE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MANUAL_RC_EXPO] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MANUAL_RC_YAW_EXPO] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MANUAL_PITCH_RATE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MANUAL_ROLL_RATE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MANUAL_YAW_RATE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_NAV_FW_CRUISE_THR] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_NAV_FW_PITCH2THR] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_FW_ALT_PID_OUTPUTS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_FW_POS_PID_OUTPUTS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MC_VEL_X_PID_OUTPUTS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MC_VEL_Y_PID_OUTPUTS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MC_VEL_Z_PID_OUTPUTS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_MC_POS_XYZ_P_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_ROLL_PIDS] = OSD_POS(2, 10); + osdLayoutsConfig->item_pos[0][OSD_PITCH_PIDS] = OSD_POS(2, 11); + osdLayoutsConfig->item_pos[0][OSD_YAW_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_LEVEL_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_POS_XY_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_POS_Z_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_VEL_XY_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_VEL_Z_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_HEADING_P] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_BOARD_ALIGN_ROLL] = OSD_POS(2, 10); + osdLayoutsConfig->item_pos[0][OSD_BOARD_ALIGN_PITCH] = OSD_POS(2, 11); + osdLayoutsConfig->item_pos[0][OSD_RC_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_RC_YAW_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_THROTTLE_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_PITCH_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_ROLL_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_YAW_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_RC_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_RC_YAW_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_PITCH_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_ROLL_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_YAW_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_NAV_FW_CRUISE_THR] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_NAV_FW_PITCH2THR] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_FW_ALT_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_FW_POS_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MC_VEL_X_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MC_VEL_Y_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MC_VEL_Z_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MC_POS_XYZ_P_OUTPUTS] = OSD_POS(2, 12); - osdLayoutsConfig->item_pos[0][OSD_POWER] = OSD_POS(15, 1); + osdLayoutsConfig->item_pos[0][OSD_POWER] = OSD_POS(15, 1); - osdLayoutsConfig->item_pos[0][OSD_IMU_TEMPERATURE] = OSD_POS(19, 2); - osdLayoutsConfig->item_pos[0][OSD_BARO_TEMPERATURE] = OSD_POS(19, 3); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_0_TEMPERATURE] = OSD_POS(19, 4); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_1_TEMPERATURE] = OSD_POS(19, 5); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_2_TEMPERATURE] = OSD_POS(19, 6); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_3_TEMPERATURE] = OSD_POS(19, 7); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_4_TEMPERATURE] = OSD_POS(19, 8); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_5_TEMPERATURE] = OSD_POS(19, 9); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_6_TEMPERATURE] = OSD_POS(19, 10); - osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_7_TEMPERATURE] = OSD_POS(19, 11); + osdLayoutsConfig->item_pos[0][OSD_IMU_TEMPERATURE] = OSD_POS(19, 2); + osdLayoutsConfig->item_pos[0][OSD_BARO_TEMPERATURE] = OSD_POS(19, 3); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_0_TEMPERATURE] = OSD_POS(19, 4); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_1_TEMPERATURE] = OSD_POS(19, 5); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_2_TEMPERATURE] = OSD_POS(19, 6); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_3_TEMPERATURE] = OSD_POS(19, 7); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_4_TEMPERATURE] = OSD_POS(19, 8); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_5_TEMPERATURE] = OSD_POS(19, 9); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_6_TEMPERATURE] = OSD_POS(19, 10); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_7_TEMPERATURE] = OSD_POS(19, 11); - osdLayoutsConfig->item_pos[0][OSD_AIR_SPEED] = OSD_POS(3, 5); - osdLayoutsConfig->item_pos[0][OSD_WIND_SPEED_HORIZONTAL] = OSD_POS(3, 6); - osdLayoutsConfig->item_pos[0][OSD_WIND_SPEED_VERTICAL] = OSD_POS(3, 7); + osdLayoutsConfig->item_pos[0][OSD_AIR_SPEED] = OSD_POS(3, 5); + osdLayoutsConfig->item_pos[0][OSD_WIND_SPEED_HORIZONTAL] = OSD_POS(3, 6); + osdLayoutsConfig->item_pos[0][OSD_WIND_SPEED_VERTICAL] = OSD_POS(3, 7); - osdLayoutsConfig->item_pos[0][OSD_GFORCE] = OSD_POS(12, 4); - osdLayoutsConfig->item_pos[0][OSD_GFORCE_X] = OSD_POS(12, 5); - osdLayoutsConfig->item_pos[0][OSD_GFORCE_Y] = OSD_POS(12, 6); - osdLayoutsConfig->item_pos[0][OSD_GFORCE_Z] = OSD_POS(12, 7); + osdLayoutsConfig->item_pos[0][OSD_GFORCE] = OSD_POS(12, 4); + osdLayoutsConfig->item_pos[0][OSD_GFORCE_X] = OSD_POS(12, 5); + osdLayoutsConfig->item_pos[0][OSD_GFORCE_Y] = OSD_POS(12, 6); + osdLayoutsConfig->item_pos[0][OSD_GFORCE_Z] = OSD_POS(12, 7); - osdLayoutsConfig->item_pos[0][OSD_VTX_POWER] = OSD_POS(3, 5); + osdLayoutsConfig->item_pos[0][OSD_VTX_POWER] = OSD_POS(3, 5); - osdLayoutsConfig->item_pos[0][OSD_GVAR_0] = OSD_POS(1, 1); - osdLayoutsConfig->item_pos[0][OSD_GVAR_1] = OSD_POS(1, 2); - osdLayoutsConfig->item_pos[0][OSD_GVAR_2] = OSD_POS(1, 3); - osdLayoutsConfig->item_pos[0][OSD_GVAR_3] = OSD_POS(1, 4); + osdLayoutsConfig->item_pos[0][OSD_GVAR_0] = OSD_POS(1, 1); + osdLayoutsConfig->item_pos[0][OSD_GVAR_1] = OSD_POS(1, 2); + osdLayoutsConfig->item_pos[0][OSD_GVAR_2] = OSD_POS(1, 3); + osdLayoutsConfig->item_pos[0][OSD_GVAR_3] = OSD_POS(1, 4); - osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_0] = OSD_POS(2, 7); - osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_1] = OSD_POS(2, 8); - osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_2] = OSD_POS(2, 9); - osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_3] = OSD_POS(2, 10); + osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_0] = OSD_POS(2, 7); + osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_1] = OSD_POS(2, 8); + osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_2] = OSD_POS(2, 9); + osdLayoutsConfig->item_pos[0][OSD_SWITCH_INDICATOR_3] = OSD_POS(2, 10); #if defined(USE_ESC_SENSOR) - osdLayoutsConfig->item_pos[0][OSD_ESC_RPM] = OSD_POS(1, 2); - osdLayoutsConfig->item_pos[0][OSD_ESC_TEMPERATURE] = OSD_POS(1, 3); + osdLayoutsConfig->item_pos[0][OSD_ESC_RPM] = OSD_POS(1, 2); + osdLayoutsConfig->item_pos[0][OSD_ESC_TEMPERATURE] = OSD_POS(1, 3); #endif #if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE) - osdLayoutsConfig->item_pos[0][OSD_RC_SOURCE] = OSD_POS(3, 4); + osdLayoutsConfig->item_pos[0][OSD_RC_SOURCE] = OSD_POS(3, 4); #endif #ifdef USE_POWER_LIMITS - osdLayoutsConfig->item_pos[0][OSD_PLIMIT_REMAINING_BURST_TIME] = OSD_POS(3, 4); - osdLayoutsConfig->item_pos[0][OSD_PLIMIT_ACTIVE_CURRENT_LIMIT] = OSD_POS(3, 5); - osdLayoutsConfig->item_pos[0][OSD_PLIMIT_ACTIVE_POWER_LIMIT] = OSD_POS(3, 6); + osdLayoutsConfig->item_pos[0][OSD_PLIMIT_REMAINING_BURST_TIME] = OSD_POS(3, 4); + osdLayoutsConfig->item_pos[0][OSD_PLIMIT_ACTIVE_CURRENT_LIMIT] = OSD_POS(3, 5); + osdLayoutsConfig->item_pos[0][OSD_PLIMIT_ACTIVE_POWER_LIMIT] = OSD_POS(3, 6); #endif - // Under OSD_FLYMODE. TODO: Might not be visible on NTSC? - osdLayoutsConfig->item_pos[0][OSD_MESSAGES] = OSD_POS(1, 13) | OSD_VISIBLE_FLAG; + // Under OSD_FLYMODE. TODO: Might not be visible on NTSC? + osdLayoutsConfig->item_pos[0][OSD_MESSAGES] = OSD_POS(1, 13) | OSD_VISIBLE_FLAG; - for (unsigned ii = 1; ii < OSD_LAYOUT_COUNT; ii++) { - for (unsigned jj = 0; jj < ARRAYLEN(osdLayoutsConfig->item_pos[0]); jj++) { - osdLayoutsConfig->item_pos[ii][jj] = osdLayoutsConfig->item_pos[0][jj] & ~OSD_VISIBLE_FLAG; - } - } + for (unsigned ii = 1; ii < OSD_LAYOUT_COUNT; ii++) { + for (unsigned jj = 0; jj < ARRAYLEN(osdLayoutsConfig->item_pos[0]); jj++) { + osdLayoutsConfig->item_pos[ii][jj] = osdLayoutsConfig->item_pos[0][jj] & ~OSD_VISIBLE_FLAG; + } + } } /** @@ -3882,648 +3882,648 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) * @return uint8_t The row number after the logo(s). */ uint8_t drawLogos(bool singular, uint8_t row) { - uint8_t logoRow = row; - uint8_t logoColOffset = 0; - bool usePilotLogo = (osdConfig()->use_pilot_logo && osdDisplayIsHD()); + uint8_t logoRow = row; + uint8_t logoColOffset = 0; + bool usePilotLogo = (osdConfig()->use_pilot_logo && osdDisplayIsHD()); #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is in use, the pilot logo cannot be used, due to font issues. - if (isBfCompatibleVideoSystem(osdConfig())) - usePilotLogo = false; + if (isBfCompatibleVideoSystem(osdConfig())) + usePilotLogo = false; #endif - uint8_t logoSpacing = osdConfig()->inav_to_pilot_logo_spacing; + uint8_t logoSpacing = osdConfig()->inav_to_pilot_logo_spacing; - if (logoSpacing > 0 && ((osdDisplayPort->cols % 2) != (logoSpacing % 2))) { - logoSpacing++; // Add extra 1 character space between logos, if the odd/even of the OSD cols doesn't match the odd/even of the logo spacing - } + if (logoSpacing > 0 && ((osdDisplayPort->cols % 2) != (logoSpacing % 2))) { + logoSpacing++; // Add extra 1 character space between logos, if the odd/even of the OSD cols doesn't match the odd/even of the logo spacing + } - // Draw Logo(s) - if (usePilotLogo && !singular) { - logoColOffset = ((osdDisplayPort->cols - (SYM_LOGO_WIDTH * 2)) - logoSpacing) / 2; - } else { - logoColOffset = floor((osdDisplayPort->cols - SYM_LOGO_WIDTH) / 2.0f); - } + // Draw Logo(s) + if (usePilotLogo && !singular) { + logoColOffset = ((osdDisplayPort->cols - (SYM_LOGO_WIDTH * 2)) - logoSpacing) / 2; + } else { + logoColOffset = floor((osdDisplayPort->cols - SYM_LOGO_WIDTH) / 2.0f); + } - // Draw INAV logo - if ((singular && !usePilotLogo) || !singular) { - unsigned logo_c = SYM_LOGO_START; - uint8_t logo_x = logoColOffset; - for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) { - for (uint8_t lCol = 0; lCol < SYM_LOGO_WIDTH; lCol++) { - displayWriteChar(osdDisplayPort, logo_x + lCol, logoRow, logo_c++); - } - logoRow++; - } - } + // Draw INAV logo + if ((singular && !usePilotLogo) || !singular) { + unsigned logo_c = SYM_LOGO_START; + uint8_t logo_x = logoColOffset; + for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) { + for (uint8_t lCol = 0; lCol < SYM_LOGO_WIDTH; lCol++) { + displayWriteChar(osdDisplayPort, logo_x + lCol, logoRow, logo_c++); + } + logoRow++; + } + } - // Draw the pilot logo - if (usePilotLogo) { - unsigned logo_c = SYM_PILOT_LOGO_LRG_START; - uint8_t logo_x = 0; - logoRow = row; - if (singular) { - logo_x = logoColOffset; - } else { - logo_x = logoColOffset + SYM_LOGO_WIDTH + logoSpacing; - } - - for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) { - for (uint8_t lCol = 0; lCol < SYM_LOGO_WIDTH; lCol++) { - displayWriteChar(osdDisplayPort, logo_x + lCol, logoRow, logo_c++); - } - logoRow++; - } - } + // Draw the pilot logo + if (usePilotLogo) { + unsigned logo_c = SYM_PILOT_LOGO_LRG_START; + uint8_t logo_x = 0; + logoRow = row; + if (singular) { + logo_x = logoColOffset; + } else { + logo_x = logoColOffset + SYM_LOGO_WIDTH + logoSpacing; + } + + for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) { + for (uint8_t lCol = 0; lCol < SYM_LOGO_WIDTH; lCol++) { + displayWriteChar(osdDisplayPort, logo_x + lCol, logoRow, logo_c++); + } + logoRow++; + } + } - return logoRow; + return logoRow; } uint8_t drawStats(uint8_t row) { #ifdef USE_STATS - char string_buffer[30]; - uint8_t statNameX = (osdDisplayPort->cols - 22) / 2; - uint8_t statValueX = statNameX + 21; + char string_buffer[30]; + uint8_t statNameX = (osdDisplayPort->cols - 22) / 2; + uint8_t statValueX = statNameX + 21; - if (statsConfig()->stats_enabled) { - displayWrite(osdDisplayPort, statNameX, row, "ODOMETER:"); - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_MILE)); - string_buffer[5] = SYM_MI; - break; - default: - case OSD_UNIT_GA: - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_NAUTICALMILE)); - string_buffer[5] = SYM_NM; - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_KILOMETER)); - string_buffer[5] = SYM_KM; - break; - } - string_buffer[6] = '\0'; - displayWrite(osdDisplayPort, statValueX-5, row, string_buffer); + if (statsConfig()->stats_enabled) { + displayWrite(osdDisplayPort, statNameX, row, "ODOMETER:"); + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_MILE)); + string_buffer[5] = SYM_MI; + break; + default: + case OSD_UNIT_GA: + tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_NAUTICALMILE)); + string_buffer[5] = SYM_NM; + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + tfp_sprintf(string_buffer, "%5d", (int)(statsConfig()->stats_total_dist / METERS_PER_KILOMETER)); + string_buffer[5] = SYM_KM; + break; + } + string_buffer[6] = '\0'; + displayWrite(osdDisplayPort, statValueX-5, row, string_buffer); - displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL TIME:"); - uint32_t tot_mins = statsConfig()->stats_total_time / 60; - tfp_sprintf(string_buffer, "%2d:%02dH:M", (int)(tot_mins / 60), (int)(tot_mins % 60)); - displayWrite(osdDisplayPort, statValueX-7, row, string_buffer); + displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL TIME:"); + uint32_t tot_mins = statsConfig()->stats_total_time / 60; + tfp_sprintf(string_buffer, "%2d:%02dH:M", (int)(tot_mins / 60), (int)(tot_mins % 60)); + displayWrite(osdDisplayPort, statValueX-7, row, string_buffer); #ifdef USE_ADC - if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) { - displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL ENERGY:"); - osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4); - displayWrite(osdDisplayPort, statValueX-4, row, string_buffer); - displayWriteChar(osdDisplayPort, statValueX, row, SYM_WH); + if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) { + displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL ENERGY:"); + osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4); + displayWrite(osdDisplayPort, statValueX-4, row, string_buffer); + displayWriteChar(osdDisplayPort, statValueX, row, SYM_WH); - displayWrite(osdDisplayPort, statNameX, ++row, "AVG EFFICIENCY:"); - if (statsConfig()->stats_total_dist) { - uint32_t avg_efficiency = statsConfig()->stats_total_energy / (statsConfig()->stats_total_dist / METERS_PER_KILOMETER); // mWh/km - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); - string_buffer[3] = SYM_WH_MI; - break; - case OSD_UNIT_GA: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); - string_buffer[3] = SYM_WH_NM; - break; - default: - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3); - string_buffer[3] = SYM_WH_KM; - break; - } - } else { - string_buffer[0] = string_buffer[1] = string_buffer[2] = '-'; - } - string_buffer[4] = '\0'; - displayWrite(osdDisplayPort, statValueX-3, row++, string_buffer); - } + displayWrite(osdDisplayPort, statNameX, ++row, "AVG EFFICIENCY:"); + if (statsConfig()->stats_total_dist) { + uint32_t avg_efficiency = statsConfig()->stats_total_energy / (statsConfig()->stats_total_dist / METERS_PER_KILOMETER); // mWh/km + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); + string_buffer[3] = SYM_WH_MI; + break; + case OSD_UNIT_GA: + osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); + string_buffer[3] = SYM_WH_NM; + break; + default: + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3); + string_buffer[3] = SYM_WH_KM; + break; + } + } else { + string_buffer[0] = string_buffer[1] = string_buffer[2] = '-'; + } + string_buffer[4] = '\0'; + displayWrite(osdDisplayPort, statValueX-3, row++, string_buffer); + } #endif // USE_ADC - } + } #endif // USE_STATS - return row; + return row; } static void osdSetNextRefreshIn(uint32_t timeMs) { - resumeRefreshAt = micros() + timeMs * 1000; - refreshWaitForResumeCmdRelease = true; + resumeRefreshAt = micros() + timeMs * 1000; + refreshWaitForResumeCmdRelease = true; } static void osdCompleteAsyncInitialization(void) { - if (!displayIsReady(osdDisplayPort)) { - // Update the display. - // XXX: Rename displayDrawScreen() and associated functions - // to displayUpdate() - displayDrawScreen(osdDisplayPort); - return; - } + if (!displayIsReady(osdDisplayPort)) { + // Update the display. + // XXX: Rename displayDrawScreen() and associated functions + // to displayUpdate() + displayDrawScreen(osdDisplayPort); + return; + } - osdDisplayIsReady = true; + osdDisplayIsReady = true; #if defined(USE_CANVAS) - if (osdConfig()->force_grid) { - osdDisplayHasCanvas = false; - } else { - osdDisplayHasCanvas = displayGetCanvas(&osdCanvas, osdDisplayPort); - } + if (osdConfig()->force_grid) { + osdDisplayHasCanvas = false; + } else { + osdDisplayHasCanvas = displayGetCanvas(&osdCanvas, osdDisplayPort); + } #endif - displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); - displayClearScreen(osdDisplayPort); + displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); + displayClearScreen(osdDisplayPort); - uint8_t y = 1; - displayFontMetadata_t metadata; - bool fontHasMetadata = displayGetFontMetadata(&metadata, osdDisplayPort); - LOG_DEBUG(OSD, "Font metadata version %s: %u (%u chars)", - fontHasMetadata ? "Y" : "N", metadata.version, metadata.charCount); + uint8_t y = 1; + displayFontMetadata_t metadata; + bool fontHasMetadata = displayGetFontMetadata(&metadata, osdDisplayPort); + LOG_DEBUG(OSD, "Font metadata version %s: %u (%u chars)", + fontHasMetadata ? "Y" : "N", metadata.version, metadata.charCount); - if (fontHasMetadata && metadata.charCount > 256) { - hasExtendedFont = true; - - y = drawLogos(false, y); - y++; - } else if (!fontHasMetadata) { - const char *m = "INVALID FONT"; - displayWrite(osdDisplayPort, OSD_CENTER_S(m), y++, m); - } + if (fontHasMetadata && metadata.charCount > 256) { + hasExtendedFont = true; + + y = drawLogos(false, y); + y++; + } else if (!fontHasMetadata) { + const char *m = "INVALID FONT"; + displayWrite(osdDisplayPort, OSD_CENTER_S(m), y++, m); + } - if (fontHasMetadata && metadata.version < OSD_MIN_FONT_VERSION) { - const char *m = "INVALID FONT VERSION"; - displayWrite(osdDisplayPort, OSD_CENTER_S(m), y++, m); - } + if (fontHasMetadata && metadata.version < OSD_MIN_FONT_VERSION) { + const char *m = "INVALID FONT VERSION"; + displayWrite(osdDisplayPort, OSD_CENTER_S(m), y++, m); + } - char string_buffer[30]; - tfp_sprintf(string_buffer, "INAV VERSION: %s", FC_VERSION_STRING); - uint8_t xPos = (osdDisplayPort->cols - 19) / 2; // Automatically centre, regardless of resolution. In the case of odd number screens, bias to the left. - displayWrite(osdDisplayPort, xPos, y++, string_buffer); + char string_buffer[30]; + tfp_sprintf(string_buffer, "INAV VERSION: %s", FC_VERSION_STRING); + uint8_t xPos = (osdDisplayPort->cols - 19) / 2; // Automatically centre, regardless of resolution. In the case of odd number screens, bias to the left. + displayWrite(osdDisplayPort, xPos, y++, string_buffer); #ifdef USE_CMS - displayWrite(osdDisplayPort, xPos+2, y++, CMS_STARTUP_HELP_TEXT1); - displayWrite(osdDisplayPort, xPos+6, y++, CMS_STARTUP_HELP_TEXT2); - displayWrite(osdDisplayPort, xPos+6, y++, CMS_STARTUP_HELP_TEXT3); + displayWrite(osdDisplayPort, xPos+2, y++, CMS_STARTUP_HELP_TEXT1); + displayWrite(osdDisplayPort, xPos+6, y++, CMS_STARTUP_HELP_TEXT2); + displayWrite(osdDisplayPort, xPos+6, y++, CMS_STARTUP_HELP_TEXT3); #endif #ifdef USE_STATS - y = drawStats(++y); + y = drawStats(++y); #endif - displayCommitTransaction(osdDisplayPort); - displayResync(osdDisplayPort); - osdSetNextRefreshIn(SPLASH_SCREEN_DISPLAY_TIME); + displayCommitTransaction(osdDisplayPort); + displayResync(osdDisplayPort); + osdSetNextRefreshIn(SPLASH_SCREEN_DISPLAY_TIME); } void osdInit(displayPort_t *osdDisplayPortToUse) { - if (!osdDisplayPortToUse) - return; + if (!osdDisplayPortToUse) + return; - BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(63,63)); + BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(63,63)); - osdDisplayPort = osdDisplayPortToUse; + osdDisplayPort = osdDisplayPortToUse; #ifdef USE_CMS - cmsDisplayPortRegister(osdDisplayPort); + cmsDisplayPortRegister(osdDisplayPort); #endif - armState = ARMING_FLAG(ARMED); - osdCompleteAsyncInitialization(); + armState = ARMING_FLAG(ARMED); + osdCompleteAsyncInitialization(); } static void osdResetStats(void) { - stats.max_current = 0; - stats.max_power = 0; - stats.max_speed = 0; - stats.max_3D_speed = 0; - stats.max_air_speed = 0; - stats.min_voltage = 5000; - stats.min_rssi = 99; - stats.min_lq = 300; - stats.min_rssi_dbm = 0; - stats.max_altitude = 0; + stats.max_current = 0; + stats.max_power = 0; + stats.max_speed = 0; + stats.max_3D_speed = 0; + stats.max_air_speed = 0; + stats.min_voltage = 5000; + stats.min_rssi = 99; + stats.min_lq = 300; + stats.min_rssi_dbm = 0; + stats.max_altitude = 0; } static void osdUpdateStats(void) { - int32_t value; + int32_t value; - if (feature(FEATURE_GPS)) { - value = osdGet3DSpeed(); - const float airspeed_estimate = getAirspeedEstimate(); + if (feature(FEATURE_GPS)) { + value = osdGet3DSpeed(); + const float airspeed_estimate = getAirspeedEstimate(); - if (stats.max_3D_speed < value) - stats.max_3D_speed = value; + if (stats.max_3D_speed < value) + stats.max_3D_speed = value; - if (stats.max_speed < gpsSol.groundSpeed) - stats.max_speed = gpsSol.groundSpeed; + if (stats.max_speed < gpsSol.groundSpeed) + stats.max_speed = gpsSol.groundSpeed; - if (stats.max_air_speed < airspeed_estimate) - stats.max_air_speed = airspeed_estimate; + if (stats.max_air_speed < airspeed_estimate) + stats.max_air_speed = airspeed_estimate; - if (stats.max_distance < GPS_distanceToHome) - stats.max_distance = GPS_distanceToHome; - } + if (stats.max_distance < GPS_distanceToHome) + stats.max_distance = GPS_distanceToHome; + } - value = getBatteryVoltage(); - if (stats.min_voltage > value) - stats.min_voltage = value; + value = getBatteryVoltage(); + if (stats.min_voltage > value) + stats.min_voltage = value; - value = abs(getAmperage()); - if (stats.max_current < value) - stats.max_current = value; + value = abs(getAmperage()); + if (stats.max_current < value) + stats.max_current = value; - value = labs(getPower()); - if (stats.max_power < value) - stats.max_power = value; + value = labs(getPower()); + if (stats.max_power < value) + stats.max_power = value; - value = osdConvertRSSI(); - if (stats.min_rssi > value) - stats.min_rssi = value; + value = osdConvertRSSI(); + if (stats.min_rssi > value) + stats.min_rssi = value; - value = osdGetCrsfLQ(); - if (stats.min_lq > value) - stats.min_lq = value; + value = osdGetCrsfLQ(); + if (stats.min_lq > value) + stats.min_lq = value; - if (!failsafeIsReceivingRxData()) - stats.min_lq = 0; + if (!failsafeIsReceivingRxData()) + stats.min_lq = 0; - value = osdGetCrsfdBm(); - if (stats.min_rssi_dbm > value) - stats.min_rssi_dbm = value; + value = osdGetCrsfdBm(); + if (stats.min_rssi_dbm > value) + stats.min_rssi_dbm = value; - stats.max_altitude = MAX(stats.max_altitude, osdGetAltitude()); + stats.max_altitude = MAX(stats.max_altitude, osdGetAltitude()); } static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) { - const char * disarmReasonStr[DISARM_REASON_COUNT] = { "UNKNOWN", "TIMEOUT", "STICKS", "SWITCH", "SWITCH", "KILLSW", "FAILSAFE", "NAV SYS", "LANDING"}; - uint8_t top = 1; // Start one line down leaving space at the top of the screen. - size_t multiValueLengthOffset = 0; + const char * disarmReasonStr[DISARM_REASON_COUNT] = { "UNKNOWN", "TIMEOUT", "STICKS", "SWITCH", "SWITCH", "KILLSW", "FAILSAFE", "NAV SYS", "LANDING"}; + uint8_t top = 1; // Start one line down leaving space at the top of the screen. + size_t multiValueLengthOffset = 0; - const uint8_t statNameX = osdDisplayIsHD() ? 11 : 1; - const uint8_t statValuesX = osdDisplayIsHD() ? 30 : 20; - char buff[10]; + const uint8_t statNameX = osdDisplayIsHD() ? 11 : 1; + const uint8_t statValuesX = osdDisplayIsHD() ? 30 : 20; + char buff[10]; - if (page > 1) - page = 0; + if (page > 1) + page = 0; - displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); - displayClearScreen(osdDisplayPort); + displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); + displayClearScreen(osdDisplayPort); - if (isSinglePageStatsCompatible) { - displayWrite(osdDisplayPort, statNameX, top++, "--- STATS ---"); - } else if (page == 0) { - displayWrite(osdDisplayPort, statNameX, top++, "--- STATS --- 1/2 ->"); - } else if (page == 1) { - displayWrite(osdDisplayPort, statNameX, top++, "--- STATS --- <- 2/2"); - } + if (isSinglePageStatsCompatible) { + displayWrite(osdDisplayPort, statNameX, top++, "--- STATS ---"); + } else if (page == 0) { + displayWrite(osdDisplayPort, statNameX, top++, "--- STATS --- 1/2 ->"); + } else if (page == 1) { + displayWrite(osdDisplayPort, statNameX, top++, "--- STATS --- <- 2/2"); + } - if (isSinglePageStatsCompatible || page == 0) { - if (feature(FEATURE_GPS)) { - if (isSinglePageStatsCompatible) { - displayWrite(osdDisplayPort, statNameX, top, "MAX/AVG SPEED :"); - osdFormatVelocityStr(buff, stats.max_3D_speed, true, false); - osdLeftAlignString(buff); - strcat(osdFormatTrimWhiteSpace(buff),"/"); - multiValueLengthOffset = strlen(buff); - displayWrite(osdDisplayPort, statValuesX, top, buff); - osdGenerateAverageVelocityStr(buff); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); - } else { - displayWrite(osdDisplayPort, statNameX, top, "MAX SPEED :"); - osdFormatVelocityStr(buff, stats.max_3D_speed, true, false); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + if (isSinglePageStatsCompatible || page == 0) { + if (feature(FEATURE_GPS)) { + if (isSinglePageStatsCompatible) { + displayWrite(osdDisplayPort, statNameX, top, "MAX/AVG SPEED :"); + osdFormatVelocityStr(buff, stats.max_3D_speed, true, false); + osdLeftAlignString(buff); + strcat(osdFormatTrimWhiteSpace(buff),"/"); + multiValueLengthOffset = strlen(buff); + displayWrite(osdDisplayPort, statValuesX, top, buff); + osdGenerateAverageVelocityStr(buff); + osdLeftAlignString(buff); + displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); + } else { + displayWrite(osdDisplayPort, statNameX, top, "MAX SPEED :"); + osdFormatVelocityStr(buff, stats.max_3D_speed, true, false); + osdLeftAlignString(buff); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - displayWrite(osdDisplayPort, statNameX, top, "AVG SPEED :"); - osdGenerateAverageVelocityStr(buff); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } + displayWrite(osdDisplayPort, statNameX, top, "AVG SPEED :"); + osdGenerateAverageVelocityStr(buff); + osdLeftAlignString(buff); + displayWrite(osdDisplayPort, statValuesX, top++, buff); + } - displayWrite(osdDisplayPort, statNameX, top, "MAX DISTANCE :"); - osdFormatDistanceStr(buff, stats.max_distance*100); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, statNameX, top, "MAX DISTANCE :"); + osdFormatDistanceStr(buff, stats.max_distance*100); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - displayWrite(osdDisplayPort, statNameX, top, "TRAVELED DISTANCE:"); - osdFormatDistanceStr(buff, getTotalTravelDistance()); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } + displayWrite(osdDisplayPort, statNameX, top, "TRAVELED DISTANCE:"); + osdFormatDistanceStr(buff, getTotalTravelDistance()); + displayWrite(osdDisplayPort, statValuesX, top++, buff); + } - displayWrite(osdDisplayPort, statNameX, top, "MAX ALTITUDE :"); - osdFormatAltitudeStr(buff, stats.max_altitude); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, statNameX, top, "MAX ALTITUDE :"); + osdFormatAltitudeStr(buff, stats.max_altitude); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - switch (rxConfig()->serialrx_provider) { - case SERIALRX_CRSF: - if (isSinglePageStatsCompatible) { - displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI %/DBM :"); - itoa(stats.min_rssi, buff, 10); - osdLeftAlignString(buff); - strcat(osdFormatTrimWhiteSpace(buff), "%/"); - multiValueLengthOffset = strlen(buff); - displayWrite(osdDisplayPort, statValuesX, top, buff); - itoa(stats.min_rssi_dbm, buff, 10); - tfp_sprintf(buff, "%s%c", buff, SYM_DBM); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); - } else { - displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI % :"); - itoa(stats.min_rssi, buff, 10); - strcat(buff, "%"); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + switch (rxConfig()->serialrx_provider) { + case SERIALRX_CRSF: + if (isSinglePageStatsCompatible) { + displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI %/DBM :"); + itoa(stats.min_rssi, buff, 10); + osdLeftAlignString(buff); + strcat(osdFormatTrimWhiteSpace(buff), "%/"); + multiValueLengthOffset = strlen(buff); + displayWrite(osdDisplayPort, statValuesX, top, buff); + itoa(stats.min_rssi_dbm, buff, 10); + tfp_sprintf(buff, "%s%c", buff, SYM_DBM); + osdLeftAlignString(buff); + displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); + } else { + displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI % :"); + itoa(stats.min_rssi, buff, 10); + strcat(buff, "%"); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI DBM :"); - itoa(stats.min_rssi_dbm, buff, 10); - tfp_sprintf(buff, "%s%c", buff, SYM_DBM); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } + displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI DBM :"); + itoa(stats.min_rssi_dbm, buff, 10); + tfp_sprintf(buff, "%s%c", buff, SYM_DBM); + displayWrite(osdDisplayPort, statValuesX, top++, buff); + } - displayWrite(osdDisplayPort, statNameX, top, "MIN LQ :"); - itoa(stats.min_lq, buff, 10); - strcat(buff, "%"); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - break; - default: - displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI :"); - itoa(stats.min_rssi, buff, 10); - strcat(buff, "%"); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } + displayWrite(osdDisplayPort, statNameX, top, "MIN LQ :"); + itoa(stats.min_lq, buff, 10); + strcat(buff, "%"); + displayWrite(osdDisplayPort, statValuesX, top++, buff); + break; + default: + displayWrite(osdDisplayPort, statNameX, top, "MIN RSSI :"); + itoa(stats.min_rssi, buff, 10); + strcat(buff, "%"); + displayWrite(osdDisplayPort, statValuesX, top++, buff); + } - displayWrite(osdDisplayPort, statNameX, top, "FLY TIME :"); - uint16_t flySeconds = getFlightTime(); - uint16_t flyMinutes = flySeconds / 60; - flySeconds %= 60; - uint16_t flyHours = flyMinutes / 60; - flyMinutes %= 60; - tfp_sprintf(buff, "%02u:%02u:%02u", flyHours, flyMinutes, flySeconds); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, statNameX, top, "FLY TIME :"); + uint16_t flySeconds = getFlightTime(); + uint16_t flyMinutes = flySeconds / 60; + flySeconds %= 60; + uint16_t flyHours = flyMinutes / 60; + flyMinutes %= 60; + tfp_sprintf(buff, "%02u:%02u:%02u", flyHours, flyMinutes, flySeconds); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - displayWrite(osdDisplayPort, statNameX, top, "DISARMED BY :"); - displayWrite(osdDisplayPort, statValuesX, top++, disarmReasonStr[getDisarmReason()]); - } - - if (isSinglePageStatsCompatible || page == 1) { - if (osdConfig()->stats_min_voltage_unit == OSD_STATS_MIN_VOLTAGE_UNIT_BATTERY) { - displayWrite(osdDisplayPort, statNameX, top, "MIN BATTERY VOLT :"); - osdFormatCentiNumber(buff, stats.min_voltage, 0, osdConfig()->main_voltage_decimals, 0, osdConfig()->main_voltage_decimals + 2); - } else { - displayWrite(osdDisplayPort, statNameX, top, "MIN CELL VOLTAGE :"); - osdFormatCentiNumber(buff, stats.min_voltage/getBatteryCellCount(), 0, 2, 0, 3); - } - tfp_sprintf(buff, "%s%c", buff, SYM_VOLT); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, statNameX, top, "DISARMED BY :"); + displayWrite(osdDisplayPort, statValuesX, top++, disarmReasonStr[getDisarmReason()]); + } + + if (isSinglePageStatsCompatible || page == 1) { + if (osdConfig()->stats_min_voltage_unit == OSD_STATS_MIN_VOLTAGE_UNIT_BATTERY) { + displayWrite(osdDisplayPort, statNameX, top, "MIN BATTERY VOLT :"); + osdFormatCentiNumber(buff, stats.min_voltage, 0, osdConfig()->main_voltage_decimals, 0, osdConfig()->main_voltage_decimals + 2); + } else { + displayWrite(osdDisplayPort, statNameX, top, "MIN CELL VOLTAGE :"); + osdFormatCentiNumber(buff, stats.min_voltage/getBatteryCellCount(), 0, 2, 0, 3); + } + tfp_sprintf(buff, "%s%c", buff, SYM_VOLT); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - if (feature(FEATURE_CURRENT_METER)) { - displayWrite(osdDisplayPort, statNameX, top, "MAX CURRENT :"); - osdFormatCentiNumber(buff, stats.max_current, 0, 2, 0, 3); - tfp_sprintf(buff, "%s%c", buff, SYM_AMP); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + if (feature(FEATURE_CURRENT_METER)) { + displayWrite(osdDisplayPort, statNameX, top, "MAX CURRENT :"); + osdFormatCentiNumber(buff, stats.max_current, 0, 2, 0, 3); + tfp_sprintf(buff, "%s%c", buff, SYM_AMP); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - displayWrite(osdDisplayPort, statNameX, top, "MAX POWER :"); - bool kiloWatt = osdFormatCentiNumber(buff, stats.max_power, 1000, 2, 2, 3); - buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; - buff[4] = '\0'; - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, statNameX, top, "MAX POWER :"); + bool kiloWatt = osdFormatCentiNumber(buff, stats.max_power, 1000, 2, 2, 3); + buff[3] = kiloWatt ? SYM_KILOWATT : SYM_WATT; + buff[4] = '\0'; + displayWrite(osdDisplayPort, statValuesX, top++, buff); - displayWrite(osdDisplayPort, statNameX, top, "USED CAPACITY :"); - if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - tfp_sprintf(buff, "%d%c", (int)getMAhDrawn(), SYM_MAH); - } else { - osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3); - tfp_sprintf(buff, "%s%c", buff, SYM_WH); - } - displayWrite(osdDisplayPort, statValuesX, top++, buff); + displayWrite(osdDisplayPort, statNameX, top, "USED CAPACITY :"); + if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { + tfp_sprintf(buff, "%d%c", (int)getMAhDrawn(), SYM_MAH); + } else { + osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3); + tfp_sprintf(buff, "%s%c", buff, SYM_WH); + } + displayWrite(osdDisplayPort, statValuesX, top++, buff); - int32_t totalDistance = getTotalTravelDistance(); - bool moreThanAh = false; - bool efficiencyValid = totalDistance >= 10000; - if (feature(FEATURE_GPS)) { - displayWrite(osdDisplayPort, statNameX, top, "AVG EFFICIENCY :"); - uint8_t digits = 3U; // Total number of digits (including decimal point) - #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values - if (isBfCompatibleVideoSystem(osdConfig())) { - // Add one digit so no switch to scaled decimal occurs above 99 - digits = 4U; - } - #endif - switch (osdConfig()->units) { - case OSD_UNIT_UK: - FALLTHROUGH; - case OSD_UNIT_IMPERIAL: - if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_MILE / totalDistance), 1000, 0, 2, digits); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_MI); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_MAH_MI_0; - buff[4] = SYM_MAH_MI_1; - buff[5] = '\0'; - } - } else { - osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits); - tfp_sprintf(buff, "%s%c", buff, SYM_WH_MI); - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - } - } - break; - case OSD_UNIT_GA: - if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_NAUTICALMILE / totalDistance), 1000, 0, 2, digits); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_MAH_NM_0; - buff[4] = SYM_MAH_NM_1; - buff[5] = '\0'; - } - } else { - osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_NAUTICALMILE / totalDistance), 0, 2, 0, digits); - tfp_sprintf(buff, "%s%c", buff, SYM_WH_NM); - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - } - } - break; - case OSD_UNIT_METRIC_MPH: - FALLTHROUGH; - case OSD_UNIT_METRIC: - if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { - moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000000.0f / totalDistance), 1000, 0, 2, digits); - if (!moreThanAh) { - tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); - } else { - tfp_sprintf(buff, "%s%c", buff, SYM_AH_KM); - } - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - buff[3] = SYM_MAH_KM_0; - buff[4] = SYM_MAH_KM_1; - buff[5] = '\0'; - } - } else { - osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10000.0f / totalDistance), 0, 2, 0, digits); - tfp_sprintf(buff, "%s%c", buff, SYM_WH_KM); - if (!efficiencyValid) { - buff[0] = buff[1] = buff[2] = '-'; - } - } - break; - } - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX, top++, buff); - } - } + int32_t totalDistance = getTotalTravelDistance(); + bool moreThanAh = false; + bool efficiencyValid = totalDistance >= 10000; + if (feature(FEATURE_GPS)) { + displayWrite(osdDisplayPort, statNameX, top, "AVG EFFICIENCY :"); + uint8_t digits = 3U; // Total number of digits (including decimal point) + #ifndef DISABLE_MSP_BF_COMPAT // IF BFCOMPAT is not supported, there's no need to check for it and change the values + if (isBfCompatibleVideoSystem(osdConfig())) { + // Add one digit so no switch to scaled decimal occurs above 99 + digits = 4U; + } + #endif + switch (osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { + moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_MILE / totalDistance), 1000, 0, 2, digits); + if (!moreThanAh) { + tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_MI_0, SYM_MAH_MI_1); + } else { + tfp_sprintf(buff, "%s%c", buff, SYM_AH_MI); + } + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + buff[3] = SYM_MAH_MI_0; + buff[4] = SYM_MAH_MI_1; + buff[5] = '\0'; + } + } else { + osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits); + tfp_sprintf(buff, "%s%c", buff, SYM_WH_MI); + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + } + } + break; + case OSD_UNIT_GA: + if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { + moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000.0f * METERS_PER_NAUTICALMILE / totalDistance), 1000, 0, 2, digits); + if (!moreThanAh) { + tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_NM_0, SYM_MAH_NM_1); + } else { + tfp_sprintf(buff, "%s%c", buff, SYM_AH_NM); + } + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + buff[3] = SYM_MAH_NM_0; + buff[4] = SYM_MAH_NM_1; + buff[5] = '\0'; + } + } else { + osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_NAUTICALMILE / totalDistance), 0, 2, 0, digits); + tfp_sprintf(buff, "%s%c", buff, SYM_WH_NM); + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + } + } + break; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + if (osdConfig()->stats_energy_unit == OSD_STATS_ENERGY_UNIT_MAH) { + moreThanAh = osdFormatCentiNumber(buff, (int32_t)(getMAhDrawn() * 10000000.0f / totalDistance), 1000, 0, 2, digits); + if (!moreThanAh) { + tfp_sprintf(buff, "%s%c%c", buff, SYM_MAH_KM_0, SYM_MAH_KM_1); + } else { + tfp_sprintf(buff, "%s%c", buff, SYM_AH_KM); + } + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + buff[3] = SYM_MAH_KM_0; + buff[4] = SYM_MAH_KM_1; + buff[5] = '\0'; + } + } else { + osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10000.0f / totalDistance), 0, 2, 0, digits); + tfp_sprintf(buff, "%s%c", buff, SYM_WH_KM); + if (!efficiencyValid) { + buff[0] = buff[1] = buff[2] = '-'; + } + } + break; + } + osdLeftAlignString(buff); + displayWrite(osdDisplayPort, statValuesX, top++, buff); + } + } - const float max_gforce = accGetMeasuredMaxG(); - displayWrite(osdDisplayPort, statNameX, top, "MAX G-FORCE :"); - osdFormatCentiNumber(buff, max_gforce * 100, 0, 2, 0, 3); - displayWrite(osdDisplayPort, statValuesX, top++, buff); + const float max_gforce = accGetMeasuredMaxG(); + displayWrite(osdDisplayPort, statNameX, top, "MAX G-FORCE :"); + osdFormatCentiNumber(buff, max_gforce * 100, 0, 2, 0, 3); + displayWrite(osdDisplayPort, statValuesX, top++, buff); - const acc_extremes_t *acc_extremes = accGetMeasuredExtremes(); - const float acc_extremes_min = acc_extremes[Z].min; - const float acc_extremes_max = acc_extremes[Z].max; - displayWrite(osdDisplayPort, statNameX, top, "MIN/MAX Z G-FORCE:"); - osdFormatCentiNumber(buff, acc_extremes_min * 100, 0, 2, 0, 4); - osdLeftAlignString(buff); - strcat(osdFormatTrimWhiteSpace(buff),"/"); - multiValueLengthOffset = strlen(buff); - displayWrite(osdDisplayPort, statValuesX, top, buff); - osdFormatCentiNumber(buff, acc_extremes_max * 100, 0, 2, 0, 3); - osdLeftAlignString(buff); - displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); - } + const acc_extremes_t *acc_extremes = accGetMeasuredExtremes(); + const float acc_extremes_min = acc_extremes[Z].min; + const float acc_extremes_max = acc_extremes[Z].max; + displayWrite(osdDisplayPort, statNameX, top, "MIN/MAX Z G-FORCE:"); + osdFormatCentiNumber(buff, acc_extremes_min * 100, 0, 2, 0, 4); + osdLeftAlignString(buff); + strcat(osdFormatTrimWhiteSpace(buff),"/"); + multiValueLengthOffset = strlen(buff); + displayWrite(osdDisplayPort, statValuesX, top, buff); + osdFormatCentiNumber(buff, acc_extremes_max * 100, 0, 2, 0, 3); + osdLeftAlignString(buff); + displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); + } - if (savingSettings == true) { - displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS)); - } else if (notify_settings_saved > 0) { - if (millis() > notify_settings_saved) { - notify_settings_saved = 0; - } else { - displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(OSD_MSG_SETTINGS_SAVED)); - } - } + if (savingSettings == true) { + displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS)); + } else if (notify_settings_saved > 0) { + if (millis() > notify_settings_saved) { + notify_settings_saved = 0; + } else { + displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(OSD_MSG_SETTINGS_SAVED)); + } + } - displayCommitTransaction(osdDisplayPort); + displayCommitTransaction(osdDisplayPort); } // HD arming screen. based on the minimum HD OSD grid size of 50 x 18 static void osdShowHDArmScreen(void) { dateTime_t dt; - char buf[MAX(osdDisplayPort->cols, FORMATTED_DATE_TIME_BUFSIZE)]; - char buf2[MAX(osdDisplayPort->cols, FORMATTED_DATE_TIME_BUFSIZE)]; - char craftNameBuf[MAX_NAME_LENGTH]; - char versionBuf[osdDisplayPort->cols]; - uint8_t safehomeRow = 0; - uint8_t armScreenRow = 2; // Start at row 2 + char buf[MAX(osdDisplayPort->cols, FORMATTED_DATE_TIME_BUFSIZE)]; + char buf2[MAX(osdDisplayPort->cols, FORMATTED_DATE_TIME_BUFSIZE)]; + char craftNameBuf[MAX_NAME_LENGTH]; + char versionBuf[osdDisplayPort->cols]; + uint8_t safehomeRow = 0; + uint8_t armScreenRow = 2; // Start at row 2 - armScreenRow = drawLogos(false, armScreenRow); - armScreenRow++; + armScreenRow = drawLogos(false, armScreenRow); + armScreenRow++; - if (strlen(systemConfig()->craftName) > 0) { - osdFormatCraftName(craftNameBuf); - strcpy(buf2, "ARMED!"); - tfp_sprintf(buf, "%s - %s", craftNameBuf, buf2); - } else { - strcpy(buf, "ARMED!"); - } - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + if (strlen(systemConfig()->craftName) > 0) { + osdFormatCraftName(craftNameBuf); + strcpy(buf2, "ARMED!"); + tfp_sprintf(buf, "%s - %s", craftNameBuf, buf2); + } else { + strcpy(buf, "ARMED!"); + } + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); #if defined(USE_GPS) #if defined (USE_SAFE_HOME) - if (safehome_distance) { - safehomeRow = armScreenRow; - armScreenRow++; + if (safehome_distance) { + safehomeRow = armScreenRow; + armScreenRow++; } #endif // USE_SAFE_HOME #endif // USE_GPS armScreenRow++; - if (posControl.waypointListValid && posControl.waypointCount > 0) { + if (posControl.waypointListValid && posControl.waypointCount > 0) { #ifdef USE_MULTI_MISSION - tfp_sprintf(buf, "MISSION %u/%u (%u WP)", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + tfp_sprintf(buf, "MISSION %u/%u (%u WP)", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); #else - strcpy(buf, "*MISSION LOADED*"); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + strcpy(buf, "*MISSION LOADED*"); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); #endif - } - armScreenRow++; + } + armScreenRow++; #if defined(USE_GPS) - if (feature(FEATURE_GPS)) { - if (STATE(GPS_FIX_HOME)) { - if (osdConfig()->osd_home_position_arm_screen) { - osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat); - osdFormatCoordinate(buf2, SYM_LON, GPS_home.lon); - uint8_t gap = 1; - uint8_t col = strlen(buf) + strlen(buf2) + gap; + if (feature(FEATURE_GPS)) { + if (STATE(GPS_FIX_HOME)) { + if (osdConfig()->osd_home_position_arm_screen) { + osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat); + osdFormatCoordinate(buf2, SYM_LON, GPS_home.lon); + uint8_t gap = 1; + uint8_t col = strlen(buf) + strlen(buf2) + gap; - if ((osdDisplayPort->cols %2) != (col %2)) { - gap++; - col++; - } + if ((osdDisplayPort->cols %2) != (col %2)) { + gap++; + col++; + } - col = (osdDisplayPort->cols - col) / 2; + col = (osdDisplayPort->cols - col) / 2; - displayWrite(osdDisplayPort, col, armScreenRow, buf); - displayWrite(osdDisplayPort, col + strlen(buf) + gap, armScreenRow++, buf2); - - int digits = osdConfig()->plus_code_digits; - olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); - } - + displayWrite(osdDisplayPort, col, armScreenRow, buf); + displayWrite(osdDisplayPort, col + strlen(buf) + gap, armScreenRow++, buf2); + + int digits = osdConfig()->plus_code_digits; + olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + } + #if defined (USE_SAFE_HOME) - if (safehome_distance) { // safehome found during arming - if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) { - strcpy(buf, "SAFEHOME FOUND; MODE OFF"); - } else { - osdFormatDistanceStr(buf2, safehome_distance); - tfp_sprintf(buf, "%c SAFEHOME %u @ %s", SYM_HOME, safehome_index, buf2); - } - textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT; - // write this message below the ARMED message to make it obvious - displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, safehomeRow, buf, elemAttr); - } + if (safehome_distance) { // safehome found during arming + if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) { + strcpy(buf, "SAFEHOME FOUND; MODE OFF"); + } else { + osdFormatDistanceStr(buf2, safehome_distance); + tfp_sprintf(buf, "%c SAFEHOME %u @ %s", SYM_HOME, safehome_index, buf2); + } + textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT; + // write this message below the ARMED message to make it obvious + displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, safehomeRow, buf, elemAttr); + } #endif - } else { - strcpy(buf, "!NO HOME POSITION!"); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); - } + } else { + strcpy(buf, "!NO HOME POSITION!"); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + } armScreenRow++; - } + } #endif - if (rtcGetDateTimeLocal(&dt)) { - tfp_sprintf(buf, "%04u-%02u-%02u %02u:%02u:%02u", dt.year, dt.month, dt.day, dt.hours, dt.minutes, dt.seconds); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); - armScreenRow++; - } + if (rtcGetDateTimeLocal(&dt)) { + tfp_sprintf(buf, "%04u-%02u-%02u %02u:%02u:%02u", dt.year, dt.month, dt.day, dt.hours, dt.minutes, dt.seconds); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + armScreenRow++; + } - tfp_sprintf(versionBuf, "INAV VERSION: %s", FC_VERSION_STRING); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, armScreenRow++, versionBuf); + tfp_sprintf(versionBuf, "INAV VERSION: %s", FC_VERSION_STRING); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, armScreenRow++, versionBuf); armScreenRow++; #ifdef USE_STATS @@ -4535,80 +4535,80 @@ static void osdShowHDArmScreen(void) static void osdShowSDArmScreen(void) { dateTime_t dt; - char buf[MAX(osdDisplayPort->cols, FORMATTED_DATE_TIME_BUFSIZE)]; + char buf[MAX(osdDisplayPort->cols, FORMATTED_DATE_TIME_BUFSIZE)]; char buf2[MAX(osdDisplayPort->cols, FORMATTED_DATE_TIME_BUFSIZE)]; - char craftNameBuf[MAX_NAME_LENGTH]; - char versionBuf[osdDisplayPort->cols]; - // We need 12 visible rows, start row never < first fully visible row 1 - uint8_t armScreenRow = osdDisplayPort->rows > 13 ? (osdDisplayPort->rows - 12) / 2 : 1; + char craftNameBuf[MAX_NAME_LENGTH]; + char versionBuf[osdDisplayPort->cols]; + // We need 12 visible rows, start row never < first fully visible row 1 + uint8_t armScreenRow = osdDisplayPort->rows > 13 ? (osdDisplayPort->rows - 12) / 2 : 1; uint8_t safehomeRow = 0; - strcpy(buf, "ARMED!"); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + strcpy(buf, "ARMED!"); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); safehomeRow = armScreenRow; - armScreenRow++; + armScreenRow++; - if (strlen(systemConfig()->craftName) > 0) { - osdFormatCraftName(craftNameBuf); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(systemConfig()->craftName)) / 2, armScreenRow++, craftNameBuf ); - } + if (strlen(systemConfig()->craftName) > 0) { + osdFormatCraftName(craftNameBuf); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(systemConfig()->craftName)) / 2, armScreenRow++, craftNameBuf ); + } - if (posControl.waypointListValid && posControl.waypointCount > 0) { + if (posControl.waypointListValid && posControl.waypointCount > 0) { #ifdef USE_MULTI_MISSION - tfp_sprintf(buf, "MISSION %u/%u (%u WP)", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow, buf); + tfp_sprintf(buf, "MISSION %u/%u (%u WP)", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow, buf); #else - strcpy(buf, "*MISSION LOADED*"); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow, buf); + strcpy(buf, "*MISSION LOADED*"); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow, buf); #endif - } - armScreenRow++; + } + armScreenRow++; #if defined(USE_GPS) - if (feature(FEATURE_GPS)) { - if (STATE(GPS_FIX_HOME)) { - if (osdConfig()->osd_home_position_arm_screen) { - osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat); - osdFormatCoordinate(buf2, SYM_LON, GPS_home.lon); + if (feature(FEATURE_GPS)) { + if (STATE(GPS_FIX_HOME)) { + if (osdConfig()->osd_home_position_arm_screen) { + osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat); + osdFormatCoordinate(buf2, SYM_LON, GPS_home.lon); uint8_t gpsStartCol = (osdDisplayPort->cols - (strlen(buf) + strlen(buf2) + 2)) / 2; - displayWrite(osdDisplayPort, gpsStartCol, armScreenRow, buf); - displayWrite(osdDisplayPort, gpsStartCol + strlen(buf) + 2, armScreenRow++, buf2); - + displayWrite(osdDisplayPort, gpsStartCol, armScreenRow, buf); + displayWrite(osdDisplayPort, gpsStartCol + strlen(buf) + 2, armScreenRow++, buf2); + int digits = osdConfig()->plus_code_digits; - olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); - } + olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + } #if defined (USE_SAFE_HOME) - if (safehome_distance) { // safehome found during arming - if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) { - strcpy(buf, "SAFEHOME FOUND; MODE OFF"); - } else { - osdFormatDistanceStr(buf2, safehome_distance); + if (safehome_distance) { // safehome found during arming + if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) { + strcpy(buf, "SAFEHOME FOUND; MODE OFF"); + } else { + osdFormatDistanceStr(buf2, safehome_distance); tfp_sprintf(buf, "%c SAFEHOME %u @ %s", SYM_HOME, safehome_index, buf2); - } - textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT; - // write this message below the ARMED message to make it obvious - displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, safehomeRow, buf, elemAttr); - } + } + textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT; + // write this message below the ARMED message to make it obvious + displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, safehomeRow, buf, elemAttr); + } #endif - } else { - strcpy(buf, "!NO HOME POSITION!"); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); - } + } else { + strcpy(buf, "!NO HOME POSITION!"); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + } armScreenRow++; - } + } #endif if (rtcGetDateTimeLocal(&dt)) { - tfp_sprintf(buf, "%04u-%02u-%02u %02u:%02u:%02u", dt.year, dt.month, dt.day, dt.hours, dt.minutes, dt.seconds); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); - armScreenRow++; - } + tfp_sprintf(buf, "%04u-%02u-%02u %02u:%02u:%02u", dt.year, dt.month, dt.day, dt.hours, dt.minutes, dt.seconds); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); + armScreenRow++; + } - tfp_sprintf(versionBuf, "INAV VERSION: %s", FC_VERSION_STRING); - displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, armScreenRow++, versionBuf); + tfp_sprintf(versionBuf, "INAV VERSION: %s", FC_VERSION_STRING); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(versionBuf)) / 2, armScreenRow++, versionBuf); armScreenRow++; #ifdef USE_STATS @@ -4620,220 +4620,220 @@ static void osdShowSDArmScreen(void) // called when motors armed static void osdShowArmed(void) { - displayClearScreen(osdDisplayPort); + displayClearScreen(osdDisplayPort); - if (osdDisplayIsHD()) { - osdShowHDArmScreen(); - } else { - osdShowSDArmScreen(); - } + if (osdDisplayIsHD()) { + osdShowHDArmScreen(); + } else { + osdShowSDArmScreen(); + } } static void osdFilterData(timeUs_t currentTimeUs) { - static timeUs_t lastRefresh = 0; - float refresh_dT = US2S(cmpTimeUs(currentTimeUs, lastRefresh)); + static timeUs_t lastRefresh = 0; + float refresh_dT = US2S(cmpTimeUs(currentTimeUs, lastRefresh)); - GForce = fast_fsqrtf(vectorNormSquared(&imuMeasuredAccelBF)) / GRAVITY_MSS; - for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) GForceAxis[axis] = imuMeasuredAccelBF.v[axis] / GRAVITY_MSS; + GForce = fast_fsqrtf(vectorNormSquared(&imuMeasuredAccelBF)) / GRAVITY_MSS; + for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) GForceAxis[axis] = imuMeasuredAccelBF.v[axis] / GRAVITY_MSS; - if (lastRefresh) { - GForce = pt1FilterApply3(&GForceFilter, GForce, refresh_dT); - for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) pt1FilterApply3(GForceFilterAxis + axis, GForceAxis[axis], refresh_dT); - } else { - pt1FilterInitRC(&GForceFilter, GFORCE_FILTER_TC, 0); - pt1FilterReset(&GForceFilter, GForce); + if (lastRefresh) { + GForce = pt1FilterApply3(&GForceFilter, GForce, refresh_dT); + for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) pt1FilterApply3(GForceFilterAxis + axis, GForceAxis[axis], refresh_dT); + } else { + pt1FilterInitRC(&GForceFilter, GFORCE_FILTER_TC, 0); + pt1FilterReset(&GForceFilter, GForce); - for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) { - pt1FilterInitRC(GForceFilterAxis + axis, GFORCE_FILTER_TC, 0); - pt1FilterReset(GForceFilterAxis + axis, GForceAxis[axis]); - } - } + for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; ++axis) { + pt1FilterInitRC(GForceFilterAxis + axis, GFORCE_FILTER_TC, 0); + pt1FilterReset(GForceFilterAxis + axis, GForceAxis[axis]); + } + } - lastRefresh = currentTimeUs; + lastRefresh = currentTimeUs; } // Detect when the user is holding the roll stick to the right static bool osdIsPageUpStickCommandHeld(void) { - static int pageUpHoldCount = 1; + static int pageUpHoldCount = 1; - bool keyHeld = false; + bool keyHeld = false; - if (IS_HI(ROLL)) { - keyHeld = true; - } + if (IS_HI(ROLL)) { + keyHeld = true; + } - if (!keyHeld) { - pageUpHoldCount = 1; - } else { - ++pageUpHoldCount; - } + if (!keyHeld) { + pageUpHoldCount = 1; + } else { + ++pageUpHoldCount; + } - if (pageUpHoldCount > 20) { - pageUpHoldCount = 1; - return true; - } + if (pageUpHoldCount > 20) { + pageUpHoldCount = 1; + return true; + } - return false; + return false; } // Detect when the user is holding the roll stick to the left static bool osdIsPageDownStickCommandHeld(void) { - static int pageDownHoldCount = 1; + static int pageDownHoldCount = 1; - bool keyHeld = false; - if (IS_LO(ROLL)) { - keyHeld = true; - } + bool keyHeld = false; + if (IS_LO(ROLL)) { + keyHeld = true; + } - if (!keyHeld) { - pageDownHoldCount = 1; - } else { - ++pageDownHoldCount; - } + if (!keyHeld) { + pageDownHoldCount = 1; + } else { + ++pageDownHoldCount; + } - if (pageDownHoldCount > 20) { - pageDownHoldCount = 1; - return true; - } + if (pageDownHoldCount > 20) { + pageDownHoldCount = 1; + return true; + } - return false; + return false; } static void osdRefresh(timeUs_t currentTimeUs) { - osdFilterData(currentTimeUs); + osdFilterData(currentTimeUs); #ifdef USE_CMS - if (IS_RC_MODE_ACTIVE(BOXOSD) && (!cmsInMenu) && !(osdConfig()->osd_failsafe_switch_layout && FLIGHT_MODE(FAILSAFE_MODE))) { + if (IS_RC_MODE_ACTIVE(BOXOSD) && (!cmsInMenu) && !(osdConfig()->osd_failsafe_switch_layout && FLIGHT_MODE(FAILSAFE_MODE))) { #else - if (IS_RC_MODE_ACTIVE(BOXOSD) && !(osdConfig()->osd_failsafe_switch_layout && FLIGHT_MODE(FAILSAFE_MODE))) { + if (IS_RC_MODE_ACTIVE(BOXOSD) && !(osdConfig()->osd_failsafe_switch_layout && FLIGHT_MODE(FAILSAFE_MODE))) { #endif - displayClearScreen(osdDisplayPort); - armState = ARMING_FLAG(ARMED); - return; - } + displayClearScreen(osdDisplayPort); + armState = ARMING_FLAG(ARMED); + return; + } - bool statsSinglePageCompatible = (osdDisplayPort->rows >= OSD_STATS_SINGLE_PAGE_MIN_ROWS); - static uint8_t statsCurrentPage = 0; - static bool statsDisplayed = false; - static bool statsAutoPagingEnabled = true; + bool statsSinglePageCompatible = (osdDisplayPort->rows >= OSD_STATS_SINGLE_PAGE_MIN_ROWS); + static uint8_t statsCurrentPage = 0; + static bool statsDisplayed = false; + static bool statsAutoPagingEnabled = true; - // Detect arm/disarm - if (armState != ARMING_FLAG(ARMED)) { - if (ARMING_FLAG(ARMED)) { - // Display the "Arming" screen - statsDisplayed = false; - osdResetStats(); - osdShowArmed(); - uint32_t delay = osdConfig()->arm_screen_display_time; + // Detect arm/disarm + if (armState != ARMING_FLAG(ARMED)) { + if (ARMING_FLAG(ARMED)) { + // Display the "Arming" screen + statsDisplayed = false; + osdResetStats(); + osdShowArmed(); + uint32_t delay = osdConfig()->arm_screen_display_time; #if defined(USE_SAFE_HOME) - if (safehome_distance) - delay+= 3000; + if (safehome_distance) + delay+= 3000; #endif - osdSetNextRefreshIn(delay); - } else { - // Display the "Stats" screen - statsDisplayed = true; - statsCurrentPage = 0; - statsAutoPagingEnabled = osdConfig()->stats_page_auto_swap_time > 0 ? true : false; - osdShowStats(statsSinglePageCompatible, statsCurrentPage); - osdSetNextRefreshIn(STATS_SCREEN_DISPLAY_TIME); - } + osdSetNextRefreshIn(delay); + } else { + // Display the "Stats" screen + statsDisplayed = true; + statsCurrentPage = 0; + statsAutoPagingEnabled = osdConfig()->stats_page_auto_swap_time > 0 ? true : false; + osdShowStats(statsSinglePageCompatible, statsCurrentPage); + osdSetNextRefreshIn(STATS_SCREEN_DISPLAY_TIME); + } - armState = ARMING_FLAG(ARMED); - } + armState = ARMING_FLAG(ARMED); + } - // This block is entered when we're showing the "Splash", "Armed" or "Stats" screens - if (resumeRefreshAt) { - - // Handle events only when the "Stats" screen is being displayed. - if (statsDisplayed) { + // This block is entered when we're showing the "Splash", "Armed" or "Stats" screens + if (resumeRefreshAt) { + + // Handle events only when the "Stats" screen is being displayed. + if (statsDisplayed) { - // Manual paging stick commands are only applicable to multi-page stats. - // ****************************** - // For single-page stats, this effectively disables the ability to cancel the - // automatic paging/updates with the stick commands. So unless stats_page_auto_swap_time - // is set to 0 or greater than 4 (saved settings display interval is 5 seconds), then - // "Saved Settings" should display if it is active within the refresh interval. - // ****************************** - // With multi-page stats, "Saved Settings" could also be missed if the user - // has canceled automatic paging using the stick commands, because that is only - // updated when osdShowStats() is called. So, in that case, they would only see - // the "Saved Settings" message if they happen to manually change pages using the - // stick commands within the interval the message is displayed. - bool manualPageUpRequested = false; - bool manualPageDownRequested = false; - if (!statsSinglePageCompatible) { - // These methods ensure the paging stick commands are held for a brief period - // Otherwise it can result in a race condition where the stats are - // updated too quickly and can result in partial blanks, etc. - if (osdIsPageUpStickCommandHeld()) { - manualPageUpRequested = true; - statsAutoPagingEnabled = false; - } else if (osdIsPageDownStickCommandHeld()) { - manualPageDownRequested = true; - statsAutoPagingEnabled = false; - } - } + // Manual paging stick commands are only applicable to multi-page stats. + // ****************************** + // For single-page stats, this effectively disables the ability to cancel the + // automatic paging/updates with the stick commands. So unless stats_page_auto_swap_time + // is set to 0 or greater than 4 (saved settings display interval is 5 seconds), then + // "Saved Settings" should display if it is active within the refresh interval. + // ****************************** + // With multi-page stats, "Saved Settings" could also be missed if the user + // has canceled automatic paging using the stick commands, because that is only + // updated when osdShowStats() is called. So, in that case, they would only see + // the "Saved Settings" message if they happen to manually change pages using the + // stick commands within the interval the message is displayed. + bool manualPageUpRequested = false; + bool manualPageDownRequested = false; + if (!statsSinglePageCompatible) { + // These methods ensure the paging stick commands are held for a brief period + // Otherwise it can result in a race condition where the stats are + // updated too quickly and can result in partial blanks, etc. + if (osdIsPageUpStickCommandHeld()) { + manualPageUpRequested = true; + statsAutoPagingEnabled = false; + } else if (osdIsPageDownStickCommandHeld()) { + manualPageDownRequested = true; + statsAutoPagingEnabled = false; + } + } - if (statsAutoPagingEnabled) { - // Alternate screens for multi-page stats. - // Also, refreshes screen at swap interval for single-page stats. - if (OSD_ALTERNATING_CHOICES((osdConfig()->stats_page_auto_swap_time * 1000), 2)) { - if (statsCurrentPage == 0) { - osdShowStats(statsSinglePageCompatible, statsCurrentPage); - statsCurrentPage = 1; - } - } else { - if (statsCurrentPage == 1) { - osdShowStats(statsSinglePageCompatible, statsCurrentPage); - statsCurrentPage = 0; - } - } - } else { - // Process manual page change events for multi-page stats. - if (manualPageUpRequested) { - osdShowStats(statsSinglePageCompatible, 1); - statsCurrentPage = 1; - } else if (manualPageDownRequested) { - osdShowStats(statsSinglePageCompatible, 0); - statsCurrentPage = 0; - } - } - } + if (statsAutoPagingEnabled) { + // Alternate screens for multi-page stats. + // Also, refreshes screen at swap interval for single-page stats. + if (OSD_ALTERNATING_CHOICES((osdConfig()->stats_page_auto_swap_time * 1000), 2)) { + if (statsCurrentPage == 0) { + osdShowStats(statsSinglePageCompatible, statsCurrentPage); + statsCurrentPage = 1; + } + } else { + if (statsCurrentPage == 1) { + osdShowStats(statsSinglePageCompatible, statsCurrentPage); + statsCurrentPage = 0; + } + } + } else { + // Process manual page change events for multi-page stats. + if (manualPageUpRequested) { + osdShowStats(statsSinglePageCompatible, 1); + statsCurrentPage = 1; + } else if (manualPageDownRequested) { + osdShowStats(statsSinglePageCompatible, 0); + statsCurrentPage = 0; + } + } + } - // Handle events when either "Splash", "Armed" or "Stats" screens are displayed. - if ((currentTimeUs > resumeRefreshAt) || OSD_RESUME_UPDATES_STICK_COMMAND) { - // Time elapsed or canceled by stick commands. - // Exit to normal OSD operation. - displayClearScreen(osdDisplayPort); - resumeRefreshAt = 0; - statsDisplayed = false; - } else { - // Continue "Splash", "Armed" or "Stats" screens. - displayHeartbeat(osdDisplayPort); - } - - return; - } + // Handle events when either "Splash", "Armed" or "Stats" screens are displayed. + if ((currentTimeUs > resumeRefreshAt) || OSD_RESUME_UPDATES_STICK_COMMAND) { + // Time elapsed or canceled by stick commands. + // Exit to normal OSD operation. + displayClearScreen(osdDisplayPort); + resumeRefreshAt = 0; + statsDisplayed = false; + } else { + // Continue "Splash", "Armed" or "Stats" screens. + displayHeartbeat(osdDisplayPort); + } + + return; + } #ifdef USE_CMS - if (!displayIsGrabbed(osdDisplayPort)) { - displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); - if (fullRedraw) { - displayClearScreen(osdDisplayPort); - fullRedraw = false; - } - osdDrawNextElement(); - displayHeartbeat(osdDisplayPort); - displayCommitTransaction(osdDisplayPort); + if (!displayIsGrabbed(osdDisplayPort)) { + displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); + if (fullRedraw) { + displayClearScreen(osdDisplayPort); + fullRedraw = false; + } + osdDrawNextElement(); + displayHeartbeat(osdDisplayPort); + displayCommitTransaction(osdDisplayPort); #ifdef OSD_CALLS_CMS - } else { - cmsUpdate(currentTimeUs); + } else { + cmsUpdate(currentTimeUs); #endif - } + } #endif } @@ -4842,318 +4842,318 @@ static void osdRefresh(timeUs_t currentTimeUs) */ void osdUpdate(timeUs_t currentTimeUs) { - static uint32_t counter = 0; + static uint32_t counter = 0; - // don't touch buffers if DMA transaction is in progress - if (displayIsTransferInProgress(osdDisplayPort)) { - return; - } + // don't touch buffers if DMA transaction is in progress + if (displayIsTransferInProgress(osdDisplayPort)) { + return; + } - if (!osdDisplayIsReady) { - osdCompleteAsyncInitialization(); - return; - } + if (!osdDisplayIsReady) { + osdCompleteAsyncInitialization(); + return; + } #if defined(OSD_ALTERNATE_LAYOUT_COUNT) && OSD_ALTERNATE_LAYOUT_COUNT > 0 - // Check if the layout has changed. Higher numbered - // boxes take priority. - unsigned activeLayout; - if (layoutOverride >= 0) { - activeLayout = layoutOverride; - // Check for timed override, it will go into effect on - // the next OSD iteration - if (layoutOverrideUntil > 0 && millis() > layoutOverrideUntil) { - layoutOverrideUntil = 0; - layoutOverride = -1; - } - } else if (osdConfig()->osd_failsafe_switch_layout && FLIGHT_MODE(FAILSAFE_MODE)) { - activeLayout = 0; - } else { + // Check if the layout has changed. Higher numbered + // boxes take priority. + unsigned activeLayout; + if (layoutOverride >= 0) { + activeLayout = layoutOverride; + // Check for timed override, it will go into effect on + // the next OSD iteration + if (layoutOverrideUntil > 0 && millis() > layoutOverrideUntil) { + layoutOverrideUntil = 0; + layoutOverride = -1; + } + } else if (osdConfig()->osd_failsafe_switch_layout && FLIGHT_MODE(FAILSAFE_MODE)) { + activeLayout = 0; + } else { #if OSD_ALTERNATE_LAYOUT_COUNT > 2 - if (IS_RC_MODE_ACTIVE(BOXOSDALT3)) - activeLayout = 3; - else + if (IS_RC_MODE_ACTIVE(BOXOSDALT3)) + activeLayout = 3; + else #endif #if OSD_ALTERNATE_LAYOUT_COUNT > 1 - if (IS_RC_MODE_ACTIVE(BOXOSDALT2)) - activeLayout = 2; - else + if (IS_RC_MODE_ACTIVE(BOXOSDALT2)) + activeLayout = 2; + else #endif - if (IS_RC_MODE_ACTIVE(BOXOSDALT1)) - activeLayout = 1; - else + if (IS_RC_MODE_ACTIVE(BOXOSDALT1)) + activeLayout = 1; + else #ifdef USE_PROGRAMMING_FRAMEWORK - if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT)) - activeLayout = constrain(logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT], 0, OSD_ALTERNATE_LAYOUT_COUNT); - else + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT)) + activeLayout = constrain(logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT], 0, OSD_ALTERNATE_LAYOUT_COUNT); + else #endif - activeLayout = 0; - } - if (currentLayout != activeLayout) { - currentLayout = activeLayout; - osdStartFullRedraw(); - } + activeLayout = 0; + } + if (currentLayout != activeLayout) { + currentLayout = activeLayout; + osdStartFullRedraw(); + } #endif #define DRAW_FREQ_DENOM 4 #define STATS_FREQ_DENOM 50 - counter++; + counter++; - if ((counter % STATS_FREQ_DENOM) == 0) { - osdUpdateStats(); - } + if ((counter % STATS_FREQ_DENOM) == 0) { + osdUpdateStats(); + } - if ((counter % DRAW_FREQ_DENOM) == 0) { - // redraw values in buffer - osdRefresh(currentTimeUs); - } else { - // rest of time redraw screen - displayDrawScreen(osdDisplayPort); - } + if ((counter % DRAW_FREQ_DENOM) == 0) { + // redraw values in buffer + osdRefresh(currentTimeUs); + } else { + // rest of time redraw screen + displayDrawScreen(osdDisplayPort); + } #ifdef USE_CMS - // do not allow ARM if we are in menu - if (displayIsGrabbed(osdDisplayPort)) { - ENABLE_ARMING_FLAG(ARMING_DISABLED_OSD_MENU); - } else { - DISABLE_ARMING_FLAG(ARMING_DISABLED_OSD_MENU); - } + // do not allow ARM if we are in menu + if (displayIsGrabbed(osdDisplayPort)) { + ENABLE_ARMING_FLAG(ARMING_DISABLED_OSD_MENU); + } else { + DISABLE_ARMING_FLAG(ARMING_DISABLED_OSD_MENU); + } #endif } void osdStartFullRedraw(void) { - fullRedraw = true; + fullRedraw = true; } void osdOverrideLayout(int layout, timeMs_t duration) { - layoutOverride = constrain(layout, -1, ARRAYLEN(osdLayoutsConfig()->item_pos) - 1); - if (layoutOverride >= 0 && duration > 0) { - layoutOverrideUntil = millis() + duration; - } else { - layoutOverrideUntil = 0; - } + layoutOverride = constrain(layout, -1, ARRAYLEN(osdLayoutsConfig()->item_pos) - 1); + if (layoutOverride >= 0 && duration > 0) { + layoutOverrideUntil = millis() + duration; + } else { + layoutOverrideUntil = 0; + } } int osdGetActiveLayout(bool *overridden) { - if (overridden) { - *overridden = layoutOverride >= 0; - } - return currentLayout; + if (overridden) { + *overridden = layoutOverride >= 0; + } + return currentLayout; } bool osdItemIsFixed(osd_items_e item) { - return item == OSD_CROSSHAIRS || - item == OSD_ARTIFICIAL_HORIZON || - item == OSD_HORIZON_SIDEBARS; + return item == OSD_CROSSHAIRS || + item == OSD_ARTIFICIAL_HORIZON || + item == OSD_HORIZON_SIDEBARS; } displayPort_t *osdGetDisplayPort(void) { - return osdDisplayPort; + return osdDisplayPort; } displayCanvas_t *osdGetDisplayPortCanvas(void) { #if defined(USE_CANVAS) - if (osdDisplayHasCanvas) { - return &osdCanvas; - } + if (osdDisplayHasCanvas) { + return &osdCanvas; + } #endif - return NULL; + return NULL; } timeMs_t systemMessageCycleTime(unsigned messageCount, const char **messages){ - uint8_t i = 0; - float factor = 1.0f; - while (i < messageCount) { - if ((float)strlen(messages[i]) / 15.0f > factor) { - factor = (float)strlen(messages[i]) / 15.0f; - } - i++; - } - return osdConfig()->system_msg_display_time * factor; + uint8_t i = 0; + float factor = 1.0f; + while (i < messageCount) { + if ((float)strlen(messages[i]) / 15.0f > factor) { + factor = (float)strlen(messages[i]) / 15.0f; + } + i++; + } + return osdConfig()->system_msg_display_time * factor; } textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenteredText) { - textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; + textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; - if (buff != NULL) { - const char *message = NULL; - char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; - // We might have up to 5 messages to show. - const char *messages[5]; - unsigned messageCount = 0; - const char *failsafeInfoMessage = NULL; - const char *invertedInfoMessage = NULL; + if (buff != NULL) { + const char *message = NULL; + char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)]; + // We might have up to 5 messages to show. + const char *messages[5]; + unsigned messageCount = 0; + const char *failsafeInfoMessage = NULL; + const char *invertedInfoMessage = NULL; - if (ARMING_FLAG(ARMED)) { - if (FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) { - if (isWaypointMissionRTHActive()) { - // if RTH activated whilst WP mode selected, remind pilot to cancel WP mode to exit RTH - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_RTH_CANCEL); - } - if (navGetCurrentStateFlags() & NAV_AUTO_WP_DONE) { - messages[messageCount++] = STATE(LANDING_DETECTED) ? OSD_MESSAGE_STR(OSD_MSG_WP_LANDED) : OSD_MESSAGE_STR(OSD_MSG_WP_FINISHED); - } else if (NAV_Status.state == MW_NAV_STATE_WP_ENROUTE) { - // Countdown display for remaining Waypoints - char buf[6]; - osdFormatDistanceSymbol(buf, posControl.wpDistance, 0); - tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", getGeoWaypointNumber(posControl.activeWaypointIndex), posControl.geoWaypointCount, buf); - messages[messageCount++] = messageBuf; - } else if (NAV_Status.state == MW_NAV_STATE_HOLD_TIMED) { - if (navConfig()->general.waypoint_enforce_altitude && !posControl.wpAltitudeReached) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ADJUSTING_WP_ALT); - } else { - // WP hold time countdown in seconds - timeMs_t currentTime = millis(); - int holdTimeRemaining = posControl.waypointList[posControl.activeWaypointIndex].p1 - (int)(MS2S(currentTime - posControl.wpReachedTime)); - holdTimeRemaining = holdTimeRemaining >= 0 ? holdTimeRemaining : 0; + if (ARMING_FLAG(ARMED)) { + if (FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) { + if (isWaypointMissionRTHActive()) { + // if RTH activated whilst WP mode selected, remind pilot to cancel WP mode to exit RTH + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_RTH_CANCEL); + } + if (navGetCurrentStateFlags() & NAV_AUTO_WP_DONE) { + messages[messageCount++] = STATE(LANDING_DETECTED) ? OSD_MESSAGE_STR(OSD_MSG_WP_LANDED) : OSD_MESSAGE_STR(OSD_MSG_WP_FINISHED); + } else if (NAV_Status.state == MW_NAV_STATE_WP_ENROUTE) { + // Countdown display for remaining Waypoints + char buf[6]; + osdFormatDistanceSymbol(buf, posControl.wpDistance, 0); + tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", getGeoWaypointNumber(posControl.activeWaypointIndex), posControl.geoWaypointCount, buf); + messages[messageCount++] = messageBuf; + } else if (NAV_Status.state == MW_NAV_STATE_HOLD_TIMED) { + if (navConfig()->general.waypoint_enforce_altitude && !posControl.wpAltitudeReached) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ADJUSTING_WP_ALT); + } else { + // WP hold time countdown in seconds + timeMs_t currentTime = millis(); + int holdTimeRemaining = posControl.waypointList[posControl.activeWaypointIndex].p1 - (int)(MS2S(currentTime - posControl.wpReachedTime)); + holdTimeRemaining = holdTimeRemaining >= 0 ? holdTimeRemaining : 0; - tfp_sprintf(messageBuf, "HOLDING WP FOR %2u S", holdTimeRemaining); + tfp_sprintf(messageBuf, "HOLDING WP FOR %2u S", holdTimeRemaining); - messages[messageCount++] = messageBuf; - } - } else { - const char *navStateMessage = navigationStateMessage(); - if (navStateMessage) { - messages[messageCount++] = navStateMessage; - } - } + messages[messageCount++] = messageBuf; + } + } else { + const char *navStateMessage = navigationStateMessage(); + if (navStateMessage) { + messages[messageCount++] = navStateMessage; + } + } #if defined(USE_SAFE_HOME) - const char *safehomeMessage = divertingToSafehomeMessage(); - if (safehomeMessage) { - messages[messageCount++] = safehomeMessage; - } + const char *safehomeMessage = divertingToSafehomeMessage(); + if (safehomeMessage) { + messages[messageCount++] = safehomeMessage; + } #endif - if (FLIGHT_MODE(FAILSAFE_MODE)) { - // In FS mode while being armed too - const char *failsafePhaseMessage = osdFailsafePhaseMessage(); - failsafeInfoMessage = osdFailsafeInfoMessage(); + if (FLIGHT_MODE(FAILSAFE_MODE)) { + // In FS mode while being armed too + const char *failsafePhaseMessage = osdFailsafePhaseMessage(); + failsafeInfoMessage = osdFailsafeInfoMessage(); - if (failsafePhaseMessage) { - messages[messageCount++] = failsafePhaseMessage; - } - if (failsafeInfoMessage) { - messages[messageCount++] = failsafeInfoMessage; - } - } - } else { /* messages shown only when Failsafe, WP, RTH or Emergency Landing not active */ - if (STATE(FIXED_WING_LEGACY) && (navGetCurrentStateFlags() & NAV_CTL_LAUNCH)) { - messages[messageCount++] = navConfig()->fw.launch_manual_throttle ? OSD_MESSAGE_STR(OSD_MSG_AUTOLAUNCH_MANUAL) : - OSD_MESSAGE_STR(OSD_MSG_AUTOLAUNCH); - const char *launchStateMessage = fixedWingLaunchStateMessage(); - if (launchStateMessage) { - messages[messageCount++] = launchStateMessage; - } - } else { - if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && !navigationRequiresAngleMode()) { - // ALTHOLD might be enabled alongside ANGLE/HORIZON/ACRO - // when it doesn't require ANGLE mode (required only in FW - // right now). If if requires ANGLE, its display is handled - // by OSD_FLYMODE. - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ALTITUDE_HOLD); - } - if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM) && !feature(FEATURE_FW_AUTOTRIM)) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTRIM); - } - if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE)) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTUNE); - if (FLIGHT_MODE(MANUAL_MODE)) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTUNE_ACRO); - } - } - if (IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE) || (navigationRequiresAngleMode() && !navigationIsControllingAltitude()))) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOLEVEL); - } - if (FLIGHT_MODE(HEADFREE_MODE)) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_HEADFREE); - } - if (FLIGHT_MODE(SOARING_MODE)) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_NAV_SOARING); - } - if (posControl.flags.wpMissionPlannerActive) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_MISSION_PLANNER); - } - if (STATE(LANDING_DETECTED)) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_LANDED); - } - } - } - } else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) { - unsigned invalidIndex; + if (failsafePhaseMessage) { + messages[messageCount++] = failsafePhaseMessage; + } + if (failsafeInfoMessage) { + messages[messageCount++] = failsafeInfoMessage; + } + } + } else { /* messages shown only when Failsafe, WP, RTH or Emergency Landing not active */ + if (STATE(FIXED_WING_LEGACY) && (navGetCurrentStateFlags() & NAV_CTL_LAUNCH)) { + messages[messageCount++] = navConfig()->fw.launch_manual_throttle ? OSD_MESSAGE_STR(OSD_MSG_AUTOLAUNCH_MANUAL) : + OSD_MESSAGE_STR(OSD_MSG_AUTOLAUNCH); + const char *launchStateMessage = fixedWingLaunchStateMessage(); + if (launchStateMessage) { + messages[messageCount++] = launchStateMessage; + } + } else { + if (FLIGHT_MODE(NAV_ALTHOLD_MODE) && !navigationRequiresAngleMode()) { + // ALTHOLD might be enabled alongside ANGLE/HORIZON/ACRO + // when it doesn't require ANGLE mode (required only in FW + // right now). If if requires ANGLE, its display is handled + // by OSD_FLYMODE. + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ALTITUDE_HOLD); + } + if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM) && !feature(FEATURE_FW_AUTOTRIM)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTRIM); + } + if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTUNE); + if (FLIGHT_MODE(MANUAL_MODE)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTUNE_ACRO); + } + } + if (IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE) || (navigationRequiresAngleMode() && !navigationIsControllingAltitude()))) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOLEVEL); + } + if (FLIGHT_MODE(HEADFREE_MODE)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_HEADFREE); + } + if (FLIGHT_MODE(SOARING_MODE)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_NAV_SOARING); + } + if (posControl.flags.wpMissionPlannerActive) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_MISSION_PLANNER); + } + if (STATE(LANDING_DETECTED)) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_LANDED); + } + } + } + } else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) { + unsigned invalidIndex; - // Check if we're unable to arm for some reason - if (ARMING_FLAG(ARMING_DISABLED_INVALID_SETTING) && !settingsValidate(&invalidIndex)) { + // Check if we're unable to arm for some reason + if (ARMING_FLAG(ARMING_DISABLED_INVALID_SETTING) && !settingsValidate(&invalidIndex)) { - const setting_t *setting = settingGet(invalidIndex); - settingGetName(setting, messageBuf); - for (int ii = 0; messageBuf[ii]; ii++) { - messageBuf[ii] = sl_toupper(messageBuf[ii]); - } - invertedInfoMessage = messageBuf; - messages[messageCount++] = invertedInfoMessage; + const setting_t *setting = settingGet(invalidIndex); + settingGetName(setting, messageBuf); + for (int ii = 0; messageBuf[ii]; ii++) { + messageBuf[ii] = sl_toupper(messageBuf[ii]); + } + invertedInfoMessage = messageBuf; + messages[messageCount++] = invertedInfoMessage; - invertedInfoMessage = OSD_MESSAGE_STR(OSD_MSG_INVALID_SETTING); - messages[messageCount++] = invertedInfoMessage; + invertedInfoMessage = OSD_MESSAGE_STR(OSD_MSG_INVALID_SETTING); + messages[messageCount++] = invertedInfoMessage; - } else { + } else { - invertedInfoMessage = OSD_MESSAGE_STR(OSD_MSG_UNABLE_ARM); - messages[messageCount++] = invertedInfoMessage; + invertedInfoMessage = OSD_MESSAGE_STR(OSD_MSG_UNABLE_ARM); + messages[messageCount++] = invertedInfoMessage; - // Show the reason for not arming - messages[messageCount++] = osdArmingDisabledReasonMessage(); + // Show the reason for not arming + messages[messageCount++] = osdArmingDisabledReasonMessage(); - } - } else if (!ARMING_FLAG(ARMED)) { - if (isWaypointListValid()) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_MISSION_LOADED); - } - } + } + } else if (!ARMING_FLAG(ARMED)) { + if (isWaypointListValid()) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_MISSION_LOADED); + } + } - /* Messages that are shown regardless of Arming state */ + /* Messages that are shown regardless of Arming state */ - if (savingSettings == true) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS); - } else if (notify_settings_saved > 0) { - if (millis() > notify_settings_saved) { - notify_settings_saved = 0; - } else { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_SETTINGS_SAVED); - } - } + if (savingSettings == true) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS); + } else if (notify_settings_saved > 0) { + if (millis() > notify_settings_saved) { + notify_settings_saved = 0; + } else { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_SETTINGS_SAVED); + } + } #ifdef USE_DEV_TOOLS - if (systemConfig()->groundTestMode) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_GRD_TEST_MODE); - } + if (systemConfig()->groundTestMode) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_GRD_TEST_MODE); + } #endif - if (messageCount > 0) { - message = messages[OSD_ALTERNATING_CHOICES(systemMessageCycleTime(messageCount, messages), messageCount)]; - if (message == failsafeInfoMessage) { - // failsafeInfoMessage is not useful for recovering - // a lost model, but might help avoiding a crash. - // Blink to grab user attention. - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } else if (message == invertedInfoMessage) { - TEXT_ATTRIBUTES_ADD_INVERTED(elemAttr); - } - // We're shoing either failsafePhaseMessage or - // navStateMessage. Don't BLINK here since - // having this text available might be crucial - // during a lost aircraft recovery and blinking - // will cause it to be missing from some frames. - } + if (messageCount > 0) { + message = messages[OSD_ALTERNATING_CHOICES(systemMessageCycleTime(messageCount, messages), messageCount)]; + if (message == failsafeInfoMessage) { + // failsafeInfoMessage is not useful for recovering + // a lost model, but might help avoiding a crash. + // Blink to grab user attention. + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } else if (message == invertedInfoMessage) { + TEXT_ATTRIBUTES_ADD_INVERTED(elemAttr); + } + // We're shoing either failsafePhaseMessage or + // navStateMessage. Don't BLINK here since + // having this text available might be crucial + // during a lost aircraft recovery and blinking + // will cause it to be missing from some frames. + } - osdFormatMessage(buff, buff_size, message, isCenteredText); - } - return elemAttr; + osdFormatMessage(buff, buff_size, message, isCenteredText); + } + return elemAttr; } #endif // OSD \ No newline at end of file diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 0d3e3ba976..14c0cf3f0c 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -129,212 +129,212 @@ #endif typedef enum { - OSD_RSSI_VALUE, - OSD_MAIN_BATT_VOLTAGE, - OSD_CROSSHAIRS, - OSD_ARTIFICIAL_HORIZON, - OSD_HORIZON_SIDEBARS, - OSD_ONTIME, - OSD_FLYTIME, - OSD_FLYMODE, - OSD_CRAFT_NAME, - OSD_THROTTLE_POS, - OSD_VTX_CHANNEL, - OSD_CURRENT_DRAW, - OSD_MAH_DRAWN, - OSD_GPS_SPEED, - OSD_GPS_SATS, - OSD_ALTITUDE, - OSD_ROLL_PIDS, - OSD_PITCH_PIDS, - OSD_YAW_PIDS, - OSD_POWER, - OSD_GPS_LON, - OSD_GPS_LAT, - OSD_HOME_DIR, - OSD_HOME_DIST, - OSD_HEADING, - OSD_VARIO, - OSD_VARIO_NUM, - OSD_AIR_SPEED, - OSD_ONTIME_FLYTIME, - OSD_RTC_TIME, - OSD_MESSAGES, - OSD_GPS_HDOP, - OSD_MAIN_BATT_CELL_VOLTAGE, - OSD_SCALED_THROTTLE_POS, - OSD_HEADING_GRAPH, - OSD_EFFICIENCY_MAH_PER_KM, - OSD_WH_DRAWN, - OSD_BATTERY_REMAINING_CAPACITY, - OSD_BATTERY_REMAINING_PERCENT, - OSD_EFFICIENCY_WH_PER_KM, - OSD_TRIP_DIST, - OSD_ATTITUDE_PITCH, - OSD_ATTITUDE_ROLL, - OSD_MAP_NORTH, - OSD_MAP_TAKEOFF, - OSD_RADAR, - OSD_WIND_SPEED_HORIZONTAL, - OSD_WIND_SPEED_VERTICAL, - OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH, - OSD_REMAINING_DISTANCE_BEFORE_RTH, - OSD_HOME_HEADING_ERROR, - OSD_COURSE_HOLD_ERROR, - OSD_COURSE_HOLD_ADJUSTMENT, - OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE, - OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE, - OSD_POWER_SUPPLY_IMPEDANCE, - OSD_LEVEL_PIDS, - OSD_POS_XY_PIDS, - OSD_POS_Z_PIDS, - OSD_VEL_XY_PIDS, - OSD_VEL_Z_PIDS, - OSD_HEADING_P, - OSD_BOARD_ALIGN_ROLL, - OSD_BOARD_ALIGN_PITCH, - OSD_RC_EXPO, - OSD_RC_YAW_EXPO, - OSD_THROTTLE_EXPO, - OSD_PITCH_RATE, - OSD_ROLL_RATE, - OSD_YAW_RATE, - OSD_MANUAL_RC_EXPO, - OSD_MANUAL_RC_YAW_EXPO, - OSD_MANUAL_PITCH_RATE, - OSD_MANUAL_ROLL_RATE, - OSD_MANUAL_YAW_RATE, - OSD_NAV_FW_CRUISE_THR, - OSD_NAV_FW_PITCH2THR, - OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE, - OSD_DEBUG, // Intentionally absent from configurator and CMS. Set it from CLI. - OSD_FW_ALT_PID_OUTPUTS, - OSD_FW_POS_PID_OUTPUTS, - OSD_MC_VEL_X_PID_OUTPUTS, - OSD_MC_VEL_Y_PID_OUTPUTS, - OSD_MC_VEL_Z_PID_OUTPUTS, - OSD_MC_POS_XYZ_P_OUTPUTS, - OSD_3D_SPEED, - OSD_IMU_TEMPERATURE, - OSD_BARO_TEMPERATURE, - OSD_TEMP_SENSOR_0_TEMPERATURE, - OSD_TEMP_SENSOR_1_TEMPERATURE, - OSD_TEMP_SENSOR_2_TEMPERATURE, - OSD_TEMP_SENSOR_3_TEMPERATURE, - OSD_TEMP_SENSOR_4_TEMPERATURE, - OSD_TEMP_SENSOR_5_TEMPERATURE, - OSD_TEMP_SENSOR_6_TEMPERATURE, - OSD_TEMP_SENSOR_7_TEMPERATURE, - OSD_ALTITUDE_MSL, - OSD_PLUS_CODE, - OSD_MAP_SCALE, - OSD_MAP_REFERENCE, - OSD_GFORCE, - OSD_GFORCE_X, - OSD_GFORCE_Y, - OSD_GFORCE_Z, - OSD_RC_SOURCE, - OSD_VTX_POWER, - OSD_ESC_RPM, - OSD_ESC_TEMPERATURE, - OSD_AZIMUTH, - OSD_CRSF_RSSI_DBM, - OSD_CRSF_LQ, - OSD_CRSF_SNR_DB, - OSD_CRSF_TX_POWER, - OSD_GVAR_0, - OSD_GVAR_1, - OSD_GVAR_2, - OSD_GVAR_3, - OSD_TPA, - OSD_NAV_FW_CONTROL_SMOOTHNESS, - OSD_VERSION, - OSD_RANGEFINDER, - OSD_PLIMIT_REMAINING_BURST_TIME, - OSD_PLIMIT_ACTIVE_CURRENT_LIMIT, - OSD_PLIMIT_ACTIVE_POWER_LIMIT, - OSD_GLIDESLOPE, - OSD_GPS_MAX_SPEED, - OSD_3D_MAX_SPEED, - OSD_AIR_MAX_SPEED, - OSD_ACTIVE_PROFILE, - OSD_MISSION, - OSD_SWITCH_INDICATOR_0, - OSD_SWITCH_INDICATOR_1, - OSD_SWITCH_INDICATOR_2, - OSD_SWITCH_INDICATOR_3, - OSD_TPA_TIME_CONSTANT, - OSD_FW_LEVEL_TRIM, - OSD_GLIDE_TIME_REMAINING, - OSD_GLIDE_RANGE, - OSD_CLIMB_EFFICIENCY, - OSD_NAV_WP_MULTI_MISSION_INDEX, - OSD_GROUND_COURSE, // 140 - OSD_CROSS_TRACK_ERROR, - OSD_PILOT_NAME, - OSD_PAN_SERVO_CENTRED, - OSD_PILOT_LOGO, - OSD_ITEM_COUNT // MUST BE LAST + OSD_RSSI_VALUE, + OSD_MAIN_BATT_VOLTAGE, + OSD_CROSSHAIRS, + OSD_ARTIFICIAL_HORIZON, + OSD_HORIZON_SIDEBARS, + OSD_ONTIME, + OSD_FLYTIME, + OSD_FLYMODE, + OSD_CRAFT_NAME, + OSD_THROTTLE_POS, + OSD_VTX_CHANNEL, + OSD_CURRENT_DRAW, + OSD_MAH_DRAWN, + OSD_GPS_SPEED, + OSD_GPS_SATS, + OSD_ALTITUDE, + OSD_ROLL_PIDS, + OSD_PITCH_PIDS, + OSD_YAW_PIDS, + OSD_POWER, + OSD_GPS_LON, + OSD_GPS_LAT, + OSD_HOME_DIR, + OSD_HOME_DIST, + OSD_HEADING, + OSD_VARIO, + OSD_VARIO_NUM, + OSD_AIR_SPEED, + OSD_ONTIME_FLYTIME, + OSD_RTC_TIME, + OSD_MESSAGES, + OSD_GPS_HDOP, + OSD_MAIN_BATT_CELL_VOLTAGE, + OSD_SCALED_THROTTLE_POS, + OSD_HEADING_GRAPH, + OSD_EFFICIENCY_MAH_PER_KM, + OSD_WH_DRAWN, + OSD_BATTERY_REMAINING_CAPACITY, + OSD_BATTERY_REMAINING_PERCENT, + OSD_EFFICIENCY_WH_PER_KM, + OSD_TRIP_DIST, + OSD_ATTITUDE_PITCH, + OSD_ATTITUDE_ROLL, + OSD_MAP_NORTH, + OSD_MAP_TAKEOFF, + OSD_RADAR, + OSD_WIND_SPEED_HORIZONTAL, + OSD_WIND_SPEED_VERTICAL, + OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH, + OSD_REMAINING_DISTANCE_BEFORE_RTH, + OSD_HOME_HEADING_ERROR, + OSD_COURSE_HOLD_ERROR, + OSD_COURSE_HOLD_ADJUSTMENT, + OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE, + OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE, + OSD_POWER_SUPPLY_IMPEDANCE, + OSD_LEVEL_PIDS, + OSD_POS_XY_PIDS, + OSD_POS_Z_PIDS, + OSD_VEL_XY_PIDS, + OSD_VEL_Z_PIDS, + OSD_HEADING_P, + OSD_BOARD_ALIGN_ROLL, + OSD_BOARD_ALIGN_PITCH, + OSD_RC_EXPO, + OSD_RC_YAW_EXPO, + OSD_THROTTLE_EXPO, + OSD_PITCH_RATE, + OSD_ROLL_RATE, + OSD_YAW_RATE, + OSD_MANUAL_RC_EXPO, + OSD_MANUAL_RC_YAW_EXPO, + OSD_MANUAL_PITCH_RATE, + OSD_MANUAL_ROLL_RATE, + OSD_MANUAL_YAW_RATE, + OSD_NAV_FW_CRUISE_THR, + OSD_NAV_FW_PITCH2THR, + OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE, + OSD_DEBUG, // Intentionally absent from configurator and CMS. Set it from CLI. + OSD_FW_ALT_PID_OUTPUTS, + OSD_FW_POS_PID_OUTPUTS, + OSD_MC_VEL_X_PID_OUTPUTS, + OSD_MC_VEL_Y_PID_OUTPUTS, + OSD_MC_VEL_Z_PID_OUTPUTS, + OSD_MC_POS_XYZ_P_OUTPUTS, + OSD_3D_SPEED, + OSD_IMU_TEMPERATURE, + OSD_BARO_TEMPERATURE, + OSD_TEMP_SENSOR_0_TEMPERATURE, + OSD_TEMP_SENSOR_1_TEMPERATURE, + OSD_TEMP_SENSOR_2_TEMPERATURE, + OSD_TEMP_SENSOR_3_TEMPERATURE, + OSD_TEMP_SENSOR_4_TEMPERATURE, + OSD_TEMP_SENSOR_5_TEMPERATURE, + OSD_TEMP_SENSOR_6_TEMPERATURE, + OSD_TEMP_SENSOR_7_TEMPERATURE, + OSD_ALTITUDE_MSL, + OSD_PLUS_CODE, + OSD_MAP_SCALE, + OSD_MAP_REFERENCE, + OSD_GFORCE, + OSD_GFORCE_X, + OSD_GFORCE_Y, + OSD_GFORCE_Z, + OSD_RC_SOURCE, + OSD_VTX_POWER, + OSD_ESC_RPM, + OSD_ESC_TEMPERATURE, + OSD_AZIMUTH, + OSD_CRSF_RSSI_DBM, + OSD_CRSF_LQ, + OSD_CRSF_SNR_DB, + OSD_CRSF_TX_POWER, + OSD_GVAR_0, + OSD_GVAR_1, + OSD_GVAR_2, + OSD_GVAR_3, + OSD_TPA, + OSD_NAV_FW_CONTROL_SMOOTHNESS, + OSD_VERSION, + OSD_RANGEFINDER, + OSD_PLIMIT_REMAINING_BURST_TIME, + OSD_PLIMIT_ACTIVE_CURRENT_LIMIT, + OSD_PLIMIT_ACTIVE_POWER_LIMIT, + OSD_GLIDESLOPE, + OSD_GPS_MAX_SPEED, + OSD_3D_MAX_SPEED, + OSD_AIR_MAX_SPEED, + OSD_ACTIVE_PROFILE, + OSD_MISSION, + OSD_SWITCH_INDICATOR_0, + OSD_SWITCH_INDICATOR_1, + OSD_SWITCH_INDICATOR_2, + OSD_SWITCH_INDICATOR_3, + OSD_TPA_TIME_CONSTANT, + OSD_FW_LEVEL_TRIM, + OSD_GLIDE_TIME_REMAINING, + OSD_GLIDE_RANGE, + OSD_CLIMB_EFFICIENCY, + OSD_NAV_WP_MULTI_MISSION_INDEX, + OSD_GROUND_COURSE, // 140 + OSD_CROSS_TRACK_ERROR, + OSD_PILOT_NAME, + OSD_PAN_SERVO_CENTRED, + OSD_PILOT_LOGO, + OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; typedef enum { - OSD_UNIT_IMPERIAL, - OSD_UNIT_METRIC, - OSD_UNIT_METRIC_MPH, // Old UK units, all metric except speed in mph - OSD_UNIT_UK, // Show everything in imperial, temperature in C - OSD_UNIT_GA, // General Aviation: Knots, Nautical Miles, Feet, Degrees C + OSD_UNIT_IMPERIAL, + OSD_UNIT_METRIC, + OSD_UNIT_METRIC_MPH, // Old UK units, all metric except speed in mph + OSD_UNIT_UK, // Show everything in imperial, temperature in C + OSD_UNIT_GA, // General Aviation: Knots, Nautical Miles, Feet, Degrees C - OSD_UNIT_MAX = OSD_UNIT_GA, + OSD_UNIT_MAX = OSD_UNIT_GA, } osd_unit_e; typedef enum { - OSD_STATS_ENERGY_UNIT_MAH, - OSD_STATS_ENERGY_UNIT_WH, + OSD_STATS_ENERGY_UNIT_MAH, + OSD_STATS_ENERGY_UNIT_WH, } osd_stats_energy_unit_e; typedef enum { - OSD_STATS_MIN_VOLTAGE_UNIT_BATTERY, - OSD_STATS_MIN_VOLTAGE_UNIT_CELL, + OSD_STATS_MIN_VOLTAGE_UNIT_BATTERY, + OSD_STATS_MIN_VOLTAGE_UNIT_CELL, } osd_stats_min_voltage_unit_e; typedef enum { - OSD_CROSSHAIRS_STYLE_DEFAULT, - OSD_CROSSHAIRS_STYLE_AIRCRAFT, - OSD_CROSSHAIRS_STYLE_TYPE3, - OSD_CROSSHAIRS_STYLE_TYPE4, - OSD_CROSSHAIRS_STYLE_TYPE5, - OSD_CROSSHAIRS_STYLE_TYPE6, - OSD_CROSSHAIRS_STYLE_TYPE7, + OSD_CROSSHAIRS_STYLE_DEFAULT, + OSD_CROSSHAIRS_STYLE_AIRCRAFT, + OSD_CROSSHAIRS_STYLE_TYPE3, + OSD_CROSSHAIRS_STYLE_TYPE4, + OSD_CROSSHAIRS_STYLE_TYPE5, + OSD_CROSSHAIRS_STYLE_TYPE6, + OSD_CROSSHAIRS_STYLE_TYPE7, } osd_crosshairs_style_e; typedef enum { - OSD_SIDEBAR_SCROLL_NONE, - OSD_SIDEBAR_SCROLL_ALTITUDE, - OSD_SIDEBAR_SCROLL_SPEED, - OSD_SIDEBAR_SCROLL_HOME_DISTANCE, + OSD_SIDEBAR_SCROLL_NONE, + OSD_SIDEBAR_SCROLL_ALTITUDE, + OSD_SIDEBAR_SCROLL_SPEED, + OSD_SIDEBAR_SCROLL_HOME_DISTANCE, - OSD_SIDEBAR_SCROLL_MAX = OSD_SIDEBAR_SCROLL_HOME_DISTANCE, + OSD_SIDEBAR_SCROLL_MAX = OSD_SIDEBAR_SCROLL_HOME_DISTANCE, } osd_sidebar_scroll_e; typedef enum { - OSD_ALIGN_LEFT, - OSD_ALIGN_RIGHT + OSD_ALIGN_LEFT, + OSD_ALIGN_RIGHT } osd_alignment_e; typedef enum { - OSD_AHI_STYLE_DEFAULT, - OSD_AHI_STYLE_LINE, + OSD_AHI_STYLE_DEFAULT, + OSD_AHI_STYLE_LINE, } osd_ahi_style_e; typedef enum { - OSD_CRSF_LQ_TYPE1, - OSD_CRSF_LQ_TYPE2, - OSD_CRSF_LQ_TYPE3 + OSD_CRSF_LQ_TYPE1, + OSD_CRSF_LQ_TYPE2, + OSD_CRSF_LQ_TYPE3 } osd_crsf_lq_format_e; typedef struct osdLayoutsConfig_s { - // Layouts - uint16_t item_pos[OSD_LAYOUT_COUNT][OSD_ITEM_COUNT]; + // Layouts + uint16_t item_pos[OSD_LAYOUT_COUNT][OSD_ITEM_COUNT]; } osdLayoutsConfig_t; PG_DECLARE(osdLayoutsConfig_t, osdLayoutsConfig); @@ -342,113 +342,113 @@ PG_DECLARE(osdLayoutsConfig_t, osdLayoutsConfig); #define OSD_SWITCH_INDICATOR_NAME_LENGTH 4 typedef struct osdConfig_s { - // Alarms - uint8_t rssi_alarm; // rssi % - uint16_t time_alarm; // fly minutes - uint16_t alt_alarm; // positive altitude in m - uint16_t dist_alarm; // home distance in m - uint16_t neg_alt_alarm; // abs(negative altitude) in m - uint8_t current_alarm; // current consumption in A - int16_t imu_temp_alarm_min; - int16_t imu_temp_alarm_max; - int16_t esc_temp_alarm_min; - int16_t esc_temp_alarm_max; - float gforce_alarm; - float gforce_axis_alarm_min; - float gforce_axis_alarm_max; + // Alarms + uint8_t rssi_alarm; // rssi % + uint16_t time_alarm; // fly minutes + uint16_t alt_alarm; // positive altitude in m + uint16_t dist_alarm; // home distance in m + uint16_t neg_alt_alarm; // abs(negative altitude) in m + uint8_t current_alarm; // current consumption in A + int16_t imu_temp_alarm_min; + int16_t imu_temp_alarm_max; + int16_t esc_temp_alarm_min; + int16_t esc_temp_alarm_max; + float gforce_alarm; + float gforce_axis_alarm_min; + float gforce_axis_alarm_max; #ifdef USE_SERIALRX_CRSF - int8_t snr_alarm; //CRSF SNR alarm in dB - int8_t link_quality_alarm; - int16_t rssi_dbm_alarm; // in dBm - int16_t rssi_dbm_max; // Perfect RSSI. Set to High end of curve. RSSI at 100% - int16_t rssi_dbm_min; // Worst RSSI. Set to low end of curve or RX sensitivity level. RSSI at 0% + int8_t snr_alarm; //CRSF SNR alarm in dB + int8_t link_quality_alarm; + int16_t rssi_dbm_alarm; // in dBm + int16_t rssi_dbm_max; // Perfect RSSI. Set to High end of curve. RSSI at 100% + int16_t rssi_dbm_min; // Worst RSSI. Set to low end of curve or RX sensitivity level. RSSI at 0% #endif #ifdef USE_BARO - int16_t baro_temp_alarm_min; - int16_t baro_temp_alarm_max; + int16_t baro_temp_alarm_min; + int16_t baro_temp_alarm_max; #endif #ifdef USE_TEMPERATURE_SENSOR - osd_alignment_e temp_label_align; + osd_alignment_e temp_label_align; #endif #ifdef USE_PITOT - float airspeed_alarm_min; - float airspeed_alarm_max; + float airspeed_alarm_min; + float airspeed_alarm_max; #endif - videoSystem_e video_system; - uint8_t row_shiftdown; - int16_t msp_displayport_fullframe_interval; + videoSystem_e video_system; + uint8_t row_shiftdown; + int16_t msp_displayport_fullframe_interval; - // Preferences - uint8_t main_voltage_decimals; - uint8_t ahi_reverse_roll; - uint8_t ahi_max_pitch; - uint8_t crosshairs_style; // from osd_crosshairs_style_e - int8_t horizon_offset; - int8_t camera_uptilt; - bool ahi_camera_uptilt_comp; - uint8_t camera_fov_h; - uint8_t camera_fov_v; - uint8_t hud_margin_h; - uint8_t hud_margin_v; - bool hud_homing; - bool hud_homepoint; - uint8_t hud_radar_disp; - uint16_t hud_radar_range_min; - uint16_t hud_radar_range_max; - uint8_t hud_radar_alt_difference_display_time; - uint8_t hud_radar_distance_display_time; - uint8_t hud_wp_disp; + // Preferences + uint8_t main_voltage_decimals; + uint8_t ahi_reverse_roll; + uint8_t ahi_max_pitch; + uint8_t crosshairs_style; // from osd_crosshairs_style_e + int8_t horizon_offset; + int8_t camera_uptilt; + bool ahi_camera_uptilt_comp; + uint8_t camera_fov_h; + uint8_t camera_fov_v; + uint8_t hud_margin_h; + uint8_t hud_margin_v; + bool hud_homing; + bool hud_homepoint; + uint8_t hud_radar_disp; + uint16_t hud_radar_range_min; + uint16_t hud_radar_range_max; + uint8_t hud_radar_alt_difference_display_time; + uint8_t hud_radar_distance_display_time; + uint8_t hud_wp_disp; - uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_e - uint8_t right_sidebar_scroll; // from osd_sidebar_scroll_e - uint8_t sidebar_scroll_arrows; + uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_e + uint8_t right_sidebar_scroll; // from osd_sidebar_scroll_e + uint8_t sidebar_scroll_arrows; - uint8_t units; // from osd_unit_e - uint8_t stats_energy_unit; // from osd_stats_energy_unit_e - uint8_t stats_min_voltage_unit; // from osd_stats_min_voltage_unit_e - uint8_t stats_page_auto_swap_time; // stats page auto swap interval time (seconds) + uint8_t units; // from osd_unit_e + uint8_t stats_energy_unit; // from osd_stats_energy_unit_e + uint8_t stats_min_voltage_unit; // from osd_stats_min_voltage_unit_e + uint8_t stats_page_auto_swap_time; // stats page auto swap interval time (seconds) #ifdef USE_WIND_ESTIMATOR - bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance + bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance #endif - uint8_t coordinate_digits; - bool osd_failsafe_switch_layout; - uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE - uint8_t plus_code_short; - uint8_t ahi_style; - uint8_t force_grid; // Force a pixel based OSD to use grid mode. - uint8_t ahi_bordered; // Only used by the AHI widget - uint8_t ahi_width; // In pixels, only used by the AHI widget - uint8_t ahi_height; // In pixels, only used by the AHI widget - int8_t ahi_vertical_offset; // Offset from center in pixels. Positive moves the AHI down. Widget only. - int8_t sidebar_horizontal_offset; // Horizontal offset from default position. Units are grid slots for grid OSDs, pixels for pixel based OSDs. Positive values move sidebars closer to the edges. - uint8_t left_sidebar_scroll_step; // How many units each sidebar step represents. 0 means the default value for the scroll type. - uint8_t right_sidebar_scroll_step; // Same as left_sidebar_scroll_step, but for the right sidebar. - bool osd_home_position_arm_screen; - uint8_t pan_servo_index; // Index of the pan servo used for home direction offset - int8_t pan_servo_pwm2centideg; // Centidegrees of servo rotation per us pwm - uint8_t pan_servo_offcentre_warning; // Degrees around the centre, that is assumed camera is wanted to be facing forwards, but isn't centred - bool pan_servo_indicator_show_degrees; // Show the degrees of offset for the pan servo - uint8_t crsf_lq_format; - uint8_t sidebar_height; // sidebar height in rows, 0 turns off sidebars leaving only level indicator arrows - uint8_t telemetry; // use telemetry on displayed pixel line 0 - uint8_t esc_rpm_precision; // Number of characters used for the RPM numbers. - uint16_t system_msg_display_time; // system message display time for multiple messages (ms) - uint8_t mAh_used_precision; // Number of numbers used for mAh drawn. Plently of packs now are > 9999 mAh - uint8_t ahi_pitch_interval; // redraws AHI at set pitch interval (Not pixel OSD) - char osd_switch_indicator0_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 0. - uint8_t osd_switch_indicator0_channel; // RC Channel to use for switch indicator 0. - char osd_switch_indicator1_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 1. - uint8_t osd_switch_indicator1_channel; // RC Channel to use for switch indicator 1. - char osd_switch_indicator2_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 2. - uint8_t osd_switch_indicator2_channel; // RC Channel to use for switch indicator 2. - char osd_switch_indicator3_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 3. - uint8_t osd_switch_indicator3_channel; // RC Channel to use for switch indicator 3. - bool osd_switch_indicators_align_left; // Align switch indicator name to left of the switch. - bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with the INAV logo. - uint8_t inav_to_pilot_logo_spacing; // The space between the INAV and pilot logos, if pilot logo is used. This number may be adjusted so that it fits the odd/even col width. - uint16_t arm_screen_display_time; // Length of time the arm screen is displayed + uint8_t coordinate_digits; + bool osd_failsafe_switch_layout; + uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE + uint8_t plus_code_short; + uint8_t ahi_style; + uint8_t force_grid; // Force a pixel based OSD to use grid mode. + uint8_t ahi_bordered; // Only used by the AHI widget + uint8_t ahi_width; // In pixels, only used by the AHI widget + uint8_t ahi_height; // In pixels, only used by the AHI widget + int8_t ahi_vertical_offset; // Offset from center in pixels. Positive moves the AHI down. Widget only. + int8_t sidebar_horizontal_offset; // Horizontal offset from default position. Units are grid slots for grid OSDs, pixels for pixel based OSDs. Positive values move sidebars closer to the edges. + uint8_t left_sidebar_scroll_step; // How many units each sidebar step represents. 0 means the default value for the scroll type. + uint8_t right_sidebar_scroll_step; // Same as left_sidebar_scroll_step, but for the right sidebar. + bool osd_home_position_arm_screen; + uint8_t pan_servo_index; // Index of the pan servo used for home direction offset + int8_t pan_servo_pwm2centideg; // Centidegrees of servo rotation per us pwm + uint8_t pan_servo_offcentre_warning; // Degrees around the centre, that is assumed camera is wanted to be facing forwards, but isn't centred + bool pan_servo_indicator_show_degrees; // Show the degrees of offset for the pan servo + uint8_t crsf_lq_format; + uint8_t sidebar_height; // sidebar height in rows, 0 turns off sidebars leaving only level indicator arrows + uint8_t telemetry; // use telemetry on displayed pixel line 0 + uint8_t esc_rpm_precision; // Number of characters used for the RPM numbers. + uint16_t system_msg_display_time; // system message display time for multiple messages (ms) + uint8_t mAh_used_precision; // Number of numbers used for mAh drawn. Plently of packs now are > 9999 mAh + uint8_t ahi_pitch_interval; // redraws AHI at set pitch interval (Not pixel OSD) + char osd_switch_indicator0_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 0. + uint8_t osd_switch_indicator0_channel; // RC Channel to use for switch indicator 0. + char osd_switch_indicator1_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 1. + uint8_t osd_switch_indicator1_channel; // RC Channel to use for switch indicator 1. + char osd_switch_indicator2_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 2. + uint8_t osd_switch_indicator2_channel; // RC Channel to use for switch indicator 2. + char osd_switch_indicator3_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 3. + uint8_t osd_switch_indicator3_channel; // RC Channel to use for switch indicator 3. + bool osd_switch_indicators_align_left; // Align switch indicator name to left of the switch. + bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with the INAV logo. + uint8_t inav_to_pilot_logo_spacing; // The space between the INAV and pilot logos, if pilot logo is used. This number may be adjusted so that it fits the odd/even col width. + uint16_t arm_screen_display_time; // Length of time the arm screen is displayed } osdConfig_t; PG_DECLARE(osdConfig_t, osdConfig); From 679ec8faeedf83f1a829bbd415aced7c6b2eb5a5 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Mon, 18 Sep 2023 08:44:23 +0100 Subject: [PATCH 084/175] More tabs to spaces Damn, I hate spaces. Tabs for alignment makes so much more sense :( --- src/main/io/osd.h | 186 +++++++++++++++++++++++----------------------- 1 file changed, 93 insertions(+), 93 deletions(-) diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 14c0cf3f0c..7df3acc404 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -280,9 +280,9 @@ typedef enum { typedef enum { OSD_UNIT_IMPERIAL, OSD_UNIT_METRIC, - OSD_UNIT_METRIC_MPH, // Old UK units, all metric except speed in mph - OSD_UNIT_UK, // Show everything in imperial, temperature in C - OSD_UNIT_GA, // General Aviation: Knots, Nautical Miles, Feet, Degrees C + OSD_UNIT_METRIC_MPH, // Old UK units, all metric except speed in mph + OSD_UNIT_UK, // Show everything in imperial, temperature in C + OSD_UNIT_GA, // General Aviation: Knots, Nautical Miles, Feet, Degrees C OSD_UNIT_MAX = OSD_UNIT_GA, } osd_unit_e; @@ -343,112 +343,112 @@ PG_DECLARE(osdLayoutsConfig_t, osdLayoutsConfig); typedef struct osdConfig_s { // Alarms - uint8_t rssi_alarm; // rssi % - uint16_t time_alarm; // fly minutes - uint16_t alt_alarm; // positive altitude in m - uint16_t dist_alarm; // home distance in m - uint16_t neg_alt_alarm; // abs(negative altitude) in m - uint8_t current_alarm; // current consumption in A - int16_t imu_temp_alarm_min; - int16_t imu_temp_alarm_max; - int16_t esc_temp_alarm_min; - int16_t esc_temp_alarm_max; - float gforce_alarm; - float gforce_axis_alarm_min; - float gforce_axis_alarm_max; + uint8_t rssi_alarm; // rssi % + uint16_t time_alarm; // fly minutes + uint16_t alt_alarm; // positive altitude in m + uint16_t dist_alarm; // home distance in m + uint16_t neg_alt_alarm; // abs(negative altitude) in m + uint8_t current_alarm; // current consumption in A + int16_t imu_temp_alarm_min; + int16_t imu_temp_alarm_max; + int16_t esc_temp_alarm_min; + int16_t esc_temp_alarm_max; + float gforce_alarm; + float gforce_axis_alarm_min; + float gforce_axis_alarm_max; #ifdef USE_SERIALRX_CRSF - int8_t snr_alarm; //CRSF SNR alarm in dB - int8_t link_quality_alarm; - int16_t rssi_dbm_alarm; // in dBm - int16_t rssi_dbm_max; // Perfect RSSI. Set to High end of curve. RSSI at 100% - int16_t rssi_dbm_min; // Worst RSSI. Set to low end of curve or RX sensitivity level. RSSI at 0% + int8_t snr_alarm; //CRSF SNR alarm in dB + int8_t link_quality_alarm; + int16_t rssi_dbm_alarm; // in dBm + int16_t rssi_dbm_max; // Perfect RSSI. Set to High end of curve. RSSI at 100% + int16_t rssi_dbm_min; // Worst RSSI. Set to low end of curve or RX sensitivity level. RSSI at 0% #endif #ifdef USE_BARO - int16_t baro_temp_alarm_min; - int16_t baro_temp_alarm_max; + int16_t baro_temp_alarm_min; + int16_t baro_temp_alarm_max; #endif #ifdef USE_TEMPERATURE_SENSOR - osd_alignment_e temp_label_align; + osd_alignment_e temp_label_align; #endif #ifdef USE_PITOT - float airspeed_alarm_min; - float airspeed_alarm_max; + float airspeed_alarm_min; + float airspeed_alarm_max; #endif - videoSystem_e video_system; - uint8_t row_shiftdown; - int16_t msp_displayport_fullframe_interval; + videoSystem_e video_system; + uint8_t row_shiftdown; + int16_t msp_displayport_fullframe_interval; // Preferences - uint8_t main_voltage_decimals; - uint8_t ahi_reverse_roll; - uint8_t ahi_max_pitch; - uint8_t crosshairs_style; // from osd_crosshairs_style_e - int8_t horizon_offset; - int8_t camera_uptilt; - bool ahi_camera_uptilt_comp; - uint8_t camera_fov_h; - uint8_t camera_fov_v; - uint8_t hud_margin_h; - uint8_t hud_margin_v; - bool hud_homing; - bool hud_homepoint; - uint8_t hud_radar_disp; - uint16_t hud_radar_range_min; - uint16_t hud_radar_range_max; - uint8_t hud_radar_alt_difference_display_time; - uint8_t hud_radar_distance_display_time; - uint8_t hud_wp_disp; + uint8_t main_voltage_decimals; + uint8_t ahi_reverse_roll; + uint8_t ahi_max_pitch; + uint8_t crosshairs_style; // from osd_crosshairs_style_e + int8_t horizon_offset; + int8_t camera_uptilt; + bool ahi_camera_uptilt_comp; + uint8_t camera_fov_h; + uint8_t camera_fov_v; + uint8_t hud_margin_h; + uint8_t hud_margin_v; + bool hud_homing; + bool hud_homepoint; + uint8_t hud_radar_disp; + uint16_t hud_radar_range_min; + uint16_t hud_radar_range_max; + uint8_t hud_radar_alt_difference_display_time; + uint8_t hud_radar_distance_display_time; + uint8_t hud_wp_disp; - uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_e - uint8_t right_sidebar_scroll; // from osd_sidebar_scroll_e - uint8_t sidebar_scroll_arrows; + uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_e + uint8_t right_sidebar_scroll; // from osd_sidebar_scroll_e + uint8_t sidebar_scroll_arrows; - uint8_t units; // from osd_unit_e - uint8_t stats_energy_unit; // from osd_stats_energy_unit_e - uint8_t stats_min_voltage_unit; // from osd_stats_min_voltage_unit_e - uint8_t stats_page_auto_swap_time; // stats page auto swap interval time (seconds) + uint8_t units; // from osd_unit_e + uint8_t stats_energy_unit; // from osd_stats_energy_unit_e + uint8_t stats_min_voltage_unit; // from osd_stats_min_voltage_unit_e + uint8_t stats_page_auto_swap_time; // stats page auto swap interval time (seconds) #ifdef USE_WIND_ESTIMATOR - bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance + bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance #endif - uint8_t coordinate_digits; - bool osd_failsafe_switch_layout; - uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE - uint8_t plus_code_short; - uint8_t ahi_style; - uint8_t force_grid; // Force a pixel based OSD to use grid mode. - uint8_t ahi_bordered; // Only used by the AHI widget - uint8_t ahi_width; // In pixels, only used by the AHI widget - uint8_t ahi_height; // In pixels, only used by the AHI widget - int8_t ahi_vertical_offset; // Offset from center in pixels. Positive moves the AHI down. Widget only. - int8_t sidebar_horizontal_offset; // Horizontal offset from default position. Units are grid slots for grid OSDs, pixels for pixel based OSDs. Positive values move sidebars closer to the edges. - uint8_t left_sidebar_scroll_step; // How many units each sidebar step represents. 0 means the default value for the scroll type. - uint8_t right_sidebar_scroll_step; // Same as left_sidebar_scroll_step, but for the right sidebar. - bool osd_home_position_arm_screen; - uint8_t pan_servo_index; // Index of the pan servo used for home direction offset - int8_t pan_servo_pwm2centideg; // Centidegrees of servo rotation per us pwm - uint8_t pan_servo_offcentre_warning; // Degrees around the centre, that is assumed camera is wanted to be facing forwards, but isn't centred - bool pan_servo_indicator_show_degrees; // Show the degrees of offset for the pan servo - uint8_t crsf_lq_format; - uint8_t sidebar_height; // sidebar height in rows, 0 turns off sidebars leaving only level indicator arrows - uint8_t telemetry; // use telemetry on displayed pixel line 0 - uint8_t esc_rpm_precision; // Number of characters used for the RPM numbers. - uint16_t system_msg_display_time; // system message display time for multiple messages (ms) - uint8_t mAh_used_precision; // Number of numbers used for mAh drawn. Plently of packs now are > 9999 mAh - uint8_t ahi_pitch_interval; // redraws AHI at set pitch interval (Not pixel OSD) - char osd_switch_indicator0_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 0. - uint8_t osd_switch_indicator0_channel; // RC Channel to use for switch indicator 0. - char osd_switch_indicator1_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 1. - uint8_t osd_switch_indicator1_channel; // RC Channel to use for switch indicator 1. - char osd_switch_indicator2_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 2. - uint8_t osd_switch_indicator2_channel; // RC Channel to use for switch indicator 2. - char osd_switch_indicator3_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 3. - uint8_t osd_switch_indicator3_channel; // RC Channel to use for switch indicator 3. - bool osd_switch_indicators_align_left; // Align switch indicator name to left of the switch. - bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with the INAV logo. - uint8_t inav_to_pilot_logo_spacing; // The space between the INAV and pilot logos, if pilot logo is used. This number may be adjusted so that it fits the odd/even col width. - uint16_t arm_screen_display_time; // Length of time the arm screen is displayed + uint8_t coordinate_digits; + bool osd_failsafe_switch_layout; + uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE + uint8_t plus_code_short; + uint8_t ahi_style; + uint8_t force_grid; // Force a pixel based OSD to use grid mode. + uint8_t ahi_bordered; // Only used by the AHI widget + uint8_t ahi_width; // In pixels, only used by the AHI widget + uint8_t ahi_height; // In pixels, only used by the AHI widget + int8_t ahi_vertical_offset; // Offset from center in pixels. Positive moves the AHI down. Widget only. + int8_t sidebar_horizontal_offset; // Horizontal offset from default position. Units are grid slots for grid OSDs, pixels for pixel based OSDs. Positive values move sidebars closer to the edges. + uint8_t left_sidebar_scroll_step; // How many units each sidebar step represents. 0 means the default value for the scroll type. + uint8_t right_sidebar_scroll_step; // Same as left_sidebar_scroll_step, but for the right sidebar. + bool osd_home_position_arm_screen; + uint8_t pan_servo_index; // Index of the pan servo used for home direction offset + int8_t pan_servo_pwm2centideg; // Centidegrees of servo rotation per us pwm + uint8_t pan_servo_offcentre_warning; // Degrees around the centre, that is assumed camera is wanted to be facing forwards, but isn't centred + bool pan_servo_indicator_show_degrees; // Show the degrees of offset for the pan servo + uint8_t crsf_lq_format; + uint8_t sidebar_height; // sidebar height in rows, 0 turns off sidebars leaving only level indicator arrows + uint8_t telemetry; // use telemetry on displayed pixel line 0 + uint8_t esc_rpm_precision; // Number of characters used for the RPM numbers. + uint16_t system_msg_display_time; // system message display time for multiple messages (ms) + uint8_t mAh_used_precision; // Number of numbers used for mAh drawn. Plently of packs now are > 9999 mAh + uint8_t ahi_pitch_interval; // redraws AHI at set pitch interval (Not pixel OSD) + char osd_switch_indicator0_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 0. + uint8_t osd_switch_indicator0_channel; // RC Channel to use for switch indicator 0. + char osd_switch_indicator1_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 1. + uint8_t osd_switch_indicator1_channel; // RC Channel to use for switch indicator 1. + char osd_switch_indicator2_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 2. + uint8_t osd_switch_indicator2_channel; // RC Channel to use for switch indicator 2. + char osd_switch_indicator3_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 3. + uint8_t osd_switch_indicator3_channel; // RC Channel to use for switch indicator 3. + bool osd_switch_indicators_align_left; // Align switch indicator name to left of the switch. + bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with the INAV logo. + uint8_t inav_to_pilot_logo_spacing; // The space between the INAV and pilot logos, if pilot logo is used. This number may be adjusted so that it fits the odd/even col width. + uint16_t arm_screen_display_time; // Length of time the arm screen is displayed } osdConfig_t; PG_DECLARE(osdConfig_t, osdConfig); From 073ea3b3eeaf0742cf901340cb7729b93daa8284 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Mon, 18 Sep 2023 13:10:45 +0100 Subject: [PATCH 085/175] More tabs to spaces --- src/main/cms/cms.h | 6 +- src/main/io/osd.h | 240 ++++++++++++++++++++++----------------------- 2 files changed, 123 insertions(+), 123 deletions(-) diff --git a/src/main/cms/cms.h b/src/main/cms/cms.h index 812975e3b4..7084df8b50 100644 --- a/src/main/cms/cms.h +++ b/src/main/cms/cms.h @@ -37,9 +37,9 @@ void cmsYieldDisplay(displayPort_t *pPort, timeMs_t duration); void cmsUpdate(uint32_t currentTimeUs); void cmsSetExternKey(cms_key_e extKey); -#define CMS_STARTUP_HELP_TEXT1 "MENU: THR MID" -#define CMS_STARTUP_HELP_TEXT2 "+ YAW LEFT" -#define CMS_STARTUP_HELP_TEXT3 "+ PITCH UP" +#define CMS_STARTUP_HELP_TEXT1 "MENU: THR MID" +#define CMS_STARTUP_HELP_TEXT2 "+ YAW LEFT" +#define CMS_STARTUP_HELP_TEXT3 "+ PITCH UP" // cmsMenuExit special ptr values #define CMS_EXIT (0) diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 7df3acc404..f911f75b02 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -32,19 +32,19 @@ // 00vb yyyy yyxx xxxx // (visible)(blink)(yCoord)(xCoord) -#define OSD_VISIBLE_FLAG 0x2000 -#define OSD_VISIBLE(x) ((x) & OSD_VISIBLE_FLAG) +#define OSD_VISIBLE_FLAG 0x2000 +#define OSD_VISIBLE(x) ((x) & OSD_VISIBLE_FLAG) -#define OSD_POS(x,y) (((x) & 0x3F) | (((y) & 0x3F) << 6)) -#define OSD_X(x) ((x) & 0x3F) -#define OSD_Y(x) (((x) >> 6) & 0x3F) -#define OSD_POS_MAX 0xFFF +#define OSD_POS(x,y) (((x) & 0x3F) | (((y) & 0x3F) << 6)) +#define OSD_X(x) ((x) & 0x3F) +#define OSD_Y(x) (((x) >> 6) & 0x3F) +#define OSD_POS_MAX 0xFFF // For DJI compatibility #define OSD_VISIBLE_FLAG_SD 0x0800 -#define OSD_POS_SD(x,y) (((x) & 0x1F) | (((y) & 0x1F) << 5)) +#define OSD_POS_SD(x,y) (((x) & 0x1F) | (((y) & 0x1F) << 5)) -#define OSD_POS_MAX_CLI (OSD_POS_MAX | OSD_VISIBLE_FLAG) +#define OSD_POS_MAX_CLI (OSD_POS_MAX | OSD_VISIBLE_FLAG) #define OSD_HOMING_LIM_H1 6 #define OSD_HOMING_LIM_H2 16 @@ -54,78 +54,78 @@ #define OSD_HOMING_LIM_V3 15 // Message defines to be use in OSD and/or telemetry exports -#define OSD_MSG_RC_RX_LINK_LOST "!RC RX LINK LOST!" -#define OSD_MSG_TURN_ARM_SW_OFF "TURN ARM SWITCH OFF" -#define OSD_MSG_DISABLED_BY_FS "DISABLED BY FAILSAFE" -#define OSD_MSG_AIRCRAFT_UNLEVEL "AIRCRAFT IS NOT LEVEL" -#define OSD_MSG_SENSORS_CAL "SENSORS CALIBRATING" -#define OSD_MSG_SYS_OVERLOADED "SYSTEM OVERLOADED" -#define OSD_MSG_WAITING_GPS_FIX "WAITING FOR GPS FIX" -#define OSD_MSG_DISABLE_NAV_FIRST "DISABLE NAVIGATION FIRST" -#define OSD_MSG_JUMP_WP_MISCONFIG "JUMP WAYPOINT MISCONFIGURED" -#define OSD_MSG_MAG_NOT_CAL "COMPASS NOT CALIBRATED" -#define OSD_MSG_ACC_NOT_CAL "ACCELEROMETER NOT CALIBRATED" -#define OSD_MSG_DISARM_1ST "DISABLE ARM SWITCH FIRST" -#define OSD_MSG_GYRO_FAILURE "GYRO FAILURE" -#define OSD_MSG_ACC_FAIL "ACCELEROMETER FAILURE" -#define OSD_MSG_MAG_FAIL "COMPASS FAILURE" -#define OSD_MSG_BARO_FAIL "BAROMETER FAILURE" -#define OSD_MSG_GPS_FAIL "GPS FAILURE" -#define OSD_MSG_RANGEFINDER_FAIL "RANGE FINDER FAILURE" -#define OSD_MSG_PITOT_FAIL "PITOT METER FAILURE" -#define OSD_MSG_HW_FAIL "HARDWARE FAILURE" -#define OSD_MSG_FS_EN "FAILSAFE MODE ENABLED" -#define OSD_MSG_KILL_SW_EN "KILLSWITCH MODE ENABLED" -#define OSD_MSG_NO_RC_LINK "NO RC LINK" -#define OSD_MSG_THROTTLE_NOT_LOW "THROTTLE IS NOT LOW" -#define OSD_MSG_ROLLPITCH_OFFCENTER "ROLLPITCH NOT CENTERED" -#define OSD_MSG_AUTOTRIM_ACTIVE "AUTOTRIM IS ACTIVE" -#define OSD_MSG_NOT_ENOUGH_MEMORY "NOT ENOUGH MEMORY" -#define OSD_MSG_INVALID_SETTING "INVALID SETTING" -#define OSD_MSG_CLI_ACTIVE "CLI IS ACTIVE" -#define OSD_MSG_PWM_INIT_ERROR "PWM INIT ERROR" -#define OSD_MSG_NO_PREARM "NO PREARM" -#define OSD_MSG_DSHOT_BEEPER "MOTOR BEEPER ACTIVE" -#define OSD_MSG_RTH_FS "(RTH)" -#define OSD_MSG_EMERG_LANDING_FS "(EMERGENCY LANDING)" -#define OSD_MSG_MOVE_EXIT_FS "!MOVE STICKS TO EXIT FS!" -#define OSD_MSG_STARTING_RTH "STARTING RTH" -#define OSD_MSG_RTH_CLIMB "ADJUSTING RTH ALTITUDE" -#define OSD_MSG_RTH_TRACKBACK "RTH BACK TRACKING" -#define OSD_MSG_HEADING_HOME "EN ROUTE TO HOME" -#define OSD_MSG_WP_FINISHED "WP END>HOLDING POSITION" -#define OSD_MSG_WP_LANDED "WP END>LANDED" -#define OSD_MSG_PREPARE_NEXT_WP "PREPARING FOR NEXT WAYPOINT" -#define OSD_MSG_ADJUSTING_WP_ALT "ADJUSTING WP ALTITUDE" -#define OSD_MSG_MISSION_PLANNER "(WP MISSION PLANNER)" -#define OSD_MSG_WP_RTH_CANCEL "CANCEL WP TO EXIT RTH" -#define OSD_MSG_WP_MISSION_LOADED "* MISSION LOADED *" -#define OSD_MSG_EMERG_LANDING "EMERGENCY LANDING" -#define OSD_MSG_LANDING "LANDING" -#define OSD_MSG_LOITERING_HOME "LOITERING AROUND HOME" -#define OSD_MSG_HOVERING "HOVERING" -#define OSD_MSG_LANDED "LANDED" -#define OSD_MSG_PREPARING_LAND "PREPARING TO LAND" -#define OSD_MSG_AUTOLAUNCH "AUTOLAUNCH" -#define OSD_MSG_AUTOLAUNCH_MANUAL "AUTOLAUNCH (MANUAL)" -#define OSD_MSG_ALTITUDE_HOLD "(ALTITUDE HOLD)" -#define OSD_MSG_AUTOTRIM "(AUTOTRIM)" -#define OSD_MSG_AUTOTUNE "(AUTOTUNE)" -#define OSD_MSG_AUTOTUNE_ACRO "SWITCH TO ACRO" -#define OSD_MSG_AUTOLEVEL "(AUTO LEVEL TRIM)" -#define OSD_MSG_HEADFREE "(HEADFREE)" -#define OSD_MSG_NAV_SOARING "(SOARING)" -#define OSD_MSG_UNABLE_ARM "UNABLE TO ARM" -#define OSD_MSG_SAVING_SETTNGS "** SAVING SETTINGS **" -#define OSD_MSG_SETTINGS_SAVED "** SETTINGS SAVED **" +#define OSD_MSG_RC_RX_LINK_LOST "!RC RX LINK LOST!" +#define OSD_MSG_TURN_ARM_SW_OFF "TURN ARM SWITCH OFF" +#define OSD_MSG_DISABLED_BY_FS "DISABLED BY FAILSAFE" +#define OSD_MSG_AIRCRAFT_UNLEVEL "AIRCRAFT IS NOT LEVEL" +#define OSD_MSG_SENSORS_CAL "SENSORS CALIBRATING" +#define OSD_MSG_SYS_OVERLOADED "SYSTEM OVERLOADED" +#define OSD_MSG_WAITING_GPS_FIX "WAITING FOR GPS FIX" +#define OSD_MSG_DISABLE_NAV_FIRST "DISABLE NAVIGATION FIRST" +#define OSD_MSG_JUMP_WP_MISCONFIG "JUMP WAYPOINT MISCONFIGURED" +#define OSD_MSG_MAG_NOT_CAL "COMPASS NOT CALIBRATED" +#define OSD_MSG_ACC_NOT_CAL "ACCELEROMETER NOT CALIBRATED" +#define OSD_MSG_DISARM_1ST "DISABLE ARM SWITCH FIRST" +#define OSD_MSG_GYRO_FAILURE "GYRO FAILURE" +#define OSD_MSG_ACC_FAIL "ACCELEROMETER FAILURE" +#define OSD_MSG_MAG_FAIL "COMPASS FAILURE" +#define OSD_MSG_BARO_FAIL "BAROMETER FAILURE" +#define OSD_MSG_GPS_FAIL "GPS FAILURE" +#define OSD_MSG_RANGEFINDER_FAIL "RANGE FINDER FAILURE" +#define OSD_MSG_PITOT_FAIL "PITOT METER FAILURE" +#define OSD_MSG_HW_FAIL "HARDWARE FAILURE" +#define OSD_MSG_FS_EN "FAILSAFE MODE ENABLED" +#define OSD_MSG_KILL_SW_EN "KILLSWITCH MODE ENABLED" +#define OSD_MSG_NO_RC_LINK "NO RC LINK" +#define OSD_MSG_THROTTLE_NOT_LOW "THROTTLE IS NOT LOW" +#define OSD_MSG_ROLLPITCH_OFFCENTER "ROLLPITCH NOT CENTERED" +#define OSD_MSG_AUTOTRIM_ACTIVE "AUTOTRIM IS ACTIVE" +#define OSD_MSG_NOT_ENOUGH_MEMORY "NOT ENOUGH MEMORY" +#define OSD_MSG_INVALID_SETTING "INVALID SETTING" +#define OSD_MSG_CLI_ACTIVE "CLI IS ACTIVE" +#define OSD_MSG_PWM_INIT_ERROR "PWM INIT ERROR" +#define OSD_MSG_NO_PREARM "NO PREARM" +#define OSD_MSG_DSHOT_BEEPER "MOTOR BEEPER ACTIVE" +#define OSD_MSG_RTH_FS "(RTH)" +#define OSD_MSG_EMERG_LANDING_FS "(EMERGENCY LANDING)" +#define OSD_MSG_MOVE_EXIT_FS "!MOVE STICKS TO EXIT FS!" +#define OSD_MSG_STARTING_RTH "STARTING RTH" +#define OSD_MSG_RTH_CLIMB "ADJUSTING RTH ALTITUDE" +#define OSD_MSG_RTH_TRACKBACK "RTH BACK TRACKING" +#define OSD_MSG_HEADING_HOME "EN ROUTE TO HOME" +#define OSD_MSG_WP_FINISHED "WP END>HOLDING POSITION" +#define OSD_MSG_WP_LANDED "WP END>LANDED" +#define OSD_MSG_PREPARE_NEXT_WP "PREPARING FOR NEXT WAYPOINT" +#define OSD_MSG_ADJUSTING_WP_ALT "ADJUSTING WP ALTITUDE" +#define OSD_MSG_MISSION_PLANNER "(WP MISSION PLANNER)" +#define OSD_MSG_WP_RTH_CANCEL "CANCEL WP TO EXIT RTH" +#define OSD_MSG_WP_MISSION_LOADED "* MISSION LOADED *" +#define OSD_MSG_EMERG_LANDING "EMERGENCY LANDING" +#define OSD_MSG_LANDING "LANDING" +#define OSD_MSG_LOITERING_HOME "LOITERING AROUND HOME" +#define OSD_MSG_HOVERING "HOVERING" +#define OSD_MSG_LANDED "LANDED" +#define OSD_MSG_PREPARING_LAND "PREPARING TO LAND" +#define OSD_MSG_AUTOLAUNCH "AUTOLAUNCH" +#define OSD_MSG_AUTOLAUNCH_MANUAL "AUTOLAUNCH (MANUAL)" +#define OSD_MSG_ALTITUDE_HOLD "(ALTITUDE HOLD)" +#define OSD_MSG_AUTOTRIM "(AUTOTRIM)" +#define OSD_MSG_AUTOTUNE "(AUTOTUNE)" +#define OSD_MSG_AUTOTUNE_ACRO "SWITCH TO ACRO" +#define OSD_MSG_AUTOLEVEL "(AUTO LEVEL TRIM)" +#define OSD_MSG_HEADFREE "(HEADFREE)" +#define OSD_MSG_NAV_SOARING "(SOARING)" +#define OSD_MSG_UNABLE_ARM "UNABLE TO ARM" +#define OSD_MSG_SAVING_SETTNGS "** SAVING SETTINGS **" +#define OSD_MSG_SETTINGS_SAVED "** SETTINGS SAVED **" #ifdef USE_DEV_TOOLS -#define OSD_MSG_GRD_TEST_MODE "GRD TEST > MOTORS DISABLED" +#define OSD_MSG_GRD_TEST_MODE "GRD TEST > MOTORS DISABLED" #endif #if defined(USE_SAFE_HOME) -#define OSD_MSG_DIVERT_SAFEHOME "DIVERTING TO SAFEHOME" -#define OSD_MSG_LOITERING_SAFEHOME "LOITERING AROUND SAFEHOME" +#define OSD_MSG_DIVERT_SAFEHOME "DIVERTING TO SAFEHOME" +#define OSD_MSG_LOITERING_SAFEHOME "LOITERING AROUND SAFEHOME" #endif typedef enum { @@ -343,12 +343,12 @@ PG_DECLARE(osdLayoutsConfig_t, osdLayoutsConfig); typedef struct osdConfig_s { // Alarms - uint8_t rssi_alarm; // rssi % - uint16_t time_alarm; // fly minutes - uint16_t alt_alarm; // positive altitude in m - uint16_t dist_alarm; // home distance in m - uint16_t neg_alt_alarm; // abs(negative altitude) in m - uint8_t current_alarm; // current consumption in A + uint8_t rssi_alarm; // rssi % + uint16_t time_alarm; // fly minutes + uint16_t alt_alarm; // positive altitude in m + uint16_t dist_alarm; // home distance in m + uint16_t neg_alt_alarm; // abs(negative altitude) in m + uint8_t current_alarm; // current consumption in A int16_t imu_temp_alarm_min; int16_t imu_temp_alarm_max; int16_t esc_temp_alarm_min; @@ -357,11 +357,11 @@ typedef struct osdConfig_s { float gforce_axis_alarm_min; float gforce_axis_alarm_max; #ifdef USE_SERIALRX_CRSF - int8_t snr_alarm; //CRSF SNR alarm in dB + int8_t snr_alarm; //CRSF SNR alarm in dB int8_t link_quality_alarm; - int16_t rssi_dbm_alarm; // in dBm - int16_t rssi_dbm_max; // Perfect RSSI. Set to High end of curve. RSSI at 100% - int16_t rssi_dbm_min; // Worst RSSI. Set to low end of curve or RX sensitivity level. RSSI at 0% + int16_t rssi_dbm_alarm; // in dBm + int16_t rssi_dbm_max; // Perfect RSSI. Set to High end of curve. RSSI at 100% + int16_t rssi_dbm_min; // Worst RSSI. Set to low end of curve or RX sensitivity level. RSSI at 0% #endif #ifdef USE_BARO int16_t baro_temp_alarm_min; @@ -383,7 +383,7 @@ typedef struct osdConfig_s { uint8_t main_voltage_decimals; uint8_t ahi_reverse_roll; uint8_t ahi_max_pitch; - uint8_t crosshairs_style; // from osd_crosshairs_style_e + uint8_t crosshairs_style; // from osd_crosshairs_style_e int8_t horizon_offset; int8_t camera_uptilt; bool ahi_camera_uptilt_comp; @@ -400,55 +400,55 @@ typedef struct osdConfig_s { uint8_t hud_radar_distance_display_time; uint8_t hud_wp_disp; - uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_e - uint8_t right_sidebar_scroll; // from osd_sidebar_scroll_e + uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_e + uint8_t right_sidebar_scroll; // from osd_sidebar_scroll_e uint8_t sidebar_scroll_arrows; - uint8_t units; // from osd_unit_e - uint8_t stats_energy_unit; // from osd_stats_energy_unit_e - uint8_t stats_min_voltage_unit; // from osd_stats_min_voltage_unit_e - uint8_t stats_page_auto_swap_time; // stats page auto swap interval time (seconds) + uint8_t units; // from osd_unit_e + uint8_t stats_energy_unit; // from osd_stats_energy_unit_e + uint8_t stats_min_voltage_unit; // from osd_stats_min_voltage_unit_e + uint8_t stats_page_auto_swap_time; // stats page auto swap interval time (seconds) #ifdef USE_WIND_ESTIMATOR - bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance + bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance #endif uint8_t coordinate_digits; bool osd_failsafe_switch_layout; - uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE + uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE uint8_t plus_code_short; uint8_t ahi_style; - uint8_t force_grid; // Force a pixel based OSD to use grid mode. - uint8_t ahi_bordered; // Only used by the AHI widget - uint8_t ahi_width; // In pixels, only used by the AHI widget - uint8_t ahi_height; // In pixels, only used by the AHI widget - int8_t ahi_vertical_offset; // Offset from center in pixels. Positive moves the AHI down. Widget only. - int8_t sidebar_horizontal_offset; // Horizontal offset from default position. Units are grid slots for grid OSDs, pixels for pixel based OSDs. Positive values move sidebars closer to the edges. - uint8_t left_sidebar_scroll_step; // How many units each sidebar step represents. 0 means the default value for the scroll type. - uint8_t right_sidebar_scroll_step; // Same as left_sidebar_scroll_step, but for the right sidebar. + uint8_t force_grid; // Force a pixel based OSD to use grid mode. + uint8_t ahi_bordered; // Only used by the AHI widget + uint8_t ahi_width; // In pixels, only used by the AHI widget + uint8_t ahi_height; // In pixels, only used by the AHI widget + int8_t ahi_vertical_offset; // Offset from center in pixels. Positive moves the AHI down. Widget only. + int8_t sidebar_horizontal_offset; // Horizontal offset from default position. Units are grid slots for grid OSDs, pixels for pixel based OSDs. Positive values move sidebars closer to the edges. + uint8_t left_sidebar_scroll_step; // How many units each sidebar step represents. 0 means the default value for the scroll type. + uint8_t right_sidebar_scroll_step; // Same as left_sidebar_scroll_step, but for the right sidebar. bool osd_home_position_arm_screen; - uint8_t pan_servo_index; // Index of the pan servo used for home direction offset - int8_t pan_servo_pwm2centideg; // Centidegrees of servo rotation per us pwm - uint8_t pan_servo_offcentre_warning; // Degrees around the centre, that is assumed camera is wanted to be facing forwards, but isn't centred - bool pan_servo_indicator_show_degrees; // Show the degrees of offset for the pan servo + uint8_t pan_servo_index; // Index of the pan servo used for home direction offset + int8_t pan_servo_pwm2centideg; // Centidegrees of servo rotation per us pwm + uint8_t pan_servo_offcentre_warning; // Degrees around the centre, that is assumed camera is wanted to be facing forwards, but isn't centred + bool pan_servo_indicator_show_degrees; // Show the degrees of offset for the pan servo uint8_t crsf_lq_format; - uint8_t sidebar_height; // sidebar height in rows, 0 turns off sidebars leaving only level indicator arrows - uint8_t telemetry; // use telemetry on displayed pixel line 0 - uint8_t esc_rpm_precision; // Number of characters used for the RPM numbers. - uint16_t system_msg_display_time; // system message display time for multiple messages (ms) - uint8_t mAh_used_precision; // Number of numbers used for mAh drawn. Plently of packs now are > 9999 mAh - uint8_t ahi_pitch_interval; // redraws AHI at set pitch interval (Not pixel OSD) + uint8_t sidebar_height; // sidebar height in rows, 0 turns off sidebars leaving only level indicator arrows + uint8_t telemetry; // use telemetry on displayed pixel line 0 + uint8_t esc_rpm_precision; // Number of characters used for the RPM numbers. + uint16_t system_msg_display_time; // system message display time for multiple messages (ms) + uint8_t mAh_used_precision; // Number of numbers used for mAh drawn. Plently of packs now are > 9999 mAh + uint8_t ahi_pitch_interval; // redraws AHI at set pitch interval (Not pixel OSD) char osd_switch_indicator0_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 0. - uint8_t osd_switch_indicator0_channel; // RC Channel to use for switch indicator 0. + uint8_t osd_switch_indicator0_channel; // RC Channel to use for switch indicator 0. char osd_switch_indicator1_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 1. - uint8_t osd_switch_indicator1_channel; // RC Channel to use for switch indicator 1. + uint8_t osd_switch_indicator1_channel; // RC Channel to use for switch indicator 1. char osd_switch_indicator2_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 2. - uint8_t osd_switch_indicator2_channel; // RC Channel to use for switch indicator 2. + uint8_t osd_switch_indicator2_channel; // RC Channel to use for switch indicator 2. char osd_switch_indicator3_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 3. - uint8_t osd_switch_indicator3_channel; // RC Channel to use for switch indicator 3. - bool osd_switch_indicators_align_left; // Align switch indicator name to left of the switch. - bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with the INAV logo. - uint8_t inav_to_pilot_logo_spacing; // The space between the INAV and pilot logos, if pilot logo is used. This number may be adjusted so that it fits the odd/even col width. - uint16_t arm_screen_display_time; // Length of time the arm screen is displayed + uint8_t osd_switch_indicator3_channel; // RC Channel to use for switch indicator 3. + bool osd_switch_indicators_align_left; // Align switch indicator name to left of the switch. + bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with the INAV logo. + uint8_t inav_to_pilot_logo_spacing; // The space between the INAV and pilot logos, if pilot logo is used. This number may be adjusted so that it fits the odd/even col width. + uint16_t arm_screen_display_time; // Length of time the arm screen is displayed } osdConfig_t; PG_DECLARE(osdConfig_t, osdConfig); From 0d3216ef07177c925f783ef9a4f886be5df70873 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 19 Sep 2023 20:55:00 +0200 Subject: [PATCH 086/175] Set EZ Tune on profile change --- src/main/fc/config.c | 3 +++ src/main/fc/fc_msp.c | 3 +++ src/main/flight/ez_tune.c | 1 - 3 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 3b884db747..65bca8f9ef 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -423,6 +423,9 @@ bool setConfigProfile(uint8_t profileIndex) systemConfigMutable()->current_profile_index = profileIndex; // set the control rate profile to match setControlRateProfile(profileIndex); +#ifdef USE_EZ_TUNE + ezTuneUpdate(); +#endif return ret; } diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index b2c04e9dc1..a60975b9dc 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -696,6 +696,9 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, constrain(pidBank()->pid[i].D, 0, 255)); sbufWriteU8(dst, constrain(pidBank()->pid[i].FF, 0, 255)); } + #ifdef USE_EZ_TUNE + ezTuneUpdate(); + #endif break; case MSP_PIDNAMES: diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index c4846d3989..2703fe870e 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -65,7 +65,6 @@ static float getYawPidScale(float input) { /** * Update INAV settings based on current EZTune settings * This has to be called every time control profile is changed, or EZTune settings are changed - * FIXME call on profile change * FIXME call on EZTune settings change */ void ezTuneUpdate(void) { From e772d085cdbdfecd0250f431cf5894b257ec797a Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 19 Sep 2023 21:14:38 +0200 Subject: [PATCH 087/175] Add EZ Tune MSP frames --- src/main/fc/config.c | 1 + src/main/fc/fc_msp.c | 43 +++++++++++++++++++++++++++++ src/main/msp/msp_protocol_v2_inav.h | 2 ++ 3 files changed, 46 insertions(+) diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 65bca8f9ef..fa7d893655 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -64,6 +64,7 @@ #include "flight/pid.h" #include "flight/imu.h" #include "flight/failsafe.h" +#include "flight/ez_tune.h" #include "fc/config.h" #include "fc/controlrate_profile.h" diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index a60975b9dc..f2c80bfd95 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -77,6 +77,7 @@ #include "flight/mixer.h" #include "flight/pid.h" #include "flight/servos.h" +#include "flight/ez_tune.h" #include "config/config_eeprom.h" #include "config/feature.h" @@ -1583,6 +1584,24 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF break; #endif +#ifdef USE_EZ_TUNE + + case MSP2_INAV_EZ_TUNE: + { + sbufWriteU8(dst, ezTune()->enabled); + sbufWriteU16(dst, ezTune()->filterHz); + sbufWriteU8(dst, ezTune()->axisRatio); + sbufWriteU8(dst, ezTune()->response); + sbufWriteU8(dst, ezTune()->damping); + sbufWriteU8(dst, ezTune()->stability); + sbufWriteU8(dst, ezTune()->aggressiveness); + sbufWriteU8(dst, ezTune()->rate); + sbufWriteU8(dst, ezTune()->expo); + } + break; + +#endif + default: return false; } @@ -3040,6 +3059,30 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) break; #endif +#ifdef USE_EZ_TUNE + + case MSP2_INAV_EZ_TUNE_SET: + { + if (dataSize == 10) { + ezTuneMutable()->enabled = sbufReadU8(src); + ezTuneMutable()->filterHz = sbufReadU16(src); + ezTuneMutable()->axisRatio = sbufReadU8(src); + ezTuneMutable()->response = sbufReadU8(src); + ezTuneMutable()->damping = sbufReadU8(src); + ezTuneMutable()->stability = sbufReadU8(src); + ezTuneMutable()->aggressiveness = sbufReadU8(src); + ezTuneMutable()->rate = sbufReadU8(src); + ezTuneMutable()->expo = sbufReadU8(src); + + ezTuneUpdate(); + } else { + return MSP_RESULT_ERROR; + } + } + break; + +#endif + default: return MSP_RESULT_ERROR; } diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index f746f5c8ff..3c38c8ffd4 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -92,3 +92,5 @@ #define MSP2_INAV_LED_STRIP_CONFIG_EX 0x2048 #define MSP2_INAV_SET_LED_STRIP_CONFIG_EX 0x2049 +#define MSP2_INAV_EZ_TUNE 0x2050 +#define MSP2_INAV_EZ_TUNE_SET 0x2051 \ No newline at end of file From 3ffb125977ff71e027bfa1a20aee75f592a0ddf0 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 23 Sep 2023 13:32:38 +0100 Subject: [PATCH 088/175] Increment PG --- src/main/io/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index ce90250d42..d336dea791 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -208,7 +208,7 @@ static bool osdDisplayHasCanvas; #define AH_MAX_PITCH_DEFAULT 20 // Specify default maximum AHI pitch value displayed (degrees) -PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 8); +PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 9); PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 1); void osdStartedSaveProcess(void) { From 92ab6b87366f5a7b950a47d605d042b8702c9358 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 23 Sep 2023 14:11:15 +0100 Subject: [PATCH 089/175] Fixed bugs post merge from master --- src/main/io/osd.c | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index d336dea791..b9b9b9c0ba 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -4496,7 +4496,7 @@ static void osdShowHDArmScreen(void) displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); #if defined(USE_GPS) #if defined (USE_SAFE_HOME) - if (safehome_distance) { + if (posControl.safehomeState.distance) { safehomeRow = armScreenRow; armScreenRow++; } @@ -4625,12 +4625,12 @@ static void osdShowSDArmScreen(void) } #if defined (USE_SAFE_HOME) - if (safehome_distance) { // safehome found during arming + if (posControl.safehomeState.distance) { // safehome found during arming if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) { strcpy(buf, "SAFEHOME FOUND; MODE OFF"); } else { - osdFormatDistanceStr(buf2, safehome_distance); - tfp_sprintf(buf, "%c SAFEHOME %u @ %s", SYM_HOME, safehome_index, buf2); + osdFormatDistanceStr(buf2, posControl.safehomeState.distance); + tfp_sprintf(buf, "%c SAFEHOME %u @ %s", SYM_HOME, posControl.safehomeState.index, buf2); } textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT; // write this message below the ARMED message to make it obvious @@ -4775,7 +4775,7 @@ static void osdRefresh(timeUs_t currentTimeUs) #if defined(USE_SAFE_HOME) if (posControl.safehomeState.distance) delay+= 3000; - +#endif osdSetNextRefreshIn(delay); } else { // Display the "Stats" screen @@ -5391,4 +5391,5 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff) return elemAttr; } + #endif // OSD From 08178edc711d57bf51292b04bf19dcbea38a37d1 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 23 Sep 2023 14:58:52 -0500 Subject: [PATCH 090/175] flight/pid.c: fix AngleOverride(yaw) to degrees --- src/main/flight/pid.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index b2fd0383a2..d2e94b9651 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -1071,7 +1071,7 @@ void FAST_CODE pidController(float dT) // In case Yaw override is active, we engage the Heading Hold state if (isFlightAxisAngleOverrideActive(FD_YAW)) { headingHoldState = HEADING_HOLD_ENABLED; - headingHoldTarget = getFlightAxisAngleOverride(FD_YAW, 0); + headingHoldTarget = DECIDEGREES_TO_DEGREES(getFlightAxisAngleOverride(FD_YAW, 0)); } if (headingHoldState == HEADING_HOLD_UPDATE_HEADING) { From 45773f4150f27c99f477769d7046d26cc2140183 Mon Sep 17 00:00:00 2001 From: MarkTan Date: Tue, 26 Sep 2023 14:22:30 +0800 Subject: [PATCH 091/175] Create CMakeLists.txt --- src/main/target/AOCODARCF722AIO/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) create mode 100644 src/main/target/AOCODARCF722AIO/CMakeLists.txt diff --git a/src/main/target/AOCODARCF722AIO/CMakeLists.txt b/src/main/target/AOCODARCF722AIO/CMakeLists.txt new file mode 100644 index 0000000000..87553f152f --- /dev/null +++ b/src/main/target/AOCODARCF722AIO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(AOCODARCF722AIO) From 81e2d8de87cc7015301979576e1e85bc15d7bd3a Mon Sep 17 00:00:00 2001 From: MarkTan Date: Tue, 26 Sep 2023 14:23:01 +0800 Subject: [PATCH 092/175] Add files via upload --- src/main/target/AOCODARCF722AIO/config.c | 44 ++++++ src/main/target/AOCODARCF722AIO/target.c | 40 ++++++ src/main/target/AOCODARCF722AIO/target.h | 175 +++++++++++++++++++++++ 3 files changed, 259 insertions(+) create mode 100644 src/main/target/AOCODARCF722AIO/config.c create mode 100644 src/main/target/AOCODARCF722AIO/target.c create mode 100644 src/main/target/AOCODARCF722AIO/target.h diff --git a/src/main/target/AOCODARCF722AIO/config.c b/src/main/target/AOCODARCF722AIO/config.c new file mode 100644 index 0000000000..a340726d49 --- /dev/null +++ b/src/main/target/AOCODARCF722AIO/config.c @@ -0,0 +1,44 @@ +/* + * @Author: g05047 + * @Date: 2023-03-22 17:15:53 + * @LastEditors: g05047 + * @LastEditTime: 2023-03-23 16:21:45 + * @Description: file content + */ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "io/piniobox.h" +#include "sensors/boardalignment.h" +#include "sensors/barometer.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" + +void targetConfiguration(void) +{ + + compassConfigMutable()->mag_align = CW90_DEG; + + // barometerConfigMutable()->baro_hardware = BARO_DPS310; + + // boardAlignmentMutable()->rollDeciDegrees = -1800; + +} diff --git a/src/main/target/AOCODARCF722AIO/target.c b/src/main/target/AOCODARCF722AIO/target.c new file mode 100644 index 0000000000..fcc6e1a796 --- /dev/null +++ b/src/main/target/AOCODARCF722AIO/target.c @@ -0,0 +1,40 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/sensor.h" + +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM + + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AOCODARCF722AIO/target.h b/src/main/target/AOCODARCF722AIO/target.h new file mode 100644 index 0000000000..fd2a559b93 --- /dev/null +++ b/src/main/target/AOCODARCF722AIO/target.h @@ -0,0 +1,175 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "F722AIO" +#define USBD_PRODUCT_STRING "AocodaRCF722AIO" + +#define LED0 PA4 + +#define USE_BEEPER +#define BEEPER PC13 +#define BEEPER_INVERTED + +/*** UART ***/ +#define USB_IO +#define USE_VCP + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define SERIAL_PORT_COUNT 6 + +/*** Gyro & Acc ***/ +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_MPU6500 +#define MPU6500_CS_PIN PB2 +#define MPU6500_SPI_BUS BUS_SPI1 +#define MPU6500_EXTI_PIN PC4 + +#define IMU_MPU6500_ALIGN CW180_DEG + +#define USE_IMU_MPU6000 +#define MPU6000_CS_PIN PB2 +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_EXTI_PIN PC4 + +#define IMU_MPU6000_ALIGN CW180_DEG + +#define USE_IMU_ICM42605 +#define ICM42605_CS_PIN PB2 +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_EXTI_PIN PC4 + +#define IMU_ICM42605_ALIGN CW180_DEG + +/*** I2C (Baro & Mag) ***/ +#define USE_I2C + +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +// Baro +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_SPL06 +#define USE_BARO_DPS310 + +// Mag +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +/*** Onboard Flash ***/ +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PD2 + +#define W25N01G_SPI_BUS BUS_SPI3 +#define W25N01G_CS_PIN PD2 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +/*** OSD ***/ +#define USE_OSD +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +/*** ADC ***/ +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC0 +#define ADC_CHANNEL_3_PIN PC1 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3 +#define RSSI_ADC_CHANNEL ADC_CHN_2 + +/*** LED ***/ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +/*** Optical Flow & Lidar ***/ +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_OPFLOW +#define USE_OPFLOW_MSP + +/*** Misc ***/ +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX) +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define SERIALRX_UART SERIAL_PORT_USART2 +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF + +#define MAX_PWM_OUTPUT_PORTS 8 + +#define CURRENT_METER_SCALE 250 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) From 3a96bfadc5b43cfb4c67fe329e4ab161c11c66b0 Mon Sep 17 00:00:00 2001 From: MarkTan Date: Tue, 26 Sep 2023 16:18:54 +0800 Subject: [PATCH 093/175] Remove the code TIM_USE_FW_MOTOR Remove the code TIM_USE_FW_MOTOR --- src/main/target/AOCODARCF722AIO/target.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/target/AOCODARCF722AIO/target.c b/src/main/target/AOCODARCF722AIO/target.c index fcc6e1a796..229a880fb1 100644 --- a/src/main/target/AOCODARCF722AIO/target.c +++ b/src/main/target/AOCODARCF722AIO/target.c @@ -29,10 +29,10 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU65 timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0, 0), // S4 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED }; From 359b45f104608f706a1cb05742e0f4d9d325842a Mon Sep 17 00:00:00 2001 From: MarkTan Date: Tue, 26 Sep 2023 17:21:10 +0800 Subject: [PATCH 094/175] Update config.c Modifying MCU direction --- src/main/target/AOCODARCF722AIO/config.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/AOCODARCF722AIO/config.c b/src/main/target/AOCODARCF722AIO/config.c index a340726d49..8996c3c5d3 100644 --- a/src/main/target/AOCODARCF722AIO/config.c +++ b/src/main/target/AOCODARCF722AIO/config.c @@ -39,6 +39,6 @@ void targetConfiguration(void) // barometerConfigMutable()->baro_hardware = BARO_DPS310; - // boardAlignmentMutable()->rollDeciDegrees = -1800; + boardAlignmentMutable()->rollDeciDegrees = -450; } From 34d1b969b3615a90cd24919fe9689d59d704e0a1 Mon Sep 17 00:00:00 2001 From: MarkTan Date: Tue, 26 Sep 2023 19:23:11 +0800 Subject: [PATCH 095/175] Replace the value with TIME_USE_OUTPUT_AUTO Replace the value with TIME_USE_OUTPUT_AUTO --- src/main/target/AOCODARCF722AIO/target.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/target/AOCODARCF722AIO/target.c b/src/main/target/AOCODARCF722AIO/target.c index 229a880fb1..1d06778cbf 100644 --- a/src/main/target/AOCODARCF722AIO/target.c +++ b/src/main/target/AOCODARCF722AIO/target.c @@ -29,10 +29,10 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU65 timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR, 0, 0), // S1 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR, 0, 0), // S2 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // S3 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0, 0), // S4 + DEF_TIM(TIM3, CH1, PB4, TIME_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PB5, TIME_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PB0, TIME_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PB1, TIME_USE_OUTPUT_AUTO, 0, 0), // S4 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED }; From f185efac28c6fc1393908e18040cbca3b74f3cfb Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 26 Sep 2023 16:41:56 +0200 Subject: [PATCH 096/175] Fix typo --- src/main/target/AOCODARCF722AIO/target.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/target/AOCODARCF722AIO/target.c b/src/main/target/AOCODARCF722AIO/target.c index 1d06778cbf..4d9deb5683 100644 --- a/src/main/target/AOCODARCF722AIO/target.c +++ b/src/main/target/AOCODARCF722AIO/target.c @@ -29,10 +29,10 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU65 timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH1, PB4, TIME_USE_OUTPUT_AUTO, 0, 0), // S1 - DEF_TIM(TIM3, CH2, PB5, TIME_USE_OUTPUT_AUTO, 0, 0), // S2 - DEF_TIM(TIM3, CH3, PB0, TIME_USE_OUTPUT_AUTO, 0, 0), // S3 - DEF_TIM(TIM3, CH4, PB1, TIME_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED }; From 52f5cffc43e73283f599054236ff5b460ea146ed Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Tue, 26 Sep 2023 23:33:56 +0100 Subject: [PATCH 097/175] prevent unwanted resets on disarm --- src/main/fc/fc_core.c | 12 +++++- src/main/fc/runtime_config.h | 1 + src/main/io/osd.c | 6 ++- src/main/navigation/navigation.c | 34 ++++++++++------ .../navigation/navigation_pos_estimator.c | 40 ++++++++++++++----- 5 files changed, 67 insertions(+), 26 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 76d1a2626c..66c275366b 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -436,6 +436,7 @@ void disarm(disarmReason_t disarmReason) lastDisarmReason = disarmReason; lastDisarmTimeUs = micros(); DISABLE_ARMING_FLAG(ARMED); + DISABLE_STATE(IN_FLIGHT_EMERG_REARM); #ifdef USE_BLACKBOX if (feature(FEATURE_BLACKBOX)) { @@ -522,6 +523,7 @@ bool emergInflightRearmEnabled(void) if (isProbablyStillFlying() || mcDisarmVertVelCheck) { emergRearmStabiliseTimeout = currentTimeMs + 5000; // activate Angle mode for 5s after rearm to help stabilise craft + ENABLE_STATE(IN_FLIGHT_EMERG_REARM); return true; } @@ -574,11 +576,13 @@ void tryArm(void) ENABLE_ARMING_FLAG(WAS_EVER_ARMED); //It is required to inform the mixer that arming was executed and it has to switch to the FORWARD direction ENABLE_STATE(SET_REVERSIBLE_MOTORS_FORWARD); - logicConditionReset(); + if (!STATE(IN_FLIGHT_EMERG_REARM)) { + logicConditionReset(); #ifdef USE_PROGRAMMING_FRAMEWORK - programmingPidReset(); + programmingPidReset(); #endif + } headFreeModeHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw); @@ -902,6 +906,10 @@ void taskMainPidLoop(timeUs_t currentTimeUs) processDelayedSave(); } + if (armTime > 1 * USECS_PER_SEC) { // reset in flight emerg rearm flag 1 sec after arming once it's served its purpose + DISABLE_STATE(IN_FLIGHT_EMERG_REARM); + } + #if defined(SITL_BUILD) if (lockMainPID()) { #endif diff --git a/src/main/fc/runtime_config.h b/src/main/fc/runtime_config.h index 16d1b411df..241e5f7e25 100644 --- a/src/main/fc/runtime_config.h +++ b/src/main/fc/runtime_config.h @@ -139,6 +139,7 @@ typedef enum { FW_HEADING_USE_YAW = (1 << 24), ANTI_WINDUP_DEACTIVATED = (1 << 25), LANDING_DETECTED = (1 << 26), + IN_FLIGHT_EMERG_REARM = (1 << 27), } stateFlags_t; #define DISABLE_STATE(mask) (stateFlags &= ~(mask)) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index f5daeaf63c..b34751096e 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -4579,9 +4579,13 @@ static void osdRefresh(timeUs_t currentTimeUs) osdResetStats(); osdShowArmed(); uint32_t delay = ARMED_SCREEN_DISPLAY_TIME; + if (STATE(IN_FLIGHT_EMERG_REARM)) { + delay /= 3; + } #if defined(USE_SAFE_HOME) - if (posControl.safehomeState.distance) + else if (posControl.safehomeState.distance) { delay *= 3; + } #endif osdSetNextRefreshIn(delay); } else { diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index b6cf9583c7..0465eceab6 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2530,11 +2530,15 @@ bool findNearestSafeHome(void) *-----------------------------------------------------------*/ void updateHomePosition(void) { - // Disarmed and have a valid position, constantly update home + // Disarmed and have a valid position, constantly update home before first arm (depending on setting) + // Update immediately after arming thereafter if reset on each arm (required to avoid home reset after emerg in flight rearm) + static bool setHome = false; + navSetWaypointFlags_t homeUpdateFlags = NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING; + if (!ARMING_FLAG(ARMED)) { if (posControl.flags.estPosStatus >= EST_USABLE) { const navigationHomeFlags_t validHomeFlags = NAV_HOME_VALID_XY | NAV_HOME_VALID_Z; - bool setHome = (posControl.rthState.homeFlags & validHomeFlags) != validHomeFlags; + setHome = (posControl.rthState.homeFlags & validHomeFlags) != validHomeFlags; switch ((nav_reset_type_e)positionEstimationConfig()->reset_home_type) { case NAV_RESET_NEVER: break; @@ -2545,24 +2549,16 @@ void updateHomePosition(void) setHome = true; break; } - if (setHome) { -#if defined(USE_SAFE_HOME) - findNearestSafeHome(); -#endif - setHomePosition(&posControl.actualState.abs.pos, posControl.actualState.yaw, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, navigationActualStateHomeValidity()); - // save the current location in case it is replaced by a safehome or HOME_RESET - posControl.rthState.originalHomePosition = posControl.rthState.homePosition.pos; - } } } else { static bool isHomeResetAllowed = false; - // If pilot so desires he may reset home position to current position if (IS_RC_MODE_ACTIVE(BOXHOMERESET)) { if (isHomeResetAllowed && !FLIGHT_MODE(FAILSAFE_MODE) && !FLIGHT_MODE(NAV_RTH_MODE) && !FLIGHT_MODE(NAV_WP_MODE) && (posControl.flags.estPosStatus >= EST_USABLE)) { - const navSetWaypointFlags_t homeUpdateFlags = STATE(GPS_FIX_HOME) ? (NAV_POS_UPDATE_XY | NAV_POS_UPDATE_HEADING) : (NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING); - setHomePosition(&posControl.actualState.abs.pos, posControl.actualState.yaw, homeUpdateFlags, navigationActualStateHomeValidity()); + homeUpdateFlags = 0; + homeUpdateFlags = STATE(GPS_FIX_HOME) ? (NAV_POS_UPDATE_XY | NAV_POS_UPDATE_HEADING) : (NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING); + setHome = true; isHomeResetAllowed = false; } } @@ -2577,6 +2573,18 @@ void updateHomePosition(void) posControl.homeDirection = calculateBearingToDestination(tmpHomePos); updateHomePositionCompatibility(); } + + setHome &= !STATE(IN_FLIGHT_EMERG_REARM); // prevent reset following emerg in flight rearm + } + + if (setHome && (!ARMING_FLAG(WAS_EVER_ARMED) || ARMING_FLAG(ARMED))) { +#if defined(USE_SAFE_HOME) + findNearestSafeHome(); +#endif + setHomePosition(&posControl.actualState.abs.pos, posControl.actualState.yaw, homeUpdateFlags, navigationActualStateHomeValidity()); + // save the current location in case it is replaced by a safehome or HOME_RESET + posControl.rthState.originalHomePosition = posControl.rthState.homePosition.pos; + setHome = false; } } diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index 5c314bfddd..220ff277c4 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -108,15 +108,35 @@ static bool updateTimer(navigationTimer_t * tim, timeUs_t interval, timeUs_t cur } } -static bool shouldResetReferenceAltitude(void) +static bool shouldResetReferenceAltitude(uint8_t updateSource) { - switch ((nav_reset_type_e)positionEstimationConfig()->reset_altitude_type) { - case NAV_RESET_NEVER: - return false; - case NAV_RESET_ON_FIRST_ARM: - return !ARMING_FLAG(ARMED) && !ARMING_FLAG(WAS_EVER_ARMED); - case NAV_RESET_ON_EACH_ARM: - return !ARMING_FLAG(ARMED); + /* Altitude reference reset constantly before first arm. + * After first arm altitude ref only reset immediately after arming (to avoid reset after emerg in flight rearm) + * Need to check reset status for both altitude sources immediately after rearming before reset complete */ + + static bool resetAltitudeOnArm = false; + if (ARMING_FLAG(ARMED) && resetAltitudeOnArm) { + static uint8_t sourceCheck = 0; + sourceCheck |= updateSource; + bool allAltitudeSources = STATE(GPS_FIX) && sensors(SENSOR_BARO); + + if ((allAltitudeSources && sourceCheck > SENSOR_GPS) || (!allAltitudeSources && sourceCheck)) { + resetAltitudeOnArm = false; + sourceCheck = 0; + } + return !STATE(IN_FLIGHT_EMERG_REARM); + } + + if (!ARMING_FLAG(ARMED)) { + switch ((nav_reset_type_e)positionEstimationConfig()->reset_altitude_type) { + case NAV_RESET_NEVER: + return false; + case NAV_RESET_ON_FIRST_ARM: + break; + case NAV_RESET_ON_EACH_ARM: + resetAltitudeOnArm = true; + } + return !ARMING_FLAG(WAS_EVER_ARMED); } return false; @@ -226,7 +246,7 @@ void onNewGPSData(void) if (!posControl.gpsOrigin.valid) { geoSetOrigin(&posControl.gpsOrigin, &newLLH, GEO_ORIGIN_SET); } - else if (shouldResetReferenceAltitude()) { + else if (shouldResetReferenceAltitude(SENSOR_GPS)) { /* If we were never armed - keep altitude at zero */ geoSetOrigin(&posControl.gpsOrigin, &newLLH, GEO_ORIGIN_RESET_ALTITUDE); } @@ -309,7 +329,7 @@ void updatePositionEstimator_BaroTopic(timeUs_t currentTimeUs) float newBaroAlt = baroCalculateAltitude(); /* If we are required - keep altitude at zero */ - if (shouldResetReferenceAltitude()) { + if (shouldResetReferenceAltitude(SENSOR_BARO)) { initialBaroAltitudeOffset = newBaroAlt; } From 4c7d42854c3737d7d37f6f0697cda5b2e4e62a2e Mon Sep 17 00:00:00 2001 From: MarkTan Date: Wed, 27 Sep 2023 15:22:08 +0800 Subject: [PATCH 098/175] Update target.c --- src/main/target/AOCODARCF722AIO/target.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/target/AOCODARCF722AIO/target.c b/src/main/target/AOCODARCF722AIO/target.c index 4d9deb5683..229a880fb1 100644 --- a/src/main/target/AOCODARCF722AIO/target.c +++ b/src/main/target/AOCODARCF722AIO/target.c @@ -29,10 +29,10 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU65 timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0, 0), // S4 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED }; From f31ba1fc112075b713b43d9c0a318a753196d24f Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 27 Sep 2023 10:36:41 +0200 Subject: [PATCH 099/175] Update target.c --- src/main/target/AOCODARCF722AIO/target.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/target/AOCODARCF722AIO/target.c b/src/main/target/AOCODARCF722AIO/target.c index 229a880fb1..90d21bbf2f 100644 --- a/src/main/target/AOCODARCF722AIO/target.c +++ b/src/main/target/AOCODARCF722AIO/target.c @@ -29,10 +29,10 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU65 timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR, 0, 0), // S1 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR, 0, 0), // S2 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // S3 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0, 0), // S4 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S4 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED }; From a181fc7f4eca15e8ff5e29fe54d3dd22dbb12eac Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Thu, 28 Sep 2023 13:19:10 +0100 Subject: [PATCH 100/175] fixes - rearm check sequence + altitude reset --- src/main/fc/fc_core.c | 7 +++---- src/main/io/osd.c | 2 +- src/main/navigation/navigation_pos_estimator.c | 3 +++ 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 66c275366b..1272ad3aa1 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -553,10 +553,10 @@ void tryArm(void) #endif #ifdef USE_PROGRAMMING_FRAMEWORK - if (!isArmingDisabled() || emergencyArmingIsEnabled() || emergInflightRearmEnabled() || + if (emergInflightRearmEnabled() || !isArmingDisabled() || emergencyArmingIsEnabled() || LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY)) { #else - if (!isArmingDisabled() || emergencyArmingIsEnabled() || emergInflightRearmEnabled()) { + if (emergInflightRearmEnabled() || !isArmingDisabled() || emergencyArmingIsEnabled()) { #endif // If nav_extra_arming_safety was bypassed we always // allow bypassing it even without the sticks set @@ -568,8 +568,6 @@ void tryArm(void) ENABLE_STATE(NAV_EXTRA_ARMING_SAFETY_BYPASSED); } - resetLandingDetectorActiveState(); // reset landing detector after arming to avoid false detection before flight - lastDisarmReason = DISARM_NONE; ENABLE_ARMING_FLAG(ARMED); @@ -578,6 +576,7 @@ void tryArm(void) ENABLE_STATE(SET_REVERSIBLE_MOTORS_FORWARD); if (!STATE(IN_FLIGHT_EMERG_REARM)) { + resetLandingDetectorActiveState(); // reset landing detector after arming to avoid false detection before flight logicConditionReset(); #ifdef USE_PROGRAMMING_FRAMEWORK programmingPidReset(); diff --git a/src/main/io/osd.c b/src/main/io/osd.c index b34751096e..3e464f2d76 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1202,7 +1202,7 @@ int32_t osdGetAltitude(void) static inline int32_t osdGetAltitudeMsl(void) { - return getEstimatedActualPosition(Z)+GPS_home.alt; + return getEstimatedActualPosition(Z) + posControl.gpsOrigin.alt; } uint16_t osdGetRemainingGlideTime(void) { diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index 220ff277c4..4422d6fe9e 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -121,6 +121,9 @@ static bool shouldResetReferenceAltitude(uint8_t updateSource) bool allAltitudeSources = STATE(GPS_FIX) && sensors(SENSOR_BARO); if ((allAltitudeSources && sourceCheck > SENSOR_GPS) || (!allAltitudeSources && sourceCheck)) { + if (positionEstimationConfig()->reset_home_type == NAV_RESET_ON_EACH_ARM) { + posControl.rthState.homePosition.pos.z = 0; + } resetAltitudeOnArm = false; sourceCheck = 0; } From a2a18257e877d5f2943659a9d872e19eee421d10 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Fri, 22 Sep 2023 01:37:24 -0500 Subject: [PATCH 101/175] IPF: Yaw operand --- docs/Programming Framework.md | 3 +++ src/main/programming/logic_condition.h | 5 +++-- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index 42a4f2a83f..fe6b9fb88f 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -152,6 +152,9 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn | 35 | AGL_STATUS | boolean `1` when AGL can be trusted, `0` when AGL estimate can not be trusted | | 36 | AGL | integer Above The Groud Altitude in `cm` | | 37 | RANGEFINDER_RAW | integer raw distance provided by the rangefinder in `cm` | +| 38 | ACTIVE_MIXER_PROFILE | Which mixers are currently active (for vtol etc) | +| 39 | MIXER_TRANSITION_ACTIVE | Currently switching between mixers (quad to plane etc) | +| 40 | ATTITUDE_YAW | current heading (yaw) in `degrees` | #### FLIGHT_MODE diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 941e47f8d0..cb87566f81 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -135,8 +135,9 @@ typedef enum { LOGIC_CONDITION_OPERAND_FLIGHT_AGL_STATUS, //0,1,2 // 35 LOGIC_CONDITION_OPERAND_FLIGHT_AGL, //0,1,2 // 36 LOGIC_CONDITION_OPERAND_FLIGHT_RANGEFINDER_RAW, //int // 37 - LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE, //int // 39 - LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE, //0,1 // 40 + LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE, //int // 38 + LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE, //0,1 // 39 + LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_YAW, // deg // 40 } logicFlightOperands_e; typedef enum { From 2a3fa86d61fa0162c8f3d592341a51af8e19036d Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Fri, 22 Sep 2023 01:45:55 -0500 Subject: [PATCH 102/175] IPF: Yaw operand --- src/main/programming/logic_condition.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index d3b45453c9..52e5e909c3 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -704,6 +704,10 @@ static int logicConditionGetFlightOperandValue(int operand) { return constrain(attitude.values.pitch / 10, -180, 180); break; + case LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_YAW: // deg + return constrain(attitude.values.yaw / 10, 0, 360); + break; + case LOGIC_CONDITION_OPERAND_FLIGHT_IS_ARMED: // 0/1 return ARMING_FLAG(ARMED) ? 1 : 0; break; From 150dcd184291256b0a75f5ab45b75af00580cc08 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 30 Sep 2023 16:33:26 +0200 Subject: [PATCH 103/175] HITL: hd osd support --- src/main/fc/fc_msp.c | 40 ++++++++++++++++++------------- src/main/io/displayport_msp_osd.c | 5 ++++ 2 files changed, 29 insertions(+), 16 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index a2bc170b0a..626be3708b 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -3279,7 +3279,7 @@ bool isOSDTypeSupportedBySimulator(void) { #ifdef USE_OSD displayPort_t *osdDisplayPort = osdGetDisplayPort(); - return (osdDisplayPort && osdDisplayPort->cols == 30 && (osdDisplayPort->rows == 13 || osdDisplayPort->rows == 16)); + return (!!osdDisplayPort && !!osdDisplayPort->vTable->readChar); #else return false; #endif @@ -3291,18 +3291,25 @@ void mspWriteSimulatorOSD(sbuf_t *dst) //scan displayBuffer iteratively //no more than 80+3+2 bytes output in single run //0 and 255 are special symbols - //255 - font bank switch - //0 - font bank switch, blink switch and character repeat + //255 [char] - font bank switch + //0 [flags,count] [char] - font bank switch, blink switch and character repeat + //original 0 is sent as 32 + //original 0xff, 0x100 and 0x1ff are forcibly sent inside command 0 static uint8_t osdPos_y = 0; static uint8_t osdPos_x = 0; + //indicate new format hitl 1.4.0 + sbufWriteU8(dst, 255); if (isOSDTypeSupportedBySimulator()) { displayPort_t *osdDisplayPort = osdGetDisplayPort(); - sbufWriteU8(dst, osdPos_y | (osdDisplayPort->rows == 16 ? 128: 0)); + sbufWriteU8(dst, osdDisplayPort->rows); + sbufWriteU8(dst, osdDisplayPort->cols); + + sbufWriteU8(dst, osdPos_y); sbufWriteU8(dst, osdPos_x); int bytesCount = 0; @@ -3313,7 +3320,7 @@ void mspWriteSimulatorOSD(sbuf_t *dst) bool blink = false; int count = 0; - int processedRows = 16; + int processedRows = osdDisplayPort->rows; while (bytesCount < 80) //whole response should be less 155 bytes at worst. { @@ -3324,7 +3331,7 @@ void mspWriteSimulatorOSD(sbuf_t *dst) while ( true ) { displayReadCharWithAttr(osdDisplayPort, osdPos_x, osdPos_y, &c, &attr); - if (c == 0 || c == 255) c = 32; + if (c == 0) c = 32; //REVIEW: displayReadCharWithAttr() should return mode with _TEXT_ATTRIBUTES_BLINK_BIT ! //for max7456 it returns mode with MAX7456_MODE_BLINK instead (wrong) @@ -3339,7 +3346,7 @@ void mspWriteSimulatorOSD(sbuf_t *dst) lastChar = c; blink1 = blink2; } - else if (lastChar != c || blink2 != blink1 || count == 63) + else if ((lastChar != c) || (blink2 != blink1) || (count == 63)) { break; } @@ -3347,12 +3354,12 @@ void mspWriteSimulatorOSD(sbuf_t *dst) count++; osdPos_x++; - if (osdPos_x == 30) + if (osdPos_x == osdDisplayPort->cols) { osdPos_x = 0; osdPos_y++; processedRows--; - if (osdPos_y == 16) + if (osdPos_y == osdDisplayPort->rows) { osdPos_y = 0; } @@ -3360,6 +3367,7 @@ void mspWriteSimulatorOSD(sbuf_t *dst) } uint8_t cmd = 0; + uint8_t lastCharLow = (uint8_t)(lastChar & 0xff); if (blink1 != blink) { cmd |= 128;//switch blink attr @@ -3375,27 +3383,27 @@ void mspWriteSimulatorOSD(sbuf_t *dst) if (count == 1 && cmd == 64) { - sbufWriteU8(dst, 255); //short command for bank switch + sbufWriteU8(dst, 255); //short command for bank switch with char following sbufWriteU8(dst, lastChar & 0xff); bytesCount += 2; } - else if (count > 2 || cmd !=0 ) + else if ((count > 2) || (cmd !=0) || (lastChar == 255) || (lastChar == 0x100) || (lastChar == 0x1ff)) { cmd |= count; //long command for blink/bank switch and symbol repeat sbufWriteU8(dst, 0); sbufWriteU8(dst, cmd); - sbufWriteU8(dst, lastChar & 0xff); + sbufWriteU8(dst, lastCharLow); bytesCount += 3; } else if (count == 2) //cmd == 0 here { - sbufWriteU8(dst, lastChar & 0xff); - sbufWriteU8(dst, lastChar & 0xff); + sbufWriteU8(dst, lastCharLow); + sbufWriteU8(dst, lastCharLow); bytesCount+=2; } else { - sbufWriteU8(dst, lastChar & 0xff); + sbufWriteU8(dst, lastCharLow); bytesCount++; } @@ -3409,7 +3417,7 @@ void mspWriteSimulatorOSD(sbuf_t *dst) } else { - sbufWriteU8(dst, 255); + sbufWriteU8(dst, 0); } } #endif diff --git a/src/main/io/displayport_msp_osd.c b/src/main/io/displayport_msp_osd.c index 17f49c8b78..4269b2a561 100644 --- a/src/main/io/displayport_msp_osd.c +++ b/src/main/io/displayport_msp_osd.c @@ -42,6 +42,7 @@ #include "drivers/osd_symbols.h" #include "fc/rc_modes.h" +#include "fc/runtime_config.h" #include "io/osd.h" #include "io/displayport_msp.h" @@ -113,6 +114,10 @@ static void checkVtxPresent(void) if (vtxActive && (millis()-vtxHeartbeat) > VTX_TIMEOUT) { vtxActive = false; } + + if (ARMING_FLAG(SIMULATOR_MODE_HITL)) { + vtxActive = true; + } } static int output(displayPort_t *displayPort, uint8_t cmd, uint8_t *subcmd, int len) From 4352ed57645d7d87dcf63416cbb70b2b26fc144b Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sun, 1 Oct 2023 02:14:54 +0300 Subject: [PATCH 104/175] Update OSD Joystick.md --- docs/OSD Joystick.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md index d5ee6a2335..b311547024 100644 --- a/docs/OSD Joystick.md +++ b/docs/OSD Joystick.md @@ -26,7 +26,7 @@ To simulate 5key joystick, it is sufficient to generate correct voltage on camer ```set osd_joystick_enabled=on``` -Also enable "Multi-color RGB LED Strinp support" in Configuration tab. +Also enable "Multi-color RGB LED Strip support" in Configuration tab. # Connection diagram From 97e1db100bc7ee288935d4268bfc29eaa4e22543 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sun, 1 Oct 2023 02:15:52 +0300 Subject: [PATCH 105/175] Update OSD Joystick.md --- docs/OSD Joystick.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md index b311547024..f4a0a59066 100644 --- a/docs/OSD Joystick.md +++ b/docs/OSD Joystick.md @@ -48,7 +48,7 @@ If default voltages does not work with your camera model, then you have to measu 2. Measure voltages on OSD pin while each key is pressed. 3. Connect camera to FC throught RC filter as shown on schematix above. 4. Enable OSD Joystick emulation (see "Enabling OSD Joystick emulation" above) -4. Use cli ```command led_pin_pwm ```, value = 0...100 to find out PWM values for each voltage. +4. Use cli command ```led_pin_pwm ```, value = 0...100 to find out PWM values for each voltage. 5. Specify PWM values in configuration and save: ```set osd_joystick_down=0``` From e4bd847e0ea4bbebb1fd81e1e925b30c1b8ff4df Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Wed, 27 Sep 2023 00:04:03 -0500 Subject: [PATCH 106/175] servos.c: Correct servo throttle off when disarmed --- src/main/flight/servos.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 4d4bb497d1..cb3004ed61 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -376,8 +376,9 @@ void servoMixer(float dT) const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t from = currentServoMixer[i].inputSource; + // Translate minimum throttle values to -500 ... +500 servo range for use below. if (from == INPUT_STABILIZED_THROTTLE || from == INPUT_RC_THROTTLE) { - servo[target] = motorConfig()->mincommand; + servo[target] = motorConfig()->mincommand - servoParams(target)->middle; } } } From dbf85497a3c522b31fa48ce6c375861a2f27e34f Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 30 Sep 2023 23:55:15 -0500 Subject: [PATCH 107/175] SDMODELH7V1: TIM_USE_OUTPUT_AUTO --- src/main/target/SDMODELH7V1/target.c | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/main/target/SDMODELH7V1/target.c b/src/main/target/SDMODELH7V1/target.c index 086d941f1c..8851f95286 100644 --- a/src/main/target/SDMODELH7V1/target.c +++ b/src/main/target/SDMODELH7V1/target.c @@ -28,15 +28,15 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 4), // S5 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 5), // S6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 6), // S7 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 7), // S8 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 9), // LED_2812 }; From ed415c8a2510a694c2c586fa11dd7c30c7b80fa0 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 1 Oct 2023 10:17:22 +0100 Subject: [PATCH 108/175] Tabs to spaces --- src/main/common/maths.h | 86 ++++++++++++++++++++--------------------- 1 file changed, 43 insertions(+), 43 deletions(-) diff --git a/src/main/common/maths.h b/src/main/common/maths.h index b803f64086..ff0505fb53 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -25,13 +25,13 @@ #endif // Undefine this for use libc sinf/cosf. Keep this defined to use fast sin/cos approximations -#define FAST_MATH // order 9 approximation -//#define VERY_FAST_MATH // order 7 approximation +#define FAST_MATH // order 9 approximation +//#define VERY_FAST_MATH // order 7 approximation // Use floating point M_PI instead explicitly. -#define M_PIf 3.14159265358979323846f -#define M_LN2f 0.69314718055994530942f -#define M_Ef 2.71828182845904523536f +#define M_PIf 3.14159265358979323846f +#define M_LN2f 0.69314718055994530942f +#define M_Ef 2.71828182845904523536f #define RAD (M_PIf / 180.0f) @@ -56,15 +56,15 @@ #define RADIANS_TO_CENTIDEGREES(angle) (((angle) * 100.0f) / RAD) #define CENTIDEGREES_TO_RADIANS(angle) (((angle) / 100.0f) * RAD) -#define CENTIMETERS_TO_CENTIFEET(cm) (cm / 0.3048f) -#define CENTIMETERS_TO_FEET(cm) (cm / 30.48f) -#define CENTIMETERS_TO_METERS(cm) (cm / 100.0f) +#define CENTIMETERS_TO_CENTIFEET(cm) (cm / 0.3048f) +#define CENTIMETERS_TO_FEET(cm) (cm / 30.48f) +#define CENTIMETERS_TO_METERS(cm) (cm / 100.0f) -#define METERS_TO_CENTIMETERS(m) (m * 100) +#define METERS_TO_CENTIMETERS(m) (m * 100) -#define CMSEC_TO_CENTIMPH(cms) (cms * 2.2369363f) -#define CMSEC_TO_CENTIKPH(cms) (cms * 3.6f) -#define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845f) +#define CMSEC_TO_CENTIMPH(cms) (cms * 2.2369363f) +#define CMSEC_TO_CENTIKPH(cms) (cms * 3.6f) +#define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845f) #define C_TO_KELVIN(temp) (temp + 273.15f) @@ -75,28 +75,28 @@ #define SSL_AIR_TEMPERATURE 288.15f // K // copied from https://code.google.com/p/cxutil/source/browse/include/cxutil/utility.h#70 -#define _CHOOSE2(binoper, lexpr, lvar, rexpr, rvar) \ - ( __extension__ ({ \ - __typeof__(lexpr) lvar = (lexpr); \ - __typeof__(rexpr) rvar = (rexpr); \ - lvar binoper rvar ? lvar : rvar; \ - })) +#define _CHOOSE2(binoper, lexpr, lvar, rexpr, rvar) \ + ( __extension__ ({ \ + __typeof__(lexpr) lvar = (lexpr); \ + __typeof__(rexpr) rvar = (rexpr); \ + lvar binoper rvar ? lvar : rvar; \ + })) #define _CHOOSE_VAR2(prefix, unique) prefix##unique #define _CHOOSE_VAR(prefix, unique) _CHOOSE_VAR2(prefix, unique) -#define _CHOOSE(binoper, lexpr, rexpr) \ - _CHOOSE2( \ - binoper, \ - lexpr, _CHOOSE_VAR(_left, __COUNTER__), \ - rexpr, _CHOOSE_VAR(_right, __COUNTER__) \ - ) +#define _CHOOSE(binoper, lexpr, rexpr) \ + _CHOOSE2( \ + binoper, \ + lexpr, _CHOOSE_VAR(_left, __COUNTER__), \ + rexpr, _CHOOSE_VAR(_right, __COUNTER__) \ + ) #define MIN(a, b) _CHOOSE(<, a, b) #define MAX(a, b) _CHOOSE(>, a, b) -#define _ABS_II(x, var) \ - ( __extension__ ({ \ - __typeof__(x) var = (x); \ - var < 0 ? -var : var; \ - })) +#define _ABS_II(x, var) \ + ( __extension__ ({ \ + __typeof__(x) var = (x); \ + var < 0 ? -var : var; \ + })) #define _ABS_I(x, var) _ABS_II(x, var) #define ABS(x) _ABS_I(x, _CHOOSE_VAR(_abs, __COUNTER__)) @@ -104,35 +104,35 @@ // Floating point Euler angles. typedef struct fp_angles { - float roll; - float pitch; - float yaw; + float roll; + float pitch; + float yaw; } fp_angles_def; typedef union { - float raw[3]; - fp_angles_def angles; + float raw[3]; + fp_angles_def angles; } fp_angles_t; typedef struct stdev_s { - float m_oldM, m_newM, m_oldS, m_newS; - int m_n; + float m_oldM, m_newM, m_oldS, m_newS; + int m_n; } stdev_t; typedef struct filterWithBufferSample_s { - float value; - uint32_t timestamp; + float value; + uint32_t timestamp; } filterWithBufferSample_t; typedef struct filterWithBufferState_s { - uint16_t filter_size; - uint16_t sample_index; - filterWithBufferSample_t * samples; + uint16_t filter_size; + uint16_t sample_index; + filterWithBufferSample_t * samples; } filterWithBufferState_t; typedef struct { - float XtY[4]; - float XtX[4][4]; + float XtY[4]; + float XtX[4][4]; } sensorCalibrationState_t; void sensorCalibrationResetState(sensorCalibrationState_t * state); From 3c6128e8eb0bd55349eaa21b89e9d9f9f5413298 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 1 Oct 2023 15:30:35 +0100 Subject: [PATCH 109/175] simplify alt ref reset + fix 0 home alt --- src/main/navigation/navigation.c | 4 ++ .../navigation/navigation_pos_estimator.c | 54 +++++++++---------- 2 files changed, 29 insertions(+), 29 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 0465eceab6..81c9b4b85c 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2582,6 +2582,10 @@ void updateHomePosition(void) findNearestSafeHome(); #endif setHomePosition(&posControl.actualState.abs.pos, posControl.actualState.yaw, homeUpdateFlags, navigationActualStateHomeValidity()); + + if (ARMING_FLAG(ARMED) && positionEstimationConfig()->reset_altitude_type == NAV_RESET_ON_EACH_ARM) { + posControl.rthState.homePosition.pos.z = 0; // force to 0 if reference altitude also reset every arm + } // save the current location in case it is replaced by a safehome or HOME_RESET posControl.rthState.originalHomePosition = posControl.rthState.homePosition.pos; setHome = false; diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index 4422d6fe9e..d7ef73c938 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -54,6 +54,7 @@ #include "sensors/opflow.h" navigationPosEstimator_t posEstimator; +static float initialBaroAltitudeOffset = 0.0f; PG_REGISTER_WITH_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, PG_POSITION_ESTIMATION_CONFIG, 5); @@ -108,38 +109,34 @@ static bool updateTimer(navigationTimer_t * tim, timeUs_t interval, timeUs_t cur } } -static bool shouldResetReferenceAltitude(uint8_t updateSource) +static bool shouldResetReferenceAltitude(void) { - /* Altitude reference reset constantly before first arm. - * After first arm altitude ref only reset immediately after arming (to avoid reset after emerg in flight rearm) - * Need to check reset status for both altitude sources immediately after rearming before reset complete */ + /* Reference altitudes reset constantly when disarmed. + * On arming ref altitudes saved as backup in case of emerg in flight rearm + * If emerg in flight rearm active ref altitudes reset to backup values to avoid unwanted altitude reset */ - static bool resetAltitudeOnArm = false; - if (ARMING_FLAG(ARMED) && resetAltitudeOnArm) { - static uint8_t sourceCheck = 0; - sourceCheck |= updateSource; - bool allAltitudeSources = STATE(GPS_FIX) && sensors(SENSOR_BARO); + static float backupInitialBaroAltitudeOffset = 0.0f; + static int32_t backupGpsOriginAltitude = 0; + static bool emergRearmResetCheck = false; - if ((allAltitudeSources && sourceCheck > SENSOR_GPS) || (!allAltitudeSources && sourceCheck)) { - if (positionEstimationConfig()->reset_home_type == NAV_RESET_ON_EACH_ARM) { - posControl.rthState.homePosition.pos.z = 0; - } - resetAltitudeOnArm = false; - sourceCheck = 0; + if (ARMING_FLAG(ARMED) && emergRearmResetCheck) { + if (STATE(IN_FLIGHT_EMERG_REARM)) { + initialBaroAltitudeOffset = backupInitialBaroAltitudeOffset; + posControl.gpsOrigin.alt = backupGpsOriginAltitude; + } else { + backupInitialBaroAltitudeOffset = initialBaroAltitudeOffset; + backupGpsOriginAltitude = posControl.gpsOrigin.alt; } - return !STATE(IN_FLIGHT_EMERG_REARM); } + emergRearmResetCheck = !ARMING_FLAG(ARMED); - if (!ARMING_FLAG(ARMED)) { - switch ((nav_reset_type_e)positionEstimationConfig()->reset_altitude_type) { - case NAV_RESET_NEVER: - return false; - case NAV_RESET_ON_FIRST_ARM: - break; - case NAV_RESET_ON_EACH_ARM: - resetAltitudeOnArm = true; - } - return !ARMING_FLAG(WAS_EVER_ARMED); + switch ((nav_reset_type_e)positionEstimationConfig()->reset_altitude_type) { + case NAV_RESET_NEVER: + return false; + case NAV_RESET_ON_FIRST_ARM: + return !ARMING_FLAG(ARMED) && !ARMING_FLAG(WAS_EVER_ARMED); + case NAV_RESET_ON_EACH_ARM: + return !ARMING_FLAG(ARMED); } return false; @@ -249,7 +246,7 @@ void onNewGPSData(void) if (!posControl.gpsOrigin.valid) { geoSetOrigin(&posControl.gpsOrigin, &newLLH, GEO_ORIGIN_SET); } - else if (shouldResetReferenceAltitude(SENSOR_GPS)) { + else if (shouldResetReferenceAltitude()) { /* If we were never armed - keep altitude at zero */ geoSetOrigin(&posControl.gpsOrigin, &newLLH, GEO_ORIGIN_RESET_ALTITUDE); } @@ -328,11 +325,10 @@ void onNewGPSData(void) */ void updatePositionEstimator_BaroTopic(timeUs_t currentTimeUs) { - static float initialBaroAltitudeOffset = 0.0f; float newBaroAlt = baroCalculateAltitude(); /* If we are required - keep altitude at zero */ - if (shouldResetReferenceAltitude(SENSOR_BARO)) { + if (shouldResetReferenceAltitude()) { initialBaroAltitudeOffset = newBaroAlt; } From f3109ad8ccb457cef66408542f972ffa2f14dc30 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 1 Oct 2023 16:55:28 +0100 Subject: [PATCH 110/175] Fix for Mac SITL --- src/main/io/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index b9b9b9c0ba..f96611da44 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -3945,7 +3945,7 @@ uint8_t drawLogos(bool singular, uint8_t row) { if (usePilotLogo && !singular) { logoColOffset = ((osdDisplayPort->cols - (SYM_LOGO_WIDTH * 2)) - logoSpacing) / 2; } else { - logoColOffset = floor((osdDisplayPort->cols - SYM_LOGO_WIDTH) / 2.0f); + logoColOffset = floorf((osdDisplayPort->cols - SYM_LOGO_WIDTH) / 2.0f); } // Draw INAV logo From c1847b353a0c6129a3a0eca087971747314d9ed5 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 1 Oct 2023 17:06:54 +0100 Subject: [PATCH 111/175] Update osd_unittest.cc Updated for new osdFormatCentiNumber declaration. --- src/test/unit/osd_unittest.cc | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/test/unit/osd_unittest.cc b/src/test/unit/osd_unittest.cc index 6a8aa6f091..fd126c5c41 100644 --- a/src/test/unit/osd_unittest.cc +++ b/src/test/unit/osd_unittest.cc @@ -14,55 +14,55 @@ TEST(OSDTest, TestCentiNumber) //bool osdFormatCentiNumber(char *buff, int32_t centivalue, uint32_t scale, int maxDecimals, int maxScaledDecimals, int length); char buf[11] = "0123456789"; - osdFormatCentiNumber(buf, 12345, 1, 2, 3, 7); + osdFormatCentiNumber(buf, 12345, 1, 2, 3, 7, false); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, " 123.45")); memset(buf, 0, 11); - osdFormatCentiNumber(buf, 12345, 1, 2, 2, 6); + osdFormatCentiNumber(buf, 12345, 1, 2, 2, 6, false); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, "123.45")); memset(buf, 0, 11); - osdFormatCentiNumber(buf, 12345, 1, 2, 2, 5); + osdFormatCentiNumber(buf, 12345, 1, 2, 2, 5, false); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, "123.4")); memset(buf, 0, 11); - osdFormatCentiNumber(buf, 12345, 1, 2, 2, 4); + osdFormatCentiNumber(buf, 12345, 1, 2, 2, 4, false); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, " 123")); // this should be causing #8769 memset(buf, 0, 11); - osdFormatCentiNumber(buf, 12345, 1, 2, 2, 3); + osdFormatCentiNumber(buf, 12345, 1, 2, 2, 3, false); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, "123")); std::cout << "'" << buf << "'" << std::endl; memset(buf, 0, 11); - osdFormatCentiNumber(buf, -12345, 1, 2, 2, 8); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 8, false); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, " -123.45")); memset(buf, 0, 11); - osdFormatCentiNumber(buf, -12345, 1, 2, 2, 7); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 7, false); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, "-123.45")); memset(buf, 0, 11); - osdFormatCentiNumber(buf, -12345, 1, 2, 2, 6); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 6, false); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, "-123.4")); memset(buf, 0, 11); - osdFormatCentiNumber(buf, -12345, 1, 2, 2, 5); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 5, false); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, " -123")); memset(buf, 0, 11); - osdFormatCentiNumber(buf, -12345, 1, 2, 2, 4); + osdFormatCentiNumber(buf, -12345, 1, 2, 2, 4, false); std::cout << "'" << buf << "'" << std::endl; EXPECT_FALSE(strcmp(buf, "-123")); From 8f5a221a543e31bbe1834b067b84bf77af06fbb6 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Thu, 5 Oct 2023 23:40:43 +0200 Subject: [PATCH 112/175] allow hitl/sitl to arm with uncalibrated accelerometer --- src/main/fc/fc_msp.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 0f3d80829a..364babb3b8 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -3586,6 +3586,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu } #endif ENABLE_ARMING_FLAG(SIMULATOR_MODE_HITL); + ENABLE_STATE(ACCELEROMETER_CALIBRATED); LOG_DEBUG(SYSTEM, "Simulator enabled"); } From ae6b6aa7c0ea070cc5ebf452cfba007039c0a96c Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Tue, 3 Oct 2023 21:32:13 +0200 Subject: [PATCH 113/175] docker build: do not run user commands --- Dockerfile | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Dockerfile b/Dockerfile index 9c816b0c18..e0a3949517 100644 --- a/Dockerfile +++ b/Dockerfile @@ -4,15 +4,15 @@ ARG USER_ID ARG GROUP_ID ENV DEBIAN_FRONTEND noninteractive -RUN apt-get update && apt-get install -y git cmake make ruby gcc python3 python3-pip gcc-arm-none-eabi +RUN apt-get update && apt-get install -y git cmake make ruby gcc python3 python3-pip gcc-arm-none-eabi ninja-build RUN pip install pyyaml # if either of these are already set the same as the user's machine, leave them be and ignore the error -RUN addgroup --gid $GROUP_ID inav; exit 0; -RUN adduser --disabled-password --gecos '' --uid $USER_ID --gid $GROUP_ID inav; exit 0; +RUN if [ -n "$USER_ID" ]; then RUN addgroup --gid $GROUP_ID inav; exit 0; fi +RUN if [ -n "$USER_ID" ]; then RUN adduser --disabled-password --gecos '' --uid $USER_ID --gid $GROUP_ID inav; exit 0; fi -USER inav +RUN if [ -n "$USER_ID" ]; then USER inav; fi RUN git config --global --add safe.directory /src VOLUME /src From 55c1abea376acb8958c06939b4800b53a012fa09 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Tue, 3 Oct 2023 21:32:35 +0200 Subject: [PATCH 114/175] docked build: build with ninja --- cmake/docker.sh | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/docker.sh b/cmake/docker.sh index 3c10ebc8e1..843e03a48a 100755 --- a/cmake/docker.sh +++ b/cmake/docker.sh @@ -6,7 +6,7 @@ CURR_REV="$(git rev-parse HEAD)" initialize_cmake() { echo -e "*** CMake was not initialized yet, doing it now.\n" - cmake .. + cmake -GNinja .. echo "$CURR_REV" > "$LAST_CMAKE_AT_REV_FILE" } @@ -26,4 +26,4 @@ else fi # Let Make handle the arguments coming from the build script -make "$@" +ninja "$@" From ff947cb7439f945b7fe532d66090ebfed179f743 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Tue, 3 Oct 2023 21:33:30 +0200 Subject: [PATCH 115/175] docked build: added scripts for sitl build and run --- cmake/docker_build_sitl.sh | 6 ++++++ cmake/docker_run_sitl.sh | 8 ++++++++ 2 files changed, 14 insertions(+) create mode 100644 cmake/docker_build_sitl.sh create mode 100644 cmake/docker_run_sitl.sh diff --git a/cmake/docker_build_sitl.sh b/cmake/docker_build_sitl.sh new file mode 100644 index 0000000000..b1a4ada5ca --- /dev/null +++ b/cmake/docker_build_sitl.sh @@ -0,0 +1,6 @@ +#!/bin/bash +rm -r build_SITL +mkdir -p build_SITL +cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -GNinja -B build_SITL .. +cd build_SITL +ninja \ No newline at end of file diff --git a/cmake/docker_run_sitl.sh b/cmake/docker_run_sitl.sh new file mode 100644 index 0000000000..b2089137cc --- /dev/null +++ b/cmake/docker_run_sitl.sh @@ -0,0 +1,8 @@ +#!/bin/bash +cd build_SITL + +#Lauch SITL - configurator only mode +./inav_7.0.0_SITL + +#Launch SITL - connect to X-Plane. IP address should be host IP address, not 127.0.0.1. Can be found in X-Plane "Network" tab. +#./inav_7.0.0_SITL --sim=xp --simip=192.168.2.105 --simport=49000 \ No newline at end of file From a61a175107b83e0cce0c2e81a491a43cd84da4ea Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Fri, 6 Oct 2023 02:11:54 +0300 Subject: [PATCH 116/175] Update Building in Docker.md --- docs/development/Building in Docker.md | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/docs/development/Building in Docker.md b/docs/development/Building in Docker.md index 80d661ecf3..39cd887003 100755 --- a/docs/development/Building in Docker.md +++ b/docs/development/Building in Docker.md @@ -37,8 +37,19 @@ You'll have to manually execute the same steps that the build script does: + This step is only needed the first time. 2. `docker run --rm -it -u root -v :/src inav-build ` + Where `` must be replaced with the absolute path of where you cloned this repo (see above), and `` with the name of the target that you want to build. - + Note that on Windows/WSL 2 mounted /src folder is writeable for root user only. You have to run build under root user. You can achieve this by using `-u root` option in the command line above, or by removing "USER inav" line from the .\DockerFile before building image. + + Note that on Windows/WSL 2 mounted /src folder is writeable for root user only. You have to run build under root user. You can achieve this by using `-u root` option in the command line above. -3. If you need to update `Settings.md`, run `docker run --entrypoint /src/cmake/docker_docs.sh --rm -it -u root -v :/src inav-build` +3. If you need to update `Settings.md`, run: + +`docker run --entrypoint /src/cmake/docker_docs.sh --rm -it -u root -v :/src inav-build` + +4. Building SITL: + +`docker run --rm --entrypoint /src/cmake/docker_build_sitl.sh -it -u root -v :/src inav-build` + +5. Running SITL: + +`docker run -p 5760:5760 -p 5761:5761 -p 5762:5762 -p 5763:5763 -p 5764:5764 -p 5765:5765 -p 5766:5766 -p 5767:5767 --entrypoint /src/cmake/docker_run_sitl.sh --rm -it -u root -v :/src inav-build`. + + SITL command line parameters can be adjusted in `cmake/docker_run_sitl.sh`. Refer to the [Linux](#Linux) instructions or the [build script](/build.sh) for more details. From ebafe30620ff1acaf597c826b06d0f9325de16c7 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 7 Oct 2023 10:32:10 +0100 Subject: [PATCH 117/175] Bug fix after merge from master --- src/main/io/osd.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 057743d9ca..24a6bc6cb2 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -4055,7 +4055,7 @@ uint8_t drawStats(uint8_t row) { #ifdef USE_ADC if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) { displayWrite(osdDisplayPort, statNameX, ++row, "TOTAL ENERGY:"); - osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4); + osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4, false); displayWrite(osdDisplayPort, statValueX-4, row, string_buffer); displayWriteChar(osdDisplayPort, statValueX, row, SYM_WH); @@ -4066,18 +4066,18 @@ uint8_t drawStats(uint8_t row) { case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); + osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3, false); string_buffer[3] = SYM_WH_MI; break; case OSD_UNIT_GA: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3); + osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3, false); string_buffer[3] = SYM_WH_NM; break; default: case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3); + osdFormatCentiNumber(string_buffer, avg_efficiency / 10000 * METERS_PER_MILE, 0, 2, 0, 3, false); string_buffer[3] = SYM_WH_KM; break; } From bf688bbe5042d4be6202832137d2770e32ecdc6e Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 7 Oct 2023 16:13:27 +0100 Subject: [PATCH 118/175] Removed SBUS from the 24 channel options Changing SBUS to 24 channels will need more work. --- src/main/rx/sbus_channels.h | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/main/rx/sbus_channels.h b/src/main/rx/sbus_channels.h index e5ec0ff2c9..5e8a6a0268 100644 --- a/src/main/rx/sbus_channels.h +++ b/src/main/rx/sbus_channels.h @@ -20,11 +20,7 @@ #include #include "rx/rx.h" -#ifdef USE_24CHANNELS -#define SBUS_MAX_CHANNEL 26 -#else #define SBUS_MAX_CHANNEL 18 -#endif #define SBUS_FLAG_SIGNAL_LOSS (1 << 2) #define SBUS_FLAG_FAILSAFE_ACTIVE (1 << 3) From 3611477276ec8fa2f76b670e51c74b648bf104a2 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 7 Oct 2023 16:49:17 +0100 Subject: [PATCH 119/175] Update Controls.md Corrected RunCam control columns and text --- docs/Controls.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/Controls.md b/docs/Controls.md index 1b63f90e2a..3cc62b4e74 100644 --- a/docs/Controls.md +++ b/docs/Controls.md @@ -44,9 +44,9 @@ The stick positions are combined to activate different functions: | Bypass Nav Arm disable | LOW | HIGH | CENTER | CENTER | | Save setting | LOW | LOW | LOW | HIGH | | Enter OSD Menu (CMS) | CENTER | LOW | HIGH | CENTER | -| Enter Camera OSD(RuncamDevice)| RIGHT | CENTER | CENTER | CENTER | -| Exit Camera OSD (RuncamDevice)| LEFT | CENTER | CENTER | CENTER | -| Confirm - Camera OSD | RIGHT | CENTER | CENTER | CENTER | +| Enter Camera OSD(RuncamDevice)| CENTER | HIGH | CENTER | CENTER | +| Exit Camera OSD (RuncamDevice)| CENTER | LOW | CENTER | CENTER | +| Confirm - Camera OSD | CENTER | HIGH | CENTER | CENTER | | Navigation - Camera OSD | CENTER | CENTER | * | * | For graphical stick position in all transmitter modes, check out [this page](https://www.mrd-rc.com/tutorials-tools-and-testing/inav-flight/inav-stick-commands-for-all-transmitter-modes/). From 9239b5df06e7eda275b7306d678391cb14976515 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 7 Oct 2023 17:51:58 +0200 Subject: [PATCH 120/175] add gdb to allow debugging in dev containers --- Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Dockerfile b/Dockerfile index e0a3949517..71077c8ed9 100644 --- a/Dockerfile +++ b/Dockerfile @@ -4,7 +4,7 @@ ARG USER_ID ARG GROUP_ID ENV DEBIAN_FRONTEND noninteractive -RUN apt-get update && apt-get install -y git cmake make ruby gcc python3 python3-pip gcc-arm-none-eabi ninja-build +RUN apt-get update && apt-get install -y git cmake make ruby gcc python3 python3-pip gcc-arm-none-eabi ninja-build gdb RUN pip install pyyaml From 79e14749d5ba369bb4272acc2ddc4decd3a93657 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 7 Oct 2023 17:52:37 +0200 Subject: [PATCH 121/175] add option to build sitl with debug information --- cmake/docker_build_sitl.sh | 3 ++- cmake/sitl.cmake | 5 +++++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/cmake/docker_build_sitl.sh b/cmake/docker_build_sitl.sh index b1a4ada5ca..a79742ae0f 100644 --- a/cmake/docker_build_sitl.sh +++ b/cmake/docker_build_sitl.sh @@ -1,6 +1,7 @@ #!/bin/bash rm -r build_SITL mkdir -p build_SITL -cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -GNinja -B build_SITL .. +#cmake -DSITL=ON -DWARNINGS_AS_ERRORS=ON -GNinja -B build_SITL .. +cmake -DSITL=ON -DDEBUG=ON -DWARNINGS_AS_ERRORS=ON -GNinja -B build_SITL .. cd build_SITL ninja \ No newline at end of file diff --git a/cmake/sitl.cmake b/cmake/sitl.cmake index 24a4ae9b27..78697f98a9 100644 --- a/cmake/sitl.cmake +++ b/cmake/sitl.cmake @@ -53,6 +53,11 @@ set(SITL_COMPILE_OPTIONS -funsigned-char ) +if(DEBUG) + message(STATUS "Debug mode enabled. Adding -g to SITL_COMPILE_OPTIONS.") + list(APPEND SITL_COMPILE_OPTIONS -g) +endif() + if(NOT MACOSX) set(SITL_COMPILE_OPTIONS ${SITL_COMPILE_OPTIONS} -Wno-return-local-addr From 3f43a804d3215ca85089fa0ae0719b3a07a01e79 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 7 Oct 2023 19:04:37 +0300 Subject: [PATCH 122/175] Update OSD Joystick.md --- docs/OSD Joystick.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/OSD Joystick.md b/docs/OSD Joystick.md index f4a0a59066..9e0f677e45 100644 --- a/docs/OSD Joystick.md +++ b/docs/OSD Joystick.md @@ -69,7 +69,7 @@ Emulation can be enabled in unarmed state only. OSD Joystick emulation mode is enabled using the following stick combination: -```RIGHT CENTER``` +```Throttle:CENTER Yaw:RIGHT``` Than camera OSD can be navigated using right stick. See [Controls](Controls.md) for all stick combinations. @@ -78,7 +78,7 @@ Than camera OSD can be navigated using right stick. See [Controls](Controls.md) Mode is exited using stick combination: -```LEFT CENTER``` +```Throttle:CENTER Yaw:LEFT``` # RC Box From ae0e9a0f910cee02d48ca6b007109c800e924a8d Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Sat, 7 Oct 2023 19:16:47 +0200 Subject: [PATCH 123/175] fixed HITL docs --- ...1.md => Hardware In The Loop (HITL) plugin for X-Plane.md} | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) rename docs/development/{Software In The Loop (HITL) plugin for X-Plane 11.md => Hardware In The Loop (HITL) plugin for X-Plane.md} (83%) diff --git a/docs/development/Software In The Loop (HITL) plugin for X-Plane 11.md b/docs/development/Hardware In The Loop (HITL) plugin for X-Plane.md similarity index 83% rename from docs/development/Software In The Loop (HITL) plugin for X-Plane 11.md rename to docs/development/Hardware In The Loop (HITL) plugin for X-Plane.md index 0b7d106e0d..c166c5117a 100644 --- a/docs/development/Software In The Loop (HITL) plugin for X-Plane 11.md +++ b/docs/development/Hardware In The Loop (HITL) plugin for X-Plane.md @@ -1,4 +1,4 @@ -# Software In The Loop (HITL) plugin for X-Plane 11 +# Hardware In The Loop (HITL) plugin for X-Plane 11/12 **Hardware-in-the-loop (HITL) simulation**, is a technique that is used in the development and testing of complex real-time embedded systems. @@ -6,6 +6,6 @@ **INAV-X-Plane-HITL** is plugin for **X-Plane** for testing and developing flight controllers with **INAV flight controller firmware** -https://github.com/iNavFlight/inav. +https://github.com/RomanLut/INAV-X-Plane-HITL HITL technique can be used to test features during development. Please check page above for installation instructions. From 6453c3b43f65b281f21474e8f37fa0fdca0bf69b Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 8 Oct 2023 13:35:46 +0200 Subject: [PATCH 124/175] Remove not needed comment --- src/main/flight/ez_tune.c | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index 2703fe870e..ef56143cf9 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -65,7 +65,6 @@ static float getYawPidScale(float input) { /** * Update INAV settings based on current EZTune settings * This has to be called every time control profile is changed, or EZTune settings are changed - * FIXME call on EZTune settings change */ void ezTuneUpdate(void) { if (ezTune()->enabled) { From f364d3bb60d53e5bb0bd9cecab91d4e12fec3ea9 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 8 Oct 2023 14:27:53 +0200 Subject: [PATCH 125/175] Compute rate from EZ Tune --- src/main/flight/ez_tune.c | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index ef56143cf9..b08e7cf9ca 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -32,6 +32,7 @@ #include "fc/settings.h" #include "flight/pid.h" #include "sensors/gyro.h" +#include "fc/controlrate_profile.h" PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(ezTuneSettings_t, ezTune, PG_EZ_TUNE, 0); @@ -127,5 +128,14 @@ void ezTuneUpdate(void) { pidProfileMutable()->bank_mc.pid[PID_YAW].I = pidDefaultsYaw[1] * getYawPidScale(ezTune()->stability); pidProfileMutable()->bank_mc.pid[PID_YAW].D = pidDefaultsYaw[2] * getYawPidScale(ezTune()->damping); pidProfileMutable()->bank_mc.pid[PID_YAW].FF = pidDefaultsYaw[3] * getYawPidScale(ezTune()->aggressiveness); + + //Setup rates + ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rates[FD_ROLL] = scaleRange(ezTune()->rate, 0, 200, 30, 90); + ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rates[FD_PITCH] = scaleRange(ezTune()->rate, 0, 200, 30, 90); + ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rates[FD_YAW] = scaleRange(ezTune()->rate, 0, 200, 30, 90) - 10; + + ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rcExpo8 = scaleRange(ezTune()->rate, 0, 200, 40, 100); + ((controlRateConfig_t*)currentControlRateProfile)->stabilized.rcYawExpo8 = scaleRange(ezTune()->rate, 0, 200, 40, 100); + } } \ No newline at end of file From 059a46daad1551e39fca49ee8f60567a9972efd0 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 8 Oct 2023 17:39:54 +0200 Subject: [PATCH 126/175] Docs --- docs/Settings.md | 90 ++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 90 insertions(+) diff --git a/docs/Settings.md b/docs/Settings.md index c919327194..ac5df304b4 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -872,6 +872,96 @@ Enable when BLHeli32 Auto Telemetry function is used. Disable in every other cas --- +### ez_aggressiveness + +EzTune aggressiveness + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 200 | + +--- + +### ez_axis_ratio + +EzTune axis ratio + +| Default | Min | Max | +| --- | --- | --- | +| 110 | 25 | 175 | + +--- + +### ez_damping + +EzTune damping + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 200 | + +--- + +### ez_enabled + +Enables EzTune feature + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + +### ez_expo + +EzTune expo + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 200 | + +--- + +### ez_filter_hz + +EzTune filter cutoff frequency + +| Default | Min | Max | +| --- | --- | --- | +| 110 | 10 | 300 | + +--- + +### ez_rate + +EzTune rate + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 200 | + +--- + +### ez_response + +EzTune response + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 200 | + +--- + +### ez_stability + +EzTune stability + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 200 | + +--- + ### failsafe_delay Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). From 37e1faced5a3ce859afa27e961be6905f1c0fa9c Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 8 Oct 2023 17:42:46 +0200 Subject: [PATCH 127/175] Make features aware --- src/main/flight/ez_tune.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index b08e7cf9ca..918c00a122 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -88,12 +88,15 @@ void ezTuneUpdate(void) { gyroConfigMutable()->gyro_anti_aliasing_lpf_hz = MIN(MIN(ezTune()->filterHz * 2, 250), getGyroLooptime() * 0.5f); gyroConfigMutable()->gyro_anti_aliasing_lpf_type = FILTER_PT1; +#ifdef USE_DYNAMIC_FILTERS //Enable dynamic notch gyroConfigMutable()->dynamicGyroNotchEnabled = 1; gyroConfigMutable()->dynamicGyroNotchQ = 250; gyroConfigMutable()->dynamicGyroNotchMinHz = MAX(ezTune()->filterHz * 0.667f, SETTING_DYNAMIC_GYRO_NOTCH_MIN_HZ_DEFAULT); gyroConfigMutable()->dynamicGyroNotchMode = DYNAMIC_NOTCH_MODE_3D; +#endif +#ifdef USE_GYRO_KALMAN //Make sure Kalman filter is enabled gyroConfigMutable()->kalmanEnabled = 1; if (ezTune()->filterHz < 150) { @@ -101,6 +104,7 @@ void ezTuneUpdate(void) { } else { gyroConfigMutable()->kalman_q = scaleRangef(ezTune()->filterHz, 150, 300, 200, 400); } +#endif //Disable dynamic LPF gyroConfigMutable()->useDynamicLpf = 0; From e63fa473a0f55ec988932b735187536a6f182ccc Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 9 Oct 2023 17:02:10 +0900 Subject: [PATCH 128/175] minor changes on ahrs --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- src/main/flight/imu.c | 15 ++++++--------- 3 files changed, 8 insertions(+), 11 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index c919327194..b8e47c57f1 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -258,7 +258,7 @@ Inertia force compensation method when gps is avaliable, VELNED use the acclerat | Default | Min | Max | | --- | --- | --- | -| VELNED | | | +| ADAPTIVE | | | --- diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 261bf14a56..37fb701af3 100755 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1452,7 +1452,7 @@ groups: type: bool - name: ahrs_inertia_comp_method description: "Inertia force compensation method when gps is avaliable, VELNED use the accleration from gps, TURNRATE calculates accleration by turnrate multiplied by speed, ADAPTIVE choose best result from two in each ahrs loop" - default_value: VELNED + default_value: ADAPTIVE field: inertia_comp_method table: imu_inertia_comp_method diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index c9d0f0aacb..43673e790d 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -719,6 +719,7 @@ static void imuCalculateEstimatedAttitude(float dT) } if (imuConfig()->inertia_comp_method == COMPMETHOD_ADAPTIVE && isGPSTrustworthy() && STATE(AIRPLANE)) { + //pick the best centrifugal acceleration between velned and turnrate fpVector3_t compansatedGravityBF_velned; vectorAdd(&compansatedGravityBF_velned, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_velned); float velned_magnitude = fabsf(fast_fsqrtf(vectorNormSquared(&compansatedGravityBF_velned)) - GRAVITY_CMSS); @@ -726,21 +727,17 @@ static void imuCalculateEstimatedAttitude(float dT) fpVector3_t compansatedGravityBF_turnrate; vectorAdd(&compansatedGravityBF_turnrate, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_turnrate); float turnrate_magnitude = fabsf(fast_fsqrtf(vectorNormSquared(&compansatedGravityBF_turnrate)) - GRAVITY_CMSS); - if (velned_magnitude > turnrate_magnitude) - { - compansatedGravityBF = compansatedGravityBF_turnrate; - } - else - { - compansatedGravityBF = compansatedGravityBF_velned; - } + + compansatedGravityBF = velned_magnitude > turnrate_magnitude? compansatedGravityBF_turnrate:compansatedGravityBF_velned; } - else if (imuConfig()->inertia_comp_method == COMPMETHOD_VELNED && isGPSTrustworthy()) + else if (((imuConfig()->inertia_comp_method == COMPMETHOD_VELNED) || (imuConfig()->inertia_comp_method == COMPMETHOD_ADAPTIVE)) && isGPSTrustworthy()) { + //velned centrifugal force compensation, quad will use this method vectorAdd(&compansatedGravityBF, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_velned); } else if (STATE(AIRPLANE)) { + //turnrate centrifugal force compensation vectorAdd(&compansatedGravityBF, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_turnrate); } else From 704ca50f5826d5a4ec9c4410c2a879e1379c94a3 Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 9 Oct 2023 17:24:26 +0900 Subject: [PATCH 129/175] value name change --- src/main/flight/imu.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index 43673e790d..ed5cbcbfaa 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -722,13 +722,13 @@ static void imuCalculateEstimatedAttitude(float dT) //pick the best centrifugal acceleration between velned and turnrate fpVector3_t compansatedGravityBF_velned; vectorAdd(&compansatedGravityBF_velned, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_velned); - float velned_magnitude = fabsf(fast_fsqrtf(vectorNormSquared(&compansatedGravityBF_velned)) - GRAVITY_CMSS); + float velned_error = fabsf(fast_fsqrtf(vectorNormSquared(&compansatedGravityBF_velned)) - GRAVITY_CMSS); fpVector3_t compansatedGravityBF_turnrate; vectorAdd(&compansatedGravityBF_turnrate, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_turnrate); - float turnrate_magnitude = fabsf(fast_fsqrtf(vectorNormSquared(&compansatedGravityBF_turnrate)) - GRAVITY_CMSS); + float turnrate_error = fabsf(fast_fsqrtf(vectorNormSquared(&compansatedGravityBF_turnrate)) - GRAVITY_CMSS); - compansatedGravityBF = velned_magnitude > turnrate_magnitude? compansatedGravityBF_turnrate:compansatedGravityBF_velned; + compansatedGravityBF = velned_error > turnrate_error? compansatedGravityBF_turnrate:compansatedGravityBF_velned; } else if (((imuConfig()->inertia_comp_method == COMPMETHOD_VELNED) || (imuConfig()->inertia_comp_method == COMPMETHOD_ADAPTIVE)) && isGPSTrustworthy()) { From 9f45d13a68e62f50db0d408dfcad969de324b367 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Mon, 9 Oct 2023 14:39:45 +0200 Subject: [PATCH 130/175] osd joystick enabled buttons in armed state --- src/main/io/rcdevice_cam.c | 22 ++++++++++++---------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/src/main/io/rcdevice_cam.c b/src/main/io/rcdevice_cam.c index c5c54c1aa3..96e9a6141b 100644 --- a/src/main/io/rcdevice_cam.c +++ b/src/main/io/rcdevice_cam.c @@ -81,6 +81,7 @@ static void rcdeviceCameraControlProcess(void) } uint8_t behavior = RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION; + uint8_t behavior1 = RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION; switch (i) { case BOXCAMERA1: if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON)) { @@ -90,11 +91,13 @@ static void rcdeviceCameraControlProcess(void) if (!ARMING_FLAG(ARMED)) { behavior = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN; } + behavior1 = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN; } break; case BOXCAMERA2: if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON)) { behavior = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN; + behavior1 = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN; } break; case BOXCAMERA3: @@ -103,20 +106,20 @@ static void rcdeviceCameraControlProcess(void) if (!ARMING_FLAG(ARMED)) { behavior = RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE; } + behavior1 = RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE; } break; default: break; } - if (behavior != RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION) { - if ( rcdeviceIsEnabled() ) { - runcamDeviceSimulateCameraButton(camDevice, behavior); - } + if ((behavior != RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION) && rcdeviceIsEnabled()) { + runcamDeviceSimulateCameraButton(camDevice, behavior); + switchStates[switchIndex].isActivated = true; + } #ifndef UNIT_TEST #ifdef USE_LED_STRIP - else if (osdJoystickEnabled()) { - - switch (behavior) { + else if ((behavior1 != RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION) && osdJoystickEnabled()) { + switch (behavior1) { case RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN: osdJoystickSimulate5KeyButtonPress(RCDEVICE_CAM_KEY_ENTER); break; @@ -127,11 +130,10 @@ static void rcdeviceCameraControlProcess(void) osdJoystickSimulate5KeyButtonPress(RCDEVICE_CAM_KEY_DOWN); break; } - } -#endif -#endif switchStates[switchIndex].isActivated = true; } +#endif +#endif } else { #ifndef UNIT_TEST #ifdef USE_LED_STRIP From ee2ff11261486d346c7249562e244516c7f82173 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 9 Oct 2023 14:49:45 +0200 Subject: [PATCH 131/175] Lower default hover throttle to 1300 1500 is usually too high and quad tends to shoot up. throttle around 30% seems closer to reality for most small quads --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index c919327194..0276dac744 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -3438,7 +3438,7 @@ Multicopter hover throttle hint for altitude controller. Should be set to approx | Default | Min | Max | | --- | --- | --- | -| 1500 | 1000 | 2000 | +| 1300 | 1000 | 2000 | --- diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 261bf14a56..2245b5bcec 100755 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1045,7 +1045,7 @@ groups: max: PWM_RANGE_MAX - name: nav_mc_hover_thr description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering." - default_value: 1500 + default_value: 1300 field: nav.mc.hover_throttle min: 1000 max: 2000 From 37eb95e2d87eef9510052bd9e5d330c55471f8c5 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Mon, 9 Oct 2023 15:16:28 +0200 Subject: [PATCH 132/175] fixed compilation error --- src/main/io/rcdevice_cam.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/io/rcdevice_cam.c b/src/main/io/rcdevice_cam.c index 96e9a6141b..e68af2c553 100644 --- a/src/main/io/rcdevice_cam.c +++ b/src/main/io/rcdevice_cam.c @@ -116,6 +116,7 @@ static void rcdeviceCameraControlProcess(void) runcamDeviceSimulateCameraButton(camDevice, behavior); switchStates[switchIndex].isActivated = true; } + UNUSED(behavior1); #ifndef UNIT_TEST #ifdef USE_LED_STRIP else if ((behavior1 != RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION) && osdJoystickEnabled()) { From bd62d5f4115de32accb0e20d4753ffb6279b0711 Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Mon, 9 Oct 2023 15:21:06 +0200 Subject: [PATCH 133/175] fixed compilation error --- src/main/io/rcdevice_cam.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/rcdevice_cam.c b/src/main/io/rcdevice_cam.c index e68af2c553..0edbc8bf97 100644 --- a/src/main/io/rcdevice_cam.c +++ b/src/main/io/rcdevice_cam.c @@ -116,7 +116,6 @@ static void rcdeviceCameraControlProcess(void) runcamDeviceSimulateCameraButton(camDevice, behavior); switchStates[switchIndex].isActivated = true; } - UNUSED(behavior1); #ifndef UNIT_TEST #ifdef USE_LED_STRIP else if ((behavior1 != RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION) && osdJoystickEnabled()) { @@ -135,6 +134,7 @@ static void rcdeviceCameraControlProcess(void) } #endif #endif + UNUSED(behavior1); } else { #ifndef UNIT_TEST #ifdef USE_LED_STRIP From 98475635598b17ab9a1589b536eb70c1811b1a5b Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 11 Oct 2023 02:14:37 +0900 Subject: [PATCH 134/175] simplify the smix --- src/main/flight/mixer_profile.c | 4 +- src/main/flight/servos.c | 71 ++++++++++++++++++--------------- 2 files changed, 41 insertions(+), 34 deletions(-) diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index de1cdecb3b..575fb4dee0 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -23,6 +23,7 @@ #include "fc/runtime_config.h" #include "fc/settings.h" #include "fc/rc_modes.h" +#include "fc/cli.h" #include "programming/logic_condition.h" #include "navigation/navigation.h" @@ -187,8 +188,9 @@ bool checkMixerProfileHotSwitchAvalibility(void) } void outputProfileUpdateTask(timeUs_t currentTimeUs) -{ +{ UNUSED(currentTimeUs); + if(cliMode) return; bool mixerAT_inuse = mixerProfileAT.phase != MIXERAT_PHASE_IDLE; // transition mode input for servo mix and motor mix if (!FLIGHT_MODE(FAILSAFE_MODE) && (!mixerAT_inuse)) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 4d4bb497d1..354acfd6af 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -103,8 +103,14 @@ void pgResetFn_servoParams(servoParam_t *instance) int16_t servo[MAX_SUPPORTED_SERVOS]; static uint8_t servoRuleCount = 0; +static servoMixer_t currentServoMixer[MAX_SERVO_RULES]; + +/* +//Was used to keep track of servo rules in all mixer_profile, In order to Apply mixer speed limit when rules turn off static servoMixer_t currentServoMixer[MAX_SERVO_RULES*MAX_MIXER_PROFILE_COUNT]; -static bool currentServoMixerActivative[MAX_SERVO_RULES*MAX_MIXER_PROFILE_COUNT];// if true, the rule is used by current servo mixer +static bool currentServoMixerActivative[MAX_SERVO_RULES*MAX_MIXER_PROFILE_COUNT]; // if true, the rule is used by current servo mixer +*/ + static bool servoOutputEnabled; static bool mixerUsesServos; @@ -115,7 +121,7 @@ static biquadFilter_t servoFilter[MAX_SUPPORTED_SERVOS]; static bool servoFilterIsSet; static servoMetadata_t servoMetadata[MAX_SUPPORTED_SERVOS]; -static rateLimitFilter_t servoSpeedLimitFilter[MAX_SERVO_RULES*MAX_MIXER_PROFILE_COUNT]; +static rateLimitFilter_t servoSpeedLimitFilter[MAX_SERVO_RULES]; STATIC_FASTRAM pt1Filter_t rotRateFilter; STATIC_FASTRAM pt1Filter_t targetRateFilter; @@ -161,8 +167,27 @@ void servosInit(void) } int getServoCount(void) -{ - if (servoRuleCount) { +{ + bool servoRuleDetected = false; + minServoIndex = 0; + maxServoIndex = 255; + for (int j = 0; j < MAX_MIXER_PROFILE_COUNT; j++) { + for (int i = 0; i < MAX_SERVO_RULES; i++) { + // check if done + if (mixerServoMixersByIndex(j)[i].rate == 0){ + break; + } + if (mixerServoMixersByIndex(j)[i].targetChannel < minServoIndex) { + minServoIndex = mixerServoMixersByIndex(j)[i].targetChannel; + } + + if (mixerServoMixersByIndex(j)[i].targetChannel > maxServoIndex) { + maxServoIndex = mixerServoMixersByIndex(j)[i].targetChannel; + } + servoRuleDetected = true; + } + } + if (servoRuleDetected) { return 1 + maxServoIndex - minServoIndex; } else { @@ -173,30 +198,17 @@ int getServoCount(void) void loadCustomServoMixer(void) { servoRuleCount = 0; - minServoIndex = 255; - maxServoIndex = 0; memset(currentServoMixer, 0, sizeof(currentServoMixer)); - for (int j = 0; j < MAX_MIXER_PROFILE_COUNT; j++) { - const servoMixer_t* tmp_customServoMixers = &mixerServoMixersByIndex(j)[0]; - // load custom mixer into currentServoMixer - for (int i = 0; i < MAX_SERVO_RULES; i++) { - // check if done - if (tmp_customServoMixers[i].rate == 0) - break; - - if (tmp_customServoMixers[i].targetChannel < minServoIndex) { - minServoIndex = tmp_customServoMixers[i].targetChannel; - } - - if (tmp_customServoMixers[i].targetChannel > maxServoIndex) { - maxServoIndex = tmp_customServoMixers[i].targetChannel; - } - - memcpy(¤tServoMixer[servoRuleCount], &tmp_customServoMixers[i], sizeof(servoMixer_t)); - currentServoMixerActivative[servoRuleCount] = j==currentMixerProfileIndex; - servoRuleCount++; + // load custom mixer into currentServoMixer + for (int i = 0; i < MAX_SERVO_RULES; i++) { + // check if done + if (customServoMixers(i)->rate == 0){ + break; } + currentServoMixer[servoRuleCount] = *customServoMixers(i); + servoSpeedLimitFilter[servoRuleCount].state = 0; + servoRuleCount++; } } @@ -353,9 +365,6 @@ void servoMixer(float dT) inputRaw = 0; } #endif - if (!currentServoMixerActivative[i]) { - inputRaw = 0; - } /* * Apply mixer speed limit. 1 [one] speed unit is defined as 10us/s: * 0 = no limiting @@ -369,7 +378,7 @@ void servoMixer(float dT) } /* - * When not armed, apply servo low position to all outputs that include a throttle or stabilizet throttle in the mix + * When not armed, apply servo low position to all outputs that include a throttle or stabilized throttle in the mix */ if (!ARMING_FLAG(ARMED)) { for (int i = 0; i < servoRuleCount; i++) { @@ -438,7 +447,6 @@ void processServoAutotrimMode(void) if (ARMING_FLAG(ARMED)) { for (int axis = FD_ROLL; axis <= FD_YAW; axis++) { for (int i = 0; i < servoRuleCount; i++) { - if (!currentServoMixerActivative[i]) {continue;} // Reset servo middle accumulator const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; @@ -461,7 +469,6 @@ void processServoAutotrimMode(void) if (ARMING_FLAG(ARMED)) { for (int axis = FD_ROLL; axis <= FD_YAW; axis++) { for (int i = 0; i < servoRuleCount; i++) { - if (!currentServoMixerActivative[i]) {continue;} const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; if (source == axis) { @@ -474,7 +481,6 @@ void processServoAutotrimMode(void) if ((millis() - trimStartedAt) > SERVO_AUTOTRIM_TIMER_MS) { for (int axis = FD_ROLL; axis <= FD_YAW; axis++) { for (int i = 0; i < servoRuleCount; i++) { - if (!currentServoMixerActivative[i]) {continue;} const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; if (source == axis) { @@ -508,7 +514,6 @@ void processServoAutotrimMode(void) if (trimState == AUTOTRIM_SAVE_PENDING) { for (int axis = FD_ROLL; axis <= FD_YAW; axis++) { for (int i = 0; i < servoRuleCount; i++) { - if (!currentServoMixerActivative[i]) {continue;} const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; if (source == axis) { From 65fa493af1f991716893217b76a46b61956bd8cf Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 11 Oct 2023 03:41:22 +0900 Subject: [PATCH 135/175] mixer_profile rcmodes changes --- src/main/fc/fc_core.c | 2 ++ src/main/fc/fc_msp_box.c | 11 ++++++----- src/main/flight/mixer_profile.c | 8 ++++++++ src/main/flight/mixer_profile.h | 1 + src/main/flight/pid.c | 2 +- 5 files changed, 18 insertions(+), 6 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 87d9fbe746..7b22770575 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -727,6 +727,8 @@ void processRx(timeUs_t currentTimeUs) } else { DISABLE_FLIGHT_MODE(MANUAL_MODE); } + }else{ + DISABLE_FLIGHT_MODE(MANUAL_MODE); } /* In airmode Iterm should be prevented to grow when Low thottle and Roll + Pitch Centered. diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index f7c88d6e5b..5b6b8656d8 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -202,7 +202,7 @@ void initActiveBoxIds(void) //Camstab mode is enabled always ADD_ACTIVE_BOX(BOXCAMSTAB); - if (STATE(MULTIROTOR)) { + if (STATE(MULTIROTOR) || platformTypeConfigured(PLATFORM_MULTIROTOR) || platformTypeConfigured(PLATFORM_TRICOPTER)) { if ((sensors(SENSOR_ACC) || sensors(SENSOR_MAG))) { ADD_ACTIVE_BOX(BOXHEADFREE); ADD_ACTIVE_BOX(BOXHEADADJ); @@ -244,13 +244,13 @@ void initActiveBoxIds(void) #endif } - if (STATE(AIRPLANE)) { + if (STATE(AIRPLANE) || platformTypeConfigured(PLATFORM_AIRPLANE)) { ADD_ACTIVE_BOX(BOXSOARING); } } #ifdef USE_MR_BRAKING_MODE - if (mixerConfig()->platformType == PLATFORM_MULTIROTOR) { + if (mixerConfig()->platformType == PLATFORM_MULTIROTOR || platformTypeConfigured(PLATFORM_MULTIROTOR)) { ADD_ACTIVE_BOX(BOXBRAKING); } #endif @@ -259,11 +259,12 @@ void initActiveBoxIds(void) ADD_ACTIVE_BOX(BOXNAVALTHOLD); } - if (STATE(AIRPLANE) || STATE(ROVER) || STATE(BOAT)) { + if (STATE(AIRPLANE) || STATE(ROVER) || STATE(BOAT) || + platformTypeConfigured(PLATFORM_AIRPLANE) || platformTypeConfigured(PLATFORM_ROVER) || platformTypeConfigured(PLATFORM_BOAT)) { ADD_ACTIVE_BOX(BOXMANUAL); } - if (STATE(AIRPLANE)) { + if (STATE(AIRPLANE) || platformTypeConfigured(PLATFORM_AIRPLANE)) { if (!feature(FEATURE_FW_LAUNCH)) { ADD_ACTIVE_BOX(BOXNAVLAUNCH); } diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 575fb4dee0..6f2b6b0920 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -108,6 +108,14 @@ void setMixerProfileAT(void) mixerProfileAT.transitionTransEndTime = mixerProfileAT.transitionStartTime + (timeMs_t)currentMixerConfig.switchTransitionTimer * 100; } +bool platformTypeConfigured(flyingPlatformType_e platformType) +{ + if (!isModeActivationConditionPresent(BOXMIXERPROFILE)){ + return false; + } + return mixerConfigByIndex(nextProfileIndex)->platformType == platformType; +} + bool checkMixerATRequired(mixerProfileATRequest_e required_action) { //return false if mixerAT condition is not required or setting is not valid diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index bf52d45c3d..d2208d7b8c 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -71,6 +71,7 @@ static inline const mixerProfile_t* mixerProfiles_CopyArray_by_index(int _index) #define mixerMotorMixersByIndex(index) (mixerProfiles(index)->MotorMixers) #define mixerServoMixersByIndex(index) (mixerProfiles(index)->ServoMixers) +bool platformTypeConfigured(flyingPlatformType_e platformType); bool outputProfileHotSwitch(int profile_index); bool checkMixerProfileHotSwitchAvalibility(void); void activateMixerConfig(void); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 2bb4ab7035..3049fbb822 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -1130,7 +1130,7 @@ void FAST_CODE pidController(float dT) canUseFpvCameraMix = false; // FPVANGLEMIX is incompatible with TURN_ASSISTANT } - if (canUseFpvCameraMix && IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX) && currentControlRateProfile->misc.fpvCamAngleDegrees) { + if (canUseFpvCameraMix && IS_RC_MODE_ACTIVE(BOXFPVANGLEMIX) && currentControlRateProfile->misc.fpvCamAngleDegrees && STATE(MULTIROTOR)) { pidApplyFpvCameraAngleMix(pidState, currentControlRateProfile->misc.fpvCamAngleDegrees); } From ee015969baab8bd80ea9f74891bf108846b888a4 Mon Sep 17 00:00:00 2001 From: shota Date: Thu, 12 Oct 2023 22:29:17 +0900 Subject: [PATCH 136/175] fix mixer_profie configurator issue --- src/main/fc/fc_msp.c | 23 +++++++++++++++++++++-- src/main/flight/mixer_profile.c | 8 ++++---- src/main/flight/mixer_profile.h | 1 + 3 files changed, 26 insertions(+), 6 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 0f3d80829a..83e1172373 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -522,6 +522,18 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, -1); #endif } + if(MAX_MIXER_PROFILE_COUNT==1) break; + for (int i = 0; i < MAX_SERVO_RULES; i++) { + sbufWriteU8(dst, mixerServoMixersByIndex(nextMixerProfileIndex)[i].targetChannel); + sbufWriteU8(dst, mixerServoMixersByIndex(nextMixerProfileIndex)[i].inputSource); + sbufWriteU16(dst, mixerServoMixersByIndex(nextMixerProfileIndex)[i].rate); + sbufWriteU8(dst, mixerServoMixersByIndex(nextMixerProfileIndex)[i].speed); + #ifdef USE_PROGRAMMING_FRAMEWORK + sbufWriteU8(dst, mixerServoMixersByIndex(nextMixerProfileIndex)[i].conditionId); + #else + sbufWriteU8(dst, -1); + #endif + } break; #ifdef USE_PROGRAMMING_FRAMEWORK case MSP2_INAV_LOGIC_CONDITIONS: @@ -567,11 +579,18 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF #endif case MSP2_COMMON_MOTOR_MIXER: for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) { - sbufWriteU16(dst, primaryMotorMixer(i)->throttle * 1000); + sbufWriteU16(dst, constrainf(primaryMotorMixer(i)->throttle + 2.0f, 0.0f, 4.0f) * 1000); sbufWriteU16(dst, constrainf(primaryMotorMixer(i)->roll + 2.0f, 0.0f, 4.0f) * 1000); sbufWriteU16(dst, constrainf(primaryMotorMixer(i)->pitch + 2.0f, 0.0f, 4.0f) * 1000); sbufWriteU16(dst, constrainf(primaryMotorMixer(i)->yaw + 2.0f, 0.0f, 4.0f) * 1000); } + if (MAX_MIXER_PROFILE_COUNT==1) break; + for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) { + sbufWriteU16(dst, constrainf(mixerMotorMixersByIndex(nextMixerProfileIndex)[i].throttle + 2.0f, 0.0f, 4.0f) * 1000); + sbufWriteU16(dst, constrainf(mixerMotorMixersByIndex(nextMixerProfileIndex)[i].roll + 2.0f, 0.0f, 4.0f) * 1000); + sbufWriteU16(dst, constrainf(mixerMotorMixersByIndex(nextMixerProfileIndex)[i].pitch + 2.0f, 0.0f, 4.0f) * 1000); + sbufWriteU16(dst, constrainf(mixerMotorMixersByIndex(nextMixerProfileIndex)[i].yaw + 2.0f, 0.0f, 4.0f) * 1000); + } break; case MSP_MOTOR: @@ -2100,7 +2119,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) case MSP2_COMMON_SET_MOTOR_MIXER: sbufReadU8Safe(&tmp_u8, src); if ((dataSize == 9) && (tmp_u8 < MAX_SUPPORTED_MOTORS)) { - primaryMotorMixerMutable(tmp_u8)->throttle = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 1.0f); + primaryMotorMixerMutable(tmp_u8)->throttle = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 4.0f) - 2.0f; primaryMotorMixerMutable(tmp_u8)->roll = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 4.0f) - 2.0f; primaryMotorMixerMutable(tmp_u8)->pitch = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 4.0f) - 2.0f; primaryMotorMixerMutable(tmp_u8)->yaw = constrainf(sbufReadU16(src) / 1000.0f, 0.0f, 4.0f) - 2.0f; diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 6f2b6b0920..64a6c39380 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -35,7 +35,7 @@ int currentMixerProfileIndex; bool isMixerTransitionMixing; bool isMixerTransitionMixing_requested; mixerProfileAT_t mixerProfileAT; -int nextProfileIndex; +int nextMixerProfileIndex; PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1); @@ -81,7 +81,7 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) void activateMixerConfig(){ currentMixerProfileIndex = getConfigMixerProfile(); currentMixerConfig = *mixerConfig(); - nextProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT; + nextMixerProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT; } void mixerConfigInit(void) @@ -113,7 +113,7 @@ bool platformTypeConfigured(flyingPlatformType_e platformType) if (!isModeActivationConditionPresent(BOXMIXERPROFILE)){ return false; } - return mixerConfigByIndex(nextProfileIndex)->platformType == platformType; + return mixerConfigByIndex(nextMixerProfileIndex)->platformType == platformType; } bool checkMixerATRequired(mixerProfileATRequest_e required_action) @@ -171,7 +171,7 @@ bool mixerATUpdateState(mixerProfileATRequest_e required_action) isMixerTransitionMixing_requested = true; if (millis() > mixerProfileAT.transitionTransEndTime){ isMixerTransitionMixing_requested = false; - outputProfileHotSwitch(nextProfileIndex); + outputProfileHotSwitch(nextMixerProfileIndex); mixerProfileAT.phase = MIXERAT_PHASE_IDLE; reprocessState = true; //transition is done diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index d2208d7b8c..50fbb4a82f 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -54,6 +54,7 @@ bool mixerATUpdateState(mixerProfileATRequest_e required_action); extern mixerConfig_t currentMixerConfig; extern int currentMixerProfileIndex; +extern int nextMixerProfileIndex; extern bool isMixerTransitionMixing; #define mixerConfig() (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->mixer_config)) #define mixerConfigMutable() ((mixerConfig_t *) mixerConfig()) From e5d90339f495d482a55902da3554b2d528a7fcde Mon Sep 17 00:00:00 2001 From: shota Date: Fri, 13 Oct 2023 02:43:57 +0900 Subject: [PATCH 137/175] fixes servo output issue --- src/main/flight/servos.c | 64 ++++++++++++++++++++++------------------ 1 file changed, 36 insertions(+), 28 deletions(-) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 354acfd6af..d3c5da8c75 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -143,34 +143,14 @@ void servoComputeScalingFactors(uint8_t servoIndex) { servoMetadata[servoIndex].scaleMin = (servoParams(servoIndex)->middle - servoParams(servoIndex)->min) / 500.0f; } -void servosInit(void) +void computeServoCount(void) { - // give all servos a default command - for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { - servo[i] = servoParams(i)->middle; + static bool firstRun = true; + if (!firstRun) { + return; } - - /* - * load mixer - */ - loadCustomServoMixer(); - - // If there are servo rules after all, update variables - if (servoRuleCount > 0) { - servoOutputEnabled = true; - mixerUsesServos = true; - } - - for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) { - servoComputeScalingFactors(i); - } -} - -int getServoCount(void) -{ - bool servoRuleDetected = false; - minServoIndex = 0; - maxServoIndex = 255; + minServoIndex = 255; + maxServoIndex = 0; for (int j = 0; j < MAX_MIXER_PROFILE_COUNT; j++) { for (int i = 0; i < MAX_SERVO_RULES; i++) { // check if done @@ -184,10 +164,38 @@ int getServoCount(void) if (mixerServoMixersByIndex(j)[i].targetChannel > maxServoIndex) { maxServoIndex = mixerServoMixersByIndex(j)[i].targetChannel; } - servoRuleDetected = true; + mixerUsesServos = true; } } - if (servoRuleDetected) { + firstRun = false; +} + +void servosInit(void) +{ + // give all servos a default command + for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { + servo[i] = servoParams(i)->middle; + } + + /* + * load mixer + */ + computeServoCount(); + loadCustomServoMixer(); + + // If there are servo rules after all, update variables + if (mixerUsesServos) { + servoOutputEnabled = true; + } + + for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) { + servoComputeScalingFactors(i); + } +} + +int getServoCount(void) +{ + if (mixerUsesServos) { return 1 + maxServoIndex - minServoIndex; } else { From afd2848d791baf733ea39446ce62d85857a3cd8a Mon Sep 17 00:00:00 2001 From: Hugo Chiang <31283897+DusKing1@users.noreply.github.com> Date: Sat, 14 Oct 2023 08:37:50 +0800 Subject: [PATCH 138/175] add icm42605 driver for SKYSTARSF405HD --- src/main/target/SKYSTARSF405HD/target.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/main/target/SKYSTARSF405HD/target.h b/src/main/target/SKYSTARSF405HD/target.h index ac88a72084..b8a696e14d 100644 --- a/src/main/target/SKYSTARSF405HD/target.h +++ b/src/main/target/SKYSTARSF405HD/target.h @@ -45,6 +45,11 @@ #define BMI270_SPI_BUS BUS_SPI1 #define BMI270_CS_PIN PA4 +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW180_DEG_FLIP +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + // *************** M25P256 flash ******************** #define USE_FLASHFS #define USE_FLASH_M25P16 From d36d3ccd8126713148a35f4c089fcb5d0eaad3e0 Mon Sep 17 00:00:00 2001 From: shota Date: Sun, 15 Oct 2023 17:25:04 +0900 Subject: [PATCH 139/175] mixer_profile switch support --- src/main/fc/config.c | 3 +++ src/main/fc/fc_msp.c | 9 +++++++++ src/main/msp/msp_protocol_v2_inav.h | 2 ++ 3 files changed, 14 insertions(+) diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 3950d76376..2f5c4d6c6b 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -500,6 +500,9 @@ void setConfigMixerProfileAndWriteEEPROM(uint8_t profileIndex) resumeRxSignal(); } beeperConfirmationBeeps(profileIndex + 1); + if (mixerConfig()->PIDProfileLinking) { + setConfigProfileAndWriteEEPROM(profileIndex); + } } void setGyroCalibration(float getGyroZero[XYZ_AXIS_COUNT]) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 83e1172373..4e0c102d33 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -461,6 +461,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, packSensorStatus()); sbufWriteU16(dst, averageSystemLoadPercent); sbufWriteU8(dst, (getConfigBatteryProfile() << 4) | getConfigProfile()); + sbufWriteU8(dst, getConfigMixerProfile()); sbufWriteU32(dst, armingFlags); sbufWriteData(dst, &mspBoxModeFlags, sizeof(mspBoxModeFlags)); } @@ -3013,6 +3014,14 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) } break; + case MSP2_INAV_SELECT_MIXER_PROFILE: + if (!ARMING_FLAG(ARMED) && sbufReadU8Safe(&tmp_u8, src)) { + setConfigMixerProfileAndWriteEEPROM(tmp_u8); + } else { + return MSP_RESULT_ERROR; + } + break; + #ifdef USE_TEMPERATURE_SENSOR case MSP2_INAV_SET_TEMP_SENSOR_CONFIG: if (dataSize == sizeof(tempSensorConfig_t) * MAX_TEMP_SENSORS) { diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index 9cf1881c73..9b4abbdbe4 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -94,3 +94,5 @@ #define MSP2_INAV_RATE_DYNAMICS 0x2060 #define MSP2_INAV_SET_RATE_DYNAMICS 0x2061 + +#define MSP2_INAV_SELECT_MIXER_PROFILE 0x2070 From 070175bc7dc18de0d683d66c8676b1f5bf6cfda6 Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 16 Oct 2023 09:33:49 +0900 Subject: [PATCH 140/175] minor fix --- src/main/fc/config.c | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 2f5c4d6c6b..3950d76376 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -500,9 +500,6 @@ void setConfigMixerProfileAndWriteEEPROM(uint8_t profileIndex) resumeRxSignal(); } beeperConfirmationBeeps(profileIndex + 1); - if (mixerConfig()->PIDProfileLinking) { - setConfigProfileAndWriteEEPROM(profileIndex); - } } void setGyroCalibration(float getGyroZero[XYZ_AXIS_COUNT]) From 5e608b7f66af313b5e95aa229010dd89b15c2484 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Thu, 19 Oct 2023 17:18:45 +0100 Subject: [PATCH 141/175] Update navigation.c --- src/main/navigation/navigation.c | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 4a871de084..69a9c0479a 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -949,7 +949,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE, } }, - + /** MIXER AUTOMATED TRANSITION mode, alternated althod ***************************************************/ [NAV_STATE_MIXERAT_INITIALIZE] = { .persistentId = NAV_PERSISTENT_ID_MIXERAT_INITIALIZE, @@ -992,7 +992,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { .onEvent = { [NAV_FSM_EVENT_SUCCESS] = NAV_STATE_IDLE, [NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE, - + } }, }; @@ -1514,7 +1514,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_LANDING(navigationF if (posControl.flags.estHeadingStatus == EST_NONE || checkForPositionSensorTimeout() || !validateRTHSanityChecker()) { return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING; } - + if (checkMixerATRequired(MIXERAT_REQUEST_LAND)){ return NAV_FSM_EVENT_SWITCH_TO_MIXERAT; } @@ -3919,14 +3919,14 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) } // CRUISE has priority over COURSE_HOLD and AH - if (IS_RC_MODE_ACTIVE(BOXNAVCRUISE) && STATE(AIRPLANE)) { + if (IS_RC_MODE_ACTIVE(BOXNAVCRUISE)) { if ((FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)) || (canActivatePosHold && canActivateAltHold)) return NAV_FSM_EVENT_SWITCH_TO_CRUISE; } // PH has priority over COURSE_HOLD // CRUISE has priority on AH - if (IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD) && STATE(AIRPLANE)) { + if (IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD)) { if (IS_RC_MODE_ACTIVE(BOXNAVALTHOLD) && ((FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)) || (canActivatePosHold && canActivateAltHold))) { return NAV_FSM_EVENT_SWITCH_TO_CRUISE; } From 3f5b320dd6ad708c983ce83c5f5d4fcf1755bb45 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 20 Oct 2023 11:31:54 +0200 Subject: [PATCH 142/175] Fix antialiasing filter freqency calculation --- src/main/flight/ez_tune.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index 918c00a122..0f38b39211 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -71,11 +71,10 @@ void ezTuneUpdate(void) { if (ezTune()->enabled) { // Setup filtering - //Enable Smith predictor pidProfileMutable()->smithPredictorDelay = computePt1FilterDelayMs(ezTune()->filterHz) + computePt1FilterDelayMs(gyroConfig()->gyro_anti_aliasing_lpf_hz); - + //Set Dterm LPF pidProfileMutable()->dterm_lpf_hz = MAX(ezTune()->filterHz - 5, 50); pidProfileMutable()->dterm_lpf_type = FILTER_PT2; @@ -85,7 +84,8 @@ void ezTuneUpdate(void) { gyroConfigMutable()->gyro_main_lpf_type = FILTER_PT1; //Set anti-aliasing filter - gyroConfigMutable()->gyro_anti_aliasing_lpf_hz = MIN(MIN(ezTune()->filterHz * 2, 250), getGyroLooptime() * 0.5f); + const int gyroNyquist = 1000000 / TASK_GYRO_LOOPTIME; + gyroConfigMutable()->gyro_anti_aliasing_lpf_hz = MIN(MIN(ezTune()->filterHz * 2, 250), (int)(gyroNyquist * 0.5f)); gyroConfigMutable()->gyro_anti_aliasing_lpf_type = FILTER_PT1; #ifdef USE_DYNAMIC_FILTERS From 927597c3c903196faca0e65f2fa3916efa668121 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 20 Oct 2023 12:09:42 +0200 Subject: [PATCH 143/175] Imrove processing --- src/main/flight/ez_tune.c | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/src/main/flight/ez_tune.c b/src/main/flight/ez_tune.c index 0f38b39211..c6c57afbfe 100644 --- a/src/main/flight/ez_tune.c +++ b/src/main/flight/ez_tune.c @@ -54,7 +54,7 @@ PG_RESET_TEMPLATE(ezTuneSettings_t, ezTune, #define EZ_TUNE_YAW_SCALE 0.5f static float computePt1FilterDelayMs(uint8_t filterHz) { - return 1.0f / (2.0f * M_PIf * filterHz); + return 1000.0f / (2.0f * M_PIf * filterHz); } static float getYawPidScale(float input) { @@ -71,10 +71,6 @@ void ezTuneUpdate(void) { if (ezTune()->enabled) { // Setup filtering - //Enable Smith predictor - pidProfileMutable()->smithPredictorDelay = computePt1FilterDelayMs(ezTune()->filterHz) - + computePt1FilterDelayMs(gyroConfig()->gyro_anti_aliasing_lpf_hz); - //Set Dterm LPF pidProfileMutable()->dterm_lpf_hz = MAX(ezTune()->filterHz - 5, 50); pidProfileMutable()->dterm_lpf_type = FILTER_PT2; @@ -84,10 +80,12 @@ void ezTuneUpdate(void) { gyroConfigMutable()->gyro_main_lpf_type = FILTER_PT1; //Set anti-aliasing filter - const int gyroNyquist = 1000000 / TASK_GYRO_LOOPTIME; - gyroConfigMutable()->gyro_anti_aliasing_lpf_hz = MIN(MIN(ezTune()->filterHz * 2, 250), (int)(gyroNyquist * 0.5f)); + gyroConfigMutable()->gyro_anti_aliasing_lpf_hz = SETTING_GYRO_ANTI_ALIASING_LPF_HZ_DEFAULT; gyroConfigMutable()->gyro_anti_aliasing_lpf_type = FILTER_PT1; + //Enable Smith predictor + pidProfileMutable()->smithPredictorDelay = computePt1FilterDelayMs(ezTune()->filterHz); + #ifdef USE_DYNAMIC_FILTERS //Enable dynamic notch gyroConfigMutable()->dynamicGyroNotchEnabled = 1; From 3456d60e9a4125859eded11d5a05e5fdcb0002c3 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 21 Oct 2023 17:30:18 +0200 Subject: [PATCH 144/175] Add SYM_TOTAL -> BF_SYM_TOTAL_DISTANCE mapping --- src/main/io/displayport_msp_bf_compat.c | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index 7cfa8f1bf6..b22c4affe9 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -187,13 +187,10 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_ALT_M: return BF_SYM_M; -/* case SYM_TRIP_DIST: - return BF_SYM_TRIP_DIST; - case SYM_TOTAL: - return BF_SYM_TOTAL; - + return BF_SYM_TOTAL_DISTANCE; +/* case SYM_ALT_KM: return BF_SYM_ALT_KM; From 201398e7517178de03a421c43933787ec171b71a Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 21 Oct 2023 17:34:54 +0200 Subject: [PATCH 145/175] SYM_TOTAL and SYM_TRIP_DISTANCE are the same symbol --- src/main/io/displayport_msp_bf_compat.c | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index b22c4affe9..a9831929a7 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -187,7 +187,6 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_ALT_M: return BF_SYM_M; - case SYM_TRIP_DIST: case SYM_TOTAL: return BF_SYM_TOTAL_DISTANCE; /* From ab20702dff3c342b31e9a24daecfb272b0e47fd7 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 21 Oct 2023 22:48:22 +0200 Subject: [PATCH 146/175] Add G_FORCE symbol as letter G --- src/main/io/displayport_msp_bf_compat.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index a9831929a7..315ac9a90c 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -330,10 +330,12 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_PITCH_DOWN: return BF_SYM_PITCH_DOWN; + */ case SYM_GFORCE: - return BF_SYM_GFORCE; + return 'G'; +/* case SYM_GFORCE_X: return BF_SYM_GFORCE_X; From bb3d8257c37f093a97e626b9317ef5b69d9d988b Mon Sep 17 00:00:00 2001 From: rmaia <9812730+rmaia3d@users.noreply.github.com> Date: Sun, 22 Oct 2023 12:39:12 -0300 Subject: [PATCH 147/175] BFCOMPAT - Improve wind and air speed fields --- src/main/io/displayport_msp_bf_compat.c | 38 +++++++++++++++++++------ 1 file changed, 29 insertions(+), 9 deletions(-) diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index 7cfa8f1bf6..de18f9b840 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -96,10 +96,31 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) case SYM_AH_DECORATION_DOWN: return BF_SYM_AH_DECORATION_DOWN; - - case SYM_DIRECTION: - return BF_SYM_DIRECTION; */ + case SYM_DIRECTION: + return return BF_SYM_ARROW_NORTH; + + case SYM_DIRECTION + 1: // NE pointing arrow + return BF_SYM_ARROW_7; + + case SYM_DIRECTION + 2: // E pointing arrow + return BF_SYM_ARROW_EAST; + + case SYM_DIRECTION + 3: // SE pointing arrow + return BF_SYM_ARROW_3; + + case SYM_DIRECTION + 4: // S pointing arrow + return BF_SYM_ARROW_SOUTH; + + case SYM_DIRECTION + 5: // SW pointing arrow + return BF_SYM_ARROW_15; + + case SYM_DIRECTION + 6: // W pointing arrow + return BF_SYM_ARROW_WEST; + + case SYM_DIRECTION + 7: // NW pointing arrow + return BF_SYM_ARROW_11; + case SYM_VOLT: return BF_SYM_VOLT; @@ -226,20 +247,19 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) /* case SYM_NM: return BF_SYM_NM; - +*/ case SYM_WIND_HORIZONTAL: - return BF_SYM_WIND_HORIZONTAL; + return 'W'; // W for wind +/* case SYM_WIND_VERTICAL: return BF_SYM_WIND_VERTICAL; case SYM_3D_KT: return BF_SYM_3D_KT; - - - case SYM_AIR: - return BF_SYM_AIR; */ + case SYM_AIR: + return 'A'; // A for airspeed case SYM_3D_KMH: return BF_SYM_KPH; From 76ed33e338b4fbab40d13b6ef57c214f46975c2d Mon Sep 17 00:00:00 2001 From: rmaia <9812730+rmaia3d@users.noreply.github.com> Date: Sun, 22 Oct 2023 12:44:09 -0300 Subject: [PATCH 148/175] fix typo --- src/main/io/displayport_msp_bf_compat.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/displayport_msp_bf_compat.c b/src/main/io/displayport_msp_bf_compat.c index de18f9b840..4f21e07475 100644 --- a/src/main/io/displayport_msp_bf_compat.c +++ b/src/main/io/displayport_msp_bf_compat.c @@ -98,7 +98,7 @@ uint8_t getBfCharacter(uint8_t ch, uint8_t page) return BF_SYM_AH_DECORATION_DOWN; */ case SYM_DIRECTION: - return return BF_SYM_ARROW_NORTH; + return BF_SYM_ARROW_NORTH; case SYM_DIRECTION + 1: // NE pointing arrow return BF_SYM_ARROW_7; From 013de4537ecbc99fe8bcdb3c76cf482739c124f7 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Mon, 23 Oct 2023 10:28:57 +0100 Subject: [PATCH 149/175] fix autoleveltrim --- src/main/flight/pid.c | 54 ++++++++++++++++++++++--------------------- src/main/flight/pid.h | 7 +++--- src/main/io/osd.c | 18 +++++++-------- 3 files changed, 41 insertions(+), 38 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 3049fbb822..d42d121919 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -161,7 +161,7 @@ static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn; static EXTENDED_FASTRAM bool levelingEnabled = false; #define FIXED_WING_LEVEL_TRIM_MAX_ANGLE 10.0f // Max angle auto trimming can demand -#define FIXED_WING_LEVEL_TRIM_DIVIDER 500.0f +#define FIXED_WING_LEVEL_TRIM_DIVIDER 50.0f #define FIXED_WING_LEVEL_TRIM_MULTIPLIER 1.0f / FIXED_WING_LEVEL_TRIM_DIVIDER #define FIXED_WING_LEVEL_TRIM_CONTROLLER_LIMIT FIXED_WING_LEVEL_TRIM_DIVIDER * FIXED_WING_LEVEL_TRIM_MAX_ANGLE @@ -1243,7 +1243,7 @@ void pidInit(void) navPidInit( &fixedWingLevelTrimController, 0.0f, - (float)pidProfile()->fixedWingLevelTrimGain / 100000.0f, + (float)pidProfile()->fixedWingLevelTrimGain / 50.0f, 0.0f, 0.0f, 2.0f, @@ -1255,47 +1255,51 @@ void pidInit(void) const pidBank_t * pidBank(void) { return usedPidControllerType == PID_TYPE_PIFF ? &pidProfile()->bank_fw : &pidProfile()->bank_mc; } + pidBank_t * pidBankMutable(void) { return usedPidControllerType == PID_TYPE_PIFF ? &pidProfileMutable()->bank_fw : &pidProfileMutable()->bank_mc; } +bool isFixedWingLevelTrimActive(void) +{ + return IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) && !areSticksDeflected() && + (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && !FLIGHT_MODE(SOARING_MODE) && + !navigationIsControllingAltitude(); +} + void updateFixedWingLevelTrim(timeUs_t currentTimeUs) { if (!STATE(AIRPLANE)) { return; } - static timeUs_t previousUpdateTimeUs; - static bool previousArmingState; - const float dT = US2S(currentTimeUs - previousUpdateTimeUs); + static bool previousArmingState = false; - /* - * On every ARM reset the controller - */ - if (ARMING_FLAG(ARMED) && !previousArmingState) { - navPidReset(&fixedWingLevelTrimController); - } - - /* - * On disarm update the default value - */ - if (!ARMING_FLAG(ARMED) && previousArmingState) { + if (ARMING_FLAG(ARMED)) { + if (!previousArmingState) { // On every ARM reset the controller + navPidReset(&fixedWingLevelTrimController); + } + } else if (previousArmingState) { // On disarm update the default value pidProfileMutable()->fixedWingLevelTrim = constrainf(fixedWingLevelTrim, -FIXED_WING_LEVEL_TRIM_MAX_ANGLE, FIXED_WING_LEVEL_TRIM_MAX_ANGLE); } + previousArmingState = ARMING_FLAG(ARMED); + + // return if not active or disarmed + if (!IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) || !ARMING_FLAG(ARMED)) { + return; + } + + static timeUs_t previousUpdateTimeUs; + const float dT = US2S(currentTimeUs - previousUpdateTimeUs); + previousUpdateTimeUs = currentTimeUs; /* * Prepare flags for the PID controller */ pidControllerFlags_e flags = PID_LIMIT_INTEGRATOR; - //Iterm should freeze when sticks are deflected - if ( - !IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) || - areSticksDeflected() || - (!FLIGHT_MODE(ANGLE_MODE) && !FLIGHT_MODE(HORIZON_MODE) && !FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) || - FLIGHT_MODE(SOARING_MODE) || - navigationIsControllingAltitude() - ) { + // Iterm should freeze when conditions for setting level trim aren't met + if (!isFixedWingLevelTrimActive()) { flags |= PID_FREEZE_INTEGRATOR; } @@ -1313,8 +1317,6 @@ void updateFixedWingLevelTrim(timeUs_t currentTimeUs) DEBUG_SET(DEBUG_AUTOLEVEL, 4, output); fixedWingLevelTrim = pidProfile()->fixedWingLevelTrim + (output * FIXED_WING_LEVEL_TRIM_MULTIPLIER); - - previousArmingState = !!ARMING_FLAG(ARMED); } float getFixedWingLevelTrim(void) diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index de0e3126b7..b4441b8683 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -106,8 +106,8 @@ typedef struct pidProfile_s { pidBank_t bank_mc; uint8_t dterm_lpf_type; // Dterm LPF type: PT1, BIQUAD - uint16_t dterm_lpf_hz; - + uint16_t dterm_lpf_hz; + uint8_t yaw_lpf_hz; uint8_t heading_hold_rate_limit; // Maximum rotation rate HEADING_HOLD mode can feed to yaw rate PID controller @@ -129,7 +129,7 @@ typedef struct pidProfile_s { float fixedWingCoordinatedPitchGain; // This is the gain of the pitch rate to keep the pitch angle constant during coordinated turns. float fixedWingItermLimitOnStickPosition; //Do not allow Iterm to grow when stick position is above this point uint16_t fixedWingYawItermBankFreeze; // Freeze yaw Iterm when bank angle is more than this many degrees - + float navVelXyDTermLpfHz; uint8_t navVelXyDtermAttenuation; // VEL_XY dynamic Dterm scale: Dterm will be attenuatedby this value (in percent) when UAV is traveling with more than navVelXyDtermAttenuationStart percents of max velocity uint8_t navVelXyDtermAttenuationStart; // VEL_XY dynamic Dterm scale: Dterm attenuation will begin at this percent of max velocity @@ -221,5 +221,6 @@ void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRa pidType_e pidIndexGetType(pidIndex_e pidIndex); +bool isFixedWingLevelTrimActive(void); void updateFixedWingLevelTrim(timeUs_t currentTimeUs); float getFixedWingLevelTrim(void); diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 24a6bc6cb2..2d176be0af 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1911,7 +1911,7 @@ static bool osdDrawSingleElement(uint8_t item) osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); break; - case OSD_ODOMETER: + case OSD_ODOMETER: { displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_ODOMETER); uint32_t odometerDist = (uint32_t)(getTotalTravelDistance() / 100); @@ -3955,7 +3955,7 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) /** * @brief Draws the INAV and/or pilot logos on the display - * + * * @param singular If true, only one logo will be drawn. If false, both logos will be drawn, separated by osdConfig()->inav_to_pilot_logo_spacing characters * @param row The row number to start drawing the logos. If not singular, both logos are drawn on the same rows. * @return uint8_t The row number after the logo(s). @@ -4005,7 +4005,7 @@ uint8_t drawLogos(bool singular, uint8_t row) { } else { logo_x = logoColOffset + SYM_LOGO_WIDTH + logoSpacing; } - + for (uint8_t lRow = 0; lRow < SYM_LOGO_HEIGHT; lRow++) { for (uint8_t lCol = 0; lCol < SYM_LOGO_WIDTH; lCol++) { displayWriteChar(osdDisplayPort, logo_x + lCol, logoRow, logo_c++); @@ -4129,7 +4129,7 @@ static void osdCompleteAsyncInitialization(void) if (fontHasMetadata && metadata.charCount > 256) { hasExtendedFont = true; - + y = drawLogos(false, y); y++; } else if (!fontHasMetadata) { @@ -4568,12 +4568,12 @@ static void osdShowHDArmScreen(void) displayWrite(osdDisplayPort, col, armScreenRow, buf); displayWrite(osdDisplayPort, col + strlen(buf) + gap, armScreenRow++, buf2); - + int digits = osdConfig()->plus_code_digits; olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); } - + #if defined (USE_SAFE_HOME) if (posControl.safehomeState.distance) { // safehome found during arming if (navConfig()->general.flags.safehome_usage_mode == SAFEHOME_USAGE_OFF) { @@ -4653,7 +4653,7 @@ static void osdShowSDArmScreen(void) uint8_t gpsStartCol = (osdDisplayPort->cols - (strlen(buf) + strlen(buf2) + 2)) / 2; displayWrite(osdDisplayPort, gpsStartCol, armScreenRow, buf); displayWrite(osdDisplayPort, gpsStartCol + strlen(buf) + 2, armScreenRow++, buf2); - + int digits = osdConfig()->plus_code_digits; olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, armScreenRow++, buf); @@ -5156,8 +5156,8 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTUNE_ACRO); } } - if (IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE) || (navigationRequiresAngleMode() && !navigationIsControllingAltitude()))) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOLEVEL); + if (isFixedWingLevelTrimActive()) { + messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOLEVEL); } if (FLIGHT_MODE(HEADFREE_MODE)) { messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_HEADFREE); From 235feba6f837b402897543a82b7da955b49013dd Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 23 Oct 2023 13:19:58 +0200 Subject: [PATCH 150/175] Make it easier to include all baro drivers to target Some fc don't include a baro, in that case we should include all drivers in the target, so the user has flexibility in choseing an external baro, without having to create a custom target. Downside is firmware size for f411/f722 devices. --- src/main/target/IFLIGHTF7_TWING/target.h | 4 ++-- src/main/target/common.h | 2 +- src/main/target/common_post.h | 13 +++++++++++++ 3 files changed, 16 insertions(+), 3 deletions(-) diff --git a/src/main/target/IFLIGHTF7_TWING/target.h b/src/main/target/IFLIGHTF7_TWING/target.h index 7bfbb0bbc5..4831539dee 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.h +++ b/src/main/target/IFLIGHTF7_TWING/target.h @@ -56,8 +56,8 @@ #define USE_BARO #define BARO_I2C_BUS BUS_I2C2 -#define USE_BARO_BMP280 -#define USE_BARO_DPS310 +#define USE_BARO_ALL + #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 diff --git a/src/main/target/common.h b/src/main/target/common.h index 469750c362..f377669b5f 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -193,4 +193,4 @@ #define MAX_MIXER_PROFILE_COUNT 1 #endif -#define USE_EZ_TUNE \ No newline at end of file +#define USE_EZ_TUNE diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index ec7cc83664..de55bea9ea 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -46,6 +46,19 @@ extern uint8_t __config_end; #if defined(USE_BARO) #define USE_BARO_MSP + +#if defined(USE_BARO_ALL) +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_BARO_BMP085 +#define USE_BARO_BMP388 +#define USE_BARO_LPS25H +#define USE_BARO_MS5607 +#define USE_BARO_MS5611 +//#define USE_BARO_SPI_BMP280 +#define USE_BARO_SPL06 +#endif + #endif #ifdef USE_ESC_SENSOR From 5cc10f859efe35669aa35f032794f92722ee6446 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 23 Oct 2023 13:23:01 +0200 Subject: [PATCH 151/175] Add another fc reported by users --- src/main/target/DALRCF722DUAL/target.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/main/target/DALRCF722DUAL/target.h b/src/main/target/DALRCF722DUAL/target.h index b7d2b4a0d1..ca2f1a9080 100644 --- a/src/main/target/DALRCF722DUAL/target.h +++ b/src/main/target/DALRCF722DUAL/target.h @@ -63,9 +63,7 @@ #define USE_BARO #define BARO_I2C_BUS BUS_I2C1 -#define USE_BARO_BMP280 -#define USE_BARO_MS5611 -#define USE_BARO_BMP085 +#define USE_BARO_ALL #define USE_MAG From 205cd1c20e6e713d3394276643892ec516405715 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 23 Oct 2023 13:26:59 +0200 Subject: [PATCH 152/175] Sort baros --- src/main/target/common_post.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index de55bea9ea..35f2ba31c3 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -48,10 +48,10 @@ extern uint8_t __config_end; #define USE_BARO_MSP #if defined(USE_BARO_ALL) -#define USE_BARO_BMP280 -#define USE_BARO_DPS310 #define USE_BARO_BMP085 +#define USE_BARO_BMP280 #define USE_BARO_BMP388 +#define USE_BARO_DPS310 #define USE_BARO_LPS25H #define USE_BARO_MS5607 #define USE_BARO_MS5611 From 6129f04d1603ba785aa2e3633da229af94d12894 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Mon, 23 Oct 2023 12:37:04 +0100 Subject: [PATCH 153/175] Update from master --- src/main/io/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 0b42f22914..a5c245c187 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1771,7 +1771,7 @@ static bool osdDrawSingleElement(uint8_t item) } else #endif { - if (osdFormatCentiNumber(buff, getBatteryRemainingCapacity() * 100, 1000, 0, (mah_digits - 2), mah_digits), false) { + if (osdFormatCentiNumber(buff, getBatteryRemainingCapacity() * 100, 1000, 0, (mah_digits - 2), mah_digits, false)) { // Shown in Ah buff[mah_digits] = SYM_AH; } else { From b6b5a98de39d3be135fa035be3a8b4e82a2e1f72 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Mon, 23 Oct 2023 19:00:55 +0100 Subject: [PATCH 154/175] fix delayed save + exclude manual mode --- src/main/fc/fc_core.c | 5 ++++- src/main/flight/pid.c | 3 ++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 7b22770575..1e28aa0b83 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -873,7 +873,10 @@ void taskMainPidLoop(timeUs_t currentTimeUs) if (!ARMING_FLAG(ARMED)) { armTime = 0; - processDelayedSave(); + // Delay saving for 0.5s to allow other functions to process save actions on disarm + if (currentTimeUs - lastDisarmTimeUs > USECS_PER_SEC / 2) { + processDelayedSave(); + } } #if defined(SITL_BUILD) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index d42d121919..fd6777ac82 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -1263,7 +1263,8 @@ pidBank_t * pidBankMutable(void) { bool isFixedWingLevelTrimActive(void) { return IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) && !areSticksDeflected() && - (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && !FLIGHT_MODE(SOARING_MODE) && + (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && + !FLIGHT_MODE(SOARING_MODE) && !FLIGHT_MODE(MANUAL_MODE) && !navigationIsControllingAltitude(); } From e18983a71e6c7f8320da2b7a79d7250afd536207 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 24 Oct 2023 11:26:34 +0200 Subject: [PATCH 155/175] Re-enabel baro. max chip seems to cause issues --- src/main/target/BETAFPVF435/target.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/BETAFPVF435/target.h b/src/main/target/BETAFPVF435/target.h index c8e17bd7c4..e9d7ea7e75 100644 --- a/src/main/target/BETAFPVF435/target.h +++ b/src/main/target/BETAFPVF435/target.h @@ -116,7 +116,7 @@ #define MAX7456_CS_PIN PA15 #endif -#if 0 +#if 1 // I2C #define USE_I2C #define USE_I2C_DEVICE_2 @@ -198,4 +198,4 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE //#define USE_DSHOT //#define USE_ESC_SENSOR -#define USE_ESCSERIAL \ No newline at end of file +#define USE_ESCSERIAL From 9e0488565492446d56f78778c52cae99ac27c1d9 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 24 Oct 2023 11:31:10 +0200 Subject: [PATCH 156/175] Remove #if --- src/main/target/BETAFPVF435/target.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/target/BETAFPVF435/target.h b/src/main/target/BETAFPVF435/target.h index e9d7ea7e75..2376afbcfe 100644 --- a/src/main/target/BETAFPVF435/target.h +++ b/src/main/target/BETAFPVF435/target.h @@ -116,14 +116,12 @@ #define MAX7456_CS_PIN PA15 #endif -#if 1 // I2C #define USE_I2C #define USE_I2C_DEVICE_2 #define I2C2_SCL PB10 // SCL pad #define I2C2_SDA PB11 // SDA pad #define USE_I2C_PULLUP -#endif #define USE_BARO #define BARO_I2C_BUS BUS_I2C2 From 01fcebdfefc2ac0c1a2a627995edc12fa07d681b Mon Sep 17 00:00:00 2001 From: shota Date: Tue, 24 Oct 2023 19:17:49 +0900 Subject: [PATCH 157/175] fix conflict --- src/main/msp/msp_protocol_v2_inav.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index 9b4abbdbe4..4556c86a51 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -95,4 +95,4 @@ #define MSP2_INAV_RATE_DYNAMICS 0x2060 #define MSP2_INAV_SET_RATE_DYNAMICS 0x2061 -#define MSP2_INAV_SELECT_MIXER_PROFILE 0x2070 +#define MSP2_INAV_SELECT_MIXER_PROFILE 0x2080 From 2e1f8a772f923741185d06a6bc4b21c05ceddce9 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 24 Oct 2023 16:01:38 +0200 Subject: [PATCH 158/175] Add USE_MAG_ALL and modify all targets to use it --- src/main/target/AIKONF4/target.h | 9 +------ src/main/target/AIRBOTF4/target.h | 11 ++------ src/main/target/AIRBOTF7/target.h | 7 +----- src/main/target/ALIENFLIGHTF4/target.h | 8 +----- src/main/target/ALIENFLIGHTNGF7/target.h | 9 +------ src/main/target/ANYFC/target.h | 7 +----- src/main/target/ANYFCF7/target.h | 7 +----- src/main/target/ANYFCM7/target.h | 7 +----- src/main/target/AOCODARCF405AIO/target.h | 8 +----- src/main/target/AOCODARCF4V2/target.h | 8 +----- src/main/target/AOCODARCF722AIO/target.h | 7 +----- src/main/target/AOCODARCF7DUAL/target.h | 8 +----- src/main/target/AOCODARCF7MINI/target.h | 8 +----- src/main/target/AOCODARCH7DUAL/target.h | 8 +----- src/main/target/ASGARD32F7/target.h | 6 +---- src/main/target/ATOMRCF405NAVI/target.h | 7 +----- src/main/target/AXISFLYINGF7PRO/target.h | 6 +---- src/main/target/BEEROTORF4/target.h | 9 +------ src/main/target/BETAFLIGHTF4/target.h | 9 +------ src/main/target/BETAFPVF722/target.h | 7 +----- src/main/target/BLACKPILL_F411/target.h | 8 +----- src/main/target/BLUEJAYF4/target.h | 7 +----- src/main/target/COLIBRI/target.h | 7 +----- src/main/target/DALRCF405/target.h | 8 +----- src/main/target/DALRCF722DUAL/target.h | 7 +----- src/main/target/F4BY/target.h | 7 +----- src/main/target/FIREWORKSV2/target.h | 6 +---- src/main/target/FISHDRONEF4/target.h | 8 +----- src/main/target/FLYCOLORF7MINI/target.h | 8 +----- src/main/target/FLYWOOF405PRO/target.h | 8 +----- src/main/target/FLYWOOF411/target.h | 7 +----- src/main/target/FLYWOOF745/target.h | 7 +----- src/main/target/FLYWOOF7DUAL/target.h | 6 +---- src/main/target/FOXEERF405/target.h | 6 +---- src/main/target/FOXEERF722DUAL/target.h | 6 +---- src/main/target/FOXEERF722V4/target.h | 6 +---- src/main/target/FOXEERF745AIO/target.h | 3 +-- src/main/target/FOXEERH743/target.h | 10 ++------ src/main/target/FRSKYPILOT/target.h | 7 +----- src/main/target/FRSKY_ROVERF7/target.h | 7 +----- src/main/target/FURYF4OSD/target.h | 9 +------ src/main/target/GEPRCF405/target.h | 7 +----- src/main/target/GEPRCF722/target.h | 7 +----- src/main/target/GEPRCF722_BT_HD/target.h | 7 +----- src/main/target/GEPRC_F722_AIO/target.h | 7 +----- src/main/target/HAKRCF405D/target.h | 6 +---- src/main/target/HAKRCF405V2/target.h | 6 +---- src/main/target/HAKRCF411D/target.h | 6 +---- src/main/target/HAKRCF722V2/target.h | 6 +---- src/main/target/HAKRCKD722/target.h | 7 +----- src/main/target/HGLRCF722/target.h | 8 +----- src/main/target/IFLIGHTF4_SUCCEXD/target.h | 8 +----- src/main/target/IFLIGHTF4_TWING/target.h | 7 +----- src/main/target/IFLIGHTF7_TWING/target.h | 7 +----- src/main/target/IFLIGHT_BLITZ_F722/target.h | 8 +----- src/main/target/IFLIGHT_BLITZ_F7_AIO/target.h | 7 +----- src/main/target/IFLIGHT_BLITZ_F7_PRO/target.h | 7 +----- src/main/target/IFLIGHT_H743_AIO_V2/target.h | 8 +----- src/main/target/IFLIGHT_JBF7PRO/target.h | 7 +----- src/main/target/JHEH7AIO/target.h | 10 ++------ src/main/target/KAKUTEF4/target.h | 7 +----- src/main/target/KAKUTEF7/target.h | 8 +----- src/main/target/KAKUTEF7MINIV3/target.h | 6 +---- src/main/target/KAKUTEH7/target.h | 8 +----- src/main/target/KAKUTEH7WING/target.h | 8 +----- src/main/target/KROOZX/target.h | 7 +----- src/main/target/MAMBAF405US/target.h | 9 +------ src/main/target/MAMBAF405_2022A/target.h | 11 ++------ src/main/target/MAMBAF722/target.h | 7 +----- src/main/target/MAMBAF722_2022A/target.h | 8 ++---- src/main/target/MAMBAF722_WING/target.h | 9 ++----- src/main/target/MAMBAF722_X8/target.h | 7 +----- src/main/target/MAMBAH743/target.h | 10 ++------ src/main/target/MATEKF405/target.h | 9 +------ src/main/target/MATEKF405CAN/target.h | 8 +----- src/main/target/MATEKF405SE/target.h | 8 +----- src/main/target/MATEKF405TE/target.h | 7 +----- src/main/target/MATEKF411/target.h | 6 +---- src/main/target/MATEKF411SE/target.h | 8 +----- src/main/target/MATEKF411TE/target.h | 8 +----- src/main/target/MATEKF722/target.h | 9 ++----- src/main/target/MATEKF722PX/target.h | 8 +----- src/main/target/MATEKF722SE/target.h | 8 +----- src/main/target/MATEKF765/target.h | 7 +----- src/main/target/MATEKH743/target.h | 7 +----- src/main/target/NEUTRONRCF435MINI/target.h | 3 +-- src/main/target/NEUTRONRCF435SE/target.h | 5 ++-- src/main/target/NEUTRONRCF435WING/target.h | 3 +-- src/main/target/NEUTRONRCH7BT/target.h | 7 +----- src/main/target/OMNIBUSF4/target.h | 8 +----- src/main/target/OMNIBUSF7/target.h | 7 +----- src/main/target/OMNIBUSF7NXT/target.h | 6 +---- src/main/target/PIXRACER/target.h | 8 +----- src/main/target/REVO/target.h | 7 +----- src/main/target/RUSH_BLADE_F7/target.h | 8 +----- src/main/target/SAGEATF4/target.h | 3 +-- src/main/target/SKYSTARSF405HD/target.h | 9 +------ src/main/target/SKYSTARSF722HD/target.h | 9 +------ src/main/target/SKYSTARSH743HD/target.h | 9 ++----- src/main/target/SPARKY2/target.h | 9 ++----- src/main/target/SPEEDYBEEF4/target.h | 6 +---- src/main/target/SPEEDYBEEF405MINI/target.h | 10 ++------ src/main/target/SPEEDYBEEF405V3/target.h | 7 +----- src/main/target/SPEEDYBEEF405V4/target.h | 9 +------ src/main/target/SPEEDYBEEF405WING/target.h | 11 ++------ src/main/target/SPEEDYBEEF7/target.h | 7 +----- src/main/target/SPEEDYBEEF745AIO/target.h | 7 +----- src/main/target/SPEEDYBEEF7MINI/target.h | 8 +----- src/main/target/SPEEDYBEEF7V2/target.h | 4 +-- src/main/target/SPEEDYBEEF7V3/target.h | 7 +----- src/main/target/SPRACINGF4EVO/target.h | 8 +----- src/main/target/SPRACINGF7DUAL/target.h | 7 +----- src/main/target/TMOTORF7/target.h | 10 +------- src/main/target/TMOTORF7V2/target.h | 7 +----- src/main/target/YUPIF4/target.h | 3 +-- src/main/target/YUPIF7/target.h | 3 +-- src/main/target/ZEEZF7/target.h | 8 +----- src/main/target/common_post.h | 25 +++++++++++++++++++ 118 files changed, 155 insertions(+), 731 deletions(-) diff --git a/src/main/target/AIKONF4/target.h b/src/main/target/AIKONF4/target.h index 22ee824e5f..cd057f8b87 100644 --- a/src/main/target/AIKONF4/target.h +++ b/src/main/target/AIKONF4/target.h @@ -86,14 +86,7 @@ #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS #define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS diff --git a/src/main/target/AIRBOTF4/target.h b/src/main/target/AIRBOTF4/target.h index db9c2ba7e1..9d5b0eef8b 100644 --- a/src/main/target/AIRBOTF4/target.h +++ b/src/main/target/AIRBOTF4/target.h @@ -41,14 +41,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_MAG3110 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define USE_BARO #define BARO_I2C_BUS BUS_I2C2 @@ -139,4 +132,4 @@ #define TARGET_IO_PORTD 0xffff #define USE_DSHOT -#define USE_ESC_SENSOR \ No newline at end of file +#define USE_ESC_SENSOR diff --git a/src/main/target/AIRBOTF7/target.h b/src/main/target/AIRBOTF7/target.h index d77529ed39..affa3ed435 100644 --- a/src/main/target/AIRBOTF7/target.h +++ b/src/main/target/AIRBOTF7/target.h @@ -70,12 +70,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index 5527b45a1d..52cd4cf4a9 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -46,13 +46,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_MPU9250 -#define USE_MAG_HMC5883 -#define USE_MAG_MAG3110 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/ALIENFLIGHTNGF7/target.h b/src/main/target/ALIENFLIGHTNGF7/target.h index 5971f3d848..1c8e0f901e 100644 --- a/src/main/target/ALIENFLIGHTNGF7/target.h +++ b/src/main/target/ALIENFLIGHTNGF7/target.h @@ -44,14 +44,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8963 -#define USE_MAG_MPU9250 -#define USE_MAG_HMC5883 -#define USE_MAG_MAG3110 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define AK8963_CS_PIN PC15 #define AK8963_SPI_BUS BUS_SPI3 diff --git a/src/main/target/ANYFC/target.h b/src/main/target/ANYFC/target.h index 1bda97600d..4e1abcc0d0 100644 --- a/src/main/target/ANYFC/target.h +++ b/src/main/target/ANYFC/target.h @@ -35,12 +35,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_MAG3110 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/ANYFCF7/target.h b/src/main/target/ANYFCF7/target.h index b09890a7ef..179a7211f0 100644 --- a/src/main/target/ANYFCF7/target.h +++ b/src/main/target/ANYFCF7/target.h @@ -35,12 +35,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/ANYFCM7/target.h b/src/main/target/ANYFCM7/target.h index e058ed7a28..ce6cb0e63a 100644 --- a/src/main/target/ANYFCM7/target.h +++ b/src/main/target/ANYFCM7/target.h @@ -35,12 +35,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/AOCODARCF405AIO/target.h b/src/main/target/AOCODARCF405AIO/target.h index 859caa51f4..6a95a867cc 100644 --- a/src/main/target/AOCODARCF405AIO/target.h +++ b/src/main/target/AOCODARCF405AIO/target.h @@ -98,13 +98,7 @@ // Mag #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_MLX90393 +#define USE_MAG_ALL /*** Onboard Flash ***/ #define USE_SPI_DEVICE_3 diff --git a/src/main/target/AOCODARCF4V2/target.h b/src/main/target/AOCODARCF4V2/target.h index ed524edc90..104ac193af 100644 --- a/src/main/target/AOCODARCF4V2/target.h +++ b/src/main/target/AOCODARCF4V2/target.h @@ -60,13 +60,7 @@ //*********** Magnetometer / Compass ************* #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS - -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 +#define USE_MAG_ALL // ******* SERIAL ******** #define USE_VCP diff --git a/src/main/target/AOCODARCF722AIO/target.h b/src/main/target/AOCODARCF722AIO/target.h index fd2a559b93..409bc03bfd 100644 --- a/src/main/target/AOCODARCF722AIO/target.h +++ b/src/main/target/AOCODARCF722AIO/target.h @@ -101,12 +101,7 @@ // Mag #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL /*** Onboard Flash ***/ #define USE_SPI_DEVICE_3 diff --git a/src/main/target/AOCODARCF7DUAL/target.h b/src/main/target/AOCODARCF7DUAL/target.h index 71d38f174d..5d4b0fda52 100644 --- a/src/main/target/AOCODARCF7DUAL/target.h +++ b/src/main/target/AOCODARCF7DUAL/target.h @@ -67,13 +67,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/AOCODARCF7MINI/target.h b/src/main/target/AOCODARCF7MINI/target.h index ff52565f58..9f628963d8 100644 --- a/src/main/target/AOCODARCF7MINI/target.h +++ b/src/main/target/AOCODARCF7MINI/target.h @@ -64,13 +64,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/AOCODARCH7DUAL/target.h b/src/main/target/AOCODARCH7DUAL/target.h index 58d9c4893e..1c12f198a0 100644 --- a/src/main/target/AOCODARCH7DUAL/target.h +++ b/src/main/target/AOCODARCH7DUAL/target.h @@ -116,13 +116,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_VCM5883 +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/ASGARD32F7/target.h b/src/main/target/ASGARD32F7/target.h index ddfc11f15b..0c5084db5f 100644 --- a/src/main/target/ASGARD32F7/target.h +++ b/src/main/target/ASGARD32F7/target.h @@ -42,11 +42,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/ATOMRCF405NAVI/target.h b/src/main/target/ATOMRCF405NAVI/target.h index b8ae0ab6a3..5e9c9b1bd4 100644 --- a/src/main/target/ATOMRCF405NAVI/target.h +++ b/src/main/target/ATOMRCF405NAVI/target.h @@ -74,12 +74,7 @@ */ #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS - -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL /* * Barometer diff --git a/src/main/target/AXISFLYINGF7PRO/target.h b/src/main/target/AXISFLYINGF7PRO/target.h index 4a4b95657e..39c94e47e9 100644 --- a/src/main/target/AXISFLYINGF7PRO/target.h +++ b/src/main/target/AXISFLYINGF7PRO/target.h @@ -134,11 +134,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/BEEROTORF4/target.h b/src/main/target/BEEROTORF4/target.h index 4ebde46875..1ff901b870 100644 --- a/src/main/target/BEEROTORF4/target.h +++ b/src/main/target/BEEROTORF4/target.h @@ -37,14 +37,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/BETAFLIGHTF4/target.h b/src/main/target/BETAFLIGHTF4/target.h index 13e7dd3265..05f3587298 100755 --- a/src/main/target/BETAFLIGHTF4/target.h +++ b/src/main/target/BETAFLIGHTF4/target.h @@ -112,14 +112,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/BETAFPVF722/target.h b/src/main/target/BETAFPVF722/target.h index 9d1258385d..cab6d2ff14 100755 --- a/src/main/target/BETAFPVF722/target.h +++ b/src/main/target/BETAFPVF722/target.h @@ -70,12 +70,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 #define PITOT_I2C_BUS BUS_I2C2 diff --git a/src/main/target/BLACKPILL_F411/target.h b/src/main/target/BLACKPILL_F411/target.h index f425de423e..b6f937bc9b 100644 --- a/src/main/target/BLACKPILL_F411/target.h +++ b/src/main/target/BLACKPILL_F411/target.h @@ -113,13 +113,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_AK8975 +#define USE_MAG_ALL #define PITOT_I2C_BUS BUS_I2C1 #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 689dba9282..e62120bdc8 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -41,12 +41,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/COLIBRI/target.h b/src/main/target/COLIBRI/target.h index c76b91b499..6898448809 100755 --- a/src/main/target/COLIBRI/target.h +++ b/src/main/target/COLIBRI/target.h @@ -42,12 +42,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C3 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C3 diff --git a/src/main/target/DALRCF405/target.h b/src/main/target/DALRCF405/target.h index 449be6a715..6a9a5494ff 100644 --- a/src/main/target/DALRCF405/target.h +++ b/src/main/target/DALRCF405/target.h @@ -82,13 +82,7 @@ #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/DALRCF722DUAL/target.h b/src/main/target/DALRCF722DUAL/target.h index b7d2b4a0d1..a19880da8b 100644 --- a/src/main/target/DALRCF722DUAL/target.h +++ b/src/main/target/DALRCF722DUAL/target.h @@ -70,12 +70,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h index f72f78f20e..21f91c1d49 100644 --- a/src/main/target/F4BY/target.h +++ b/src/main/target/F4BY/target.h @@ -41,12 +41,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/FIREWORKSV2/target.h b/src/main/target/FIREWORKSV2/target.h index ce8831f4a9..a2f69ae49d 100644 --- a/src/main/target/FIREWORKSV2/target.h +++ b/src/main/target/FIREWORKSV2/target.h @@ -87,11 +87,7 @@ #else #define MAG_I2C_BUS BUS_I2C2 #endif -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #if defined(OMNIBUSF4V6) #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/FISHDRONEF4/target.h b/src/main/target/FISHDRONEF4/target.h index 741a8aded8..10e325202e 100644 --- a/src/main/target/FISHDRONEF4/target.h +++ b/src/main/target/FISHDRONEF4/target.h @@ -47,13 +47,7 @@ // *************** Compass ***************************** #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_MPU9250 -#define USE_MAG_MAG3110 -#define USE_MAG_HMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_QMC5883 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // *************** Temperature sensor ***************** #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/FLYCOLORF7MINI/target.h b/src/main/target/FLYCOLORF7MINI/target.h index ece951b3c4..938913d648 100644 --- a/src/main/target/FLYCOLORF7MINI/target.h +++ b/src/main/target/FLYCOLORF7MINI/target.h @@ -58,13 +58,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 #define PITOT_I2C_BUS BUS_I2C2 diff --git a/src/main/target/FLYWOOF405PRO/target.h b/src/main/target/FLYWOOF405PRO/target.h index 39a3339c10..14b5e9e03c 100644 --- a/src/main/target/FLYWOOF405PRO/target.h +++ b/src/main/target/FLYWOOF405PRO/target.h @@ -68,13 +68,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define USE_RANGEFINDER #define USE_RANGEFINDER_HCSR04_I2C diff --git a/src/main/target/FLYWOOF411/target.h b/src/main/target/FLYWOOF411/target.h index 286b986373..ed263d5ee3 100644 --- a/src/main/target/FLYWOOF411/target.h +++ b/src/main/target/FLYWOOF411/target.h @@ -70,12 +70,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // *************** SPI OSD ***************************** #define USE_MAX7456 diff --git a/src/main/target/FLYWOOF745/target.h b/src/main/target/FLYWOOF745/target.h index e0e012aa60..3b57ccc4fa 100644 --- a/src/main/target/FLYWOOF745/target.h +++ b/src/main/target/FLYWOOF745/target.h @@ -143,12 +143,7 @@ #define BARO_I2C_BUS BUS_I2C1 #define USE_MAG -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_MAG3110 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define USE_ADC #define ADC_CHANNEL_1_PIN PC2 diff --git a/src/main/target/FLYWOOF7DUAL/target.h b/src/main/target/FLYWOOF7DUAL/target.h index 58630efe7e..1a23650521 100644 --- a/src/main/target/FLYWOOF7DUAL/target.h +++ b/src/main/target/FLYWOOF7DUAL/target.h @@ -109,11 +109,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL /*** ADC ***/ #define USE_ADC diff --git a/src/main/target/FOXEERF405/target.h b/src/main/target/FOXEERF405/target.h index 8ee53eeb70..7f97e832b9 100644 --- a/src/main/target/FOXEERF405/target.h +++ b/src/main/target/FOXEERF405/target.h @@ -104,11 +104,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL /*** ADC ***/ #define USE_ADC diff --git a/src/main/target/FOXEERF722DUAL/target.h b/src/main/target/FOXEERF722DUAL/target.h index 7698fe1abf..250a88a307 100644 --- a/src/main/target/FOXEERF722DUAL/target.h +++ b/src/main/target/FOXEERF722DUAL/target.h @@ -112,11 +112,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL /*** ADC ***/ #define USE_ADC diff --git a/src/main/target/FOXEERF722V4/target.h b/src/main/target/FOXEERF722V4/target.h index 3c6ab0b2a7..4d92f85cde 100644 --- a/src/main/target/FOXEERF722V4/target.h +++ b/src/main/target/FOXEERF722V4/target.h @@ -124,11 +124,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define BNO055_I2C_BUS BUS_I2C1 diff --git a/src/main/target/FOXEERF745AIO/target.h b/src/main/target/FOXEERF745AIO/target.h index 60666b7611..860ea18d86 100644 --- a/src/main/target/FOXEERF745AIO/target.h +++ b/src/main/target/FOXEERF745AIO/target.h @@ -112,8 +112,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 +#define USE_MAG_ALL /*** ADC ***/ #define USE_ADC diff --git a/src/main/target/FOXEERH743/target.h b/src/main/target/FOXEERH743/target.h index ffb582ea9a..f2e2f83eb4 100644 --- a/src/main/target/FOXEERH743/target.h +++ b/src/main/target/FOXEERH743/target.h @@ -83,13 +83,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_VCM5883 +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 @@ -162,4 +156,4 @@ #define MAX_PWM_OUTPUT_PORTS 8 #define USE_DSHOT -#define USE_ESC_SENSOR \ No newline at end of file +#define USE_ESC_SENSOR diff --git a/src/main/target/FRSKYPILOT/target.h b/src/main/target/FRSKYPILOT/target.h index d8100f2610..19944ac24a 100644 --- a/src/main/target/FRSKYPILOT/target.h +++ b/src/main/target/FRSKYPILOT/target.h @@ -103,12 +103,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C3 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C3 #define PITOT_I2C_BUS BUS_I2C3 diff --git a/src/main/target/FRSKY_ROVERF7/target.h b/src/main/target/FRSKY_ROVERF7/target.h index ea1c62e0d1..ff9672c742 100755 --- a/src/main/target/FRSKY_ROVERF7/target.h +++ b/src/main/target/FRSKY_ROVERF7/target.h @@ -53,12 +53,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/FURYF4OSD/target.h b/src/main/target/FURYF4OSD/target.h index 46eec2422f..79c26d178a 100644 --- a/src/main/target/FURYF4OSD/target.h +++ b/src/main/target/FURYF4OSD/target.h @@ -119,14 +119,7 @@ #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS diff --git a/src/main/target/GEPRCF405/target.h b/src/main/target/GEPRCF405/target.h index 3a628ffe59..7f641643e8 100644 --- a/src/main/target/GEPRCF405/target.h +++ b/src/main/target/GEPRCF405/target.h @@ -70,12 +70,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/GEPRCF722/target.h b/src/main/target/GEPRCF722/target.h index bc08477c45..df7cc6d3ec 100644 --- a/src/main/target/GEPRCF722/target.h +++ b/src/main/target/GEPRCF722/target.h @@ -67,12 +67,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/GEPRCF722_BT_HD/target.h b/src/main/target/GEPRCF722_BT_HD/target.h index ca32c210c6..5494ed8300 100644 --- a/src/main/target/GEPRCF722_BT_HD/target.h +++ b/src/main/target/GEPRCF722_BT_HD/target.h @@ -65,12 +65,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/GEPRC_F722_AIO/target.h b/src/main/target/GEPRC_F722_AIO/target.h index ce2ebde6a5..f7ed46bd46 100644 --- a/src/main/target/GEPRC_F722_AIO/target.h +++ b/src/main/target/GEPRC_F722_AIO/target.h @@ -65,12 +65,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/HAKRCF405D/target.h b/src/main/target/HAKRCF405D/target.h index 002fd191c3..d47ec61dc9 100644 --- a/src/main/target/HAKRCF405D/target.h +++ b/src/main/target/HAKRCF405D/target.h @@ -127,11 +127,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL /*** ADC ***/ #define USE_ADC diff --git a/src/main/target/HAKRCF405V2/target.h b/src/main/target/HAKRCF405V2/target.h index 3e7b1420d1..85cc164230 100644 --- a/src/main/target/HAKRCF405V2/target.h +++ b/src/main/target/HAKRCF405V2/target.h @@ -134,11 +134,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL /*** ADC ***/ #define USE_ADC diff --git a/src/main/target/HAKRCF411D/target.h b/src/main/target/HAKRCF411D/target.h index 96ea1a7c77..5b3a479ed1 100644 --- a/src/main/target/HAKRCF411D/target.h +++ b/src/main/target/HAKRCF411D/target.h @@ -113,11 +113,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/HAKRCF722V2/target.h b/src/main/target/HAKRCF722V2/target.h index 809f6ddb10..65325ebe41 100644 --- a/src/main/target/HAKRCF722V2/target.h +++ b/src/main/target/HAKRCF722V2/target.h @@ -137,11 +137,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/HAKRCKD722/target.h b/src/main/target/HAKRCKD722/target.h index 5b4869951d..0058b75d15 100644 --- a/src/main/target/HAKRCKD722/target.h +++ b/src/main/target/HAKRCKD722/target.h @@ -102,12 +102,7 @@ // Mag #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL /*** Onboard Flash ***/ #define USE_SPI_DEVICE_3 diff --git a/src/main/target/HGLRCF722/target.h b/src/main/target/HGLRCF722/target.h index 3cf2986f75..348f30d241 100644 --- a/src/main/target/HGLRCF722/target.h +++ b/src/main/target/HGLRCF722/target.h @@ -72,13 +72,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/IFLIGHTF4_SUCCEXD/target.h b/src/main/target/IFLIGHTF4_SUCCEXD/target.h index 2d9d7bb535..6ba059bb63 100644 --- a/src/main/target/IFLIGHTF4_SUCCEXD/target.h +++ b/src/main/target/IFLIGHTF4_SUCCEXD/target.h @@ -97,13 +97,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_AK8975 +#define USE_MAG_ALL #define PITOT_I2C_BUS BUS_I2C1 #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/IFLIGHTF4_TWING/target.h b/src/main/target/IFLIGHTF4_TWING/target.h index 77dd3992e0..e0afa9aab5 100644 --- a/src/main/target/IFLIGHTF4_TWING/target.h +++ b/src/main/target/IFLIGHTF4_TWING/target.h @@ -59,12 +59,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/IFLIGHTF7_TWING/target.h b/src/main/target/IFLIGHTF7_TWING/target.h index 7bfbb0bbc5..417dea739b 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.h +++ b/src/main/target/IFLIGHTF7_TWING/target.h @@ -61,12 +61,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/IFLIGHT_BLITZ_F722/target.h b/src/main/target/IFLIGHT_BLITZ_F722/target.h index 370cea2267..0ced96ad5f 100644 --- a/src/main/target/IFLIGHT_BLITZ_F722/target.h +++ b/src/main/target/IFLIGHT_BLITZ_F722/target.h @@ -56,13 +56,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/IFLIGHT_BLITZ_F7_AIO/target.h b/src/main/target/IFLIGHT_BLITZ_F7_AIO/target.h index c94da102b1..69ea37e535 100644 --- a/src/main/target/IFLIGHT_BLITZ_F7_AIO/target.h +++ b/src/main/target/IFLIGHT_BLITZ_F7_AIO/target.h @@ -85,12 +85,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.h b/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.h index 03e7d0e2f4..a5361a5190 100644 --- a/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.h +++ b/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.h @@ -62,12 +62,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 #define PITOT_I2C_BUS BUS_I2C2 diff --git a/src/main/target/IFLIGHT_H743_AIO_V2/target.h b/src/main/target/IFLIGHT_H743_AIO_V2/target.h index 60a235e08c..c390037668 100644 --- a/src/main/target/IFLIGHT_H743_AIO_V2/target.h +++ b/src/main/target/IFLIGHT_H743_AIO_V2/target.h @@ -66,13 +66,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 #define PITOT_I2C_BUS BUS_I2C2 diff --git a/src/main/target/IFLIGHT_JBF7PRO/target.h b/src/main/target/IFLIGHT_JBF7PRO/target.h index 8c2dfd5a76..570e1750e4 100644 --- a/src/main/target/IFLIGHT_JBF7PRO/target.h +++ b/src/main/target/IFLIGHT_JBF7PRO/target.h @@ -59,12 +59,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/JHEH7AIO/target.h b/src/main/target/JHEH7AIO/target.h index 2290b828de..00ecf856e2 100644 --- a/src/main/target/JHEH7AIO/target.h +++ b/src/main/target/JHEH7AIO/target.h @@ -55,13 +55,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 @@ -166,4 +160,4 @@ #define MAX_PWM_OUTPUT_PORTS 4 #define USE_DSHOT -#define USE_ESC_SENSOR \ No newline at end of file +#define USE_ESC_SENSOR diff --git a/src/main/target/KAKUTEF4/target.h b/src/main/target/KAKUTEF4/target.h index bf68496933..1895b4b7e7 100644 --- a/src/main/target/KAKUTEF4/target.h +++ b/src/main/target/KAKUTEF4/target.h @@ -62,12 +62,7 @@ # define USE_MAG # define MAG_I2C_BUS BUS_I2C1 -# define USE_MAG_HMC5883 -# define USE_MAG_QMC5883 -# define USE_MAG_MAG3110 -# define USE_MAG_IST8310 -# define USE_MAG_IST8308 -# define USE_MAG_LIS3MDL +# define USE_MAG_ALL # define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h index 064032b7f4..f3f4edfed4 100644 --- a/src/main/target/KAKUTEF7/target.h +++ b/src/main/target/KAKUTEF7/target.h @@ -135,13 +135,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_MAG3110 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_LIS3MDL -#define USE_MAG_MLX90393 +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/KAKUTEF7MINIV3/target.h b/src/main/target/KAKUTEF7MINIV3/target.h index c3d8983725..997cad1a97 100644 --- a/src/main/target/KAKUTEF7MINIV3/target.h +++ b/src/main/target/KAKUTEF7MINIV3/target.h @@ -116,11 +116,7 @@ */ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL /* * ADC diff --git a/src/main/target/KAKUTEH7/target.h b/src/main/target/KAKUTEH7/target.h index 388515fbbb..8f88563c02 100644 --- a/src/main/target/KAKUTEH7/target.h +++ b/src/main/target/KAKUTEH7/target.h @@ -132,13 +132,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_VCM5883 +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/KAKUTEH7WING/target.h b/src/main/target/KAKUTEH7WING/target.h index 72cf6b6806..79068b8cd8 100644 --- a/src/main/target/KAKUTEH7WING/target.h +++ b/src/main/target/KAKUTEH7WING/target.h @@ -107,13 +107,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_VCM5883 +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/KROOZX/target.h b/src/main/target/KROOZX/target.h index 9af00d2f72..ea5ee6a8e0 100755 --- a/src/main/target/KROOZX/target.h +++ b/src/main/target/KROOZX/target.h @@ -36,12 +36,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MAMBAF405US/target.h b/src/main/target/MAMBAF405US/target.h index b6b95cb12b..1b21fe60e3 100644 --- a/src/main/target/MAMBAF405US/target.h +++ b/src/main/target/MAMBAF405US/target.h @@ -74,14 +74,7 @@ //*********** Magnetometer / Compass ************* #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS - -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // ******* SERIAL ******** #define USE_VCP diff --git a/src/main/target/MAMBAF405_2022A/target.h b/src/main/target/MAMBAF405_2022A/target.h index c4c20e127f..5a24771288 100644 --- a/src/main/target/MAMBAF405_2022A/target.h +++ b/src/main/target/MAMBAF405_2022A/target.h @@ -83,14 +83,7 @@ //*********** Magnetometer / Compass ************* #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS - -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // ******* SERIAL ******** #define USE_VCP @@ -200,4 +193,4 @@ #define USE_PINIO #define USE_PINIOBOX #define PINIO1_PIN PC2 -#define PINIO2_PIN PC5 \ No newline at end of file +#define PINIO2_PIN PC5 diff --git a/src/main/target/MAMBAF722/target.h b/src/main/target/MAMBAF722/target.h index c536cc6017..20e907fa87 100644 --- a/src/main/target/MAMBAF722/target.h +++ b/src/main/target/MAMBAF722/target.h @@ -74,12 +74,7 @@ //*********** Magnetometer / Compass ************* #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS - -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // ******* SERIAL ******** #define USE_VCP diff --git a/src/main/target/MAMBAF722_2022A/target.h b/src/main/target/MAMBAF722_2022A/target.h index 0752bb368b..4ab5a75bbc 100644 --- a/src/main/target/MAMBAF722_2022A/target.h +++ b/src/main/target/MAMBAF722_2022A/target.h @@ -86,11 +86,7 @@ #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // ******* SERIAL ******** #define USE_VCP @@ -197,4 +193,4 @@ #define USE_PINIO #define USE_PINIOBOX #define PINIO1_PIN PC0 // VTX power switcher -#define PINIO2_PIN PC2 // WiFi Switcher \ No newline at end of file +#define PINIO2_PIN PC2 // WiFi Switcher diff --git a/src/main/target/MAMBAF722_WING/target.h b/src/main/target/MAMBAF722_WING/target.h index a877a74e65..654b9afdfb 100644 --- a/src/main/target/MAMBAF722_WING/target.h +++ b/src/main/target/MAMBAF722_WING/target.h @@ -55,12 +55,7 @@ //*********** Magnetometer / Compass ************* #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS - -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // ******* SERIAL ******** #define USE_VCP @@ -168,4 +163,4 @@ #define USE_PINIO #define USE_PINIOBOX #define PINIO1_PIN PC0 -#define PINIO2_PIN PC2 \ No newline at end of file +#define PINIO2_PIN PC2 diff --git a/src/main/target/MAMBAF722_X8/target.h b/src/main/target/MAMBAF722_X8/target.h index 2c8c84e9d1..1a89d3bf31 100644 --- a/src/main/target/MAMBAF722_X8/target.h +++ b/src/main/target/MAMBAF722_X8/target.h @@ -53,12 +53,7 @@ //*********** Magnetometer / Compass ************* #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS - -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // ******* SERIAL ******** #define USE_VCP diff --git a/src/main/target/MAMBAH743/target.h b/src/main/target/MAMBAH743/target.h index 27a65ded29..18070e1775 100644 --- a/src/main/target/MAMBAH743/target.h +++ b/src/main/target/MAMBAH743/target.h @@ -124,13 +124,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_VCM5883 +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 @@ -238,4 +232,4 @@ #define MAX_PWM_OUTPUT_PORTS 8 #define USE_DSHOT -#define USE_ESC_SENSOR \ No newline at end of file +#define USE_ESC_SENSOR diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index fa2af63384..667cd2b3fa 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -147,14 +147,7 @@ #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS diff --git a/src/main/target/MATEKF405CAN/target.h b/src/main/target/MATEKF405CAN/target.h index 81aa91ce99..d12b5e3e1a 100644 --- a/src/main/target/MATEKF405CAN/target.h +++ b/src/main/target/MATEKF405CAN/target.h @@ -55,13 +55,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define USE_RANGEFINDER #define RANGEFINDER_I2C_BUS BUS_I2C2 diff --git a/src/main/target/MATEKF405SE/target.h b/src/main/target/MATEKF405SE/target.h index 4c0b4b8b39..38c8f56f5d 100644 --- a/src/main/target/MATEKF405SE/target.h +++ b/src/main/target/MATEKF405SE/target.h @@ -68,13 +68,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define USE_RANGEFINDER #define USE_RANGEFINDER_US42 diff --git a/src/main/target/MATEKF405TE/target.h b/src/main/target/MATEKF405TE/target.h index acaed9daf2..fc7c1ad0ce 100644 --- a/src/main/target/MATEKF405TE/target.h +++ b/src/main/target/MATEKF405TE/target.h @@ -92,12 +92,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define USE_RANGEFINDER #define RANGEFINDER_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF411/target.h b/src/main/target/MATEKF411/target.h index 0bf0aab198..6be5949419 100755 --- a/src/main/target/MATEKF411/target.h +++ b/src/main/target/MATEKF411/target.h @@ -120,11 +120,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF411SE/target.h b/src/main/target/MATEKF411SE/target.h index abb4688457..db5652e0ca 100755 --- a/src/main/target/MATEKF411SE/target.h +++ b/src/main/target/MATEKF411SE/target.h @@ -103,13 +103,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_AK8975 +#define USE_MAG_ALL #define PITOT_I2C_BUS BUS_I2C1 #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF411TE/target.h b/src/main/target/MATEKF411TE/target.h index 7ecb2d1cb6..fd2ea8fed4 100644 --- a/src/main/target/MATEKF411TE/target.h +++ b/src/main/target/MATEKF411TE/target.h @@ -88,13 +88,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_AK8975 +#define USE_MAG_ALL #define PITOT_I2C_BUS BUS_I2C1 #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF722/target.h b/src/main/target/MATEKF722/target.h index 49cc5fac09..1908c6a5b4 100644 --- a/src/main/target/MATEKF722/target.h +++ b/src/main/target/MATEKF722/target.h @@ -56,12 +56,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 @@ -152,4 +147,4 @@ #define MAX_PWM_OUTPUT_PORTS 7 #define USE_DSHOT -#define USE_ESC_SENSOR \ No newline at end of file +#define USE_ESC_SENSOR diff --git a/src/main/target/MATEKF722PX/target.h b/src/main/target/MATEKF722PX/target.h index ce780e7c93..ae03407447 100755 --- a/src/main/target/MATEKF722PX/target.h +++ b/src/main/target/MATEKF722PX/target.h @@ -54,13 +54,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF722SE/target.h b/src/main/target/MATEKF722SE/target.h index 04dc0d8123..0679d3f531 100644 --- a/src/main/target/MATEKF722SE/target.h +++ b/src/main/target/MATEKF722SE/target.h @@ -68,13 +68,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF765/target.h b/src/main/target/MATEKF765/target.h index e40fe455be..8a726d56b3 100644 --- a/src/main/target/MATEKF765/target.h +++ b/src/main/target/MATEKF765/target.h @@ -87,12 +87,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 #define PITOT_I2C_BUS BUS_I2C2 diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index 25e0217bb0..f2e21b0ee8 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -115,12 +115,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 #define PITOT_I2C_BUS BUS_I2C2 diff --git a/src/main/target/NEUTRONRCF435MINI/target.h b/src/main/target/NEUTRONRCF435MINI/target.h index 27fc03ae5e..11083bd61e 100644 --- a/src/main/target/NEUTRONRCF435MINI/target.h +++ b/src/main/target/NEUTRONRCF435MINI/target.h @@ -95,8 +95,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 +#define USE_MAG_ALL #define DEFAULT_I2C_BUS BUS_I2C2 // temperature sensors diff --git a/src/main/target/NEUTRONRCF435SE/target.h b/src/main/target/NEUTRONRCF435SE/target.h index 5d00a09911..68efdf35ac 100644 --- a/src/main/target/NEUTRONRCF435SE/target.h +++ b/src/main/target/NEUTRONRCF435SE/target.h @@ -93,8 +93,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 +#define USE_MAG_ALL #define DEFAULT_I2C_BUS BUS_I2C2 // temperature sensors @@ -196,4 +195,4 @@ #define MAX_PWM_OUTPUT_PORTS 8 #define USE_DSHOT -#define USE_ESC_SENSOR \ No newline at end of file +#define USE_ESC_SENSOR diff --git a/src/main/target/NEUTRONRCF435WING/target.h b/src/main/target/NEUTRONRCF435WING/target.h index 4f56d86778..2438d01ddf 100644 --- a/src/main/target/NEUTRONRCF435WING/target.h +++ b/src/main/target/NEUTRONRCF435WING/target.h @@ -95,8 +95,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 +#define USE_MAG_ALL #define DEFAULT_I2C_BUS BUS_I2C2 // temperature sensors diff --git a/src/main/target/NEUTRONRCH7BT/target.h b/src/main/target/NEUTRONRCH7BT/target.h index 78a1949e04..9f4ffd118d 100644 --- a/src/main/target/NEUTRONRCH7BT/target.h +++ b/src/main/target/NEUTRONRCH7BT/target.h @@ -87,12 +87,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index 2c0bd22801..2c5a27afbb 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -91,13 +91,7 @@ #define USE_MAG #define MAG_I2C_BUS I2C_EXT_BUS -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_AK8975 +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS I2C_EXT_BUS diff --git a/src/main/target/OMNIBUSF7/target.h b/src/main/target/OMNIBUSF7/target.h index 6a5a9d6ea9..a5f1bfc6b8 100644 --- a/src/main/target/OMNIBUSF7/target.h +++ b/src/main/target/OMNIBUSF7/target.h @@ -141,12 +141,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/OMNIBUSF7NXT/target.h b/src/main/target/OMNIBUSF7NXT/target.h index 367e8b22a7..6287e83473 100644 --- a/src/main/target/OMNIBUSF7NXT/target.h +++ b/src/main/target/OMNIBUSF7NXT/target.h @@ -52,11 +52,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/PIXRACER/target.h b/src/main/target/PIXRACER/target.h index 738fc1ad91..bc3bf3a4d9 100755 --- a/src/main/target/PIXRACER/target.h +++ b/src/main/target/PIXRACER/target.h @@ -56,13 +56,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_MPU9250 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index 29619624df..713c1a8ce3 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -41,12 +41,7 @@ #define USE_DUAL_MAG #define MAG_I2C_BUS_EXT BUS_I2C2 #define MAG_I2C_BUS_INT BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/RUSH_BLADE_F7/target.h b/src/main/target/RUSH_BLADE_F7/target.h index ba5915892b..2e68f1a392 100644 --- a/src/main/target/RUSH_BLADE_F7/target.h +++ b/src/main/target/RUSH_BLADE_F7/target.h @@ -75,13 +75,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // *************** Flash **************************** diff --git a/src/main/target/SAGEATF4/target.h b/src/main/target/SAGEATF4/target.h index 3ec00a37b3..afa89aebdd 100644 --- a/src/main/target/SAGEATF4/target.h +++ b/src/main/target/SAGEATF4/target.h @@ -98,8 +98,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C3 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 +#define USE_MAG_ALL // temperature sensors //#define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/SKYSTARSF405HD/target.h b/src/main/target/SKYSTARSF405HD/target.h index b8a696e14d..c5ab2d49fe 100644 --- a/src/main/target/SKYSTARSF405HD/target.h +++ b/src/main/target/SKYSTARSF405HD/target.h @@ -122,14 +122,7 @@ #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS diff --git a/src/main/target/SKYSTARSF722HD/target.h b/src/main/target/SKYSTARSF722HD/target.h index 9c2521380b..c24b849182 100644 --- a/src/main/target/SKYSTARSF722HD/target.h +++ b/src/main/target/SKYSTARSF722HD/target.h @@ -125,14 +125,7 @@ #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS diff --git a/src/main/target/SKYSTARSH743HD/target.h b/src/main/target/SKYSTARSH743HD/target.h index d0f9360517..6e830664c5 100644 --- a/src/main/target/SKYSTARSH743HD/target.h +++ b/src/main/target/SKYSTARSH743HD/target.h @@ -71,12 +71,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 @@ -198,4 +193,4 @@ #define MAX_PWM_OUTPUT_PORTS 10 #define USE_DSHOT -#define USE_ESC_SENSOR \ No newline at end of file +#define USE_ESC_SENSOR diff --git a/src/main/target/SPARKY2/target.h b/src/main/target/SPARKY2/target.h index 76d6e93099..78f80cd609 100644 --- a/src/main/target/SPARKY2/target.h +++ b/src/main/target/SPARKY2/target.h @@ -36,15 +36,10 @@ #define MPU9250_CS_PIN PC4 #define USE_MAG -#define USE_MAG_MPU9250 #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL + +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/SPEEDYBEEF4/target.h b/src/main/target/SPEEDYBEEF4/target.h index ff7fc7189a..310f6e9b45 100644 --- a/src/main/target/SPEEDYBEEF4/target.h +++ b/src/main/target/SPEEDYBEEF4/target.h @@ -126,11 +126,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL /*** ADC ***/ #define USE_ADC diff --git a/src/main/target/SPEEDYBEEF405MINI/target.h b/src/main/target/SPEEDYBEEF405MINI/target.h index dd5b9f4cfb..1f25899ed9 100644 --- a/src/main/target/SPEEDYBEEF405MINI/target.h +++ b/src/main/target/SPEEDYBEEF405MINI/target.h @@ -107,13 +107,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 @@ -183,4 +177,4 @@ #define USE_DSHOT #define USE_SERIALSHOT -#define USE_ESC_SENSOR \ No newline at end of file +#define USE_ESC_SENSOR diff --git a/src/main/target/SPEEDYBEEF405V3/target.h b/src/main/target/SPEEDYBEEF405V3/target.h index 99711f82de..5553fe314f 100644 --- a/src/main/target/SPEEDYBEEF405V3/target.h +++ b/src/main/target/SPEEDYBEEF405V3/target.h @@ -100,12 +100,7 @@ // Mag #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // *************** Internal SD card ************************** #define USE_SPI_DEVICE_2 diff --git a/src/main/target/SPEEDYBEEF405V4/target.h b/src/main/target/SPEEDYBEEF405V4/target.h index 8f333db3c2..1c5c847597 100644 --- a/src/main/target/SPEEDYBEEF405V4/target.h +++ b/src/main/target/SPEEDYBEEF405V4/target.h @@ -106,14 +106,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_VCM5883 +#define USE_MAG_ALL #define USE_RANGEFINDER #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/SPEEDYBEEF405WING/target.h b/src/main/target/SPEEDYBEEF405WING/target.h index ad58668268..e384ee01ff 100644 --- a/src/main/target/SPEEDYBEEF405WING/target.h +++ b/src/main/target/SPEEDYBEEF405WING/target.h @@ -115,14 +115,7 @@ //Mag #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8963 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_VCM5883 +#define USE_MAG_ALL #define RANGEFINDER_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 @@ -175,4 +168,4 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) -#define MAX_PWM_OUTPUT_PORTS 11 \ No newline at end of file +#define MAX_PWM_OUTPUT_PORTS 11 diff --git a/src/main/target/SPEEDYBEEF7/target.h b/src/main/target/SPEEDYBEEF7/target.h index 7f5ed75141..032f7479b5 100644 --- a/src/main/target/SPEEDYBEEF7/target.h +++ b/src/main/target/SPEEDYBEEF7/target.h @@ -109,12 +109,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 #define PITOT_I2C_BUS BUS_I2C2 diff --git a/src/main/target/SPEEDYBEEF745AIO/target.h b/src/main/target/SPEEDYBEEF745AIO/target.h index 1cb7b7dbc1..3e82678f55 100644 --- a/src/main/target/SPEEDYBEEF745AIO/target.h +++ b/src/main/target/SPEEDYBEEF745AIO/target.h @@ -100,12 +100,7 @@ // Mag #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // *************** SPI3 SD BLACKBOX******************* #define USE_SPI_DEVICE_1 diff --git a/src/main/target/SPEEDYBEEF7MINI/target.h b/src/main/target/SPEEDYBEEF7MINI/target.h index 0dd3a6e7a8..d267ade336 100644 --- a/src/main/target/SPEEDYBEEF7MINI/target.h +++ b/src/main/target/SPEEDYBEEF7MINI/target.h @@ -70,13 +70,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/SPEEDYBEEF7V2/target.h b/src/main/target/SPEEDYBEEF7V2/target.h index 8b53b53b96..9dfcdf232b 100644 --- a/src/main/target/SPEEDYBEEF7V2/target.h +++ b/src/main/target/SPEEDYBEEF7V2/target.h @@ -95,9 +95,7 @@ // Mag #define USE_MAG -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define MAG_I2C_BUS BUS_I2C2 // *************** Flash ************************** diff --git a/src/main/target/SPEEDYBEEF7V3/target.h b/src/main/target/SPEEDYBEEF7V3/target.h index 7c1d565c37..87eeb7114f 100644 --- a/src/main/target/SPEEDYBEEF7V3/target.h +++ b/src/main/target/SPEEDYBEEF7V3/target.h @@ -100,12 +100,7 @@ // Mag #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // *************** Internal SD card ************************** diff --git a/src/main/target/SPRACINGF4EVO/target.h b/src/main/target/SPRACINGF4EVO/target.h index 6eb48977d1..8af6981e54 100755 --- a/src/main/target/SPRACINGF4EVO/target.h +++ b/src/main/target/SPRACINGF4EVO/target.h @@ -46,13 +46,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_MPU9250 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/SPRACINGF7DUAL/target.h b/src/main/target/SPRACINGF7DUAL/target.h index 20e1104720..11e1bc934d 100644 --- a/src/main/target/SPRACINGF7DUAL/target.h +++ b/src/main/target/SPRACINGF7DUAL/target.h @@ -57,12 +57,7 @@ #define MAG_I2C_BUS BUS_I2C1 #define USE_MAG -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/TMOTORF7/target.h b/src/main/target/TMOTORF7/target.h index 890e95b353..9e935d1dc6 100644 --- a/src/main/target/TMOTORF7/target.h +++ b/src/main/target/TMOTORF7/target.h @@ -58,15 +58,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_AK8975 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL // *************** SPI2 OSD *********************** #define USE_SPI_DEVICE_2 diff --git a/src/main/target/TMOTORF7V2/target.h b/src/main/target/TMOTORF7V2/target.h index 5aaab2e390..525330e120 100644 --- a/src/main/target/TMOTORF7V2/target.h +++ b/src/main/target/TMOTORF7V2/target.h @@ -104,12 +104,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define PITOT_I2C_BUS BUS_I2C1 diff --git a/src/main/target/YUPIF4/target.h b/src/main/target/YUPIF4/target.h index ab9f07cd2c..6a7bb7d545 100644 --- a/src/main/target/YUPIF4/target.h +++ b/src/main/target/YUPIF4/target.h @@ -57,8 +57,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C2 diff --git a/src/main/target/YUPIF7/target.h b/src/main/target/YUPIF7/target.h index f494222f0f..bec1035858 100644 --- a/src/main/target/YUPIF7/target.h +++ b/src/main/target/YUPIF7/target.h @@ -36,8 +36,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS BUS_I2C1 #define USE_BARO diff --git a/src/main/target/ZEEZF7/target.h b/src/main/target/ZEEZF7/target.h index 07e22f1d93..28395b274f 100755 --- a/src/main/target/ZEEZF7/target.h +++ b/src/main/target/ZEEZF7/target.h @@ -131,13 +131,7 @@ #define USE_MAG #define MAG_I2C_BUS BUS_I2C3 -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_IST8310 -#define USE_MAG_IST8308 -#define USE_MAG_MAG3110 -#define USE_MAG_LIS3MDL -#define USE_MAG_AK8975 +#define USE_MAG_ALL #endif // *************** Flash **************************** diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index ec7cc83664..ebbb12de86 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -42,8 +42,33 @@ extern uint8_t __config_end; // Enable MSP BARO & MAG drivers if BARO and MAG sensors are compiled in #if defined(USE_MAG) #define USE_MAG_MSP + +#if defined(USE_MAG_ALL) + +#define USE_MAG_HMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_LIS3MDL +#define USE_MAG_MAG3110 +#define USE_MAG_QMC5883 + +//#if (MCU_FLASH_SIZE > 512) +#define USE_MAG_AK8963 +#define USE_MAG_AK8975 +#define USE_MAG_IST8308 +#define USE_MAG_MLX90393 + +#if defined(USE_IMU_MPU9250) +#define USE_MAG_MPU9250 #endif +#define USE_MAG_RM3100 +#define USE_MAG_VCM5883 +//#endif // MCU_FLASH_SIZE + +#endif // USE_MAG_ALL + +#endif // USE_MAG + #if defined(USE_BARO) #define USE_BARO_MSP #endif From 826f02735e60b4fb426e0f40b65d31b72d1fc4a7 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 25 Oct 2023 09:19:22 +0200 Subject: [PATCH 159/175] Fix JETI EXBUS overflow --- src/main/rx/jetiexbus.c | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/src/main/rx/jetiexbus.c b/src/main/rx/jetiexbus.c index ce6ebfe958..3556483399 100644 --- a/src/main/rx/jetiexbus.c +++ b/src/main/rx/jetiexbus.c @@ -158,6 +158,7 @@ static void jetiExBusDataReceive(uint16_t c, void *data) static timeUs_t jetiExBusTimeLast = 0; static uint8_t *jetiExBusFrame; + static uint8_t jetiExBusFrameMaxSize; const timeUs_t now = microsISR(); // Check if we shall reset frame position due to time @@ -174,11 +175,13 @@ static void jetiExBusDataReceive(uint16_t c, void *data) case EXBUS_START_CHANNEL_FRAME: jetiExBusFrameState = EXBUS_STATE_IN_PROGRESS; jetiExBusFrame = jetiExBusChannelFrame; + jetiExBusFrameMaxSize = EXBUS_MAX_CHANNEL_FRAME_SIZE; break; case EXBUS_START_REQUEST_FRAME: jetiExBusRequestState = EXBUS_STATE_IN_PROGRESS; jetiExBusFrame = jetiExBusRequestFrame; + jetiExBusFrameMaxSize = EXBUS_MAX_CHANNEL_FRAME_SIZE; break; default: @@ -186,6 +189,15 @@ static void jetiExBusDataReceive(uint16_t c, void *data) } } + if (jetiExBusFramePosition == jetiExBusFrameMaxSize) { + // frame overrun + jetiExBusFrameReset(); + jetiExBusFrameState = EXBUS_STATE_ZERO; + jetiExBusRequestState = EXBUS_STATE_ZERO; + + return; + } + // Store in frame copy jetiExBusFrame[jetiExBusFramePosition] = (uint8_t)c; jetiExBusFramePosition++; From d45b168f69c51ca588fc136a63ab788c35998810 Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 25 Oct 2023 16:28:06 +0900 Subject: [PATCH 160/175] tpa on yaw and i-term limit --- src/main/fc/controlrate_profile.c | 1 + .../fc/controlrate_profile_config_struct.h | 1 + src/main/fc/settings.yaml | 19 ++++++++++++------- src/main/flight/pid.c | 17 ++++++++++++----- src/main/flight/pid.h | 6 +----- 5 files changed, 27 insertions(+), 17 deletions(-) diff --git a/src/main/fc/controlrate_profile.c b/src/main/fc/controlrate_profile.c index 18f5bd343b..c8b144e136 100644 --- a/src/main/fc/controlrate_profile.c +++ b/src/main/fc/controlrate_profile.c @@ -44,6 +44,7 @@ void pgResetFn_controlRateProfiles(controlRateConfig_t *instance) .rcMid8 = SETTING_THR_MID_DEFAULT, .rcExpo8 = SETTING_THR_EXPO_DEFAULT, .dynPID = SETTING_TPA_RATE_DEFAULT, + .dynPID_on_YAW = SETTING_TPA_ON_YAW_DEFAULT, .pa_breakpoint = SETTING_TPA_BREAKPOINT_DEFAULT, .fixedWingTauMs = SETTING_FW_TPA_TIME_CONSTANT_DEFAULT }, diff --git a/src/main/fc/controlrate_profile_config_struct.h b/src/main/fc/controlrate_profile_config_struct.h index e07c328560..e403853760 100644 --- a/src/main/fc/controlrate_profile_config_struct.h +++ b/src/main/fc/controlrate_profile_config_struct.h @@ -29,6 +29,7 @@ typedef struct controlRateConfig_s { uint8_t rcMid8; uint8_t rcExpo8; uint8_t dynPID; + bool dynPID_on_YAW; uint16_t pa_breakpoint; // Breakpoint where TPA is activated uint16_t fixedWingTauMs; // Time constant of airplane TPA PT1-filter } throttle; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 261bf14a56..a2fa4ac7ec 100755 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1267,7 +1267,7 @@ groups: min: 0 max: 100 - name: tpa_rate - description: "Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate." + description: "Throttle PID attenuation reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate." default_value: 0 field: throttle.dynPID min: 0 @@ -1278,6 +1278,11 @@ groups: field: throttle.pa_breakpoint min: PWM_RANGE_MIN max: PWM_RANGE_MAX + - name: tpa_on_yaw + description: "Throttle PID attenuation also reduces influence on YAW for multi-rotor, Should be set to ON for tilting rotors." + type: bool + field: throttle.dynPID_on_YAW + default_value: OFF - name: fw_tpa_time_constant description: "TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. See **PID Attenuation and scaling** Wiki for full details." default_value: 1500 @@ -1851,12 +1856,6 @@ groups: default_value: 0 min: 0 max: 200 - - name: fw_iterm_throw_limit - description: "Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely." - default_value: 165 - field: fixedWingItermThrowLimit - min: FW_ITERM_THROW_LIMIT_MIN - max: FW_ITERM_THROW_LIMIT_MAX - name: fw_reference_airspeed description: "Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present." default_value: 1500 @@ -1905,6 +1904,12 @@ groups: field: itermWindupPointPercent min: 0 max: 90 + - name: pid_iterm_limit_percent + description: "Limits max/min I-term value in stabilization PID controller. It solves the problem of servo saturation before take-off/throwing the airplane into the air. Or multirotors with low authority. By default, error accumulated in I-term can not exceed 33% of total pid throw (around 165us on deafult pidsum_limit of pitch/roll). Set 0 to disable completely." + default_value: 33 + field: pidItermLimitPercent + min: 0 + max: 200 - name: rate_accel_limit_roll_pitch description: "Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting." default_value: 0 diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 2bb4ab7035..ec07d52ca1 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -264,8 +264,8 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .max_angle_inclination[FD_PITCH] = SETTING_MAX_ANGLE_INCLINATION_PIT_DEFAULT, .pidSumLimit = SETTING_PIDSUM_LIMIT_DEFAULT, .pidSumLimitYaw = SETTING_PIDSUM_LIMIT_YAW_DEFAULT, + .pidItermLimitPercent = SETTING_PID_ITERM_LIMIT_PERCENT_DEFAULT, - .fixedWingItermThrowLimit = SETTING_FW_ITERM_THROW_LIMIT_DEFAULT, .fixedWingReferenceAirspeed = SETTING_FW_REFERENCE_AIRSPEED_DEFAULT, .fixedWingCoordinatedYawGain = SETTING_FW_TURN_ASSIST_YAW_GAIN_DEFAULT, .fixedWingCoordinatedPitchGain = SETTING_FW_TURN_ASSIST_PITCH_GAIN_DEFAULT, @@ -531,7 +531,7 @@ void updatePIDCoefficients(void) pidState[axis].kT = 0.0f; } else { - const float axisTPA = (axis == FD_YAW) ? 1.0f : tpaFactor; + const float axisTPA = (axis == FD_YAW && (!currentControlRateProfile->throttle.dynPID_on_YAW)) ? 1.0f : tpaFactor; pidState[axis].kP = pidBank()->pid[axis].P / FP_PID_RATE_P_MULTIPLIER * axisTPA; pidState[axis].kI = pidBank()->pid[axis].I / FP_PID_RATE_I_MULTIPLIER; pidState[axis].kD = pidBank()->pid[axis].D / FP_PID_RATE_D_MULTIPLIER * axisTPA; @@ -762,8 +762,9 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh applyItermLimiting(pidState); - if (pidProfile()->fixedWingItermThrowLimit != 0) { - pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidProfile()->fixedWingItermThrowLimit, pidProfile()->fixedWingItermThrowLimit); + if (pidProfile()->pidItermLimitPercent != 0){ + float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent * 0.01f; + pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); } axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -pidState->pidSumLimit, +pidState->pidSumLimit); @@ -837,6 +838,12 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); + + if (pidProfile()->pidItermLimitPercent != 0){ + float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent * 0.01f; + pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); + } + // Don't grow I-term if motors are at their limit applyItermLimiting(pidState); @@ -1033,7 +1040,7 @@ void checkItermLimitingActive(pidState_t *pidState) shouldActivate = isFixedWingItermLimitActive(pidState->stickPosition); } else { - shouldActivate = mixerIsOutputSaturated(); + shouldActivate = mixerIsOutputSaturated(); //just in case, since it is already managed by itermWindupPointPercent } pidState->itermLimitActive = STATE(ANTI_WINDUP) || shouldActivate; diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index de0e3126b7..7c61b7cec2 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -31,10 +31,6 @@ #define HEADING_HOLD_RATE_LIMIT_MAX 250 #define HEADING_HOLD_RATE_LIMIT_DEFAULT 90 -#define FW_ITERM_THROW_LIMIT_DEFAULT 165 -#define FW_ITERM_THROW_LIMIT_MIN 0 -#define FW_ITERM_THROW_LIMIT_MAX 500 - #define AXIS_ACCEL_MIN_LIMIT 50 #define HEADING_HOLD_ERROR_LPF_FREQ 2 @@ -121,9 +117,9 @@ typedef struct pidProfile_s { uint16_t pidSumLimit; uint16_t pidSumLimitYaw; + uint16_t pidItermLimitPercent; // Airplane-specific parameters - uint16_t fixedWingItermThrowLimit; float fixedWingReferenceAirspeed; // Reference tuning airspeed for the airplane - the speed for which PID gains are tuned float fixedWingCoordinatedYawGain; // This is the gain of the yaw rate required to keep the yaw rate consistent with the turn rate for a coordinated turn. float fixedWingCoordinatedPitchGain; // This is the gain of the pitch rate to keep the pitch angle constant during coordinated turns. From fab783a3efcbf2a36140c29b9c0a81ae123680bc Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 25 Oct 2023 16:30:29 +0900 Subject: [PATCH 161/175] update the documents --- docs/Settings.md | 32 +++++++++++++++++++++----------- 1 file changed, 21 insertions(+), 11 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index c919327194..1f8b520304 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1222,16 +1222,6 @@ Iterm is not allowed to grow when stick position is above threshold. This solves --- -### fw_iterm_throw_limit - -Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely. - -| Default | Min | Max | -| --- | --- | --- | -| 165 | FW_ITERM_THROW_LIMIT_MIN | FW_ITERM_THROW_LIMIT_MAX | - ---- - ### fw_level_pitch_gain I-gain for the pitch trim for self-leveling flight modes. Higher values means that AUTOTRIM will be faster but might introduce oscillations @@ -4772,6 +4762,16 @@ Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, 'DJIWTF' --- +### pid_iterm_limit_percent + +Limits max/min I-term value in stabilization PID controller. It solves the problem of servo saturation before take-off/throwing the airplane into the air. Or multirotors with low authority. By default, error accumulated in I-term can not exceed 33% of total pid throw (around 165us on deafult pidsum_limit of pitch/roll). Set 0 to disable completely. + +| Default | Min | Max | +| --- | --- | --- | +| 33 | 0 | 200 | + +--- + ### pid_type Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` @@ -5672,9 +5672,19 @@ See tpa_rate. --- +### tpa_on_yaw + +Throttle PID attenuation also reduces influence on YAW for multi-rotor, Should be set to ON for tilting rotors. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + ### tpa_rate -Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. +Throttle PID attenuation reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. | Default | Min | Max | | --- | --- | --- | From f4d5c3b0bda1ea9c8bc55f1fea5d557ea6ac131b Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 25 Oct 2023 10:03:22 +0200 Subject: [PATCH 162/175] Disable ASFR function on ICM426xx driver --- src/main/drivers/accgyro/accgyro_icm42605.c | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/accgyro/accgyro_icm42605.c b/src/main/drivers/accgyro/accgyro_icm42605.c index 5f536527c7..33cdfc368d 100644 --- a/src/main/drivers/accgyro/accgyro_icm42605.c +++ b/src/main/drivers/accgyro/accgyro_icm42605.c @@ -78,11 +78,13 @@ #define ICM42605_INT_TPULSE_DURATION_100 (0 << ICM42605_INT_TPULSE_DURATION_BIT) #define ICM42605_INT_TPULSE_DURATION_8 (1 << ICM42605_INT_TPULSE_DURATION_BIT) - #define ICM42605_RA_INT_SOURCE0 0x65 #define ICM42605_UI_DRDY_INT1_EN_DISABLED (0 << 3) #define ICM42605_UI_DRDY_INT1_EN_ENABLED (1 << 3) +#define ICM42605_INTF_CONFIG1 0x4D +#define ICM42605_INTF_CONFIG1_AFSR_MASK 0xC0 +#define ICM42605_INTF_CONFIG1_AFSR_DISABLE 0x40 static void icm42605AccInit(accDev_t *acc) { @@ -190,6 +192,15 @@ static void icm42605AccAndGyroInit(gyroDev_t *gyro) busWrite(dev, ICM42605_RA_INT_CONFIG1, intConfig1Value); delay(15); + //Disable AFSR as in BF and Ardupilot + uint8_t intfConfig1Value; + busRead(dev, ICM42605_INTF_CONFIG1, &intfConfig1Value); + intfConfig1Value &= ~ICM42605_INTF_CONFIG1_AFSR_MASK; + intfConfig1Value |= ICM42605_INTF_CONFIG1_AFSR_DISABLE; + busWrite(dev, ICM42605_INTF_CONFIG1, intfConfig1Value); + + delay(15); + busSetSpeed(dev, BUS_SPEED_FAST); } From 9a7de3434e6df84866e9cb024d3513f2f3fd108c Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 25 Oct 2023 21:16:56 +0900 Subject: [PATCH 163/175] 16G scale range for bmi270 --- src/main/drivers/accgyro/accgyro_bmi270.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/accgyro/accgyro_bmi270.c b/src/main/drivers/accgyro/accgyro_bmi270.c index 0b37518a3c..3e1db22253 100644 --- a/src/main/drivers/accgyro/accgyro_bmi270.c +++ b/src/main/drivers/accgyro/accgyro_bmi270.c @@ -214,7 +214,7 @@ static void bmi270AccAndGyroInit(gyroDev_t *gyro) delay(1); // Configure the accelerometer full-scale range - busWrite(busDev, BMI270_REG_ACC_RANGE, BMI270_ACC_RANGE_8G); + busWrite(busDev, BMI270_REG_ACC_RANGE, BMI270_ACC_RANGE_16G); delay(1); // Configure the gyro @@ -301,7 +301,7 @@ static void bmi270GyroInit(gyroDev_t *gyro) static void bmi270AccInit(accDev_t *acc) { // sensor is configured during gyro init - acc->acc_1G = 4096; // 8G sensor scale + acc->acc_1G = 2048; // 16G sensor scale } bool bmi270AccDetect(accDev_t *acc) From 9ee33200d5321a9c9f675519859158b4b746dcce Mon Sep 17 00:00:00 2001 From: "daniel.li" Date: Thu, 26 Oct 2023 05:28:28 +0800 Subject: [PATCH 164/175] Fixed #9399 can't find baro chip on PB6/PB7 I2C1 --- src/main/drivers/bus_i2c_at32f43x.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/bus_i2c_at32f43x.c b/src/main/drivers/bus_i2c_at32f43x.c index 97036b6186..98fdd94246 100644 --- a/src/main/drivers/bus_i2c_at32f43x.c +++ b/src/main/drivers/bus_i2c_at32f43x.c @@ -70,7 +70,7 @@ static void i2cUnstick(IO_t scl, IO_t sda); //Define thi I2C hardware map static i2cDevice_t i2cHardwareMap[I2CDEV_COUNT] = { - { .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C1_EVT_IRQn, .er_irq = I2C1_ERR_IRQn, .af = GPIO_MUX_8 }, + { .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C1_EVT_IRQn, .er_irq = I2C1_ERR_IRQn, .af = GPIO_MUX_4 }, { .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C2_EVT_IRQn, .er_irq = I2C2_ERR_IRQn, .af = GPIO_MUX_4 }, { .dev = I2C3, .scl = IO_TAG(I2C3_SCL), .sda = IO_TAG(I2C3_SDA), .rcc = RCC_APB1(I2C3), .speed = I2C_SPEED_400KHZ, .ev_irq = I2C3_EVT_IRQn, .er_irq = I2C3_ERR_IRQn, .af = GPIO_MUX_4 }, }; From 252fc49618cb1cc777ce8d1b63661e703c02bc60 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 26 Oct 2023 11:40:36 +0200 Subject: [PATCH 165/175] Move down to remove fiddling with servo mid position --- src/main/flight/servos.c | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index cb3004ed61..2e1c60270d 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -368,21 +368,6 @@ void servoMixer(float dT) servo[target] += ((int32_t)inputLimited * currentServoMixer[i].rate) / 100; } - /* - * When not armed, apply servo low position to all outputs that include a throttle or stabilizet throttle in the mix - */ - if (!ARMING_FLAG(ARMED)) { - for (int i = 0; i < servoRuleCount; i++) { - const uint8_t target = currentServoMixer[i].targetChannel; - const uint8_t from = currentServoMixer[i].inputSource; - - // Translate minimum throttle values to -500 ... +500 servo range for use below. - if (from == INPUT_STABILIZED_THROTTLE || from == INPUT_RC_THROTTLE) { - servo[target] = motorConfig()->mincommand - servoParams(target)->middle; - } - } - } - for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { /* @@ -413,6 +398,21 @@ void servoMixer(float dT) */ servo[i] = constrain(servo[i], servoParams(i)->min, servoParams(i)->max); } + + /* + * When not armed, apply servo low position to all outputs that include a throttle or stabilizet throttle in the mix + */ + if (!ARMING_FLAG(ARMED)) { + for (int i = 0; i < servoRuleCount; i++) { + const uint8_t target = currentServoMixer[i].targetChannel; + const uint8_t from = currentServoMixer[i].inputSource; + + // Translate minimum throttle values to -500 ... +500 servo range for use below. + if (from == INPUT_STABILIZED_THROTTLE || from == INPUT_RC_THROTTLE) { + servo[target] = motorConfig()->mincommand; + } + } + } } #define SERVO_AUTOTRIM_TIMER_MS 2000 From 80f3393984a7aae7ce2390579aeb699298fd48b2 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 26 Oct 2023 11:49:02 +0200 Subject: [PATCH 166/175] remove not needed comment --- src/main/flight/servos.c | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index f8d0747f60..f38a4ea108 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -424,7 +424,6 @@ void servoMixer(float dT) const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t from = currentServoMixer[i].inputSource; - // Translate minimum throttle values to -500 ... +500 servo range for use below. if (from == INPUT_STABILIZED_THROTTLE || from == INPUT_RC_THROTTLE) { servo[target] = motorConfig()->mincommand; } From fa6468d478d1338510b4cbc5e4c038196505fee8 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Thu, 26 Oct 2023 11:01:06 +0100 Subject: [PATCH 167/175] Update pid.c --- src/main/flight/pid.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index fd6777ac82..d3990821cf 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -1243,7 +1243,7 @@ void pidInit(void) navPidInit( &fixedWingLevelTrimController, 0.0f, - (float)pidProfile()->fixedWingLevelTrimGain / 50.0f, + (float)pidProfile()->fixedWingLevelTrimGain / 100.0f, 0.0f, 0.0f, 2.0f, From 45d98371ab8f08049517c7bfd45be8cf9a8b4fa7 Mon Sep 17 00:00:00 2001 From: Daniel Date: Thu, 26 Oct 2023 13:06:02 +0200 Subject: [PATCH 168/175] comment on how to clone specific INAV releases added --- .../Building in Windows 10 or 11 with Linux Subsystem.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md b/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md index a2c5894e72..f47b6db62c 100644 --- a/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md @@ -36,7 +36,7 @@ To run `cmake` in the latest version you will need to update from Ubuntu `18_04 Mount MS windows C drive and clone INAV 1. `cd /mnt/c` -1. `git clone https://github.com/iNavFlight/inav.git` +1. `git clone https://github.com/iNavFlight/inav.git` (latest code) / `git clone -b 6.1.1 --single-branch https://github.com/iNavFlight/inav.git` (option "-b" for downloading specific releases - version 6.1.1 in this example) You are ready! You now have a folder called inav in the root of C drive that you can edit in windows From d904e06692ff676cad512b5a03da13547032510b Mon Sep 17 00:00:00 2001 From: shota Date: Fri, 27 Oct 2023 14:50:37 +0900 Subject: [PATCH 169/175] allow f722 to use mixer profile --- src/main/target/common.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/common.h b/src/main/target/common.h index f377669b5f..d2d135cfa2 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -189,8 +189,8 @@ #define USE_TELEMETRY_HOTT #define USE_HOTT_TEXTMODE #define USE_24CHANNELS -#else +#define MAX_MIXER_PROFILE_COUNT 2 +#elif !defined(STM32F7) #define MAX_MIXER_PROFILE_COUNT 1 #endif - #define USE_EZ_TUNE From a376b7c575e199938f3ba6fe61862a9f077ef84a Mon Sep 17 00:00:00 2001 From: Daniel Date: Fri, 27 Oct 2023 20:06:56 +0200 Subject: [PATCH 170/175] Update Building in Windows 10 or 11 with Linux Subsystem.md --- .../Building in Windows 10 or 11 with Linux Subsystem.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md b/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md index f47b6db62c..9cee0ede25 100644 --- a/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md @@ -36,7 +36,9 @@ To run `cmake` in the latest version you will need to update from Ubuntu `18_04 Mount MS windows C drive and clone INAV 1. `cd /mnt/c` -1. `git clone https://github.com/iNavFlight/inav.git` (latest code) / `git clone -b 6.1.1 --single-branch https://github.com/iNavFlight/inav.git` (option "-b" for downloading specific releases - version 6.1.1 in this example) +2. `git clone https://github.com/iNavFlight/inav.git` +3. `git checkout 6.1.1` (to switch to a specific release tag, for this example INAV version 6.1.1) +4. `git checkout -b my-branch` (to create own branch) You are ready! You now have a folder called inav in the root of C drive that you can edit in windows From ee88f867adf0dd2d66a6ede0aae1b5feba31bd7c Mon Sep 17 00:00:00 2001 From: Sensei Date: Sat, 28 Oct 2023 12:21:59 -0500 Subject: [PATCH 171/175] Update Programming Framework.md Note about most common OVERRIDE_RC_Channel error. --- docs/Programming Framework.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index c1e1c2d0e7..1d0f4776b7 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -83,7 +83,7 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn | 35 | Trigonometry: Tangent | Computes TAN of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` | | 36 | MAP_INPUT | Scales `Operand A` from [`0` : `Operand B`] to [`0` : `1000`]. Note: input will be constrained and then scaled | | 37 | MAP_OUTPUT | Scales `Operand A` from [`0` : `1000`] to [`0` : `Operand B`]. Note: input will be constrained and then scaled | -| 38 | RC_CHANNEL_OVERRIDE | Overrides channel set by `Operand A` to value of `Operand B` | +| 38 | RC_CHANNEL_OVERRIDE | Overrides channel set by `Operand A` to value of `Operand B`. Note operand A should normally be set as a "Value", NOT as "Get RC Channel"| | 39 | SET_HEADING_TARGET | Sets heading-hold target to `Operand A`, in degrees. Value wraps-around. | | 40 | Modulo | Modulo. Divide `Operand A` by `Operand B` and returns the remainder | | 41 | LOITER_RADIUS_OVERRIDE | Sets the loiter radius to `Operand A` [`0` : `100000`] in cm. If the value is lower than the loiter radius set in the **Advanced Tuning**, that will be used. | From d8d4cb12a1328b666ef93a40b0a7f8f5e15a9755 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 29 Oct 2023 13:17:32 +0000 Subject: [PATCH 172/175] Update OSD.md Add INAV 7.0 OSD elements and details about the pilot logo. --- docs/OSD.md | 339 ++++++++++++++++++++++++++++------------------------ 1 file changed, 183 insertions(+), 156 deletions(-) diff --git a/docs/OSD.md b/docs/OSD.md index 64530f0e2c..b3526d0d76 100644 --- a/docs/OSD.md +++ b/docs/OSD.md @@ -5,163 +5,190 @@ The On Screen Display, or OSD, is a feature that overlays flight data over the v ## Features and Limitations Not all OSDs are created equally. This table shows the differences between the different systems available. -| OSD System | Character grid | Character | Canvas | MSP DisplayPort | All elements supported | -|---------------|-------------------|-----------|-----------|-------------------|---------------------------| -| Analogue PAL | 30 x 16 | X | | | YES | -| Analogue NTSC | 30 x 13 | X | | | YES | -| PixelOSD | As PAL or NTSC | | X | | YES | -| DJI OSD | 30 x 16 | X | | | NO - BF Characters only | -| DJI WTFOS | 60 x 22 | X | | X | YES | -| HDZero | 50 x 18 | X | | X | YES | -| Avatar | 53 x 20 | X | | X | YES | -| DJI O3 | 53 x 20 (HD) | X | | X (partial) | NO - BF Characters only | +| OSD System | Character grid | Character | Canvas | MSP DisplayPort | All elements supported | +|---------------|----------------|-----------|--------|-----------------|-------------------------| +| Analogue PAL | 30 x 16 | X | | | YES | +| Analogue NTSC | 30 x 13 | X | | | YES | +| PixelOSD | As PAL or NTSC | | X | | YES | +| DJI OSD | 30 x 16 | X | | | NO - BF Characters only | +| DJI WTFOS | 60 x 22 | X | | X | YES | +| HDZero | 50 x 18 | X | | X | YES | +| Avatar | 53 x 20 | X | | X | YES | +| DJI O3 | 53 x 20 (HD) | X | | X (partial) | NO - BF Characters only | ## OSD Elements Here are the OSD Elements provided by INAV. -| ID | Element | Added | -|-------|-----------------------------------------------|-------| -| 0 | OSD_RSSI_VALUE | 1.0.0 | -| 1 | OSD_MAIN_BATT_VOLTAGE | 1.0.0 | -| 2 | OSD_CROSSHAIRS | 1.0.0 | -| 3 | OSD_ARTIFICIAL_HORIZON | 1.0.0 | -| 4 | OSD_HORIZON_SIDEBARS | 1.0.0 | -| 5 | OSD_ONTIME | 1.0.0 | -| 6 | OSD_FLYTIME | 1.0.0 | -| 7 | OSD_FLYMODE | 1.0.0 | -| 8 | OSD_CRAFT_NAME | 1.0.0 | -| 9 | OSD_THROTTLE_POS | 1.0.0 | -| 10 | OSD_VTX_CHANNEL | 1.0.0 | -| 11 | OSD_CURRENT_DRAW | 1.0.0 | -| 12 | OSD_MAH_DRAWN | 1.0.0 | -| 13 | OSD_GPS_SPEED | 1.0.0 | -| 14 | OSD_GPS_SATS | 1.0.0 | -| 15 | OSD_ALTITUDE | 1.0.0 | -| 16 | OSD_ROLL_PIDS | 1.6.0 | -| 17 | OSD_PITCH_PIDS | 1.6.0 | -| 18 | OSD_YAW_PIDS | 1.6.0 | -| 19 | OSD_POWER | 1.6.0 | -| 20 | OSD_GPS_LON | 1.6.0 | -| 21 | OSD_GPS_LAT | 1.6.0 | -| 22 | OSD_HOME_DIR | 1.6.0 | -| 23 | OSD_HOME_DIST | 1.6.0 | -| 24 | OSD_HEADING | 1.6.0 | -| 25 | OSD_VARIO | 1.6.0 | -| 26 | OSD_VARIO_NUM | 1.6.0 | -| 27 | OSD_AIR_SPEED | 1.7.3 | -| 28 | OSD_ONTIME_FLYTIME | 1.8.0 | -| 29 | OSD_RTC_TIME | 1.8.0 | -| 30 | OSD_MESSAGES | 1.8.0 | -| 31 | OSD_GPS_HDOP | 1.8.0 | -| 32 | OSD_MAIN_BATT_CELL_VOLTAGE | 1.8.0 | -| 33 | OSD_SCALED_THROTTLE_POS | 1.8.0 | -| 34 | OSD_HEADING_GRAPH | 1.8.0 | -| 35 | OSD_EFFICIENCY_MAH_PER_KM | 1.9.0 | -| 36 | OSD_WH_DRAWN | 1.9.0 | -| 37 | OSD_BATTERY_REMAINING_CAPACITY | 1.9.0 | -| 38 | OSD_BATTERY_REMAINING_PERCENT | 1.9.0 | -| 39 | OSD_EFFICIENCY_WH_PER_KM | 1.9.0 | -| 40 | OSD_TRIP_DIST | 1.9.1 | -| 41 | OSD_ATTITUDE_PITCH | 2.0.0 | -| 42 | OSD_ATTITUDE_ROLL | 2.0.0 | -| 43 | OSD_MAP_NORTH | 2.0.0 | -| 44 | OSD_MAP_TAKEOFF | 2.0.0 | -| 45 | OSD_RADAR | 2.0.0 | -| 46 | OSD_WIND_SPEED_HORIZONTAL | 2.0.0 | -| 47 | OSD_WIND_SPEED_VERTICAL | 2.0.0 | -| 48 | OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH | 2.0.0 | -| 49 | OSD_REMAINING_DISTANCE_BEFORE_RTH | 2.0.0 | -| 50 | OSD_HOME_HEADING_ERROR | 2.0.0 | -| 51 | OSD_COURSE_HOLD_ERROR | 2.0.0 | -| 52 | OSD_COURSE_HOLD_ADJUSTMENT | 2.0.0 | -| 53 | OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE | 2.0.0 | -| 54 | OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE | 2.0.0 | -| 55 | OSD_POWER_SUPPLY_IMPEDANCE | 2.0.0 | -| 56 | OSD_LEVEL_PIDS | 2.0.0 | -| 57 | OSD_POS_XY_PIDS | 2.0.0 | -| 58 | OSD_POS_Z_PIDS | 2.0.0 | -| 59 | OSD_VEL_XY_PIDS | 2.0.0 | -| 60 | OSD_VEL_Z_PIDS | 2.0.0 | -| 61 | OSD_HEADING_P | 2.0.0 | -| 62 | OSD_BOARD_ALIGN_ROLL | 2.0.0 | -| 63 | OSD_BOARD_ALIGN_PITCH | 2.0.0 | -| 64 | OSD_RC_EXPO | 2.0.0 | -| 65 | OSD_RC_YAW_EXPO | 2.0.0 | -| 66 | OSD_THROTTLE_EXPO | 2.0.0 | -| 67 | OSD_PITCH_RATE | 2.0.0 | -| 68 | OSD_ROLL_RATE | 2.0.0 | -| 69 | OSD_YAW_RATE | 2.0.0 | -| 70 | OSD_MANUAL_RC_EXPO | 2.0.0 | -| 71 | OSD_MANUAL_RC_YAW_EXPO | 2.0.0 | -| 72 | OSD_MANUAL_PITCH_RATE | 2.0.0 | -| 73 | OSD_MANUAL_ROLL_RATE | 2.0.0 | -| 74 | OSD_MANUAL_YAW_RATE | 2.0.0 | -| 75 | OSD_NAV_FW_CRUISE_THR | 2.0.0 | -| 76 | OSD_NAV_FW_PITCH2THR | 2.0.0 | -| 77 | OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE | 2.0.0 | -| 78 | OSD_DEBUG | 2.0.0 | -| 79 | OSD_FW_ALT_PID_OUTPUTS | 2.0.0 | -| 80 | OSD_FW_POS_PID_OUTPUTS | 2.0.0 | -| 81 | OSD_MC_VEL_X_PID_OUTPUTS | 2.0.0 | -| 82 | OSD_MC_VEL_Y_PID_OUTPUTS | 2.0.0 | -| 83 | OSD_MC_VEL_Z_PID_OUTPUTS | 2.0.0 | -| 84 | OSD_MC_POS_XYZ_P_OUTPUTS | 2.0.0 | -| 85 | OSD_3D_SPEED | 2.1.0 | -| 86 | OSD_IMU_TEMPERATURE | 2.1.0 | -| 87 | OSD_BARO_TEMPERATURE | 2.1.0 | -| 88 | OSD_TEMP_SENSOR_0_TEMPERATURE | 2.1.0 | -| 89 | OSD_TEMP_SENSOR_1_TEMPERATURE | 2.1.0 | -| 90 | OSD_TEMP_SENSOR_2_TEMPERATURE | 2.1.0 | -| 91 | OSD_TEMP_SENSOR_3_TEMPERATURE | 2.1.0 | -| 92 | OSD_TEMP_SENSOR_4_TEMPERATURE | 2.1.0 | -| 93 | OSD_TEMP_SENSOR_5_TEMPERATURE | 2.1.0 | -| 94 | OSD_TEMP_SENSOR_6_TEMPERATURE | 2.1.0 | -| 95 | OSD_TEMP_SENSOR_7_TEMPERATURE | 2.1.0 | -| 96 | OSD_ALTITUDE_MSL | 2.1.0 | -| 97 | OSD_PLUS_CODE | 2.1.0 | -| 98 | OSD_MAP_SCALE | 2.2.0 | -| 99 | OSD_MAP_REFERENCE | 2.2.0 | -| 100 | OSD_GFORCE | 2.2.0 | -| 101 | OSD_GFORCE_X | 2.2.0 | -| 102 | OSD_GFORCE_Y | 2.2.0 | -| 103 | OSD_GFORCE_Z | 2.2.0 | -| 104 | OSD_RC_SOURCE | 2.2.0 | -| 105 | OSD_VTX_POWER | 2.2.0 | -| 106 | OSD_ESC_RPM | 2.3.0 | -| 107 | OSD_ESC_TEMPERATURE | 2.5.0 | -| 108 | OSD_AZIMUTH | 2.6.0 | -| 109 | OSD_CRSF_RSSI_DBM | 2.6.0 | -| 110 | OSD_CRSF_LQ | 2.6.0 | -| 111 | OSD_CRSF_SNR_DB | 2.6.0 | -| 112 | OSD_CRSF_TX_POWER | 2.6.0 | -| 113 | OSD_GVAR_0 | 2.6.0 | -| 114 | OSD_GVAR_1 | 2.6.0 | -| 115 | OSD_GVAR_2 | 2.6.0 | -| 116 | OSD_GVAR_3 | 2.6.0 | -| 117 | OSD_TPA | 2.6.0 | -| 118 | OSD_NAV_FW_CONTROL_SMOOTHNESS | 2.6.0 | -| 119 | OSD_VERSION | 3.0.0 | -| 120 | OSD_RANGEFINDER | 3.0.0 | -| 121 | OSD_PLIMIT_REMAINING_BURST_TIME | 3.0.0 | -| 122 | OSD_PLIMIT_ACTIVE_CURRENT_LIMIT | 3.0.0 | -| 123 | OSD_PLIMIT_ACTIVE_POWER_LIMIT | 3.0.0 | -| 124 | OSD_GLIDESLOPE | 3.0.1 | -| 125 | OSD_GPS_MAX_SPEED | 4.0.0 | -| 126 | OSD_3D_MAX_SPEED | 4.0.0 | -| 127 | OSD_AIR_MAX_SPEED | 4.0.0 | -| 128 | OSD_ACTIVE_PROFILE | 4.0.0 | -| 129 | OSD_MISSION | 4.0.0 | -| 130 | OSD_SWITCH_INDICATOR_0 | 5.0.0 | -| 131 | OSD_SWITCH_INDICATOR_1 | 5.0.0 | -| 132 | OSD_SWITCH_INDICATOR_2 | 5.0.0 | -| 133 | OSD_SWITCH_INDICATOR_3 | 5.0.0 | -| 134 | OSD_TPA_TIME_CONSTANT | 5.0.0 | -| 135 | OSD_FW_LEVEL_TRIM | 5.0.0 | -| 136 | OSD_GLIDE_TIME_REMAINING | 6.0.0 | -| 137 | OSD_GLIDE_RANGE | 6.0.0 | -| 138 | OSD_CLIMB_EFFICIENCY | 6.0.0 | -| 139 | OSD_NAV_WP_MULTI_MISSION_INDEX | 6.0.0 | -| 140 | OSD_GROUND_COURSE | 6.0.0 | -| 141 | OSD_CROSS_TRACK_ERROR | 6.0.0 | -| 142 | OSD_PILOT_NAME | 6.0.0 | -| 143 | OSD_PAN_SERVO_CENTRED | 6.0.0 | \ No newline at end of file +| ID | Element | Added | +|-----|--------------------------------------------------|--------| +| 0 | OSD_RSSI_VALUE | 1.0.0 | +| 1 | OSD_MAIN_BATT_VOLTAGE | 1.0.0 | +| 2 | OSD_CROSSHAIRS | 1.0.0 | +| 3 | OSD_ARTIFICIAL_HORIZON | 1.0.0 | +| 4 | OSD_HORIZON_SIDEBARS | 1.0.0 | +| 5 | OSD_ONTIME | 1.0.0 | +| 6 | OSD_FLYTIME | 1.0.0 | +| 7 | OSD_FLYMODE | 1.0.0 | +| 8 | OSD_CRAFT_NAME | 1.0.0 | +| 9 | OSD_THROTTLE_POS | 1.0.0 | +| 10 | OSD_VTX_CHANNEL | 1.0.0 | +| 11 | OSD_CURRENT_DRAW | 1.0.0 | +| 12 | OSD_MAH_DRAWN | 1.0.0 | +| 13 | OSD_GPS_SPEED | 1.0.0 | +| 14 | OSD_GPS_SATS | 1.0.0 | +| 15 | OSD_ALTITUDE | 1.0.0 | +| 16 | OSD_ROLL_PIDS | 1.6.0 | +| 17 | OSD_PITCH_PIDS | 1.6.0 | +| 18 | OSD_YAW_PIDS | 1.6.0 | +| 19 | OSD_POWER | 1.6.0 | +| 20 | OSD_GPS_LON | 1.6.0 | +| 21 | OSD_GPS_LAT | 1.6.0 | +| 22 | OSD_HOME_DIR | 1.6.0 | +| 23 | OSD_HOME_DIST | 1.6.0 | +| 24 | OSD_HEADING | 1.6.0 | +| 25 | OSD_VARIO | 1.6.0 | +| 26 | OSD_VARIO_NUM | 1.6.0 | +| 27 | OSD_AIR_SPEED | 1.7.3 | +| 28 | OSD_ONTIME_FLYTIME | 1.8.0 | +| 29 | OSD_RTC_TIME | 1.8.0 | +| 30 | OSD_MESSAGES | 1.8.0 | +| 31 | OSD_GPS_HDOP | 1.8.0 | +| 32 | OSD_MAIN_BATT_CELL_VOLTAGE | 1.8.0 | +| 33 | OSD_SCALED_THROTTLE_POS | 1.8.0 | +| 34 | OSD_HEADING_GRAPH | 1.8.0 | +| 35 | OSD_EFFICIENCY_MAH_PER_KM | 1.9.0 | +| 36 | OSD_WH_DRAWN | 1.9.0 | +| 37 | OSD_BATTERY_REMAINING_CAPACITY | 1.9.0 | +| 38 | OSD_BATTERY_REMAINING_PERCENT | 1.9.0 | +| 39 | OSD_EFFICIENCY_WH_PER_KM | 1.9.0 | +| 40 | OSD_TRIP_DIST | 1.9.1 | +| 41 | OSD_ATTITUDE_PITCH | 2.0.0 | +| 42 | OSD_ATTITUDE_ROLL | 2.0.0 | +| 43 | OSD_MAP_NORTH | 2.0.0 | +| 44 | OSD_MAP_TAKEOFF | 2.0.0 | +| 45 | OSD_RADAR | 2.0.0 | +| 46 | OSD_WIND_SPEED_HORIZONTAL | 2.0.0 | +| 47 | OSD_WIND_SPEED_VERTICAL | 2.0.0 | +| 48 | OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH | 2.0.0 | +| 49 | OSD_REMAINING_DISTANCE_BEFORE_RTH | 2.0.0 | +| 50 | OSD_HOME_HEADING_ERROR | 2.0.0 | +| 51 | OSD_COURSE_HOLD_ERROR | 2.0.0 | +| 52 | OSD_COURSE_HOLD_ADJUSTMENT | 2.0.0 | +| 53 | OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE | 2.0.0 | +| 54 | OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE | 2.0.0 | +| 55 | OSD_POWER_SUPPLY_IMPEDANCE | 2.0.0 | +| 56 | OSD_LEVEL_PIDS | 2.0.0 | +| 57 | OSD_POS_XY_PIDS | 2.0.0 | +| 58 | OSD_POS_Z_PIDS | 2.0.0 | +| 59 | OSD_VEL_XY_PIDS | 2.0.0 | +| 60 | OSD_VEL_Z_PIDS | 2.0.0 | +| 61 | OSD_HEADING_P | 2.0.0 | +| 62 | OSD_BOARD_ALIGN_ROLL | 2.0.0 | +| 63 | OSD_BOARD_ALIGN_PITCH | 2.0.0 | +| 64 | OSD_RC_EXPO | 2.0.0 | +| 65 | OSD_RC_YAW_EXPO | 2.0.0 | +| 66 | OSD_THROTTLE_EXPO | 2.0.0 | +| 67 | OSD_PITCH_RATE | 2.0.0 | +| 68 | OSD_ROLL_RATE | 2.0.0 | +| 69 | OSD_YAW_RATE | 2.0.0 | +| 70 | OSD_MANUAL_RC_EXPO | 2.0.0 | +| 71 | OSD_MANUAL_RC_YAW_EXPO | 2.0.0 | +| 72 | OSD_MANUAL_PITCH_RATE | 2.0.0 | +| 73 | OSD_MANUAL_ROLL_RATE | 2.0.0 | +| 74 | OSD_MANUAL_YAW_RATE | 2.0.0 | +| 75 | OSD_NAV_FW_CRUISE_THR | 2.0.0 | +| 76 | OSD_NAV_FW_PITCH2THR | 2.0.0 | +| 77 | OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE | 2.0.0 | +| 78 | OSD_DEBUG | 2.0.0 | +| 79 | OSD_FW_ALT_PID_OUTPUTS | 2.0.0 | +| 80 | OSD_FW_POS_PID_OUTPUTS | 2.0.0 | +| 81 | OSD_MC_VEL_X_PID_OUTPUTS | 2.0.0 | +| 82 | OSD_MC_VEL_Y_PID_OUTPUTS | 2.0.0 | +| 83 | OSD_MC_VEL_Z_PID_OUTPUTS | 2.0.0 | +| 84 | OSD_MC_POS_XYZ_P_OUTPUTS | 2.0.0 | +| 85 | OSD_3D_SPEED | 2.1.0 | +| 86 | OSD_IMU_TEMPERATURE | 2.1.0 | +| 87 | OSD_BARO_TEMPERATURE | 2.1.0 | +| 88 | OSD_TEMP_SENSOR_0_TEMPERATURE | 2.1.0 | +| 89 | OSD_TEMP_SENSOR_1_TEMPERATURE | 2.1.0 | +| 90 | OSD_TEMP_SENSOR_2_TEMPERATURE | 2.1.0 | +| 91 | OSD_TEMP_SENSOR_3_TEMPERATURE | 2.1.0 | +| 92 | OSD_TEMP_SENSOR_4_TEMPERATURE | 2.1.0 | +| 93 | OSD_TEMP_SENSOR_5_TEMPERATURE | 2.1.0 | +| 94 | OSD_TEMP_SENSOR_6_TEMPERATURE | 2.1.0 | +| 95 | OSD_TEMP_SENSOR_7_TEMPERATURE | 2.1.0 | +| 96 | OSD_ALTITUDE_MSL | 2.1.0 | +| 97 | OSD_PLUS_CODE | 2.1.0 | +| 98 | OSD_MAP_SCALE | 2.2.0 | +| 99 | OSD_MAP_REFERENCE | 2.2.0 | +| 100 | OSD_GFORCE | 2.2.0 | +| 101 | OSD_GFORCE_X | 2.2.0 | +| 102 | OSD_GFORCE_Y | 2.2.0 | +| 103 | OSD_GFORCE_Z | 2.2.0 | +| 104 | OSD_RC_SOURCE | 2.2.0 | +| 105 | OSD_VTX_POWER | 2.2.0 | +| 106 | OSD_ESC_RPM | 2.3.0 | +| 107 | OSD_ESC_TEMPERATURE | 2.5.0 | +| 108 | OSD_AZIMUTH | 2.6.0 | +| 109 | OSD_CRSF_RSSI_DBM | 2.6.0 | +| 110 | OSD_CRSF_LQ | 2.6.0 | +| 111 | OSD_CRSF_SNR_DB | 2.6.0 | +| 112 | OSD_CRSF_TX_POWER | 2.6.0 | +| 113 | OSD_GVAR_0 | 2.6.0 | +| 114 | OSD_GVAR_1 | 2.6.0 | +| 115 | OSD_GVAR_2 | 2.6.0 | +| 116 | OSD_GVAR_3 | 2.6.0 | +| 117 | OSD_TPA | 2.6.0 | +| 118 | OSD_NAV_FW_CONTROL_SMOOTHNESS | 2.6.0 | +| 119 | OSD_VERSION | 3.0.0 | +| 120 | OSD_RANGEFINDER | 3.0.0 | +| 121 | OSD_PLIMIT_REMAINING_BURST_TIME | 3.0.0 | +| 122 | OSD_PLIMIT_ACTIVE_CURRENT_LIMIT | 3.0.0 | +| 123 | OSD_PLIMIT_ACTIVE_POWER_LIMIT | 3.0.0 | +| 124 | OSD_GLIDESLOPE | 3.0.1 | +| 125 | OSD_GPS_MAX_SPEED | 4.0.0 | +| 126 | OSD_3D_MAX_SPEED | 4.0.0 | +| 127 | OSD_AIR_MAX_SPEED | 4.0.0 | +| 128 | OSD_ACTIVE_PROFILE | 4.0.0 | +| 129 | OSD_MISSION | 4.0.0 | +| 130 | OSD_SWITCH_INDICATOR_0 | 5.0.0 | +| 131 | OSD_SWITCH_INDICATOR_1 | 5.0.0 | +| 132 | OSD_SWITCH_INDICATOR_2 | 5.0.0 | +| 133 | OSD_SWITCH_INDICATOR_3 | 5.0.0 | +| 134 | OSD_TPA_TIME_CONSTANT | 5.0.0 | +| 135 | OSD_FW_LEVEL_TRIM | 5.0.0 | +| 136 | OSD_GLIDE_TIME_REMAINING | 6.0.0 | +| 137 | OSD_GLIDE_RANGE | 6.0.0 | +| 138 | OSD_CLIMB_EFFICIENCY | 6.0.0 | +| 139 | OSD_NAV_WP_MULTI_MISSION_INDEX | 6.0.0 | +| 140 | OSD_GROUND_COURSE | 6.0.0 | +| 141 | OSD_CROSS_TRACK_ERROR | 6.0.0 | +| 142 | OSD_PILOT_NAME | 6.0.0 | +| 143 | OSD_PAN_SERVO_CENTRED | 6.0.0 | +| 144 | OSD_MULTI_FUNCTION | 7.0.0 | +| 145 | OSD_ODOMETER | 7.0.0 | +| 146 | OSD_PILOT_LOGO | 7.0.0 | + +# Pilot Logos + +From INAV 7.0.0, pilots can add their own logos to the OSD. These can appear in 2 places: the power on/arming screens or as an element on the standard OSD. Please note that the power on/arming screen large pilot logos are only available on HD systems. + +To use the pilot logos, you will need to make a custom font for your OSD system. Base fonts and information can be found in the [OSD folder](https://github.com/iNavFlight/inav-configurator/tree/master/resources/osd) in the Configurator resources. Each system will need a specific method to create the font image files. So they will not be covered here. There are two pilot logos. + +Default small INAV Pilot logoThe small pilot logo appears on standard OSD layouts, when you add the elemement to the OSD screen. This is a 3 character wide symbol (characters 469-471). + +Default large INAV Pilot logoThe large pilot logo appears on the power on and arming screens, when you enable the feature in the CLI. To do this, set the `osd_use_pilot_logo` parameter to `on`. This is a 10 character wide, 4 character high symbol (characters 472-511). + +## Settings + +* `osd_arm_screen_display_time` The amount of time the arming screen is displayed. +* `osd_inav_to_pilot_logo_spacing` The spacing between two logos. This can be set to `0`, so the original INAV logo and Pilot Logo can be combined in to a larger logo. Any non-0 value will be adjusted to best align the logos. For example, the Avatar system has an odd number of columns. If you set the spacing to 8, the logos would look misaligned. So the even number will be changed to an odd number for better alignment. +* `osd_use_pilot_logo` Enable to use the large pilot logo. + +## Examples + +This is an example of the arming screen with the pilot logo enabled. This is using the default settings. +![Arming screen example using default settings with osd_use_pilot_logo set to on](https://user-images.githubusercontent.com/17590174/271817487-eb18da4d-0911-44b2-b670-ea5940f79176.png) + +This is an example of setting the `osd_inav_to_pilot_logo_spacing` to 0. This will allow a larger, single logo. +![Power on screen example with 0 spacing between logos](https://user-images.githubusercontent.com/17590174/271817352-6206402c-9da4-4682-9d83-790cc2396b00.png) From b414566b00c96c3562f08578b55166d9f9301039 Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 30 Oct 2023 00:28:21 +0900 Subject: [PATCH 173/175] update vtol documents --- docs/MixerProfile.md | 143 +++++------ docs/Screenshots/mixerprofile_4puls1_mix.png | Bin 0 -> 21457 bytes docs/Screenshots/mixerprofile_flow.png | Bin 0 -> 24390 bytes docs/Screenshots/mixerprofile_fw_mixer.png | Bin 0 -> 321288 bytes docs/Screenshots/mixerprofile_mc_mixer.png | Bin 0 -> 403235 bytes .../mixerprofile_servo_transition_mix.png | Bin 0 -> 19083 bytes docs/VTOL.md | 236 ++++++++++++++++++ 7 files changed, 292 insertions(+), 87 deletions(-) create mode 100644 docs/Screenshots/mixerprofile_4puls1_mix.png create mode 100644 docs/Screenshots/mixerprofile_flow.png create mode 100644 docs/Screenshots/mixerprofile_fw_mixer.png create mode 100644 docs/Screenshots/mixerprofile_mc_mixer.png create mode 100644 docs/Screenshots/mixerprofile_servo_transition_mix.png create mode 100644 docs/VTOL.md diff --git a/docs/MixerProfile.md b/docs/MixerProfile.md index f6688feaee..ec8685d0d4 100644 --- a/docs/MixerProfile.md +++ b/docs/MixerProfile.md @@ -1,80 +1,30 @@ # MixerProfile -A MixerProfile is a set of motor mixer, servo-mixer and platform type configuration settings to enable VTOL transitions. +A MixerProfile is a set of motor mixer, servo-mixer and platform type configuration settings. It is designed for experienced inav users. -Currently two profiles are supported on targets other than F411 and F722 (due to resource constraints on these FC). i.e VTOL transition is not available on F411 and F722 targets. +### For a tutorial of vtol setup, Read https://github.com/iNavFlight/inav/blob/master/docs/VTOL.md -By default, switching between profiles requires reboot to take affect. However, when all conditions are met, and a suitable [configuration](#configuration) has been applied, `mixer_profile` also allows in-flight profile [switching](#rc-mode-settings) to allow things like VTOL operation. This is the recommended operating mode. +Not limited to VTOL. air/land/sea mixed vehicle is also achievable with this feature. Model behaves according to current mixer_profile's platform_type and configured custom motor/servo mixer + +Currently two profiles are supported on targets other than F411(due to resource constraints on F411). i.e VTOL transition is not available on F411. + +For VTOL setup. one mixer_profile is used for multi-rotor(MR) and the other is used for fixed-wing(FW) +By default, switching between profiles requires reboot to take affect. However, using the RC mode: `MIXER PROFILE 2` will allow in flight switching for things like VTOL operation +. And will re-initialize pid and navigation controllers for current MC or FW flying mode. Please note that this is an emerging / experimental capability that will require some effort by the pilot to implement. -## Setup for VTOL -- A VTOL specific FC target or `timer_output_mode` overrides was required in the early stage of the development, But since unified mapping introduced in INAV 7.0 It is not needed anymore. -- ~~For mixer profile switching it is necessary to keep motor and servo PWM mapping consistent between Fixed-Wing (FW) and Multi-rotor (MR) profiles~~ -- ~~Traditionally, FW and MR have had different enumerations to define the PWM mappings. For VTOL operation it is necessary to set the `timer_output_mode` overrides to allow a consistent enumeration and thus mapping between MR and FW modes.~~ -- ~~In operation, it is necessary to set the `mixer_profile` and the `pid_profile` separately and to set a [RC mode](#rc-mode-settings) to switch between them.~~ -## Configuration -### Timer overrides -Set the timer overrides for the outputs that you are intended to use. -For SITL builds, is not necessary to set timer overrides. -Please note that there are some display issues on the configurator that will show wrong mapping on the mixer_profile which has less motor/servo compared with the another -### Profile Switch - -Setup the FW mode and MR mode separately in two different mixer profiles: - -In this example, FW mode is `mixer_profile` 1 and MR mode is `mixer_profile` 2. - -Currently, the INAV Configurator does not fully support `mixer_profile`, so some of the settings have to be done in CLI. - -Add `set mixer_pid_profile_linking = ON` in order to enable `pid_profile` auto handling. It will change the `pid profile` index according to the `mixer_profile` index on FC boot and allow `mixer_profile` hot switching (this is recommended usage). - -The following 2 `mixer_profile` sections are added in the CLI: - -``` -#switch to mixer_profile by cli -mixer_profile 1 - -set platform_type = AIRPLANE -set model_preview_type = 26 -# motor stop feature have been moved to here -set motorstop_on_low = ON -# enable pid_profile auto handling (recommended). -set mixer_pid_profile_linking = ON -save -``` -Then finish the aeroplane setting on mixer_profile 1 - -``` -mixer_profile 2 - -set platform_type = TRICOPTER -set model_preview_type = 1 -# also enable pid_profile auto handling -set mixer_pid_profile_linking = ON -save -``` -Then finish the multi-rotor setting on `mixer_profile` 2. - -Note that default profile is profile `1`. - -You can use `MAX` servo input to set a fixed input for the tilting servo. Speed setting for `MAX` input is available in the CLI. - -It is recommended to have some amount of control surface (elevon / elevator) mapped for stabilization even in MR mode to get improved authority when airspeed is high. - -**Double check all settings in CLI with the `diff all` command**; make sure you have set the correct settings. Also check what will change with `mixer_profile`. For example servo output min / max range will not change. But `smix` and `mmix` will change. - -### Mixer Transition input +## Mixer Transition input Typically, 'transition input' will be useful in MR mode to gain airspeed. -Both the servo mixer and motor mixer can accept transition mode as an input. The associated motor or servo will then move accordingly when transition mode is activated. Transition input is disabled when navigation mode is activate The use of Transition Mode is recommended to enable further features and future developments like fail-safe support. Mapping motor to servo output, or servo with logic conditions is **not** recommended -#### Servo +## Servo -38 is the input source for transition input; use this to tilt motor to gain airspeed. +`Mixer Transition` is the input source for transition input; use this to tilt motor to gain airspeed. Example: Increase servo 1 output by +45 with speed of 150 when transition mode is activated for tilted motor setup: @@ -82,15 +32,14 @@ Example: Increase servo 1 output by +45 with speed of 150 when transition mode i # rule no; servo index; input source; rate; speed; activate logic function number smix 6 1 38 45 150 -1 ``` -Please note there will be a time window that tilting motors is providing up lift but rear motor isn't. Result in a sudden pitch raise on the entering of the mode. More forward tilting servo position on transition input(you can use 'speed' in servo rules to slowly move to this position), A faster tilting servo speed on `MAX` servo input will reduce the time window. OR lower the throttle on the entering of the FW mode to mitigate the effect. -#### Motor +## Motor -The default `mmix` throttle value is 0.0, It will not show in `diff` command when throttle value is 0.0 (unused); this causes the motor to stop. +The default `mmix` throttle value is 0.0, It will not show in `diff` command when throttle value is 0.0 (unused); - 0.0>O&bezTNRyQG-`*guoVSrul_DW2kD@%WASbS0c70*! zPC|0E?dzDZ`SW^;fEN_w{R3;xG|&u*k^QvOFR?R7_s;Q(AK8d$Lu`OtSH-D`)8#Yh>R_pt(a z_JYA9o$=@<1uF|XF=L~7V&~`^XW~M(UNW#o2L=Jp3$cwO{x4;XRq9jry#SD zs+VH$>G$-nc-+Ss9a(H#LbrBBH!+w>?eo(7g+>V^o9Yu819r1KQNnIk)4*f?NZU4L zFM9-kQ69OMPw2OV^8;=ymX7e-MJE#jLP%6-$?&)E&W#nG{^D4j0MSOI-*(P>t%XCQ z{i1Nett_j4*C{`zfE6}VKm2Vc*Xp}Y6P0y)b#LH8Q7~Ot#%RUN>~5hW=z(f& zH9qt+Jkm&&G~;oJ+q;I*%kF)E z11LWLPvTI!(>#_f2S3T!7wfZ(G~VxZ*fqgCZERe3GM#DT6q94EsTAM##y7733{llx}*2~BqD;I8_ zH*ql{#;~nx0Or>aNsJ(5eAT}|bHa&?I8E<5)~kZFQ31Ih&ZR=JMejR5g0DJm^m0eL z8`y>EA%|DkWbNNK&Dp2}3uB_5iPpu;(Ls7W6YjeG5RT}dC_#ZQV|T2?trqh)?ux&Z zMpq~_w)yv=>LhKU6mfwgW-WRfzYin7z8|Cw0l??ejqnr3K2D##k`SE!KB~qXT40f+ z4Hd?NL0IKzEl?a#h!D${jvw#WUUt|k8nD;g=ZIj~4@nOQ2%!^flvX`r+RL1MBJ)mp zrUZ=wQlGum1qQ67AleC+Z$2g7#xA9tHc9qlvZnC+sw|Do(ic^2AF9AY2{kX$rE>P~ z*VB~MP9_mRejowgCV(i)vT&Y0ljB99)q$TA0} zo|?&(oQ}7ZdwO4%taC2!hYO*QvG_PPy-Ir3jzyaaG}Eu;CWKs(Z1O+xOo%%K5b7vbQq~_0`EsxIs-GGJeo*r(`t+USqiH5`a!hbXTzun*8 z4*0gayBh|?fs*heXrOOF;RbB0iZCE?o+K{xFswxec;P03e_I12s9!Vcf!2S2U(A0i?x_F_G-F4Y^TJ&# zsJp9ws#Kx5XEXO`p7Za10aZ2!hK+$_K|NK3`gy9dsXDN*Y@F*(FIt*ID9uG-HfSor{k z7_5ZlbiH2T_15EjL~{cUp1tJE_j8~GnpXgEc$|bzv=5HK30RO}@>FN&mcxE0y`(E* z*U|JiJe=0cBisyX_7vowtY_5aU0<$_w06-zx=no?M#-0GC5V9&o6G3IPlXjqYh(Nk z3;|PZh9f4?;=ZCZ@?WrWx_KG*O%(O#AoV4;H&w_Aey){DfJ1F0?Pr7xTyDXQzk9Lx zg8bbU_29_LR5mqWR%(ZEtl+EJ{oZPVl=|erhNl0%>DG=L@?b2mAGXxleNIO~QFLe8 z*Bt4(_XpLj08O5#7aZO^EH0rR_cwBHde?S4(Ls)4U?2G2itA@oMiC^`Gf**;7zqXX z1HqLX0L+wMz$uN6nP;J`WV95WRDAb9$4LYld1z=ciVIkdYd-YCoz~&|NejlmTN%~$ zg(Wljhyd(H=Y9r-IRxl{&EeML4=q}Az@^O&nu?0aPHkL`Csokt7+U1@clt~h`c3js zqQrO9f25OBvv(rQ8Cc|xQx}t6k~b@|gITXPZNO0_<_Mb{ALEN2E)n$$Ya$@avJ{VJ z1L^v1H;fN<%~rMH^(D-uMW9)yzGh>|TdTb!^K>`B88dna41Yyx&9tAAIDV~ecQFIW zi#)&51YV-Eq|-meJk!yi6H*j6He?s|@7rx28I{~EsjK?75DReV!aCz>J1~}IJQ^&y zPJRk=EEQW-wt4BEicd|2S3L2PRTmGC7#~wxd5+O>4dAT_+0bV5oRRx|bQ3*{A2lei z<{R8)?Gqt$DB14MzcVgD)7v+dDWNwN0Q;&&aW!J-IA6l$+s}X(NArqxn5&>j$P`3P zSTIG_1nn=$0VW9BTsXOBwQwPC^{M`J%Mcv5HBnb)^P!61z+-CBr;?Owmxn-=I4E%U z`-};(U{mTaO)9hz14j7J)jEsOf;j(`x5H8?JjVFaU|h zFB?;e3ksfGE1$e3;a)Mkw+0mzYVgVfeW&5Gr>kX?7)FS4z&>;~ARt+5H!`sG6*ZE> z%NvdO!p2k&mP1^GpLFgog4FJkl$Pm<)cHhWQhZF!ne4NFHmz}VC0ohKwFAV9M@tEE z)TtKEx<3BAV?BY}2gN>;6TFs5s?%>xg~!9nInnD;m22yJG7AX)6D{CU?*$F7dpNVg zen@W4#@uA14!*;@IEaa|>e#=i@dzi1<*J8Vh-A>-n=St!Ecfv>2cYkX)2zEJ&pn^Q z41P*M+6h&~H_`Ul_a_e_+N($QLvv68!7(S4DWyAa3#?1y{r;Hsbx4jqN4C1+W$ zj9^StNb-B5!);!jV7d)`B7J|q?WmBPZe+xbXXaI7QHojrn|v>ReNM*H6{g@OZdJn6 zNx7L2rrJI#`2NN96H2Xp)jB}TjEL5O-AM#UCdL_C(e@U=Y&O2>OaUtcs>PdmE5_{K z-&j%SKt^^Iis^sc<7a8%jNBZd=RPp-sz#!8kP#0b?0-Njv^280Qw24!}0t zt1;F#@WX1rZnikq*1gb8W|GVET_p)gGxx2$?aIfEqYs?oZ#LCTbD<#VntDBD1mniW zA$z{70g#%S&7q;e7eLK6m)Zw_aE0q$0x& zi;x)I@O^7A(k8CR{L8)f?(x`_i`Z_FXUbF6@<^qKQLz)ey}z|uesyEcYli?=TT1j7 zrR_+MH_mDL@gh0bIkp|_Ha0>oLpz)>-J zJu_+V zM@0vN@fJD2Dye^;yIj{H~){RB6G|_lI=sHO|pfoo^w*?;+mLI?eIjJcF7@ zx~XgkzbVfeC-1P)n7aJYbfxi)S$wZL?L zBFt{ar2EBC_x^o*`p3`7M5}eTqw&~|t$X5)6;l`HbpQbjYxw;qTKL8Lv;hxP8J~*q z-wxfQ%p1JfY0d#>R4?lh`56`G6U&`f*h5y(G#Svy#8Yv~Ihiw{tR}r_jIVEH8ayf< zZY@3F_|`Vjudj0zxlX*ixvG&+WmPeXYBe9~vH5Jih5MGYw_bQE)s&A@d#%P9&fX+YF!46Hq1t*ODTb!| z%V?@6!d2sgPb5FGvMN%u`8(NWIL)~N<6GhS4pY%=VYeQcy}=r#da*=Lc5ZZ^yAF4N z)^uP#X}F#SuL~_0r6Pcc65wEU3J4E<)h#O z`E$i@Y^n#F0EFSGRSFZMocO7O4cn=62MyeP?A&y`)R}s^7z}vDDA7%p=aoDXzA=Vq zEy*vYwehc5CG=h)!ydmjb@lwhMS$EPX{wYW%vLEV7z4D2KeSrchA2Ti; zRUQRR1VB#bnfzBDnp#0Zx$@t82>VwaX0x+4jh9q4yp-z%uFy=Jq`zuV@%|lo1 ztKR3u1#aZ*Vs*+R`v%4^m82^E$7bvpI}@TPJsezM z)jbLeH$_J)6?I#ld=P>BQeGxuWY5V~OiT*0)jLpgSAki3_2Y@mq#As>i%`dHALkY> z%}&bz=R?nfq9HlZyr?QIf9w7Wf(gASs}*B$QD1wQyf8hU?BTvE_EJVV35nYOFXH_F zwg}M&pIJ zcCMMMaVZ@iHvm0&H0X&7m5gFRj7S#1TC|KY#~U9mhlvsV02v~qoZq{uC2+;V64)1Q zs{>w2g&$icUL=1UT%Uv%i7`j{vyhM~N=XHIZjM{bQO6A`PN5`EMFI-630Z1n%1)ze zj0+2OVuJDMeH2OQ{WaM+06F=O+FF7p0tL}eGU|q|kzRV8@6V4)vqO`TJJk@5kVjc+ z_)rn5hfv*&RngQBM5T(?jzw4B5N71$|MC9gwda}qD3d!>b~&g6zQEg(Bj7+yP*6Jy z=5xyZzuHTH-uOgtX0KRn+Q##tJ7jCosPO$kL4Di)M74AF6H0w<5n~NHHaAEHNrn=h zz6I|I%nJ4tDxNQlr>++`9Tl*lpqdjQ?`-eVb`y2U7OSN125$69P>tbWE9pBDL6s#a z`~Xeep>7nG+Kob^r}wf_@D?DSXewTJ@_ujAYQ4tk(~~Sa|JZ_mA;5<8+~OyS-e&$a z+nuy$MyG>)A_hkvgFD1I4$q-)&~f&PJhZaf*q>ACi}m$v2p$uS#hAROOzW%18&IE! zD58!7Tv3&himGKsEp$FVI7vwa9#ySS&8<}~BO0DB>GzMWs9h&jOj$Lx2vLO$hJ~ix zJ5Q^AD9g&mX0LIgL1*F*e9~sFIT)>|HVSir9z%3 z6bc{qG9>it7fFeuD6c_Nj&kXqKswjnu4NSbYu7eMj^+NAm)JB|CfaO(V;jNT_kmgh z%&E&pej0L;n~;0R=2tMmXB+2m+0vcPUQtziLOMooz8WLM6z3AmocqOIAl?A{0|k4DrN5bc=J6J@OvT2D)-TNPfh31%MZJi z@IrSBKB}4oWtH36xy(ahR|MT5fkuj3RUSBY9TVcjn*KIupYvRAseRYp(tgv= z;V-(UN8T>P?@sG8B#;-`mEaIl+50V(uIhB;O~u{E^!5W^D0Pn(WzjCa9Z~VPyiu;| zwRCW?!^bYXK|}CTAdi>N**Tkddwb8K#U9*#>aNld(^OINtzCO=t%F%w)Qe*? z97N1E;WJ`V`LR=Qe6v@q-j+krk=b?6f!CS`%z2LLLx&gLAmpiFz-xU>n3IF~BaWy3 zMMBO~5Jx%i*t;!z7Ohhshqi{V*G!WW*Hm<=f-0l4ADs!}Hn0zU02s(&Ifm69*4)ewvj6>2V&I_>X%5)eM42@hggnD6)o>%p z_`ksS9S_nU=S*6_{Qgj4ST$wh!ge$AKlqMlfMouEkG|Np&4PY=R7-(^K1E!SK?hY%DqRTsJMXkcb zEG#^qgixj~`P5MMMu`m|(cx~m{RFdX{_8@9N4=J|_anm!y zG5ms{)~fbX25FL@-YS=TAV119GZS^d639g4Oo9d|D6bj;^RtO9GkjbbXumt7M-&NG zAKwlV8QCKrNSS-rscPnQC2A>D1jC0AC_BoL&~*Q+7n>PbyZeMLE}1=%pNWIPWPTdo z-h)K}YY-p7HHhlYxuJvGHW%!N{>ro$(?+}*&?#1<4;lW&v_Uq&;HAZ7&RXD8&GZS% zm3|NFjE_kChTFi~j21)Cu8_mhRseRwg;21TfzJt;2@DS)Op4G6S86i;g?C#XTU74R zHm;~-FZ`2t5ubp{k-cd-?e43#$1+cmFBcdo7!EV1fn|{s8EI?=Jc|_Ki?ruR82*^tZP`11 zSS!LecogprsMY@P@qy}INm*;Yo^87fk&jbAzS%cuXaqR|3MfjN)RGrUIc&eP*_6=T zq(9Y5-&y-E^6d@Ew$}&8auRT?*=&@q3Xbd zs@m&th9&YctqfLKc`V~bcd%Xq_gK^Q?xxpC7g#%rjz49IU^hCod}!p-Cgi@u zpUkF@n1x+}ocJK6+peUA;Hs8u$8tGq>}8EXSBT+G2eSk+rl;vmQ0BXr9|xF=w0WyO=c+E`hg&e^|Y6GWqP zws(tPdzT(R3n4U`Yp*)$Z_^xhqZmN=#6!(blbkjNF;&)~^834H2DV3E1C+w9)T{yv zUbb9Xv4QBWwVE+F^CTt-%PNXz)7`RPH6m2SOxtZ7s26-IESs$xEF)b@Xiqr=q$HeJ zq&O#uV2)7b>Qw`VzakHW(og6rqWld-x?4t=yZpvfat#+pb#ijfV0bRhC|O>n4%aW~J_%@b?B zJ!h|5PpEYkFIsBkCpb-x6G}^Q+ejYcO?63y$j#NWVWuKNqPij@8V zT%{>Z@&r1%ysqQp1AI!)h*uAsb0V3-Zq~?2RF<>O(pQjQ#>`2sdp0$jiF3}OIsRhb z6HQZJ&V1Ff-9zW$Zht4bIquf2%>6PY3~<$^A@GQIW*icwK#&vFj5Q|(;2`ykz z%CYg}Y@^8A^{-)JVQDu=F5O<$c5%OVVS)mXBENJ-MJqUnOp zin|e;`7AYulCwR|{dWPK=7QY&Gk_r};Pv^RW`N&ye`z%VqcagS79~+Q6HZ_Bh`p0D zq~1?s47Zgxa@cj7*lxHRY)uUu0Wk9iYuzqa_-{0=UN&XnM|Udf1329M?6 ze&bbF&HD$@uiKhNM=!+bP|;J_=k|h}1wN3FCfm)ah}ulnKPRe@ztrHM<9;@a%2(Ee zk>z>_QGIq_*~z?n{@S{VDE$kWN!xmS4@)OC0AW62_i{(UKYR7B?HbRS+*ho)IQZ3h zZA3H#idzid%9=OgjaBOxxJ=))>tee~PcsLG)4U7hxCMIz&Gxi_iX_j;o=-8kYOUEd zI3(y+UZUk@@w7WBN^7`K0-%Ttj|DAz&dPdQ^Tmn6lKmM<4naNQOa7!b!0s7v-PPnogtiJuYrJ+17)x|t0H$>6m?&x^NdghbVcjQbxjNYDt;Y8{sBP$?I*7%C&dAX8p}{mA9hXc19tFbz3^|+QNnUWgovyb-S(4EF6pNf2v{*O z-J;F9s|;)4E-nMp8SQ-4{_t*fBfa3q4_T@(mcrnoQf=!aZVIEau4IRh_K@cIwFY7D zMTMTd={h&EWQR^^a&t+O^lxvyx004Vz;(#y9_vXBhR#jSADk^RmeyXl9O94{IB!F!s%_@s`w)=@M^`*ap>*% z@AL~WL}XrrZi(q2=H!epP^Jcx4DqbYQ2w|#bGLZ{PS{rbo@j0zTlvv1{#2@Emn_a% zlgM0gPai4iSEk)BdI|wl!TK3Xb*l}3Y$@VHJgZAueUQ(|uB4gU_0#FEhj9m%%mqGG zX=YHK{zYdjg3;_ET9aRkUs-Y44pC|i*LI7uYkrnd;PiSCXt#mYmNpy=^IDmFDm{^S z1(x~atsu)|9R*3efs#x1C;oblaifl@*h%Hb`D2|W3EwbX9Dz{Nz9Jp3A znwfq;{>ezyZ=91frni9LzrpnT8NjVLYt9`t{ZF92g)-@IfW{gv|rTS zZ=2<+IOP^Hjg4h4TeLowe?(sU=jC_E;BO~Z+ zha`w|V?ij2fJL)f)1@lHt^|dq=*ku482IMkC$m{fN-CCNb;alfcmoaHl|QmhilGRT zapgA1$_<)O4zNPiJ()feWQJahD9_C4WjcL2xG_D0&iwvz?mBdCrl6?TOStr#l2>y| z7G;2YL|r}b%q%3yyc%NSP{Pazn&&(O3){ps0lkZYU!^8LqiD2E(dvBNBiLnVJ>5rP z6o?R>_?koswdn}q@_UngSR+nMp7F!>bW`pFI&i_Z<$#A~-*=i5L>tdci;{*0F|=on zreUpH9)9B@$@w~~o&-(_iAN<@i7sDYlf;?JmqT>~R(Xo^o7Q>)y}joS~y%6!?v zD-JoVe8ZX~zdG=Yt3dA87wS72ZV(>GkOY{~Y-H39^AMfPL#~w=$n@b0@R*Z+f0s`AXDIabjL2@EQM_#X0XagY}1J zCpEtx{c-Sl9%`oOedtwiLBUVXbMIQN)6(X`Ax4}PG8aL)r{I2HqSqX#b4YYckfn$b zJHWtNf%aSxWNdvh<5UO8+n_nKO3gL`@c|?*Ua?t=oG~ z!ChX)m(wERZY@g5T)H!u?8*D}W7Uu+E>ZH#LTV;@D~nNB*}mWE=AT_t??i}^jgE$O zx=FuBrtP;New)hG8GhY8p=YrFg}%4{LEo@{(zjhdEko1)j=%9=b6jQv%oY0AH&t>D zl4ugn&mdKZQjv6W>)oG*cpLG*R($_?(jV99k^*h|hZdi?SDj>~0?M|j$Rm6;wvi7hC7L-ObX(c5+s{olR?ldZCtC!KEy`>Lv|hUcGOm9SVcde-ve|4X>oU z^wDzBE1OX?JH}v*+bGkXrD6in=N-E9Oo5~$DeGNE8YacbGHG@s&+!UVOh+Gkb>8fd zsz!R|54FhI?=rS?HSx_R%ePQaXd?S%@=i^2bnm-Hj}c^WAL|@!29Xl2}tjAsS?*ntfnK3Zkfn9V4q$xy|$ub6XoES8>f%fwC66 zkHfqg+qst!tDa%MXu-_>p1MbF)m_8(Zk@qw`rKUicwe>b8=;X}TVGFyhcTcJ6`6GC zZm7$L3cg$UQlEG1C0-Ro24KtMW@WG2cxskGztpfp6Yoi%)qR7Rq@Y_$II|;6U2wlD z3CXojz1xO~J+;JQ{5i20PZ;4OCgo{j8-&RCzW_nllrnu5XdN!JR*@#j|8~L*YK{o|&da2=z)pMGzHl7I6 zDm^zdDv^7Ffq(SAd$-Q^&>0tShJU}SyUY%wLgj3)7e%%0)MCmr^>J5I<-eu?)(a)x zNAhXkppX&S*UF|5ipaFSj+pc+^YY)395z%N7f7i>m$0;_y3q)!Djp*t4uAD3&k)ct zH#j(0M?-^!H|`2aljWba^={``ZB2hxTjxm3sHPO$;qLj9!ioAq2dM|C^2d2H$da7v z`8zAMQbsH0FK&H_7V`dRZDDfre^8Ny1V)JcUNn=4Fe^qKFw0G>zjEq`^_NkgE=aA& zS3&`ZHFIi|r}jV2(=+n{W5o}WUV&7i*&p`uhSvPD?|(bgnncE|==rBfT}PzM%$@nh zd&Gv*pb+d8F{@GVW#CjsfRS$^udao2i8jSAJKwW@Dbmsc#_^jeuQPD`#a92P7r(>w z-*v0fnF(C_b)O)zL;t2x_q&%cWBIaEYFrcg9Yy%eue_qBNCPzm)pRuB0}*fMBSvD{ z^29=0l)eyo%D%$c?W%O{jw|i?5C?@Rb0r|}T@O+c4TV3nrd}kctG2Sedv5(ZE4fNS zGD7vst{%D}bnd(etbYeejAjs5|CD)up1vk$W&Vpjt|NxHWHc9`$ky=eq$9}m!A`k) zB_`k>z&0Q_EcualDTYuR7{^w#lK^a?NL+G>-%8_d7nLK?Fn@^L|Gc$O0>)q z()4FY@=T3$S~Zo+e)$C^{jrP__RveID3WO5=yJJ=NL3JAigDC0%2&wyo!~+H=~Xx( z&S6f{ci4M_q&9AD6~i!?u7SaNTnqibCGkJJh__+puiPATIrTr4Anj|bGuH=_Dq(s* z@gdlA{Q=QI(A`)NP~o%j4&rwTp~cwPw7MPh3TIH( zI|~&enM5~nO;_0<$>pvhH6SBv@1@NV`?I*;n zlk!vtlP$TkRGeuy2{!ZQx2yB$rH+gg7iN^T?pKa$Qvr|>_IMlrs z-s%+wT_c(I%^1)cSw1z=G$~$0uh~0^oy*JOXSwshF|BAOUrqmDEUv#&R@UyPp1s~0 zC!%?{aA0vJrT($hlDVq;>fN$pZC8^tG1i(rwr+mktm)+bO_*z=r0LczG>tG4PJGa3 zLcKDS%mD3j2D;xUzQ{%}|W z3H>s7zfNCyz1I1gRxA`=*nVB6S2kDvOTCFpW20xbrduOwnXn9GtG4=n%Z2*l76Ob5G+; ziM>ZIOvg59E2m>aO6nH5@XMz*(69q~Vjqon+hx+vbh5J^Tlema=Uf{UCJ!k9tYv8t zc!vv1QS&R<&CBHCX<1)ztF}8!PdV3OKf4X^E%{zk(CZdIwqO!JJjau`_i4unu6a< zL%1#xoAXKTJo>HYd!}+eKVL)*$)h9~EutvFph6B{3EfG?0h@3nB@Sl~%L!qr*Eg9QJ@$}Bn@$7}2fKRS|mmoEr zdq>xd1%!vn>l#L`8P#`Ij$AW7FY&h-%NKyy?f*do1kp=qc(oQlR;3@lb^2cHP%L}s ztIwf3sdT5C zTsX(WJldY@VmGHvlsC)XEA}CN0!GJtrmT$z+94-AN^=szN_r-MD*b`G`3if>&6Ub> zbj4#EB}LI^;^qn8KyqOU(bD7h;(Eqy0=$=MEXr#xN-vo;_YhsGz|6o?qDx6^g|NDy z7S5!>)@(Hw_(K8=MQ7g}k((FjMZ2<1yKI@3)cU>CC_?0_p{U>I{|tzisFH3!+}V+G z0uKbi059vO`DR(i7M+y{OD?p`^u_lH4RQ;6*}D6?WL%Cetp@of3evhGY&z|Eq&D9P zX3=ZiwG;uH8C(oQX6@bD8b;}1_l=DXn>BXcaj&G8Yqc*y;tguoUCEIUD#6QXRE{rD zW<1`z^w^E~UoK$bTq!zB6htF*jwHf(Ii6C-F`#m&?z#|}%!&Uj_8~8uXxM5R-&G<1x#4maO_GfuKX=|C&6fIzq_=CS77@tl!!pgE0~Ypy%2?= zG)=$yG)CK!!RQ2t=z;&tzspwlc$WX2{WN9S_VWM4dtw;)YLprDv*%|_Yb$N{m?g5b z;i1(^sKKa?sEjH};JhrHaEbj_%7Ni_y-*@Akb4s|B`=;TU~m}d7y`M0%or;B-nQTC zV>4MnXtZPSn+Ts=RJq9PAo+zEY~z5b*%3k{e}At&9)$_h9e96H($dMQt(?$?6Wnd0 zu9`c0?D9G4zH9bPz?dPu5{si4Gi#0Gk?b)%FvC&UETI7qBG6FkBMgID5ke1bx9Rps zg@0zh>4JrIs-2WsFQr8@9M5Y>yWL;)tk>1hm{<8e*4re6n@%KZk8Cxva7hG>pu)T? z4~6dBxtu(8A(1RTImW~-*m8y%yeW?n!s%id1|Su$EB%~mIC(TIo+98=c7d9?IC@O7 zB(EM7lG}*3HyY;0zU&LHYwsmqF#zl2bL>3SaJXtW$=X)jc?A~ITtRAGz4r&KZ>~IK za)JhADC8TyibqIORi2g{Pt8s#ihFpXH}OV3#ce|BMS(7mp4pprW1)x03%)b&1vg{t zQVvxo+O7zl4jCP?M3s6ITJ6|RAPp!qVh5>UWM$20K7yba{;?p)I$)FQ{MHfd8GrIk zYasxV&aX<(W*F$OPvzrh5eAJg#J>Cpb;>)f)>=b;{JylmsK*}-;-M^Fdx;K2pH3L; zn)IEroP1jiJo?5@SZ=OSR%WS}y04s$OKI!>5(~^{=9;{KD~AaLuGFUhpqO#wYU+K& z2xjJ~IU~W?2Wy%ary~cKZxr^AX#|4ALc=!AvTT$hsVgNV1)4)vtPp!C&5gdBN6!|% zLF0@wte9adjTbyOX3S0VHz;=n(enH*DYG*UbT&4eMNXnn!El4!rsPr_s(EFkO`la1 z?SX5I<8n%@^porC*vjkQJCuMo&FqvseSkKH&?}>AylV7aY}G8`P5!>9@$&bvhLVqP zZ!SLT&~? znVaWtZVVCDOO7;F@`~Z`!6pPFU16NQ%V2IZ^~jzwsIYXe22-P3hYy{7=k`8*tk4)Y zS^smkU*XmMN#WG!Q{NEgX4|^`LEkzDgCsBUaK6DQ_hP5&MBX>UdtKG(1DG1yrQ90K z$x)<|cbm`j#ryl%Id<-jV)tTb|3tW;;L^E>6Q{Uzb4NT+4V~r9>C88je1k|rQf4*F zT@C<@89=N@POm$(RFO?M1V*;X#-Z(ZV ztx2dF9*O|0+tYXmeOjI89#golqUw<1;)3}o#ZG0;5aa#D__6gK#ZshKVmrr(NIu9E zpZzM`r>}58!^OWTJ~NrmxYIqZvJc7bgDlR*KHN(xnHO{&e)Brb^`VtPY2KSajVT2J zcxtIF4!U}4#??J6KWWS`H0%&}xvmy; z$xs&&;zMd90bb4fBRDU+JLWl%nC0cyc_2_xS((I1n%Df3Mz&R1qC0*lIiL>2Ui_VR zO9CHBMXzO)ZfS!=ScNCxHW|8;3M_WxC&y}vqr^tNp5jbtG@5OERKkbPH0muxnQFy1 zrHMA0s@xajerxhdjtb|(qZ{L&?ab%XoA7MOL$%w<=)^UqRV8Yz>ZC&bYoFI2E^##9 z)UHs_k@x?>?HZ9bbnsTgofJ2Im_EEtqcsQ~U|)%F5U^`Mk32pYtcObwc74{44fG_% z4PYq}rRt?U!%J&w`akC+pw(8*_=Y(qYiau=x?%;ysjWjYBk)tw6Z0_@qr%IpZ6r07 z1oP^HKren6&HybDD{(aXhxjo5$Z}6lqQo72iSwyzf+_W5Iv1I^!}59-v*NjkU5SGc zj5kPoi^qE_uV(K9lkKxNX0<`?$Z!TPOk#>p@l|5R=q|{!JYWRqe2zXq)=qL{liRDMd&%I_I@HB2Z;g2iubeo4X4nKWQ z^eyU@68QGU#{r8%i2$X{9vxd3F`;^)z)sXp|xG;pS7Xmnb8ie^1%t)7)G3 z9of$M?*7u0_=i@w5nRSUR9U&kX{bYxrJ!@38UESb7#Ke&!%{p^5a+}g?=n+^GobLY zYiEg~o?_hlN#RS?*2eh7U_-$lAz(Cvb`DsU(OKhD85qp~}MO>0oR~C{$j7lGw&4iSTATbSY z64!X}eyu49n`wSlTM2q%PgcjTbr_pLmHNoXq%U&VW$$;T@aUBpl;m;a5W(N`(E{ey z`#)PE^RSw!AqIj_qb}bxyGjDetX(@9#f={y%wJucS>di{=BlL9(h1dOG2XCjxe_5R zlH|0Nb<&l*Zw^#j zdEn{Y`m>t8nnd&D!(~l2m1O1yVvjzmsN8LDw)gZAE|2Z3^)nmZ?y0VE`cxU}r>($> z9~AZDTMbo29HCcy+>!PX%!6YhA&Cdghu`x3r}eZ6J1h_*s1kZ6^(7zDH;duzk|V31 zYq&g{0XvKuWV>kY%N-95X3zbOp6~?Vr2cbve+}vA^LBY*7~LbuL$_ATBEeS$)>E!NILy|j z9X1yN4J23|bor(jCKu&Db+8NhM$0re>fQaMIrTPd$DmB?uAlX0O~S!eY$4o6)r{4`fv$g@X(&oiM_j0($g7#DBxokB)tOAtL~o+mcfHto z)-193HZo4UAy&k*Oj_G4EFtg}Hu&WJ3ecu%Ic5z-GpkN7k=JFD5HA$*2i0wu4El75 z9AbyjHl6<>-`n$eY}N@>V2iA!wYI~6Rt{A{s;bm##$0s5E?dF(Ot3pUR#R+WM%QKF z0mnZ+^M!a%Hv2Zyz3HxAlv!JRXjp_fovI&snpH{{jOE&>`@_G?HLE)5s?hx@3R%6Q zGEC!h$x$tFQ5SGb$Af2CoGN6YQ3+AMiXWwSTt zw!xURsN+q49#!b6OZ9Q17qnKb zEQnt3b1Am8cnM}+vM)S!;8#{Q_m;Pyek=LOP;8BtHGX6zSrNNIEiqUhUj6p4h?Nh} zj3L^a*M43~EAR*U+P@V*&Vg;AF_r)ZIqla}4DeKrQ%H(HH z@>_Z9!SFz?JTXlhwikRe^GuUA&Z|nfo-f8r^Qa?7=5KWdW<2hoxGvsQ(b~y+8L=Ri zF({?IKUgr}LHPNd!E*vXnX;{|y4^1#7xlRrhFai5+9SQMrfz@P4Nb(J+P{slmLSk< ztSHW+{_sxD@0)prYOL5F9ogH(99gv$uWSuSvKmhAs>Z}z@NR3m?m4T{c+&Hz(HnYeR#^Tp&!liI!_y~6EoaG!dc*57 zBOnTY!ZLKqq6XHR8GX&D#wVXR{aE)dpSdL}Ho9&l;*si!H*59qq`BlVGDFY|g8`8LiH@0L}8On1{A3k4yvEI6nFnL8gs`8?JyGtZBy1F#Iel%>lKS108 z!!(PxAMFyX1ZKRQ5K)gU-k@);&?n~Nq?hQaq?arM7?u&Q@%zO1V1Bt2kDkeS%)*xD zb1s?0!d%z0PnIXZV}A$DoNd(Icyu-HaIRBu*9Ev=QEODOx6s?s908*`rY>(LhU~fP z3$jbGEkZsJ}UVk?7ODv!AFVl%3XXiTXp=zDC}pc}%KW){`f39pa(g z%!`<<4$=1U`JL7XzG_|NLA&TQf#Sp7ry6p;4~jbn`u3tEXM%!LI9Jkqux2cU&s9goWfA&=$C#^Iy#$}aktOyj|`<=
Pr{mZ?&OPOfHFB%GlD5^h;5(G?!dv7!xy_M&le#DVJt5h8d~cHnWl~ zw#HBC{Bi#Iy?%c`ulMWqTwb5&c|Xtde!r1J&Od-vj^XO-_rrjv&}71pb?Uek+(=8y zO4AT>pW*NR$y)+z>j|t0*j$cLkDPYnX{Lr4YF7>n37S8wsBEjg?!EP`-*5N0)R4W- ze-1?oVJh#Nraal!iIK-C=%o0HiDgtd8Z&?&q%fDPD{zfz@GqI#p-?(^_d#dOLJKq3 zFmvA~Q3c5xocgSktYX~})eFNf^UEN-ME$^^m#NXNHn{{rcU~gT&%d;q&x!4Zho?Tu zh~Au7=lM7&zlEBJXheGtI4w`>mF(w9diK*#^YI^5lq9ONu`PYN{p{&ZWkvcCiI8L1 z+1z*dk}NEuOh-l!S%i;){2Z=^x7|s{)tN(^;Awh=OGg6i1M!zk1x_^{VY?#*B@lBP z(OGP+OOs4k;%VMTK^ih+<9&mPGo10NI^30bL%}v4Ob=U~Ha;%G*2IfaB7ucjwu`>9 zr~00;+%M!za*(G(;1Dsi=$8!JjJIJvN#u2Nb$hlH zd)-#O>oxa2MuK~1GeubAPP^XS&=`lXRv@tnqXk{bd;Fj^u2;%ToK~w!KdchkdOW+q z*4J|nQnWq1F)D#Yx!$r^tYsN@6tlqhzlUDF;gFltMV-&+;bwq|7@9u;99WVQV;3gs zvcXT2)WS7OhWnsgMG8@V%ISV%JDm+Pr#d2(6EnZZbuAR`v-_A)W~kry=M%9sPoP>) zFgi&Qw~|xsbo)4Rz9X;z`n-gD-A#TLYvr4sz|U&O2M%Z(+>xW1P6$l6_bsRy+f=H8 zk{@P11|r-WIFYhekL4$wrjh*8ocJxLi)(3U9)&nNGXgumt!bW51mv?@Nwz3UzvwxP zg)k*^KJ)Imdq->?c=&ehT=3{GdryRjXbedOFW;2dT6R7Wjpa5F>c_B|T+!<|d8aY+ zuhe~5Tak^+b%h}Ze^zC+sG2ngU6T>oVV|G4G1Lyw%mRe$Vj4N(;-%tQpuf}Aw)7NS zy}!6iAiu`?WcEaJ=x2l(1bQ}!?SU6GO%-mJLHh8g%Gy-t6JvBzrNUCx-n!DaK{T`R zXyBFl8=hRua259<3dyYc{`Zu%m&z>lvxn#rVUeB?X)Qe%nRx3CA~m#b!^>_gE(ceW z=`S1dgk=+1fMu_NC@RuE$RVFr0O^WNP)fb%xO!0EaMOqA*(=PY7aG+ave0V|sJ#cf z`!Il{Uk9kw6IgJEZn-JH*jHx{LI8}*kqYwLbLw_&*U95~Q4gj5SE6WlL&vl8Lq{7% zrbl-DH;dO zF}qLxX6wfoHyQLuSTyS-5^|d$Joqs2xd1h^?L(GhxDGljXkzRTi1-W!+@vg^HUH7xx)1F;2pP=to7 z9-q!Rs>hj70Wua4V#+U}7P$DK;zC{s$kxBeLMxsG;GBKa z>V3Yv!zPNmyX6Zv5Gttno)6mnR|SvGuN&>xRZ_imLuI{1V~xVOlso&Sxc*AxdI$2N zG%H?sSt&?KhF2o32N|tO-{U`K+-yEJ=20jy}a=aCnE_N;+Pks5AK|j=G{Ee%5Img2Uik>;H`ZV9tz6=g z8Q{|tD5=<8nzd#uM*J1n^wjNC^a+&m>O*5#jLQz`(!|rKQAFz`(vlfDQu~D9|^K2fMVO=8KDp zqzG8m1i>-r1j15SUKk9lCJz417!q_2>nNq|0tSZE_wV>Jgtm z?Ws18HuU-X(Et`U5CSHcBG>@(m>Nz)sfNr1yMNiy|c= z;(eLoVew!uCBjIN9wPs}%lGwsqt@fneuDcmL)Bs>TS*87LKp?FTf_$o)CQ}fB>X#f zMg9M^vGx$j@32SreVJF`d&rGzV92LrHF0F3|Jb6jJ6)@@e)X4Yy>_ybwHopCX*He% zDuRB&VW&cYQ_TQW3XbwIaH0*;?J~KuO*YwVKDoj!3RS_>sXtDf>-Va4Si(cK&zB|r7ku2#fzUOk4KaMFK>a$HL zuA1tEig_C82@-=M0xQKJ0MDoYuJBvJv@8eoPF2Ed` zmbScszqqiYgs_Sb6DHFeF>#7di^epVsEKJQg2iQFdqnXe-!>1OD19a*Zgp8}E8?`x zcn!?ZxAP6hqN@%+mr>qGv9=?PFxQlVu9`qounza~(^u`^Uy=0ME)YJHhz~vxwz<}x z8rcl2+%sG#p*9BFiN!WP9%S>E*V1k@wLN~R32e3z1LOQ90p;p3)J;Tmv@wml7=zTG z(zn{Tv7o{W*UY11dczzbhmRhP+R=XEij0Wxxb>*V+Y0^?(lSrrQs1N!;|%TDmH@f= z1zl}dX|w!zbsTZmx@+aUv|`M5?pfi)4_!T^Xz~R60BM)EUC++(8S;GjdxvYdV3q37 zYxygOzd>Fc|2L$EprQv{vxb@b(k~}lc5%~wenxilu^q549}6cg~JQx0coUxXvH{24X1gc)}@XiP4 z@nDjS=yzRN1?`h%K)wV^D>JR%REC+OOeuYIYR_&iwF|Ld3tyk|G)v1H%}eRjpw52K zvjCeo0q=y{m7|M@yMSh2^v+S%R%cJJG*MbhfEOv56IMSFotUvSB~eQwo#yb0R{7v% z(P}S?-H&*i_*LV0o2AWW&P04g6R~=1qIA5-5__1S>`F+@SZs%L<=L%?t~x4BHXF4v zGG%btu})fuIDKo#< z>9wOr8W>9Fg*&~3!#aM*hQ8kP^kPn&DkT*U@RmuL%ou|V zjf1C47Mg0qJ{-E(-Iz50(ra4C5Fv)yH}&c=?^F1)${yyyrT;;+rQIQ!R&W_|e<@d~ zdsSjI1zTG~c`=DCwP!;g5z)uY5_?UcEQwYY^-86HRWGIF`Gh@%*W@=XxQG5i2EX-7 zmnygCeN{MKemZkEv~q(O8Q)Sy45VdPQmB%h-W)q9!g1eChQSLMmC+D;d{Gj(;Nc?a zu8+cemeCCJXoqE4`)u)s1=iP68uor>z`JkN?MF0!X7dkg9vbour^TVCs8cbYp07Xc zH9@pLoEtZemR=)F(O)b2M-5TQqC5WmyQ*A8%T7qVxQWd~A32b@Ika8$N!Sl98w>Ok zaC>?87}(#gT6Et=b#uT>vAlR$`NM>-7~l=|`AmidYdwIYQojAo!Svct+Vg>x#~)=C z>43I;dJ8iv_IEVeTMK)(;OA*q;`KSu>|%%PG^t`aq>IY=aSfQAvBDc%xBt%F@yB<= zXsn|$?8R>OsfkiA1zJl@XCQQJS!liZ7K^x-SCFWu4*t=Fo70;H!mIPKqXqx+-4{dA zuQeAkc=RYktA!u@nnrwhm~MznowF2ytJF53+xO0vPe9||_yCYC^_OOLgESo+^q7P7 zLg(zNCv@qGR=;S@t}XT^>t2nmw6Fc+@9$(Z-fa>e*I_fJsH1}0Vy>qgK6f_r%RXyw zOr>HuJEX+nWMV;2%13fT5jNpDQ|lkXE@p?H+O$XXL!1)dp3i;<6%1B*2PK-tM{M7 zGu?7qS!QH0iVw9ORr?kLNfWl+sL*r$@8>v^q|iBpRsut1UmXA4**TcBh+q zG|GUxsaK!nq&z2%lbzozO#ihIhkGxvTxXoWE6|NGRP5Q~d#D?~+ahXkrUbZ~Z%-pX zk{W6|vK0$!;J55IyuOVDkwjhoys?rSfK;Y}p0Ebvr7XutQJ*iZ68OTTsY?_&2=-+Im>H~Dr023dvKe7lE7<;kl&{&+}1qD?1 zkM}dSwVtFL)T?;PK2ejUM!e?Lm zKyPG3Z&jb9l6ES*t>6CEXsmd1B}4Z2en+oVrJFWG`Fs~&^LRF?Rep}OJKw)Rr19h30#$bUhSZnyoTYN;#&hWC zEBmRsD0>Hb;4+c-whAe)eWSx=84o_Wy-?npB9O1Tm82PdvB1<@GhBL?$cVFJF z?&OWz{VgVVSypmVb45@uB@?+;}aZA-SkA(v=eyKmyYm zE(N;r|G62)Skf3ZB|h)#7xrICokB?#T^s0$FV~(rjH^7(`XObN87@_?68js&=|oyM zchX<6KV~Yejq&4I-b^Oily@t*6BKVDsgb zbqqpQvCqU5gds=ifX1eFfkuMRV{L_0U05KntU?#e5t1E42?AiEPTH8X<%(Cg13_@ZS&Tjb^U;+(4<~`S z2eFnF0`q-LD@|X7i^ig(9V&Gp6ooJZJ$O67O{7f4CR$K#YUM!W{HhX^<v~kPbsiih36R#gMt}AK!Tm4E2@1@oIcM-`4JxiHymz zswy#K3qEI6YRM>oVWp(wK$~L4wLx0Yy8HVW^ z0GRP+vl->ReA=oWkTlx>(Vc2lfB@d>ocy)L&3bf=eDMW_T85|L9oHKpjdF5I7 zAR1_Tmp-ADu4Jj2JC_2z&XaH?zift|r^7o41ZATNVENz_L zt*xCBne%6KD1KTQ_fr$;J#?P6liX3T#HB5=6-Gu4GcD(jSZ4P;prP^l7oeS6`;l9cL3btEqY=B9irez$s>1x_40qqMLQ-m`;-akWIXY1Oq zLG*mQgld?wH>xQ{1X}|>`GFUFMeaN4!Z5J*)!FkmOAWTzM1FV5Z}*Fae;Pr&V$m>8 z)4&T-K|x^!7r^~5B4_Ju*wfR~77SpjaUKItB7<|U3j4Rs-2(U>C)q< z;EyfFFh1PovzwHr)?E*oHdu0^#x7enU)fN-cC6`1@7&O;6~G)QQeQEcb=(nSm$^}i z&vgE|D;?r?bAYRY9YYkpC8R?<@C(`LcWnZ?(M#N!m08yRg4(W*()Yt35_9Dfm)jO{%)Ysi^YfCdyAS^trXpc{>){!M-8wQqqw&i-;q{A1q zUp>`VH9wB8hx2P#EtPqCS#ZhxEq`A7=j}~2!Wwuu|P#^^>;fWm(WE73}6Y0F8p-u;C&W*?Q zNGUip)Z}_+V8x&(D}mcnq%hx%KcHeGvW>`#P`S`zE9bDQcY#6@;-Lezr-LcX=hZO@ z4x+|hk)s!owQc3$EN3c5?2tpq)><9c2<_Qqun23g+K_OjAaA!%vY-oCyDen88= zO@Sq|P-pY5u=d!m8&1Rz-Xz!pgCDn)=Xd9JGdv0dKvsxhpg2+{|+0e9ms{9+tpKQ$%2Mrx?C@rixwOD`D2Yc>Kj z(Z)!KYNi72a$vO~zNC-rMQ5wM97(GOUlTW#7Be4jf#?&LE3Px$%oHILlU`UL`eh&H zY;N!2W|feHMwNTxbB*)9%n#|ztUa4l4q=mW>r zWVMINgqG(q^J`o;wbt^29oHnLq-vzHl3v91JL3CIAO(~L*3-eI*;C7Eukc^Z^|mN{ z4_M3;jT;V@+9u8_f(;^jg@trCbL!$Ui5y3bm=85dD1HDU;s>O1j^}ZsBUTs*u}}N= zIx0SWgaWfNzSNcztu&QETG((9rM*aGZ|I7z-az$8eGyhF**b(akhhD&^ zk5)?w0TF+dnAE537A}T<()hWrih**B-}N&Lyt9eoPrRFoc4q<^TCsarBOzqbk8n~{ zq9qp!V)GMU^6RpJ^jmv`jhAhhkBx-p)^b*!g`nQX87I&EsP)5>eu z-z2MXo4j{BkU%cU?6e~$mn%TXx#?TisA&ZoE|pFb@bOGV&%iKUXQ_BG6cZgCTv^HR zc*udxW@)^75#)KZub6!A#aq1g&Xa0K_tUoNFAC2Uk0h$zv;1H!m z8I*T`$(I?I(fD|cX#e%K?QJ0t?w$}0b&B1orTx&;t&IAs_vgR1d2o^CEU! z*8?4yHvV^<##o}2j044AwHry_Wjy8bvu)LxFigWDF^TF%e2qsf@Wh+S{VpsZFQR)E_+y~ zc^x<_R+ z)|(*Avc>2^6Yt+zO~CyPI6xh_(_s{~|=RV!(ZwbDX(bhg6Bx~D#E1zP#O>GGx0I+)F%1gyDR zGjsHt-KI-?UR*Tq&S&#^>IY=^pFWChIjW#;d|bmgG>Osvjf~IDr&I)v_APC9uz2+< zDdd=uFF&mCk)c&abIB|e25+bBpE^>r;4}VW=4yT^D`e2cu@O}@8oGZ}M|33xk<{sj zuYHB>o-e1!wy}l3&&<-4-!T_EFB;dLm{yaa=w#vbc>0ku=iRIvGmnT5VyglbsH-am z8<+I@X_$)gF&9l=pRc-~8-osb&+BO%Zz#~BleM_CuxNUY`T#7Yip{?*?FvEo{wrG2 zY<>IW=^rLWdDx)TilOYC_j)2@lnDk*%4Y)C_}cT9rDRhA^Ho*AbeCqj*{ZE5sF#ve z$T=D%LKn61lG_$eRtKV2uC;j;OwiO?GWKDuk8F(WwNjp`J2EGlUv38{Crh;UG~vBODpinq3$LeVA!v@^g? z4vTTQ>Uo;Dr8UWFo>qwyyw6bhz7~4f6vlK!xvQZ}5YDTo5M*=E8S{?9sj|4AaUpa$ zMx#YoJkXZ9@yN5&QdbFeF?;yK6bp;>Lc~i=VaS;N$UFF53xvaOI`31IUEF!>;w)@l zLAA&5n=hfOIHwTkGU8EC)66HK%R#3|F&i>9x~$5&1n|KkH{F_6P*|pJd0Lc(2g8Dp z(wAb4h!v%)j(c5`tKAv)r`=pT>YymnxFAL9ib>TUl=*JLy-MlX!=|VMGB__{t_RHf z6bJ$a_AA)@`Jl;cZA=wl~^eBtNgGLy9S!W=}t68BezTo}sgQbNI~bhiqI z{@Q-#b-mdc?0XjbcQH1{Pzoo~CCSSVghf3|iNDbpH%q~a8g-BG5gvf3-|@c)9O_co zsOqUi3VtpR3a@L}ErH8QirOfTl2|(Bs6@?-?#B^F9-!bsFnAYAyf--P+I+oY#|%*9 zZD*x}Ym3{fk$S76L!Vrm%dVTTiy0r_tt;e89$I5UvbnS(Ae!Lty!xed2j>(N@)B@> znYvrG=s~`Vka0|Xv`H!YR`YJe2#rNig@^hR6$AynNwC)eSyOdM@CKg`%pY?mirKa{ zD!*yt@|nqz)&U)!(c30633z+e+2$Mn9XBHdGUd#I9W?q+pK`QlcC8K;sK%;5$6Msx zEC{UBg%$1Mp~*fhVga0(#V+pXE>LDrsTrE6wHUtI)BiXCT79=DdkMnZ-Cel=CG?o- zQYhyJ=ftIv?E3AFsGaAvO!2Xf>O0#^Qbz*oKuE#-GV$1P2$Kdu-{h%EeTSQuu>R`m zc<5}^0+O}8%3PdoR_>rF0*KzBq8$|n8&iLyHHJCI$jhE{20?xPTDW4w?IWYOzf44- z;tqnL>FUJ0&ptz>{WP%9i@rbm*SmlcyC@23ocz=qUFLloKPr|}1`s@y(hs`TFb%3IfVw3f92&3gI3pIFTDdpg`-+%A?~#W7yT)!PEa}s3z~s*5rD0zM zu4cVdAj$+H8JZo2B^9(>1{<1T$0vn*A&&(@Kj63!6?D1Hwk-Ka-{xT zbdW)?GQl1U*INQ6hzmL`ePvKR;xYg;y>h<^4a$R!NrAD|dukP3eh(BM&&P;-u8V4} z@Q5=L7!ZD96cC=x+`BJyLtCqHxjheFVp|%klNKZbO!Kek#Zp z7u!~E2h7fAx(IZ*>{#Q3oKh8H*3-)WNEBmU9>|<4rms1_jAI3C*K_FCSjx}^eCj#F zNU0nGi8w)8WS70v0DP3m^~R*+^;s`C&ioMc!U^v*zbXgsiHL4JUqTxY#%F)I-6sH} z(;Jw3BL%z~d~|B>YRQ|QI+oGaMvM`LxG0rw~>ztwh zC2M$|JX>}T%FwT7d$IpKH*vD~=mdCb3{v+zfsMR=Y;oU?Q{u!aoQ7^1;zqw#BMl_p z(`eoK0Nf$?mvhcrQo3A~l#Na!suEF32ji6`AkxqnfRWoX{U0CD#eeEiO9ahBruD;kJn&9^8xPR@XhExd;!Vn1Vg70FizjsjrXOiRbJ17z)X~N*7|2n z5qLW&8g2mN`Fp$LYJJ4heN>CqpyGR72IyeAHl`dtR#UXiXskwR$vHAgdKP3*yPM{eAHL{1N`p^>~oeNH8N}+9nVYnf>_y@7i9uixF*TU&Oy2wOwO?5S5 z_QsGP$<{HI_e7!4x*mc*;PFSmn8qs}xOvQ9fkt@AM&Fov{V0}-RajrXN364_T~T_^ z0|f+p99Y|tbCPrvZ7SohV{X~OWy{$3liZBd&&tjgG?oK}TS4v<1}8@&n}AjutH!Bc z>)P$^`2uW^98*I%0YgBYcWJZt$Mb^;Rat2g4g1N8Cl!^H3&xi^;Nbm zOG@b`imt}m5J@qOau_{-%xy1l3XD@eyD0E9YOZ67gl{~{CVce9WUpk1l<6F7CB@u@ zM_K2c59G0srqV$M4aZxILQY5*Gh*dz1%HS}Ev-T;?ylXY`H8mY>Ksa!>NfJ-lu=DR znM_a=R@8PPRn@o`Yo{B z;#l-J$@C)&`F5ITCqU<*p}gSyb`o4{q}aXrNz>5BkV4VZn40;l|9(4@kWDkItIsdh z-hvG!6zJi26)l8vsdVbE%H8}vIgv3al`>`-y-8%Q4?upv8KgCKbV|LtkQW#0z553p zQ6pGYwY5WHRuM;%s0nSAi@=8xob&Z?+$TVY2prB$CEi+ULG@SW@QAk*&S1JPbx7O$mPbr^N^0Ev zhq#@8GN3kR0r20D2&9k3k$TP8$Ev*^3i2vh@7rH7>j;4$cxXYEDS>xpZL|0z%nnN^ zEct8SsiIQMNB=dLlnv+sdM~BWUk;zTkEwrei!+qg7q^^0N!bwv_ z`9S&Z?8ISshr+r{}$bREq&8cfbi+0K48;Kua z2!YOp|GtB=upAZwqH(TgTjkl5|Cy@)x;Ha}_&^aK?}_DTV-pLM`yrWEBJkV5bJ?&g z_s_TJJ{ZKi?xJ0&+aQfR_(SObhOc526NFxn;#!T)=+!p{ZRW%Td;qVMCUn@)fiC@Q zxe@P~1X=C186?u?4)|}excxK&ZSEH&q)p>s|8oIkQ1SxBmltF? zRL8aPs0{q~_%!$UAzYrPB^ORKM4`u{73JWbv441o4DFkc*v?y0YC@2C08NipBhu;v zkvd>HgC9XME)NQ_u!0%h>p09at7mZ?4?7O8yBB4;|7NZ!8+MAQ3 ze|I7GkUo!NmGQx-zDZ`WdGSdKf{Abvhe>+OS%F`h5>+_LI0mN<5FJc?1HrA3VH3l zS2`%c2VsDh_f}HOf712r2Z4Wfx<&;d<}dV!udC4&YdL{wpC0iuq^z+I8c%omR-VmE zIPNfjDS8YHO_Kuv;qWlSp`9eJY&&ZkHi!Ut>RJi(Cs|1_hTjEO4~>ZMG*%<8iIYI& zFFU#a>HQ}bVKKMH#lZwefR?L7MJ2uCtfx$z^%YrhEZk4CWE6;5#}T6d&$i`1*iOrk z=M5bqF63m>WAU8ZCGD^eWLX1IC=jZ~ci;M>m>Is|C#8RGEUuI{4tMxj#nzgx*KY3Y(Wy>hN-+!}pPxQc2f z5FibjQsB{BK`0Vm#+mDbgx~ZOTP0`Xq(Dou7?V8ewq79;W_B!Sg@e}YTCWu&GdUvw zS*GCkN{A&q;xIrI3M9T98Pg`jv;04Ig+*XRmXsq_buxpcVvTnp4fHKTsm?W2R+_~` zk$|jWTcg|O+vgVL=hg;1O&IQs18 zrU72Cc{Rddo+ENQD=%DKHQc@_xsT6o*dcUxFGS2)S0Eh1JJQ8OiD9MRu~ER?@d?x} zSsI-hY4PU7Q#!{t6phq#$7SY#4?El0p4FVVMeM+7zjhY3Ui9Yy%x2Gc!)!1ckyFy| z{Y47g`K>}uLm!A8>e_EF86R2#0WcN@XwgH}m!WAEp|>>;2JTPKg5aoUhuy1(_>q-Z zL}$^q5^h_UhF$)1mYz&ZazqP6kU#^iQqI{+aW^)$Ze`v=M$~NmC(liL`xPQ^q{dW` z3nwj3x#PFDl-WVbwVzmM^G#!mF$Wn)XJ;CGxZPg-$Z7PvYpv3o`arzv3uyQbtD3VM zy<{4qRl`kqYFhh*gNfmtMYqw;Su2r;*E=zY#`+Cv7i2ur^J;T<3nK9u*M|-(?`}`&ktpJ z-6uH2{S65=W~voueib?mfddB&WAI~xPUI>Vmw(I1a^!U)v|IvW%Sr~7(Z_@wtX)i|*;b&Au{E%(B7bBhzR}K2?tz2Jrv4^4kG<|t7 zdOl!FPSxy_!PU?#eGv^k3tDsqX&Dif4UnHX6he2*GYnI(@E{S^t-_KDTaRrj?lJ+Q z=ub16uBprXp{K27Cbq@=dh##*Q1QR$HCv~Bp1Z4D(MoU|BcEp#$iyDHA7SU*zpCkX zWy}uKb`RZXvhwzPg<|Rlto_e>`1z-lwRMO;vEoix=>b$<{xsE;s=`JHHvZnNiF>%- z1sVNZW(xOpXO;lv=j`#&Dj>o3V}0EgP^?7i?)0bkM&7#JPbtDCzM3Ce8C{2%8xm7* zapO$@Y4XiO(A(8jBK*c=5{g$Hi$7)QOp#j1$r>|}Rd(s8cK+z@^UsszV{e!p)hMSS zTi)yLHkM|;9t8p^>OF}z(zBHN&7vUkhe2#B9|TaULDa{5OoiMqlW26f;9?~^?A8W> z)h3Kc70N+H0@nUzl7sK9$6$@a0Xj$5^=DjCHg@4kSs*{3kzJ@nhIWLQU2HLylO~7| zNZRkEPU4T*fnQ!TwlwEr)%*t$8__4JEi zg$w8-GP1XP%%$9~19xFA_YiE=e@1}qzZ_s`kTH}*H=)l&a(m6h=X`dqDl$97TBg(r z3+rdkU3NYl`|BzCKTirZ`s))^HnaF%eo$A1$r=(xYhFff)r#c|AI3eJo5u2K0MXSJ zh%*<|vu9ObgIkrJ{dRMt-m0p^?~lay2by_uRyt&2PQg`0uFDt9-_FL3S5Ql#<_UAl zd~{g?U^Wj4fkcV(pL>YL%~n5&;fdxOTAFZM+imJVX%@~U2tS9Di|HT)pgRzd^k*(K zdV+i?s^xVUCZhLu{>PFp3G}i|a14S{Ojq2CzMyJ>o|4MQYw3YKe|!|byH{BQ1BzeaOMB_!u?GU>%Z zT4UXm@AVK1~u&VP&avJgGljHGbyAPz;)V26)tYW+|VW7eK=L3=6 z`1g8|UAgwpj?xKE@Bw z|MM!9(^$f2mY3)uR-lBBmX@+Q!;;q~DK7(twq%fR|D=CA7&Em5IbYs!@;Dz9EztUH ze~6iLOorl(Pc4XtF?@*J!e9ngu!`H@F!%OCQL?4YDzg@1xHdmv17vtqD*pJgcfzQb z`tykK_uC3Sp0q2rW)%elqWh!fr{_t*Nzub%mqyWxq)Ps`$)JmvH5;_Tk-j%|Q@zpm zm^o}|>9Aop3T12iQm09kTswj|W|8-7Gydt_zf`Xaz9pbs+m*-f9_btVqox)7+{rHD z{f@kgueD^H=YOkkVW?=!f!z5~Q!gaDKTlRf7hRR_EAchTowL#{{!~RY`G@xjw$=R+ z*KSJyRw?5?ySshIM}{2*`k#i8^IhQ`nd11`(KC*kZatO)Buv4vC496&UpdgOeSe@k}ZyS{IS!bX;@q;`fn*FL&HM_ZgklEyn&HzeyG^uHzoJ|B1mw z-~&ZepW0^fme_OZk9_lgRE;Ij`;vHQNh7G7_A(tAIwOec^OeCKr26%GvP4UOk+D3kH z^#%;C-)1R~dM>T-k2AZNlk=F%Pwpy0epoM53JeDJu4wIuV5hBL78KcKPDNkUx`>lL zU_&TVWRet1mP%AADp0)PG1XptcY|7M@l3WaBlt`s*TzAKq5Vh^1IT+(|IVGg*W-lr zg|`u<(%P9NS<{lsLEvU2+zA7=TX5ZtW2p$L>n8;Y1qK_G@tMtckp(<Zp0 z?5V+0WL)wW*Y$KEBAnt@3Bbeb%C1{gO-+IX5-bFwTGAoEA}j>^o%hsZU6Y;X4U`wE zY%-~|DeI%&hPKz2)TOoV{`7O`+okgA%i}4(_+~3zz1$Jg@0?>ZNmdAKTcV7th^Yxt z5~etuw2v8lKVKF;Gx9pMfaES}L5fjxN5qor-|sCMQSRc3-!VtgN*HN&EtLf++>VvH zsNZkj`OlYnnK}0M?p<$O%xpW$7`^>W<~&NOxaUJT;b@O2fY@T*q^jEC5>1a<-Vx5r z3`^&mW$lqG;M=abRk0d;s^V6wKa^saQjX~)Ask!soPZf=P%arV3s67t;pHF4)HGfh z(0K|9tHJTL*vc)X`peKMN(H7_fFf)U!etJnozoP^z*{!N6sUP?y+A(iU%tW^X=*iJ zj*Cv551}k1XO_Mpx_*kSF9Qu!R)y#R5UNn6n?dDLNMSCZ4vo&w+QP7rs;RQ2nKI8QEvAe7r8~;6)NTX+tmJpdErZ| z;!YlOYfQ)sdQm6Z=NGgqny;)!l=J+*)^E=&p_fozw*n3LlCJE{LuP-v`<3SB`nkcR zc7DfkDGuIgn;-Jxiy1wa{p1Z7mJ#aoaR=-4FU}=>`KdveN?je?TKxHFCMZ|dpwR>4 zhm4kCZ3^!7j>f;C6c;{G!e~)=Poy?(gTQ;wf5eNwO0la2>vq17lc=zn?L&>>da=f2 za^1wEpl?yVP8g`I8Ct7peztQyJDxqcNn9=1?AIAT=E{JgBlp-<@?tW588N!AF#W*6 z#P+1HF}Ln;R;Bu^7-m+?%Ac5Vu_ltlf3S`^v2)kM<}kuKoXT#z z^{z)oHZ77b%=-&-<_+yjGndw_&<@k7+-?z!h%BHOS~VTdQk_XIFs+=SnuR-!l{6C& zE(RZBQ8I-yd^|`xfrU5rs-xdlFhjwg0GKMsyM{uGh^|Zjwu%!=z_fFkN%y}qcu>KS z)eE7#Bs-PWJ=H*D0c0Qs(;(Nm!q+oc212+^V+2%Fq^TXwUmcvS)yUNi1xG`!0T@|v z2Jmjy>SV%EzE*ZUx3fNuFMggxs0(@T_9X1qIc`v(Y>p|sNP&$uSyYS#wo08tU z0g4a%_vrF191M6Mj|;TfUdpvd$Fs-7-uwgx(8p11cXwLptw@pRBqpqypM9c(gpHHH zSbLt%#?@Bzl!zLSo^O@cr@4P^;LXk1y<)%2-S$@>z!;<2q(=NWC%oli0d8E zFK6%5fgXCCdZGxdE|ni;tipAlM|g9^^clSI;Dj9PeA2Q7>Jh;yv|#naVYLd%OK{}% zGQUI=rUVl|QrPCBOitVNz7Qs?nf{{5$WurXWNO|*(HZZ0X4}K9ln9}gP#rZ zZ5!Ey`F;QVM>K9y3Of{Brs7v&QjgLqWv$p3mYoTR`5%$4vdVdvzINEqUyHPyD^oNU zv($izvZ@P=>KcKlk!P*Wt0VLA^}(MY8~Ck^X)P3W1Tw?+=gYA_!Np^*71M;|_4BUZ z)y?^KyJt)3|szB4o_-^TXii>=INS3Z-YtW8x-K-6vQNX-eEVheN_R4ZVT zyHrks5AD@rgAg~$vw~HNx9$-7vStU4WC ze!ftCbP-ltM~K1b$S`5?%inlSxzVA15wSaRu})!+z{D-uOGr2ANNky+wNr?klR?ED z8728b@<6pPPA{$`{Nd|GcF{r)@z4D(SS`OD@TM;#WYN_T#sC=!E?TAz8;O3q!WqWm z@)4`ri>Fla4bF$}6sR=8V$3He?ME$yOG)5$_EP0}d05zNec|qV^;dbqPneX$YIB8O z`=42^HD8+A_vLLMY?-$3(qlfv4ZTFwx40Ne7d0+dTbd4C^7*Rul>&WUHk8!ptf` zSxPBwdM8CX{bSS}LDgiQd>EG%`>dZ~bT_X-aBf^KgP3NNO}taT_G2y&(7%wrm4_2Sn4#54T~VTIcbs@EEQbOq(lmb7Japts*t3!;JdEX&QlT0Rh}H)Qilsv0Aq zc@6xs$%n$Y1T+==>e4d9F2_m%jEfk`%gw-yg-<1e;A$g}a;p6N;UA0O0Ng^R)}+9iuE!e` z#!v4k=8@UFE$?fZ(E8kZshE=iIzz%eXTQRmZ%5B^N`;?=z|G|Mgzr=A5Re;%H3H;w z^J0K$9BRe>#vpEArn}~|2>B9ER%Sj4_u$5od4P-SO-{3pinrrqqlnU+k zK4|o>u4f=FZt|Vr@Qlb4n%`%PE(8j$I>EiOq7S?qaa2PEocwS+LdMf^#_YexQ*HZXo^DD0~tn*ypN z1y}wOLCh=ux&l?ZOz=I)?S^}EA7zf_>dtbTGmUE%{1#6xe~GJfBPTqqF_FcS3@*}+ zWTRGGeznp_K}F-0>CsWsfaKMMpO9Jp1zp9Et87)Bneu$;hqxKvv$D_<_)82e7#ud_ z2fNY_4`)FdY1k0KZ&7>?IODZeVFdG5s;_$LZU9SO6dFm00s0%Ky4{{1v~O$% zLKkV(dc+m zt1mJhRHclay=bcZ?2Rcu)>4(xtJ3pu@zst;Q!pi2uB>S{J3U2nqFuzbl{wna;r}_F zKqa?pzs>iIt`qOCj!??Zxx19AY=E|E56A50!oPnT?#V0Z(t|phc%@|vd%fLKRO{<_Xjw4s0v_2;~!m-+P*2n&p2UNk3u~`&HM7q zrd~}mjly5LZdLk`t2*~?N%>>&EJM?p_ZKuQCLsdGUyCcMUmwK((yr+ z!utPvv(hd#h4voWY+)Amiyd(svT`7=th|0Fxp*2ksT?`tYOkyuF!d|n(39CV3Nr|o7H1Yf&Ha*3EHtQz>iw7PqPC^e$JS?|y3TUMtw+5rcT(LPj z<5n4A7am{$&qB6QonDPy8k;Xytt5cnDUf^Go(mTs;&pdv;K6_ zasgh@RRK<6^i0!!B&mH1|(Ne{#P$u0(PaC3B<2)Nb zIGr;%ox-8k7>kY|Oh`7EDUBxrI9AoDRgTUembL3VH#qD#&IZR4076Bqlo$^OMNX-X z@K_Jdw+1}+P}#6#&3%>EU)Q&;bAFhT;)Bf$b=+j z77iau_xA{Xzh5c1VP)F?3jobw`rPu$F^h|P=Fm3VJoi7RkL z=_#(wU^8UyOvNsaB%NtQ8_G1apjH4>dUmLgKVZdK)+*GZNj(HVAj?ZwFO-TkH2rGD za-4SJ2Tyz)q2^>%R!E&)=mA3oMHMB^$c*&5*pBn8cFFwUkJh3-W<~b z!C%@#ygmfY84cfiqMyP3W!P%q&Rp?F|Mc!avu4ZuB>mcC0s|;<)JHh_zTwY|{HdQB zzB&J}OMJOIoN!Ot^mOr8^lIvrg&;8XE8K!d42@Wrb*dno$gS|M9Y(0>LP|bCXHNT9 z^1YF`^V2@%xJwNvWXSFxFmUzK`A${1n8P)R2&k|K()}N|=JXc zyXr3|90gO@chnkR6H3`X?(?sC;P!>Tyc78cIK({q@|7nieZ+^yPfI9UMN|NsIqvY1 z0Lf4_eSj>Ms$As72FdEvVtnn4L0M{~xiEP-g*hE7Rx)9hm`*Jxgs4v$AbQvUOb9Lq zQnd06DnG~NV(eml6Hh5d)?xS%L}(Fz(_;)HcmLo-YAUwB#$O>J#uz_MHYAz6ayhS% z3wELw@zi5vt)L)>3p2E2;*h&&4FtnBH^21SIAK#y!`l1XFz0-Vk2)G%s@-c_=gqq| zH|>IUrD0LpH$3vOB?N0a!tt-WnWP>F7tDObWmU31?HNWd)pbGPJ^i#oq%FBA-j$a? zEthycV#+@zM=6;lcE<56zv8_Ge47lLNG>~1k)3}kcp9UMCQ02yGrJYRQq>ZbHQbM) z8a&13a2ycs)$e``SC%3>HXe2Ub|kDN?mgz&?|g*J_JEM+O zkeu!MPj8U8A{^ZAGF!lPuodG&97r1rRw25S(8j+EEq1ro4BCR1tt{YRvG>44&}3JO zxBm{HeBo@^?gcVFPEmGt`c!3o3pjHI=~#bT{YpJzx(-)Jz8gsVcIT+(%F3ng zhQWRMaVVoFHd2CIRsNLQ-hWP;U8wj&7Q5j2aS?1K3F;Tvw8_6Fr zhI%NvP#Zn=7>_HYJs>X(^%J6J3A2?IAk*B<9q20p>cq8ayx*ykNCI1xi=Y70kg;)0 zw9Zc*eA1T|-W>J9idm%abtG~cRWOoZd1AFpjduMBsu?5r4I*-gjmpD^tz}%C(@U(d z4>O8UarDXXZbEW6hHzEBMCtb^5WBF?ZTgzh^Q5%(?1{b1YYSa5cV%~waMX|a>Earu zTp}ygz~zMjv+|yP#>LKOY^Z9oO*2antdGt1SYhJ4nugi;t5pp31m0jjs*pyBT^d!v z5WnDcncRAPB!wsxNcwka#-TYT;MsvkE2yMCrOQIgxAI1BYYp3Gr#8BAs|tsIQvA13 z)_-~9{4XD-L9?6cUzyg2%6=p@5UU+0tN#;tUTRAaDeV02j~N?pHR)?VFUNa+8G;mkv~JDswhQp<-$+CCJ}6;vQClyT zQPE(TxEnt6!sJ-l*aJY0shQ7Fp%78$QqmkkBe8Ds4sXvR8}gcWg(9^eWG`^t-+6ia ztzO4>9!;yU{P`FX*^63dOk7+#1(LM;t=F2B%13>TB(K+#PHG1|3~Chg^lM}a*{Sb1 zGC*{L8#{V>tgr85oj&DXCflAF2`bmZh#tAv6SgFVc=2tHZLw&ev* ztKO`U!=cP>agBsMicabt zT|7^SUZK|*;g8{u6_%ci^EX>;Z-35&0TjaWe4h+qCT=Yf4D7MEBXxEKMniDF(Zhb2 zN0E+Fm~IKbxwL*mTzL#`Z>1u#u<2ED-Q_vDs6tema;JV-AEl@Be{QjErxEW{lH6XQ zSm7>|Drp8T;&JrFZOqIVurD3{NS#Y5ph-?|POZ4{(G%(xr_W(b?u_)ZHWZ zsO-b6jnmd#T5(NPK!vaGU{etl^6QRzu#3BdrwU;|IVtRsP{I>W{D>|2!h&L?Gz<5m z(FOIA@J*Fysana3a#kv4DOaoBU=*P=BY5s9vE7r!rB^{F8~DpAZmVY_Hs)p01Z!)5 z4%_efv6iiGQFWA`CP>X*AMWq6RbTLb7;mNBztl(N@X7-#bX>Q1snJLJa!vP>pi8Rr}v%T zl@}=!_6v-zjc|2iTTQ*`<|-aMN6;QuYw;?>%;ye;WPI5ZAh$DD+V+O-?x-{|x}!pUA@sT_ zNXpdq$`@9%YD&I2r_`%ErsX24e5cQY9p{&2Hp`0XwmbC3qcG&dT1AF~Cr&wb|;MGo~wL;$Fr~z5=PM`r-^+W*N88N9jPl0x@T*> zODKmfHEqZi;b|gYU{iZ4HvGU4W}GLY6tt#&0iw3$R{r?@kd>9su%6wLI@q*|`^Xd_ zoR8!4k0f?~@%7|W-I zuO|p%>=+YeGCgu0Z3ibm^oE{d*r0OY_)^a8{tmj@rFe&Gs1R|=-IOR zPfh+f;?n&gCNOaqWl@(BYn3lOgc8V|%pNqsmTtj7TTJf});j7K0WZ8j^b3P!?SqV* zV%O~EWpuFbE&cLls#q*Vh@k{we%|o+P3H2VbkFH>NWwi|JK2%Rkb5ACmHM#em5qqx z-)8RM3!+nvHG>JlbWiD)Vx1@kaq;@kTOBM=jW1$wcYldqK7?1%wdYn}kXVh|Jk63= z&{hvs$Ku}GzKH_uiTs1-7ZZs9fbx~~H`0$NiRsRAxAW(D5l2US-f`b_JZ30bX?>=6 zS#YMG7JGaWo{b5gYr?E*s(c+VoVI zuF`WQAhgqE!)^IVO^EMNVUdHw*^I*MZA5Lpr{x&q&}=h5UmDfT#5VyCGHEa&Qc*J` z3hR-%NibUtx?Y&mTEWB0|DnyuF!v&YnYon+47xnj8on?R2AUdJ9_^fD&=J1pL6c>s z#Ey7jbkRP}%GLP*eQ7sS0a8tgc-RV>Mab_(`byYb$ zI1jIoU6t;4O^Kre2&tQ_4F>>wmZ$`?vq)zt4ffTagF!DO(1Za(M~S!wZ!_MwYWT3kH%R z18@SH`b(pLnUKc!(pniF<=ffR_u-gV?MMUa?L-_{1u()b?bzE)GVp`OMEdia{-&oM z`-%Gw)m5WlQl?J#H0xi?_x|U!@BjY}{!C784ZC)8}VW``Zn)PS5EV6vvu& z2M!Vvvm04Di`^{T=+VWM*r7;CoO{^lkWkyQysoDog#wPsFULFXpLJNsbPZbRxAGt? zIQ=F)0Cfn9{1(kt6BP8L*|dwgpDp&gh8`>b4k4o0{kgoVqIHZ(wDn~(7J#uJ0is5) z@)g?KpDFo(BO?}+9TV3~J_cKxMvOx}>P(CO?8CrLksA2{?tsHgOwfGH7nsdGbY9KX z-BAyCd0N%{DT2$=EawHf`UHhmUP9yVb}NaA;@Ti6+gtX z#}k?|G~4dR$0BeWKTqo%8=?%)*bZITz(axp6cmG#?C(9nL+`FO1|CaGZ?&lW@PGJd z@!f{^Sd!_$Rf=JAUli z;_A2tB+(eIy0kdn_-dogImEbX>s)%c`hcmf-`@b*eX*8=L#LWHQu68zzjp zg90P#Lr_<=%lnq~h1PAD%P(PD9duvFE?B9UWQYX10EQmi-D%01gm3Yi%Y3W7* zy6JjeI?q8Qg7aA?C@4I940OqA-YdDJ(|}bu0+s@Q*zz#D*!hse**5xmVTfB>I*~wx z@kL}mxc}Pb$`0E7lUNp)2+o~kyr#<>ng1Y=!%zu?~lHukgs2B@@ zKq|*TE~UE)4ze-XR_tuc&!?Q3wrXKM2!H;Zf@rU6V|?A;pVjP&L-cTK7`^#;jA1u? zz(Rxf)mPb#mW-%Zx63jeZX@J^3)Y5rI>Y5qy^8iAi?o#5^wuFq3GZ0@$tcLGG^BomLD zKGEo=mLQ>&bP~d_uo=I@@t6(&5qWlQ@yEI-4l|Cjg7t}f^Uy|GPtCio^Z+CX1n2eRr0bleO<3|08-^&nh>AMy>or%FR#s%GG`1{2s){ zSc_047(A)Qi|68kA@kv8MP9a>*)2q=dPBZJ9tTs(a$GbfULMlkWtqIr^R41rcZrW;-AOr zYE@|~UL%0Dzd57xhXRxivOjLn!l5<8gtdVQMl_0-jWf$@Gv3QNkes95y`{^|EKBA$ ziOWr}o=I|(0OQb;(OZPr^A|xSK#Yjs2+ipV>Xxse>L>coML1E zGB7tx12VA4Kce2p7K6XfrZUt6%wk?9`#D0J9p5oWMe!&8*K(?kXh8w?Y)Ty}j%A9T1q?Zj8!F&G%B%W%0ya6@itne+9>--|_5L<_C@q z@*&pttLz=S@Lyf$K@B|I4MOqS9{~4md)CdzuJ@)~U0{Z1}z#f7ERuK<2meHsxlM}y0I*+OX=dod`vR3>O|C zL#8cp0ZsxKSMqCFuu4FBs?9cQmT+KxHa!lT%fJu!jwA|*r)z{{z@^gvG>#IDRg^Vc{Y3!mX$17ITDF9)U_#nLnq8SP*MxuY-04@&or7dlT!8J_M|+OV2Z~mGnwou zpN$ufYLAW^RBxx7{-UQvl9?n}r_;vkbtj93wa31j z&p;!vu)(*wJ&%GO-VQ(=FQ}SW7@`N+0ifQ4^~v@jijS9$sUQD9S=wYxF4w6Z*4vl+69vw1$?4=~QKm+DXZkzG9- z?R4rRW7cutXHE`sKTTG#J#sI2#iN}eJ2b~pA1vRj0uf=ceRe=0WV;+uhqebQ}Y;L*;Nc0Aib@cD@M z;~eAYC~+@$=Z>GsA|NjqxnN!M(Z&%71wfU})9NzgI#RUr$xI9|p~?|*bvAfMK+*u%MI>!mhFg5*me`P7XPMKpV5 zp^WYlF}X6*&ft2ap@ww=T2D1VL$(Xjy|2mC@&!QGt%NU-1pmjFS6>);F$+#Lo6f;)3aump$TGPp}{_rT!p?l8#k zanAdFcb$9xyVk!}_w=egUDZ`xyY_zS*}EgvROE0lDKU|dkZ?ZBf6_ogLODl5dYOWb z`YZwRFNHr}UbtzI_z zh2}O|y6&2eHqOcx?xtT%-A$imNJzf)=JqzuYECwe?r!wL2EO#(^uk>4>3yDm!SDYm zar5x=|L+1Jp8t2xe`@?)HUif{RPd0Hp7=k1lGO4xK1_f0)vyoz)IQ|g+*jH>6{%PC zMKS5^4~lg`6*IInL7T}MoW$>Sd+nctLw~U_I#iIyy;K=ytbT>ceemmh97WQZ#L67F zVA>X<>cw<$BlK8vGLkCrus!my{FSBX>-x5VW6w_e?c4Xd75J69F|t9g(f@S}6AteI z7vVF_TmcB=ZgXy3rLP{?IS7n@-GUy(g@Ya2zi_sHkRlKuZgz%(N{@lE@wu#!x2XNs z9dDN2{%{C#Glq)oBZ?&czYaktHp{t6eNC55eJ&eup8%xKWsvR_XV0{D>HtbLMnus@ z15Y)}{pS)Kr!toMlJB0#>FB_OCKnb&INr{G%BJ&g2OiY% zWOKx96KQNx2uzH85smc2s%RRI(l8)Y#Cp%{fiyJj6!{_2qX+PsAY5pOp=n}yxja-y zSXkISNA0Zl_qix#?7q2U;l$)(&WFt4;NabpgDJ;T{nx8H81qGA7$e>*fsglrYsFeD@`kBo4oY6cJAF3d~@J>Fj{E5!?hGzn0s{?4I}>?S;&f6rX?qoQf{1*GSf zBUi_-BgU(UR;9uOJ4fNN(9h$Ge?p9!mp?KR2F{sDDk@e3`qf{Mp5D7`_M0Y}ykMLL z$Hp>g#xXZFH?7^E)rd()dR^|S&(e4%=p=OQT-eCGmYb!>JwiV^r|pXA6B85DFG|VG zgocuPGAjvYP;G}C|Kf>1&XYYqTWkpLJM*S4P)Vn(%A_G}%3D&&#QL}PO<^T|p@pCs z)EP!9r}E(*VwB(rS=g(-!)woWx@_i7<*2B1xD=TBS7M+eDVbj6g`_|hz7bP0k zyWvD1sRBePxML7prukI4gk0Z5suOQVg>4#Og+F0!I47oKo}yv$!$XRgl(h5U%r=xP z(I_k@1}5lUQCCNLqC*yo{Jx?g;1suCUO1gKD~*(oaX@0oeurM!@WlM|i_ zA2rO>+Rkn&G~)R3@;axWfa?C{WXgYB^>|hB?Z%pPc&*uZPN$8gzk2qp_c~)5>oAjQ z#vjdSA&1%1f18Xov*4x#9Uz!wO!R^;1MGRASLJcQJH=n-!T&MO)YzDIaEPtKYRvJ< zpghrgL;Ia2%ee-_d13bk-@M0Ll~TYuRhG+!g5qM#p(J)05AE7G#Uj^ahT9au%Ybo#h@eg>3#%VV@C&l%mt^zmU6*Bp z>KZ)g6&6=PlYVG2W*=8mGw3oxJdVG#u=JC%GEV1O1wfa>pb1+s>HQ1?oIGh?$gO7O z-|K~pN=t(s*hYN-bNZc^Z0wn2=s5=xq>ih;lyI^vG+(coud4$rdM+FlQDhaU;_T)0 zDyS@IZR$;P68Uja%Y{os0crPTq~1EJa-oV`*_{2#uua7|QbXqrX4q9wP*@uslC}fQ zv&fY-8gktF1?xBVPB>}Zs`C!Wd$$^c+a=XavyG)WiLv+GSnnGU)CD`Pj5KoNLW#aw zy)J!_lyf4RJUR#kYFMb<*+jr{7XgS^r9ipxfOIS1HNJe0kIBb{w>4un^<`ycDeWfW zfO35yt$yop$J3VP62-aboa$;KQj)raP%TQ#e~sEOMlfAPtc)+2{AJy!z#pKxgj=2S zNx1iXFFf>YQ^P)%iK^19N1?TwIv`a=V2`D4<8!zhiO(PPBJ^6kkcmmUNroL2_g53+ zG@X0P`1S*g*R}Tqan7K!s?;r=3=vhVmuqT2WMs%mjHajER-GGas!9tB@k?N(6K;X9 zGJ^uSdUd_tk@qd|R}~9KRtXmS$pobuHz%`gII0rxUw~B?MrsmwRq?ZsWvyU_vqRi) zV>Hzzlmg-Wm518A9i!^gan7cvL*6m#?4URW$++3v$AV0d0^X6kpb_ZqedxTpV?w3* z0)I_?-JbdUhabbUt#-+n1|N|3Gx})3T5MEoY$Y{0lWQ&Bd_(_wE9i4-oIGhtXhq6O zW!}egR%e|TV|W8IR)Vzxzpli0sP>`r3k#QFWYpcgZmc{yWyWPUp{u_uD$O)73N*{h zs?h+|7_pB8er9%bDmUR*5xnJg$saX<(Qha1*3WQLX>QnE)>L6+%x;wVTs0By{P!uC z+^9+IKNzOHM=GQTS}gx^9U7<1=Se&MC8a7sXd`0vu<`b%H5*?pxcBp;hP=5sgH%UW zMuy@pZF)8pYM5`>ljs+6oTrFuPO#Hb$;oHz2Yc^y6@VNp(>>bdY&xD zW*j>@Xz1#GO)LQ%On@4BwEyi`@hx9kv7FZg5)SFk%xQY51HIRn&qn_$s^G23%;_fj zcZV!_cbL!rEkKb>0mnE&4E`Gk!nZ_G-~4ZIs`J(F@jvt8KsBm=Tk&UDmn);`BrvJZIk^bjk`F`(JMt-6Pd!qiN_=eSGNbK`(1r2h};7agH z$XPcV{=ti8S*@3Op)X1+XJPSnaA-(fOZV4E75A{r|9I>UMtE1?w{^njC0}afhA~rW z92^vc{OrMVe*HqZ*dFQH*Di6HYZ|KfGC=5%Q8vu`|83z#T%AFSHFtT_KC7X}mi8&A z)w$7dw!;5q`J(IF{hgWIibDJ~dGhA#!^x;t!zj`J+3(I*ii=;Qy6t7MI5Jgt5lY}{QSq%T;WFX$szmfYUlktaAUhRL*go~rxRY`7LJ;#^#;?pvJNL#kSbk*d`0t z4(KJP##P&de`aQKpzU~ndr*b8&LF8Yd(lYE0+qcFmpny9MHAc7Q7!B`Mn#BSDL1>om9%X3sNvG4pK{}Cj7>q4Fm$gb3h|?qNu%UVY#TzW z`G8I?!%_q=4em5aW7fQc+T0b-pGqF-Ej3N`MoioB-OyjJmB=i=Q}8z%iHTg-3=DTo zc>Lm`?CH&*HJq4=o^(b}?0DTWL0-B~scqsXWv(Eo03A7!f-D7s;l`pyfH2PjB5n&u zWyZ5i@p|yrWe13rSu`cs%HBpU z9A(t-xYFNhw=~Z3i=a&5Yz*B_IpyEGOF!v(&IYcdNA86+6A|XW$lUwUACNg#Fl2l! z583;AW&y9Bv)9k3iu zS+N>E%)@<+y^Q@djG>~?i*4GNIE+_&D&K^CsF~Sb=B*YDKHwxPSyA!K#DgTxN0h7N zeoV(<_(uEy%TcQXhy4~I}mA|9!g~A8E=FCHjwr3em$9 ziCr_1Ke6Q}NtbzxhZmCp~-S}H84ub%$AZ-v9l`?FE1<{AB;H* z3*h0(U}t9sRob(<A`kFPC{$wQRel+8>A_&nY)ddT4L^UQZXaI&)gC6`^zV+W0r%EicF|IsG4k6=QMWw==7!hcV(qFlcx zir?X9V6iXZ{u1x4KtS*;;?bt-54u>iYd|}Q?(x3!m9=y8STqmhdCSvZk}04%hPoR5 z-oJmtUEg@4FVCpiGgipx{~1v(EYsXMwN0Pa4IM!1Tx3bu-Pe6BZ>GZj3!J;vfuYnH zo7#{lQC1#wlFz(({pL(&@A6SK;-{9D%1C^k1*YMVQ7w~`lQnynrp)Js!@uYud)!NE z@k%nwO3DtFi+b0VImT0CZN&oX1KlCSbHR@<@8$?XqH)AUN(GpTQ8Jme)=A`YZ>Mtm zoI{I6P$##4v|Y>!dvQe3fr;19=sq3Ja&zQk5y`bwk7}EKD7qVc98k@9@(LhZv&s~+ znk+W>T(A(!$!S~)8?Vj`zdZwwc>%e|yYrP(FZ)W%4C?o{Xj9rYK2Na(xSei&!U&ZH zVHu%D;Ut}*u)-ey<9f&#?4={q*uF2{npfRm1vyK0;$D2=x~rq#`K)!<%k)=oq&N12 zt`fv?{r*jIdIIy!#3OV)uGhv1*>k0ZrpFV@Lj(dp+ z_EdobXkyHvE(u5}Ywhs7BVXy&rBzPok3_5~yHe91gU-Ce*!NnE|2XT;VKYADvGA53 z10*YZ_`!y-d}+%`r@9HZAFB1kUntdLCdhc-pf;8(hm&tM@f-1|ds}hbd~#J39Tm5t z&(k#zNE&M=oO!7~S_K_VO#ihM`%MZ@Y2fy+)<0rJ2xt2EVmY4BW6yX?5Iv0aMKkz`3*TS-ln>`^EJ;;B_`_j2a(uB8|T%|z`6A93Tb{29kK z*J%C}biXXjXiS$Ak&_N~ft8#QL9L%%sEw$SYOl`Y9yCCikU0;g0L$ zg_4oI8E>M|(;ZiB!RwP1Xm~ipN>}v6>Tb~kW+Yhggyh-QP9dI@$Eyh^^NDroLF`c!{7e26CQf969Lj;GAj;VzrwD?sLB=+Vc4;YdbgAj zxfhVz0r`gb3d|enE|}Ray53e&DzjLKcedSeFJRvoEox1ht0>)8!(a)LT0 zkNx?hpi*X$nUg}(Y}0%D*Yea&P=X^2qAI-gSXA0TVPE>l7xR&;_+e%ggW)&N7)$oMXdnF< z*yeGKKw;B91VXLM@^xyvarJ{r89Qk8#bv;4S47F(^si%xfIyd_UQxmHy99%`W8%?) z5>IX+^^P>$Lyf!L=Gxk~$)Q*#>D$7#rMlt;s~rIdSb%NtS!XXg@A*mF14(J?7k2;C zTspI{WwG01ulDe#+w1z%7zM_*isQx|+EU$0e+1TGtl}x> z(;ZX+@k-(zK6bWvF_vA@jCHf@i&x&@$B^N-&thcls-5BPrE*2>cW z?u`eNye(;eQ1rW%rt6%@l~afEG*?z~7Z@-|2H4u!o|OeW;knn;+gZ$dQ;un6f!8Dj2Ud8vf_I-Yt8#AChMHfUQe&lQ`_1SWcgsal;HH`s62$=b3m zw%|LNnTfG(fBW@@S<~j%AMRdrmsUku+J}!6mCIgHPY3MVpt zvU3^bR5BkD>F&h3tPP_#k9aNzL}K74uF`26bp8 zWWD?WBDA<$Vu0%Q9@{`ru-th(V594y0k&&SM^78fLZFi~`4thzi?b_Xg;c3L+}6>+ zHTWd>INa?WHhZ0^hERPm9MB7H8WK14qwuJTyU zPoJ->(!bJwr_-^NdI4IC|Afp>?9+M*AZD0cij2@~)fpBKIk)A8c4JuCyb_H>0zH~C z5?K<%-hVXuoKZZ56`y>WZO4V}B}sr8Js59=+o_=&y-&}E>WhX{Kt`HM1JCfgTE3v) zuFq|%L&_GHD21!sirkr=F}GtWs^^aqy%Q)djy44Z3|M2o%Ck7tRbnp9c&V6$7Mx9; z%7DJ}+bSHBN4$N9C@!P~a1tpYzKq0a#hpJQ*J-GW4r{%kzl;XH20b)nSPp^cxw*c6 za^fU;;~cQbfG&X$TxU{^E9~E(@{9+mW}a@YeKDqeFS{fWol=7ujx&tse;Qm^T-;gk zbk2D;m5IKufVetxas2LDv zmFWwBted}#6%iJ@e70_#WbF}+ZaeF3H_HWVs}q#pO4Hopm3|FBt=>F+RMfUeQg(P~lpRo>u=f%ExK z--)Jc(5J;$^PEj8Cfe>4(r+B>$|d_Iht@R5kYyzBhLgEBN4}WSX@7bDE#!kx1QE^=b6HUs1A!#p z+9w$oWVGwU?&~9*{u1WE#IdC5KzgR}ihGh4|4rft7ozt7Dtpr3_8xCm%q0)bGzGyA zNO3jyCT@Z?g&H9(oqi$0lrF_^#<id>En++0^m%;nxU<7+zjfJ!1>+$o>z6=O3Q-E~lCSOYX9~mCYGKB~C;m_O*4EbY zU=ILn&ct2VNPnZ*_r_6d{vQbC$mmQH#k!^whLW@8G>V%*M{WV&wl#~nz_KMEWEc8b(}YM z)hS~CfhS~KTC&bjU%DcRX4}k}JlpQ(69%toM8@X^mOc#Cw9J_tjP0gv5?*B@qVW7f zXgf0Age^@ZVEm&`hvawwj^9P>UgjpF^wWRQiYYaIq4(D;rXnnbwZcpxxTqM$ctv~<+i$y(Tc0Kp!c_mmMph3kFQ)Da*u7e zn5Z zs{bR^Pqf1nO+9Q)`k)A&YtrI2Z_|vy4d(Tll5=57-Z!e#Orf-BS?5(Po*Y31UZyvQ zsfeFt&c22qme6nKpy7cF8z1w&lEEXvG`NrR)>hF?wgH?VxcL{M1;50yw?{qg9NDg8 zcSdW0TCEvF(%67BA8}x77O`{_ zGQp&EwRY+c3oAJf{R9a#g3fh^3up_2iOdfZ5HF2fV>372%cMo41m!BG#T_E-ia zmh;`vuNpx=Q)dS>T<-01DlNf@nDf#4_LnOUy#l9*`{e=>H?6G4>+JALzgs04>VN}V zJJb5PS}Lu1^~&qD6*zv|nbXSeg_AY|0S%ir^FGgpG!Cr<9czhqL33uk9n#^aWljMG zSg?(SDxc^KW0yA5l%kN_$!})}_!!;q7utml#!Kg0L#}byzj9(Hm!@(Pv+V#-Sv{M% zkoB?ThqC&mVv;gw`R|$}q`(1L zHK^bVK#|?XnEAIM(d3HhgOW7p^r)ZeGKgPq>ho*;}CMQOUlBf4* z>h)wJRE{#q3iqR1spFu5T6Eti_qM6Lh@p}pl()%LjbDZlY_qC+2M1GhS8&lvr!SWT zf)zpAEg3@NZ;}nd{zmL-72sxF_S@;N1E}U^%IY`U|BW<)$z`IpFHD zzu@CT<#yT=E;Z1Myf!b3IECZja-M5H@+4u5y;A`jRiPyPq!gncGt@yF z%8{vfZ|EKOHTUW{hU0;VLopxRyEkZRGPPLL?5z&_Y~vz`Qd`=Bt&*(SF4|yi{n;fl zNjX)(E_5kYU^$|*Q!4$;Z$NEMM+0Q}i8g?(q*#kJZ^mvlI&iQ=sg@4QI=3P*QGR+}c#;9q|mX4$;DPL2el*zG+E4)_y7~ zEG%;RM^kk#)F0ZkZ(CMMeY|F}b-57kUjkWy$9e6poPBH;LOz?UJ-CF4_?u=%dT{^4 zLzCm>sy;F7Gw;+6MBBC$^P@;~YXHg&UnJY!R2s!c$e6N}_p#qBhI=jf;yJEV=zj3j z?h-lf-8MMx-q*lF#=rs?UH}X$3yIIHZR?*{h-fY@LR=-v=hGYx%H=M4>$4n=t_1xz z?kBvLnpZhXreIf;4ho&{9_!{qS?bme2J2;KD*b7(SXdjDx>sABfHtGDr8}oC7H~_{ z!%}Kxkz_ZuKIn&pSYd;+yVlLRB7ujG`@;sm2#B;yy0GGXtK$m%ql{XQn6B;%-v9y8 zGMtJ}U8j6>!Ed<=AIjwyL{tmCJ=j~Rmxef0)Ab$py&3djDI1JuLtMK5rv1vTCbcZg+gajYZ z7K3=VCjaDI2*?>Rev?L0oD5&O$IWtk{UV$tMj!)DQkRbYdJasiDsd%93%>M8qekER z^5KVey5}8IhWDj<%k4VgP!vQtBDeB87a|sF1ze1K3^yRas9&F35f5u+QZc*#u4?OJ zd7wDk=D;-1@N)L?+%!aqfO?^hDjhsB+jyledbQ~04Z45h&QH_jR=o1~P)B2ZY~K;L z)JLFxQqVypQqepI?fOfEmi|XhiMcrH4$;;asUtx0sW%80Mt)@3>2=GjCQ_q5UE)*x z=!#$v7k`)6&s&m=mFT7tPULeeDkfGFkOdstP!)}9^}X5OqjhRNaJbvjG}103aVfpk zyfTq`e0TMiv)E)g{fEipIs>QaanED894DtDGKp-ZtsaeF`~!%{EiQrkw|f+@GbX+-g_ly~>IhjNOFSmllTwluhpUpK#c zsun6lGu)Q9-R)=BP_p?AlpEJ#+Rc=9Y^aK77m)FC{-gUTk6#4xdEZ)?ei8Xj@NBf1 z&$q`ip#r~6s2EA>%^Z&~1yx1Eo&0Xfe`oG(L~*pdE^V(j<|q1BR~kkKuj)yqUD&8;saD!?n;%cAovqcK;8 zHiAnM~dTSlsT#PJ-|c|EqJ^$6Hf=*;nQ_L_YL zJ{Pr{zDv%+)LbQgmCdEa4~(WBbG62u>A(;vCt5>XHYH28b1WeTSlJc2$`&fDHKYfl z8C1&K#s1Aea5d^>{V0>mcMOtjdoAc)tV7>*u>{q`+ zrue-*k{ZtHIS37Sw0l^~eBf@oRt0vYJNaOVUy9I8{%8l^^QQ?3d7Sx%AA`x zLz{OI>&fli&o$%f+aHglIopcDY&zq^U`Af)8B%^GPcO>SHspIVA2yj%1e|CAQ2nwg zX0n=vrKwohbgTVGx8Rt{utd)HsUvX*&~{0-Pjmr?F1kX!djD+F^i(~W_zY@j5L*rW zB;U?IKC+tnhB*-aWco%rtHh6e8Lo{s5~tRU{Jp35ch*He)kk%9Qm9eXmlGH2BfycY zrsMO9*uj}L=8=)AxI=SaV1YJMkT}`PEKNyBAtGC?fnH)N%g%KA<=$BK;PjM>PEPKf z#FeayE#~)&+KD&SWFp!}{?jbAD1OYoU^Yy=c2rHip!JsvYE?Hf)BRdDE*T=^TGXz# z+%VQ?kwy99+qc@jKL=}33g|eOkOK6|0N3dPlkjx4EzaUQd_ydUCT2kobT_SKk!FK< zt+Uz^QLp-pk0;-T@Hv>n^|s^$+fkHtmV(<}+2ISg%?xc0GTozS4XO+EK^}XpMMf)3 zfnNv3Sf>gTxMqfPjjqQU*bbe+QITe%Zq(=|hy2694ArfRes#gMPS^CfI$iSG1-j1l z@b>5+qWhX4hy^6qR}WRcyn)DQ2s*AY>q404Yy9bTJF#-=arejcV&DANbgrh|I$z8> zYsHmWIgj|G{R@5#3$gR(OHkv?4GC_0R2Tb3VPcu&t{)<;ZhYGGla?_~ zFK%bmHWHYieBb0i)d>+-c%?D_DKU9eB_!aAjS&Qzd}rQQzCWoQ{8HGyI`VVti!0{J z?@XtErc~D-PXZ+VCXm~y)o(5O1q35j9(w5{h-U1%2f8zj>yonwPIQ{LY4eolv@mT7RF)H^l0kebXg62P}DuTpO2r zQx(PG0rZ9Rg$4WPd2-qJPdC9&UC*4>S%z0T6%}W@-yqPBks4#;XUQ|#)}t`?-?DJO zazD6afVLri0#w=_kGu}ZPMz^Ej-C`qKKlDSw;nJ5yc$DO&2w&xaQHk=FxlQZcqn(03QiX17k{{Y2it* z8wS(#^dX-wo@zXyxpMY_FT7Q0IzK+TqC^i~{WK~swTNS0}n3F&0#AtXU*F*KK4IDc6(F1G4b)xZ!e**p<4}rQXf@1sR4vejYcHL zc9WAJMM=9A%Bl9BgIgC+i9?o^{NZD|yzU`+sd1qkbgS*j{vT61QK%A-RSHnG+q(09 z_m0cpM(7aojxpIsMZFdAkd&KpF$_`5I{%$_{u@}0PQXcaqIyN8D^9;G#b*S^#U3`w z@A^4aR`ZwPb{IL`VNtjFLMAZ@NnS>WJ23isR$}#TJ#1aoiL!9mhH0u*=}qIX9AQ&m zQBBAr2`eE5zf{kgNAcVQ3L|+Ax1_7UpKn2*(slCOjJu4p3TX1xxU@&LGu-%Wr;?f{ zYHhKo_l5EjS`oxbgU0Wn`0A?hqrvjV;;^8>Jv_ULGqc6`A+h+0(1XINMcGdE2E`I? zCl!is`(Q!~J^lrCfclF9mf}JG=eoTFCN0T!t8?o0U$|LYaTD?O4aMm6t>qG%y+zAV zwEUeNU?Ct{4M%46KI%OR9S?VAOWBddP-d1ImW#?{op@eX@wE#eVdU?Ua|d_!zD6}u znA=I~ZtIgjO28SGc&YrIANlQV--O4_68Xc!&J=$it^sFlM{Pb~KPl*17&nsM!z^m*}3(M$x z?v|ffkxMnWq5qVl6Oc2hZmS-L63fM2ai92p&4Xl8bcj2qpwzN{w!wLyJ(dZjqoU6UwbNg5c=6baC^R}n z$xXDI#L~V^fPtjgAoKjoaq^NZ3P7+11Q&By58X*R8v=pYmcv2LsZ`vR4vJvVtFrj76&Iv-vxVz$~{n$}yWVLyF ze0joArdAX7&{P_Ox-rHxa(%Ju(|7O=dxk@{(@b-35z_Iq$Jw*?wJzXgDiqI$9Y;9E zJk-JbP9&qMtEL|B+BN{B<0zYOfLzSuN;()PlNY$NDK6-{pxr-)Lo~#`Ht*HjUuRGL zj-=g?J;A#7#Wcbp@1htDdY@6^2ETKpoQ)B<7=a?IO;P1I#3%FCCF4B5W? zzGq`d#bUIF+V$gpPBF)7P8Owj`;BF7$25rW8o`l{@WTbWZRf&^z4mt|)0B3v&d(QA zJKaps)&U~IGe&p;J%(a9BJHMhrQ+Lja|pG@u2PC33qn$Don3OPc$Y134`$CQq=*~)FsJ@ zxy_XX>Z&AwGX21xO^t;t6*;X;A@hy35vce0H^Ut*X1s)>$ioH=#8^A9+&{FEJ0{py zY#cpRaBb#_;)`+)Y*e#5j1dy!_{E%y2}dgPB{Bboi5}b0>%$`%wRA`xpne9{1%7%g zEj7`&`m+9q-cGcgyI_hqkqCwB1mImffho7YH{-9I@;~&=7~M|4lz?H@K0PeooTWPjpgmmx zpMphJT$vE}?Fg!;%PZ&sS+ACW27GdDn@Hkz4X@I5OJVV;?FR3DJr&(P#7+4}td4!> z)R<_nd0!k(s~<(OvtSVL@eT&^7L`MxhZreCLx&vBhBG4*2LvP`n=E2D$_`rkU$=vxc4 zvK^7F%qxfpTf4UtRd9#h%zDc7L0l5N;3vY=0%!< zF>U*FH21p9ofg=ayX?4F4-AG3vxd~TB0ooR%2>HVwc5LT^{NAk&60=AVRx$}hq|>n zAXkDhwMU;g*}W9?>)!+}4;IbK-n50}8{l5JJUFUS>S>phB=YjRyNAbKZLbi1P?YGk z;_M1nLZrSrzo}A$NE#QD+3B@cCnZ+FB+rlWX32U(xJnt96^JZj9&fBor-t#e=9uvu zwK;z0M5eP?_;L?1qZL0mQGM__z7jooxhl)?GyA+T7`feN+XMUEVMX}-Gf84F;lvsw zFqS{4PhQcq_Tgp?E=Ma9o`?J)FHMC;W+*#Y(9>Jux)!;Xgw)=5Q$XJnZ_`v=`^93h zgwuzjDkqPQvb!^Y&YSa`5%0qRG6I*RoSY`w<^Ip2XPa2NkwRI9BLph(mHqILa)Uol zL;#JVmK(%|MCXNEK!~>@)}8;37yj)8#3Y>;tp`sW{XS7ApFIvQ6?g8?Y%)r;Qy~@T z*>;n;0y~&jZ#(VbTsK%jkhYyCLbKLxU1kOI%;4G|`_ZQ2fO|myS}A9>bP04#MkLKg z%Gqhf{VSMpmzBhg5cp}Q{nY2-EE9q8cj$6IIVc+`)pqw-HQ-v4TF4dU#BWEW((_3F zk^U!Zc{>86n@9%{z3UeOX5P9kw}D0CXhot9pv|;fTU+|@WUOW1)m2G8e*X0)JLnYW zpLkm4Uek#jnG^x9j5q@~w~GW;mREnr5e1*V2>jv=rSakTVY;3voMF4RZJBK%kG1gT zhkx}zx{hwx{=Ta>brI*KKA~a5VlX`vZ5#Vull|}AvsL7NBN^Q+t}hTxUtkFXc!jLh za!Iw6E#b2xH{m-_TR4kA$B$mU#5s|Drb~O+@H%ql8!-|cg_gAb4(Ige2p8LIVHc2Z z*YQ?;VfAt~q627^QZTXK&8EF!EobN!Fu>+XRAErGoeKKX2`KXQDaI@m=PHNDX*h1S z@iSs)R*}`u;#bd4)Zg-8j{-wOMDUiwz^7@#2^!WVJDvQqSXOdGQWmx7WC?}7a=70+ zoMAkPu3Gu(k$vWM8*oEPc)xfIZDXpqz%d1j!)J~Qr8Q;|OxQ*KxGL*mgA%^LGFLv# z6~`G@_O;f&3niBof9$rzfQNE4D-bXp&LV!wV>r?mK1iA=LIwM*gI4E_{YuX3WiVL( zGNRQPJ+HZr9{N~QCFJUp#fo~g2s z_2A9xvDgYu?B<>*@Anwd3olX^Fr4D$w(9XnA)1OG=V}*9!!fArtDWF7k|Q)7=h5e|vaeE&q~R*ri2qQ!)48s$c3r0(L1JrX zS84iqXG#+19(>K&e5o;e$S-=ku(C_`2v?H(Cz&lDuk8Tt0&Q!ftzYqEb8Lj?vm}Z* zwkva%1~e6Yjy{&Oil=nQro7#|;8m*X5~V3z<&NpXdd_{ORax5PYae~*twI+Fb)^kT zbR#G%4QA&;mjg1)ctaab973HA~ zz)_Et#~ud8*2UJp*+2h9tUY*Q^7#WOxw!6tIjY2-!i_wEjzE>5Gtcd>n36bQ3C|19 z=`|fPg7?rV5$pqZa&!H^X&Ql?V?P>IR!4^7C)d0D8wNFXNJW%aMGk531t8lAzUA!x zp<`kR*=-z8&WgA5t@bX^k3t{nM-_y9g1$yE^MuVkep5odjRjQ^Ajcm=X+&T^Iuvqj%kuIB&L{ z&Bl#lLI9(MTt!xcJhLS*miJ<9Sknu1K{ux*@+t52y*Yc5*D+o!<`T9C``&gJRmQr2t;kd*8M9#$QPk z_tlM(DA5^sxP?|iM&3F59i@CAeJ`587x@e^{qLqCXvDF359pg|0#Cqr9dwWK?Q%>( zz{C;maI2sFx(p{0wH;s9Udm@9MGtLwY7fPGu1ftq)!5l;dwaR zDo!I%wiUrrGPh9A@lYj1CFI(@ed(Uy%@tob%g*lWG}v&Ui)35LDYCT3qu z#PQ-w&v2uHE^m|hxF*?*&V-mQU^9x*L3wy?E(Ui!8MhMwW?UO?bO6$FuG8+pWArmU zwM9-ZLsHS*2?C3XT`;0yH=kvDcY6#bh%EuOAyIb2KhRbl5_gSiU&VL2b|0ze28*|{ zg#S1?bQcKL#Few#qp&NFEl}>a`2|)K$nrh<;Ot)edu}RU>AQaRUWri@vZDf*QW|e| zW{ku_S8m;z_PyY7zx2*sD!~;gJuuI!rcep42NhVVxbd`ZCsH9Zbch8B*JKCT#CMy)!H{crls=z)nSVoltqLl_p@~xaYZf4E~cLs}GakOSvQ8J!muI>xs+?zlE z*I~u`1Q*1%?Tuk(jP2yOB;u*4<3(Pmmcl>LKx<;>l!nTEHD<|{MLUc|a*CeN zModI8y#GKv*3V*$5V!ci>Vf+_^Kr@$TopfVy5soMTrD9gjr~hjE>0jLOc>j|qJXXy z99*nQ6*zVh>@*%8*k;`Q9?tBE;@o71WHf?fO((w_*sve@JFAKg^E$WH7yn(N2ST3w zaZp9`Bn$L(#gHW530n$EilfEGy-P$%xHrYVMV(k#2+lBOZOye7@*rG7M6gP*+CK~t z7{{;mthvYB&rz^xZ2}6d?7!PiRdC2Bro~qd|9A=WU4BV)K%sqe^|XA_@w7qLWvCyO zLx;fMj=~I~^Tm!&2F@I8%mGTrZ$dNu2;&_VWWm6yYfxDQl1Nna)tSBNW&II~={qV; zVjQ;p8HTSz(cRiNFD_<~;ak7IDa)Uyr7e~n=3$1atL0O*mHJ<;LeDleRoAyu9eW+> zmy3a6M1f~J^CZ-$%!LZlqJSwNn~)nMsnG+gT6 zwJ^iro@mmY8pWrbY1lzgQ#*LK9(1#^_CWSG1+~^0;_x+YRE1h%nQP1SaMq=4-27r~ zWHv;tY$Th1M@VYxM_25zVtJqt@yD&1%X}s|w zB#L$1Zv$+-;Fr9N6nxzoxY)AeTeMr9$jIbmNarkOt@rEHV}lhr zrr|k>qk0JJgLXnG8L~`=y8AhQtL6+dYBxOwsr$o{@fc4Zypb6Gfc)mLm@g_@lq3#m z^orS&gSsyvkCakR*5U0fkVht5*HwA3u&xy2A-k||+zWKyZ1~-k=dSpU!>gf0f%~Dm zdeyHmO7_JyB^ABAGljQ*X6=V%-z)9=T$ET4qUB0fK!T+J5E_rizJs9ok%sNCHTm_tV*pc%Pa>-YU?~B=b*~uwL>>p_wI%*DB zUL~u_75SQBnWglB|M-rW@B|@B=!IZW(?`3#Hx;ghxXIOu_z|4t{l15P<7)FubGn_} zNPZiqwh3~*SqYGsDb*8u^ORdmQ1Ru=tkj?x7ut#tj-wSTUMet{>*QOuhBhaobG`W$jHV;6r_ zB1>U; zh|zy*Xu#+{GhzvK#BIl}8i}>j+B}1si)8fi2@sp{Spg%*-jRR~*(PGDL9>uG?vnvP z7KPbg4x{&lF}drbyHhR->~hOz!uOtrL=awoL9D2qhdhc$OI@CV*~tuoYo&p$`Zv_5 zW=A%1Yn3q5SQKpv=iR-9H2tByy1{RR7N2`!?KCJ4_+&*xBeu!*4l=HZ`t24WzW}z| z*NQ3r4RP7Qbo7Qr>KTCYZ0Pwk^AI4FX02^w)}sM!*$lqfrH0z=%*%6QLz7>$ysE+OGQ5fG)As zaF4egn^|n^-J+p!T+oRhS`S1F^?q8%j<=9!?eRQW{h^zv|Gt~4M!gD(H=$!ZaRWht zy2Xw@8bfgx?9CMNXR3I9@z@?OHr_7b1(2r-ICL^eATV0*583M%OW7{W`=+DW$D!@B zrpK&_gRFM;)RXBdf9(WBSZ|15;p<=V{gHU+W;%P0q8X`%8nsvxsAPy1wI83p5oqJG z=yF!Fv@Lr9y%?%nIq7n!&z}if0|mt7uFY6$+S!DAu4H#sIWFlxToy?5Jbwz~pY0+! zYuIVWz18OdGmic#^uhZqFWEh9k8~p)V`)3u^}E7>klXeux3(^h1O{-I4N&^~#DBL7 z)Y_3Lar(8*((oS_V(QuD#lJwCrk}cmi?89p&hw+Fc9D_MYM!;ek<q3SFjn(p7QeJj!>(ybs0qq{*#rDHUV z66x+%x{>ad8r_{Eq&uWXH=}do*?s?>=f$&sU~j(r?EAUS^EfWPO5W{-8T-c+TPXxI ztGeW9xURl{iOjBX218tz@_e#nE9lV0t)dIH^I-=gX@RM07qYY-ys4EV^LKm@YA22> zFYu4KJM%?)%sx|R-i7YnZiPfiElExLOKqTlJ}a(Qx<%u25EjLQD9vKX?E>r6%ohVz z*{LQcZW|QQrC0|?)b@`zO!5UO>P4b(exWl+!A1A(rwK4KbpLFZ>B%|eFcu-zV0E2n zYJTL{mqpWOAeU*kO}kuJg^v#B7qjEW*~_iut|A2Ia8Xucsi_DAg*7P_if3h*=A ztuibnZp)qtRd>`hxx58e^XxY~rLqyTBi@|uqRs6YKjaLd(07rCIA4gP6yZV!{fLfU znAT@-{`2Ej)gtuNfmK)%IUILaw9w+$2(TxH=IqhII7;OFf$N!#sBM@h_LOV?33#PS z<-SH=`H?2Gi^49+ka(FUprh3IOKCbL{2SR=a=2o}T!cEYA3a>UNHh0PJA+rF(#e1{ zP3Ik33SqLNn6POuuf(j)XIG9NNhpD2BP!tcM+t@U#_P4xInIEJ!df+2N{1|wqo@0a z6sdI&l%Mv#^0cw9il=F=yv~0)#nSsa&uViI{GvPaUVrXHvJT}qXP$eacPr-N#fEag zBGJoZ&Gx(LNG~Aef@!1_ zmKVxoYZ}~LjLtXvo6kCL53Wh^XhZ~#<#X^wl8pb&36WSazuWPO;8lQ8&ldL94f1+J zd>h#HmFa@)Mt>6j^gIGoV(_;#T3d4pQwUAUj4LpB1$T-jGbmIAV z;wthO%v{yyy#}XgKU#CgWj^y;XoKCfooTXniBRL8ev?Q203UJ7ffWiBgLQ+?(EjZj zdmTo`@%eo2+=&sc&p%th7ZW&M^7#+h83nxoXZ1E}RJwKdD}mMXmfXR{b}k$PlJDQl zo%HDszlw>7^opEvy=R5dC{_&iUr#(}*-GpYyO%_L%|A|Brz>63q+*aM3}Dy@om+@) z=2m8=!os%=ojaQ`yyQ04#+80U{2|S_xU2JlcxnANB)EAs&t0Oz=K`H^yVXZuFa6YV zCk}I7u($B z&bD8?+G7c-gC`CLen!q@i%w}@6u>9;teSZ?*y>f43B2YF(6zkjBS5}@!qJ_|R6vdm z$|}HKsg$FLNCO9d0WxAO^6Kn-)xouK8~C0)f;GhWw@9uaWY8r)Aj)&V^{7OD%lCKz zmfBS>%Rn=e1jkP|XP)HB)2ruJLr~hyu-~xn^Cfv6$2unFz6*(uMV!-A#>q<4tkSUI zgwWZ)R{-1Wx$;63`aS1F?hca=8!#c#JBNQ+)Fu{nMf;bLN#k4&q(2-`uS>s$Zx{?^*y6!nkJz5eB%Cb#Qj3V$PRNt;qE3OTr z1o%87`|%6U_eUO2;e$2KdrCY!JR8We-lTQC?`d65utA3pXyt)t)VJc(Dpt2Tj!WjJ zi}15T8; zXNLYlEkXpV>Rh^y_e@~+hTjrNaNTF(3YZO87c1pV)8kY%n5RFZP9M&t>5!y`#msa@zD>_$BN|>hf%VxmxQ9(`?{662@6Mw?8(0; z!h=2>*-u7v?dAA`3{CZ0Li&+tSXbvQZRbPmMK1yJiV}p4vr3|x<=fc6wJhp05&1ju z6;QXvmmiecs0z549^A`aiCw0GO&A7$`N|v6AV1l5L-ERrq}THS1CZ_ePj*O$13#^L zG!z3(kiud}=x&cqw%Mdo^MUx-lO{R$nQDgwlC2&$D4=7ruZjp7+3oIYh~DC?5ZFpL zZtUrFUfmSjQUm_%K`pB%Pf`ST?;GA8tjMt@mrfB0?&VG|8@3UBpSy8s;OnL!`(fY1 z;6;cP;wlo+Uc=}V#zZowZu6*R6VOqG5_2Qdw{riGUQkAk>TM`fo{N(Q_GDbT7qD5; z?_ChK5{Pm;|B|Ju&hpaSoKOPr{K(cqQPZooP3uRzMqdRfyAV?@WR-md$S9>G0`8_2 zeAb5iG=>=6As^crqu(MMynu^TEhb)G zu3+%#q(SRY^+gIakK7-Z`$o8=y#ThP{Y1<9ESN-ccn>8qch42ysT`{$KBg+9U`s0~ zZr!bWSxGIm}{BY)#C! z-p&!ZBVv)n4L|=ODSNP0hzxXuWI;lq%{RJ80&XT`FP@5OR(L6d*3SdTKx17ZlY%Xt zUa<7fQ*InrHg77hXkYgxVl1P+$HVBmn&Zuw|KkVH-y1H(xwT>N$iei&zRed6r%0r? zMXr6f==;;eGlCsig^R6F7LDn98c8g6N11@Dbi9v+R@i%oYA(TtXyI{wI`BDj1lFK3 z64(E7k}7q7h2)Kp5|gJf^Jf|Vv|-KN^WcGl4)N!M37GivrTE>h|5ICI0kZ+IX6Lug z^Qvd8GQbbo2UzH}s83uJ@b!IweuEV;Vk_f0=HHsDdJZB{bC*@O9z*hyZz;uJ&+PU*zA0_vr3YUyYpGx9+dr7HgJT9iv*j!2>CcXRv;M5#Vj&|k zBh8bB_h;%|!_HDza+6(~SfWm01v?i?G*ai;dqy$R2RchVL^emNOp;Lt@f15sD^Q8* zd_2r+`9hUxD|JLkjQWV9K-+Sn9#fgQ3N=fD^dluxQc17QN6x<#;r)>eiO6LKdU&m~_l z9jczxqJFmVX3o8)aA{^`sPXvT@NLz3u9Jh$sxbW+IogflKs-820ZuXJL$ohVuKpS`AFW!XG51M9t+NA7JjGvE8MI$(&4=M46gL_mN#c;15UY>XsVR8Q-%0u0-uO z+QOb8;`>wHraueL5gnBz;#H-e~9=a zT^FFpplq<+^Kw#rGIo4i$w1Z3&2MO35tC5Vo9!37uAQW``O;{Xc>FL)0?6%sWN5bc5d0j%!`w)--Nb$Q9Cvk|ekwyQNgWhO&H3 z;o#=q#YanF+i!S{oH6#U`Vg&23O5+IGcOd6tWFJ$N`{EmNlKZe6*Qs5RB8&e0UztO z>a*3XFdx+Xb^>fy5Nu{=L5*j}Hk!9hjCH5R#qXo}=$JoZDmiCiJ1^pgUIc3Uc6dcp z@NP)14Z$HX5+mPP=xfy+I$BGzL7B+Ds$M-B^g>rEDW_*i+UvauVvSU_{?Rkllt5I% zj>VWmX8XK_f)m%`pS>~Jp66B%OuP&wbLBPKPu_O%Yyu-d$6sKy43 ztu22vR1lEu2Y>xa$65Q5pD-lFm%eD(11hBB>B+?K9-{0nCAD_k`;aat(gb*P6tmtV zZ}bpK%30GUD)Z^&tVoiL_Y;>;7WoN7!SB{Lz+GNy2orl2d04v@dxbcA{$*h$w@gJd z&u^nab>#u0b#?W^LM&P(ADAJPQ+FC+)?5F=o`Wa$Es{CT)=n3N?0%Rj23}0MdV1&Q z%05)MAC>l}oSxx1&%qPO=97opk*2^gUr;Z>iuYN^9V}EVsHyYB)@v0NfZlZzYdELw zWazg;{B-^NXkGFC8x(5MR`s;11#2FD+u6-!TqrU}fAQrIgpYupA@Jl=*ye8CT-~7u zA9IAvrDzfomh+tJVjtHYK|b5J{>sYiG!u~l=NqTW>-RVAS6Uty;o?uf*LWlF)jr@* zcI_gr2F0i7(U9-?&kFcu&*%95zh|D*kthS24@z|u6ub04#b6zJqp|=U`^IHi$hSk$ zaW}MOHVFXh2X3S>K(2OK(>(5^(vAyn#!h6=&d%GWjl2NxH^j8fzSY?Kv3%->>1SkI z&KjcQx>+6~p$>PX7S#B39o7%s%nVoZ-Vqm%h$SahicyIoBBEERBMV2~X3<-rLcT<9 z{yDX|(|%F(Tl?Zj_W6~Y(jd^SB(ac}SX6W;A=EU?nk|Z_m@CpZp>)`Pz_i@hHTAN_;#S?`?AhuDVc48$Y8U<$_K42%4jAGQh<+w$$6@mTl19s z5=;b=KK*;?)3e7mhbBG_T_G_!aTgCov)Ki3AGAYt!4 z4|o}6uUB$lI^CeG*0G2blZ15I)bymq&sNHy<5Nqx+sFE;IuU4ALSN$rUoGIIvU<5t z@mua69W5A!Sj5tA2t>rfP)&i8oAioy7 zM1vNyNX^~A&c^?@Ny#(xAth@n zNJoHt^L+No!~gADIw#dHZ^-V3PCdwHyqz70isjj=HFT0 z^>l9Z!OKhYiZ`(ea&d#I->Fb#%%+ElnH%zlXkpg(OAF7KIq;P|*iMxXIkMis+>OL> zK(R~Kc4FMD$z3ji5#6Ylq!!*l1>ftO&XBJAWApQ1b{~*GZ~lGAHKj}8kb!M9(}x+< zq^LHxlj)-;M|vzJGv3ak@4ZYM`Z<;D`TF)toXG_KEk?Rxux^wCZpLT3S>s9e9GrbV zS}-Zd<8zLo_eq0xomaF{ov8OMUNjNWf7!!k;7Ry#Bg6v=cM0uvqg*B_Q2I)RuYVNL zR^ucpIJcIeL>8L%pU^@6!=|`6)8%;GsIgp{d3yBcFKm}kX=38JQ^nNLFR82#{H5uO zJQKF!P2a=_|1J!CIPAn+_m=r^`n=tb#3KJ^g^>PGHbnT!SU16bE+y#KcK z_1~d^E}M>X_}YG8bgT_o<$`<1PikSe4bd|{{`m^M&=ip0*FtE`yWszwNTeVBW=)<~ zTTJzyE9Z^=K-6?V3Z)tUMM=z342t~A%F05I6;eHjcJt)~s+zHpW91%w%>rWY|7k;j zB_~XPKEtt`&@H>BwV(hl4J*D@Q-xxI^3;85S8C=qql5efep}zq;v!R^$IYuvi9#GZtSm1+DBEbfKORMz7+pr-Q}PL ziqKf9DK`vaH=q%G&JdpDWX>dZO`0=5{8^G96%)Q4Lg7^x+2LJnx;LJOW2Ak|Cw$tx zg;#O+aE|S}7bBrPn8f#`g+oj(NZn?dqi^l<2gVB`yn}N6fpOjtU{p|jnl?~^$ zdERU(>dM@mr%Ojy7UFi5aiYDkd!0R>iAq9lkeOOhQjy`)bV_{ykCxE?8l{hUUQyW1 z&Mony?$5}PuMMGwmX`7L;asc10DctDh@E8As}tuFi~fi$(ojTQR=ki<(PbVzi+fmI_I`jTT-> z2=e2y#e~>VDSv#j5Sx!C8AreJFWMY``u><>`;A8V_pt&RL>y6@!$D}-eK!GoAncG? z#d%QnZ#iXrv?m<%FL(;eG<;XEqgweWH6HuxppqMt7eEa@IoJOz)?OnJ18y9QSHa*T zPR?ASBGw$_UFdeao(rQE343iW^gTGE2D%~*z{2-HmQ6gb7fY7}@h*?GHskWf*!b*P zB`6hM0W$e)7JrB%$qde7uNc1NCVTdDU0szT3eU_pBXQpUmJChT5x%XP<00%<4b}^r zv10e3C1n-;r=s4I)AJD*NKa(Pw~B1P$CEQ3$|_`gYy1(D*^Cd+_0-RPFy+(b2kXfr zu#EaZnN9n+FRRg+e$I{*11x1m@=*jkmBV(N?{_F+HR5+T4GMBWsT}{hh zi^_y%*nTJ=u;)2e&Jn8+w~E1@Lj=sB?IpYa^NvEi;8^#Y_xU_X$G%+50-(%L&jMnAgXRPat zqS9uXDV(kR&d2$~^!0pEHqFZ1-*EZ4Itw)@6c1O%wvxZ?Zn-P?_8Bf7m5Kb3cO;_~h1bID}-a|T9wFUfN z=<4cLZ_Q;bcKWuh5t;txUA{Bf+81tBRo5$97`0Z5mR#$STwNFE;5baTkHYIBxkT+x zak-KIk@SN9ci7+ut#huGk#xL5uQF?juFZS2 zaaRc+jB^*^Um}uOj>+13cHu2Ulj_$ZRRCeKh2*sY-YJ2_nnNC4d zxc%(;CEa7TG;9a``u@x0^AO;6g$UFw$>%JMx%8k8i@-fV9zP-yU;P8_^PRl(TD7IoW>}3&D|4G; zQY`qrlE5nWP}+0rsE+Z}P8I?;hb_VQ?n#T2dwHW;&sc3j?>)uLfj9%B_?R3Sd+Q&+ z6)9rR(WdNEnpJ$B2jAZNpPrCgtPxD}RWp-W^uR;-pChU#t|wV?V}Oxw53XRxeQDhN zmakh87G&Yqg}CyZnKe3^gR4C|Uumt8`b4n-W{&%9u^8%dN@vg=zCXq@x_C*>b2Wgz z{rQKN8?BbvE-rBji3Vv);(f5D7cy{`)n=kF)Lh)CD^1Z?$l{)ft^ySpH^=#Qo!3%h z%h2;KV6QVes85mo*@-=O%07(vR(={oTJK=Y00d0&Ed zrw_T6^-;C=Ee#KE7LB@I0IjBAh1>1vYAd9}q#w)I_89@!O>6SGcM|QbYH1hUa z^oDKpsIKl7ku@4a;6VAs969T-205$HDzlt!gG5#5k=iToxFUN0Ftey+*{ zjqQF7bPlal!mrF=QkH?tm)tM&f~*DyrhJ|RgwT4ujWKH7}zT19h~%Xp`Gx+HT+7gT#q zIxP2|0C|UdANHH}yO+8G|HvdI<-r*J1tl!MIF?KY4tF2(7%frK_l`#k&(M?@xS}3r z1@2#E{K_%!EtN!{Dw+me_g%RH9>`=@#WbNN%zxwA*nzETFTSbWTag!u)NW05qC!mS zYwDm}i=Jk#+9FM4HAWanp?c?dg21X}?~-E5+o{!f8@Pn@(vw zHGX(hFDsqin17O;@LX>`F}P_K2@OMcp=ijq`y@Q00xw+on)K03$Ix7md)NR=EMfHV z>hjaGhR)=KE{K({95C>60q^bam4YYfzQJM^?cHu|3LF7}2i4Mf-a+)UI6N#_zvJ zJ_ws)4v|M^U+r%+YWvPjg%ru%CAo|E9hMef|7m}C@N#j#-Dp?<3D0=aqBZuEq;84o z>&0TV^+%E(SwB%s{C#m1NSUFES%dVG)`JIp?d{M0K%)kYDs*1nj?qe7_1X0;DZO1= z!$_FHeXLcio~x4D7JTZjyxb!JCS~KH^k*$dG|%_=k{7(aiIsv>b6T& zpngn?YvI0~NDRV*W_MnT4%x&n>_&}U4*aA=-x@Eit*`YW$lLL%n-gb1Eh0*ROtS!` zk3eUDQ5NOFo~Z=F;CxBY$l!Pwjk2#b&+1vI-EKjHMa9We8e=QF5-c4_+HH-uwOs?* z|4L-q|7PwluItu*PeGUmsgZ{7n>Isn#~8X;EFyrKQ!*;xLZqSD%1l&Zip{qEc@9oi zPh@lr-eF{`-GIrn7YynI6JsB3)DKL0ZE{cuqm-m};W*2S0u))puK1uT5T+oLWasH0 zjx?Ha=-h|N2|!x(}@@``e|MZ+MaF3ky!U%TY25%WmlI=R_^7-ovZhUh2V` zt>P=Vr!z@@;~!kZ1xqT?wEzp<`$Wu<3eJ&_TIPuve|0X0Yut2rW6r#ZWtCm&?OY2= zy0MFkU&)gu8K2FYPinPO@q>g&$0~eFN*y+migP4$8vZFn1>n|-DkdDzLVn4|4W4*p z5r40zwUA`Y4uTkzO!Lv!ATUe_2u1Eu9fU_Q?jL~Yb6CZw7_TH9n4F#a&<($cLQw7c zfT4Wp1yxyD&ptl-H2m@4W1fZwBWLfpoWY&#(%%ieTVtUk-zENt|LFOIgBMFkl7P#W zf)XA^3y1r?XL0KQH5mjml=SkF0X^f+RI(I>sdh2E&|m5f$>K=U`D4y3YqS!TS;IXp z;;6%Ri3=Flqo)NgRiT`aG{Z1$v-9kInQ9+fm8b`Y=1&tTD@|Cmn_u_G zFjB-)ebzI?2zK5zR<*^H0E~i^U)vuG;1HV{@C&V0VlrO{&{g??eC56}Do}_K()+%$ z5?ISUTy8n2BQhuQj4lCJl1Q%+8Ohb@xHu8XR z`$C+gTpPK`D{ZCPGEb!$Xoz3g%*xQICW6uUiDgzkMP^N|t#uMCYqbx=h%IdI5E%d{ z7NNxsVAkUP^Ax!b=}3};b=8G+`99-|-&6|dlVt6iBT|p^0q2Q4h;CrgrM`vr+01=v^b~YEiWq>x z1^M+wTLq+n=dVTRg#t=!M%kyTH#(0n3v23(AvF|^`0+Pbnpu<1$wU~mXZHiOAy)XR1$F>3r!;KGn#D%NG69*ElZY9)~i^#)IDPy>8f>F5u$o)Jc8sxYyTiy-f z3^e4S2&M1BF_Q)@jvl|hR080NhTZT&znFg1XV`Ig-^-zDOnTZM7x)qQU8C1Dy5!+q zKz5_L#W7BP2^eF@h%DxUu5U@XAa4XeWk!sMg#P(n-hxKURih`GAYq^ z!Q6eXw3SBc1`+iq9#(kq{sOGBv)?zL5}Wt^ubKu~(y|-6oYfv=_C^RKM$-c>)PPB! zXg5|-c_^loqXiwd-Rq4LY0_hMbv7ut zy1u~^Zb(+Q_Y}`5OoTU&V=H-@>&gII_zv*N_gX1&LtjH7$-w*EY+}(Q(UI}{gdne! zi;i?G`dMyLTxldy@8Zh#X#T!(tse->xUQaAaT{RvA<4o+F9%THv&H@vul=_4POM9L zq4;UhJar6Bn?gV+WmqWVO{MFe%Ka(u+))LX*<6ZxB)3!m2V%B52-^Q&Deo)eHzflf zgd_e&dc^*I`>*H#snEIhZ4Im}ukEpQ(H2ZfDA;pi!smi^09WpP#7;g4S7k z^V*iEQj?e^8tUMBSEH|Xa1p;$vRUdMH{P;9K_F<_*4B6yXSMjT>c_DCxj_r$<1-W*9C#C+$$evVVe= zTRr;oREhRNt_&J;o$LEH-uatu5gildhtI~+(XCyi28VuSW0>mIw4Eim&LnL8@huIE zOdJIT4d~+%{6eugpZsTIT7zBxIO}jsI*_4!RjP2wE1wNHZ3N8;iV45I%9(g|Nr(LF zj1UQJ!sw@|i%@QgXd^xiaAEg?9KFn!K+uHd|V2;&JHo3-cmmcpG5|FaZz zrcC)XH~2!{(~`5a9arYH`h)>n)D`W8-YQ{i5C?K^1|!R#+ve-KyyC3Vi`Ov>z}38C zdRjcG*X{!w>JtHaf7MsN+mdKnf`B@K>0DLWSTvZgGz8_k*9WKk0r=eU_f*eF`Po}t zCD&3cW?I+Fy+}ycbIAqvx5m`%9#bYOJ~LymQXX4- z`x(nj+p4ZAe<|tg<*XDx_Wq=d!e)4-p2Gs`k>gI0t9I9)vSQ2ISEGQFk}z|c_XONJ z)prlpjv8D)J`ZB8cs5WDQVP9}V9>}0`^-4sX|$G!gq`cJ7A!>nCciXjfxPALkrA7T zy0Hj7id4%hs}rh7s z5$%z21Y%kLchd*yOB)quu&%A`n95dqm#yuI7g6?<;AW9_CRfJcmlzz%Bj7f*s28v* zO*StcxxYs<_77#*n^={kB#iqwoJV85T7unaK?l2b!sJ8LFsi@dQtow!uFB7HykPJA znVl#`N%dE&1}}&-l6&lwa_eed;Id|gF}8KA`u->;BW3{MxVV&z=N?v<#t?PE(CNY4 ziD$vmu7@n1cG?N5Qu`Y^r^W9R6rAn;>|SWT{pSzvScMJy!B zf+eKnaCA^XsriJYqlmniRTfPc_HaXrL|J2@L+1E&-*}yIv+7p(``#|_Vm-!^5Z|8C z=ZfOv54bvjd7uZ3r;9ipzg$U>(-%FWw?W}SyF~U)SiTNaN9-r z@a5veF}A?sEPldRsnf@(fxtG064%%Lg$!O}z4~^PT=CC`Iq}sI%2Mt{^qfmt;X^)r z%NtJG4Nem~^9ApxvFfdM5_y)KEt+XS(`;nVZo#5|$=6`jq<4p}=c@XPvaNRz zI*9Xua*kA1H*F~7yu;fepCPJtSVF_E9M-&Y=$DjZm!b)NOChm51V?sz&0!fi;xY7x zI)&Q#emuvk;iTE#I9(pw(k`#)t6MINR3{SW?6mrW4xAgG2}A5Sl;k$2-eZC7AjxBa z9>>N0v1jljNe4qGcDs(2H>dd&vtx!o!9Ju4<7%wVq!m&Iu7V0LxB)4v(ab4xo81Y@ zTMg8q1lr9s3o8z|nLl5Nm|a$ToI52FUld4+?9e93ovP_ytabI!`fbu{gMhhD%7$%| zQiV`tbmcgB(sXpKeb#)!=h{h^B>vZJW=M?6{4~5w_V+9P)mHMD7~0LU^*hcLt(5@f zN<%bfj;MApMY(R{>&vng4js|OtK=iciCv9Fhl8Z%Gh0fPBaNNEm4}Um*fqbG3Wl@5 zuGkT(RlQ97~+)`d&dAXiXKaHK}|9FfINR&g`Y<=%w)DN%`g zslkZ8Yp0Jf@kOuWc1mThD1U{_{=F9LY94Mef?WFM4*J;-%x;UUQ44mC!}^#Mdlfh% zwRQM6$9rV;ZppBn)ZPGu>K#@v9Nny}P*Pp2_7JmdH<-?AU9aD2M~!Ufk!-hIUR^6Z zvOM-4Z;XbupZO|NMiCplC<>0)w5dC`w&9>icZSeRgiyqj-;yoVu8v%Nyj*NfK1g=V z`nJRwb6qJdqNMYODa3b)_t>mem@0%eE#BAgdn(sZyE}{DfAI$FyL7{6AWAm%@d zguc4AXGd$gT%(Y$l5k>ety;x~DP`1NX=x^A$Bn`FWg8?bhQP5UcGW64-;{`ttUKqWY(rqAU6sJRk)Eo zKMMnRrXiQ2kQmGjQV;p!E-WP6_KT%LHcL24GE{GakwvofaKg3mrkfOluBw*iT0^4* z%p|jrCuxD*e+|rme%TpJJE#Dr1KB}X&dUTYedP{)z17KM(q{RT#V?gubbwVCK-aZL zZ;n(4Q)qrLBlE@E>6s`oJz_Q;{ZOtXSm{dQ`(EpT zuu=V+<6yj0y6=m&ZYmmfV@;*zi~&DCQL!P}$99nRCd&SKDOb_T6-n#seH!3IJSt5J z_2(R~HK542s~|C&7{3gH`wL$&I#QR+2mt)xB?_9Lowfdgrm?qbpb{mqLo1tiQ|jVI zv=oQY|0|5ac-IB=YGW@<Kz)$%7YkVZJ_p@i2N&GlU0N_W$@g0Jq_;m+&medh>=WeGdKK2)=|MwMwwI?S z>hF9}fxK6S6z9`iS~II`vIc!*2VWEtau&G?As*Og~n9O8@7Hnr~Z*%_e39nrnA%iP?uJ z!|V{V1)^R<{YX7Nw$G3n5KDPo!9ftQyZ=Q2h9=8^-We!nT$DYp!%!50nFKogTe9=z zOA7jw=)~6byppIZFlifmH}+uQsj93@($J7yDO2EQ%s5^au|Zard68?;GaA~1s>y0$y*LI`;xog}eUIJMAFh?WA{Dx#4_zL}#9)VDI(4H4KfZsLJyg z(K|1;AA(3u&`1irEZ6qu@4RntH+EbM8d-Nn8SNOX*@pWEuy>CAB&-UphNTPFSlsJA zt%*8UTby|5A64hiXvG|zX@?n!Ic%L|5O{UGC_FmkXokPHd%W{ytYGS6JzEQizY+E5 z;KZqutJD5UkUYVS9mmKP16*D|)P){#U z?7UO+>@oCzo9oWDw~x?wE#|=eJ%UIZW2;;&!IcS2vrvz&P@Ci6AxSzu-asLpQfEPG zaDxMI#k$t37R;bp`g|1k8sU4OSS<|~(Gs;JRznq+P)Sq4y>#o^R{@_rE=7>54b|Ac zFz45lfc%5qY~3=v_8+fAgQcax1SGOwc)9j~TGn0nYWqMx=dl;P4pXE2`!k4|O+FgG zkUCk7x1V=DLM(W!_DLx#X|AUMTDw<~#>Ik^el4KpJ`D95t3_C9^mjI_)xUFsE*-hK zuloTYg6r+N>0y`Hg@_0&0=(dB-Yr!AO#lDV_4co-Remvz97`f-5T*$#yf#ob!e-G= zz?prS&}IS$%s1u1@l>q#tKea=Xar|wG1nJ4B1qy8zI;u)FJY3a=PEJC-!b+BQKxt? zPWenkTZFQlVH3GyXUYH+a{MiAh0ATXmWu~$V~H3h*2)*E#;?k`KrWualm)2F#D__? zpb0PN$bE{P%;h}OEWQ^ zyZOGP)2x)tP`cE?DR2yEKg=xneMQ7R)?z8SLogD-smo0Y^w8GWi&L5E#U)c1_CE!c zwfcuKl!U3B^Y?2k{s8xvsgMbUi{gs@VK@BYDj!+%+_1p;x-Prmi|J#sS@?{b^Jm(U zx6oN7H=_ao7S(kL@$4`wz)0hF607Jux2v+q+xeK$8zZ@@)2JF zGYFl&dRy?i_c$|!;=I&p)1{<+uhr_^9RH>TKf3;Kj3CX=SS&u}?BTk%KA)4i?CgZ% zo!BTtep26#J}FB{4oClr2nL9+^vv%}?uJRbh)I)uEc03u0atBn8LM7Lj}5y%285-b zRQEwJO2)hT({-^YN>5`S=&Kz~qY~vMw@3X6Wi_1+-_3w_S{|~R9-KV9+_#J(FO+va zs|6>S#o}iIyf{j)W`{Sv0CLHxhk$eq7|JAXxhW5h?g4El{lT+wGD zEY~X^0_VW%U)@a(TQc1bv|y#|>=KY0UksVOZbDyj!{-ybCq#}vUNHhL_vAh?cuwoz z`L*r*#$fWOay_o5|px0*7JtfZ#T z)7djlvb`TVJII%G4RLG_%UV;syMoJ}---kJyL<}qXyJipM$pxqo-=m;7wdM*LHHm2 z!zmHR{~-29`~%|6{UT$Q*CT2_`u(WtSjq22_VKkkNT2U8@z?xsQ>tN-{!#elRDIk< zxXsXgEyu^_W?0wyy)X6rmj8|AlitC#$2PXsMvmBp`pR9YyU||bx)DSX=_9|*?yHSm zdo_ZBvIu)eD|Ux24&kM}*IUuMQ*Ym52WiBHDyCfD*wOO&-aJE{JNaQX&mL%^o=nou z-*VXku2uMa#B9hZl{v@S+S=y42P%^gX`cK#@k3<2c^0io8m=7|3&!f4k<8B5Yy}9} zqWJ7F6)%pd0Xl`n2(X-}?30T+q3+TWP?8~{w$>>tExK6AGLJ4Ai$@H2XbDUz{8;Fs zj?ap0-j|Wat@Y{;9qfJ(#m}HH43+GNN+dUAV>t9XtsbzZ&dTxvydeG1pn9Hyho9u+ zgLy$?6{F0@XEMoO(j+y%JYHrEvhS=czaO@>vXn7*Px1Ogud9@8H9I^I5g`X3x%}Dl zIWZ-r%v+sZJBLd=Z^i5#JAjSmLO6w^68L4BIwS*If@>v;zrS+2pt|~>3c#vFT(w&) z@=aBszM-%|qodt~k%eveAT;d1&!2w!pe!26kU(s6cUM>QuM0YRRI2k6yh#I?!kR=% z4b&qP-Yu$G+{6eeEyDa_{C9$j!p02QpWSq$Wn~7+mr_5>eT_Z5j?V{=rE&ZCg`#l}C?pmR_LsLBK^uj#} z@iaMBT4&d z;ivlm=h_-V}NWjr{LTJt_1QWmcmdzFs! zbxzBv6t6YT4fqA@46sln5vDp7+4j8Ha1vI_5+t^F&&CF0lptay*%9^>=2Z(e8n>Pz zFh=)F{b7ThCX%@`C$L|lZ1}QmXqvGj7t1h8QuFsV6g&++TQI(?FdJYY$>BX2d)qbY4zd(rvorlz??}TW_Ky>V9mfN-)7R;D!5n&fe5BtgJoODV2!0 zYFH;ZEfpYt+(u#cb7*)AGZLUrrIGx`%%l;raOLcC&3(JYo#TUz*yJ{pe9o1WF2(=p z+s~+fEX{R1V-mUiT8#5Y7$oEgD-?thpMhf`UFgJ&nIdP3uP>dl)p52Mb(2EVTe(#T zV4rm^&OQhlF5ZlPx!8=HLO`1x-dAR;-ar@1LD3`Z>pyTQ=a1HTtu?KkK@;`IaR`bf92EFK9ys z^wVqp_;4Y)N=}pD)ces^dw)GRM|?H3nKfc<)h#jY5q2?!R{k{UWdk_qH~pvwT%8bW zzfdJ+H1sD#1GY>=mRuZMm2h$XSkp3KtQ-pMC!c$B`}ehVWG??JqESbyoy3^~%^jY? zj~nLyL=HdyE__Mbx%WM>p(DVs^YtXH`M$C~oP>z>Wc*5%<-lS1?D>_p&$RwV`B-#JZV($tv-Su4*rx znMGAv-th4-?5>(PSV*ht8W@YHmzjOL6Z2KMsc<*Z@HZM7`jx(S$SRpc4$}YyH5>)S zt3*t8_I%|)VFIrCERdO#i3x$hXqL9L=wse)mx!SFnQi>}jAv$^?$8W4ArS4LdqdOu zy~)W~;d0XTf9(vhD^eH^IbP$>C^v`&mueJW2GZWg-yU0FBVb_u2AT?}o#9ho%-$Zw z8y}yn6MrqKeEHeN-;>l!uz}lla5T{*p9WEJ%DegMTxrb~cp%0$CAaLaz9 z0gh{7Z96yw@veTHWC}_s%@}vexGfsuXG!`*+>Ws%QHgmoe#u5_!d-~AEJ<2;Y zvh5uUq-Au1r071anhZf<$?=Vy{)ClECdJd14Ec4@ChzYiTl{v_28G0d&EtJpmT@t$ zTyqn}d=so_=4oZlt)(-;P#6;8u&gdCBlflzq4+eenh_jK(1@3gB`Mgor5`;(hkWnf0kt!>BEZ35Jb`Hx{M zaZ3lspWV-__eEWC)*ptdCJEGU(eatsXJ-17`Zo15Ci997%tN*$-mqo#7q+gsEiA(- zz1Iu_&32UJBI$E7xe^iF+0z}rN4+3U-;zK(iBi&J<^X(P=HoAx z)tBB7)%wicc#Kk~*RlO7YE3V+*t7$KQ`n@=!X<}03GvWhi?2kFe@ID|w$}^EIModp z{=`m!@Ax2i{m+l+9X(=}gc+P1fBpxd*7FJRCtT1zFfP0i++29|c8Q(gtA-|(&*1N| z5A?I1u<&M+En*>BoE96nnb*RR&1yL4yKw}R>ovn%6O#LCf0O)0_!zsYHwSTT?zmUT z5az&B|AsB0+h>gZk8JixX@7Yy#QeiVLhO@>`(Z~(cE5g zy*X5HdC6Y1@Y-?~&9?W2k?Cq_rrdi4ht>{QbJj2ev7tt4{CDAti^~QbP>pmEi@1HJy5US=x1^+$ zcZOzE3kO?lRyf!T9j0a@!*LR*^u*tl(77?Z;6e}mEo)4{dH{9(%Gt&vK!{g_!)N24 zG0Y2pD6w&@9aU=(yweer?3I_Y($q82)~H-K^@F@Gv?p;;bClFw760>eM83Y^2JQvf zzH21JDUsq>A|~YpC|<=g6Kc~&926I?I1Vmw_6Eq&T+q3 zhP2E}r!yYEMMd#@74Ra64vb>T7Y@Pv3?Vn~##MRo;k3$mT3o!Bz3Bn-V@ywo4bnXcvEmtRa9e{r!UC}9?9%&6 zBlM>ahl;cNkYI1_4A9&?#J6jrDrJAT&ja1*pO~zp;=-A?1Wg6`D}ms2+^^&3dyZFK=qKClG;g&y zR+6M97e4CvTZ=}>N0@-_*jr8m4IPOR-uWDJT~xvT4CJAmtQOvuulyb;=Mf7+1;76q zbH;NQRyF~@3h~KQhBV<{V;#0#CB~vL_TQZs9!vDgYVy%r!9HRQHv|O@nq3gNRSp&@ zBL&);jQvkihJS58DXVVV89SgP7vb-x70yT`@)ycT9Z&f9+myE|X1X=>dCb)?tbd53 z?hIsd?PXA2^>XQP^YUauV+gfYX`b zQTJr^JK_1yft(L(mX2qe(RC-o9xF-apnV@tz#GIl$<@5dLS(8#16krp{ETl$IK*eC z@Cu<{(l(c)!0qrL({z@uU!GlpZ+MHloXweh^NCCHmA$*uH7S4NFP@^`6<9;;Lwcsl z(j>+&Tz+r;DsDa~l2)jHjy0VLCri{DDjwQx|NS?DO>22!@Oxv1(=@MEgbz)!UdHjc3O{|1CX880`j-g%=oN5#(it9q!#- zxZ@#vL4umMpe9PJnt`hofo;5~BO^Cz0P0{;%U`k0cPpi%%4wh(s!jC60wiF(IBqP_ zvj^`Q>Cf=j99Z2qn`=qoBg8!x96<+vYlLy#YCBy*hPfs6MW9EYagc#${8}O=l*RyK z(5#s+eJj3F?~#BzDrCf>;S+pjw3-9{g7?+i|$_N!PbU zq2oEm60V`3WAnk+_Viu!db&Mo?gj}d9WT|$EH<3xN>NnK(VkmUix8NfI`5zW*+fiorC*;lh?{sVl5(EEC4;vter=LjsMHLQ9w*QRbaII{)TE zempx`u&|M@;>Pn}YRXwqz0N#(6#v>t4Y8%FA{`|dkC@DEEqc$-TwBk)v$N`h6g~%$ zg-Z%$@sglc)K%XZGlm21uwwE3qDOVRRT)cWKzJux{lnWtbk8^oTQSn0{ZKr;Xi>&S4!wC&r z%=_HbCdlEjs9StX5_azE&NmoW8j{_KhAg{vv}&r?gyBK$hCVw~#Hk;)CX7P9TQqfp zomqH}U_W>D|D6!**QUC-rWXOD<*C1M7lSe8Lk(CN!zU(cPC9C+p^+=0<~1e-G%$|s zTJEeL2l5E5w5PdVHV5D@*qg`JXgeH`I0pnW_0Dv8?%K5C#2{#_F=-R3_1UU#@rpzjnP<+GZ4U9)C;;=>OuEmI0DZe@dK!^kz8C za0{o3%Iv?>xnFGbIEqRjetsh|CFCINZb>cEs`{9b6j|Fs5>)WM@}b`+-J-&XV#GzM zF-60cv8b2u{|pVpWOz9zOH=F7w(L5r?vxomM!9YjVQ|>?@mi+b$D6A^|}E=H=v^;C(*FA_$Ns2U0mH>Ga-25{;3aST*uMnSgfa}j9~O*m_+ z>*jv-U;i+>GVs!b)Qew;RHcdtMVtLJkCEk-sUtJHv7T8gHwnF{JmM!EPP??Y;Z}=s z#K~NkpuHQ*FO(er#M3Fkb0o5*cOy!hCi9cjgzs=j5wBw}Ia_4Db{} zx?`Pep2yke3jHfQ&IVYd13bQJ{kZE#>svW4^-o;AFrm|o40yy0;CeP9cDoQ&Q(Ae8 z?ciQ9?v>@le@Nl5XnxD+%eo?AS!Zd(FmR!hVcWS_b1?7JWk%$=(EEKaB6-4?i)f5O z-VugV0>*A{R0WFoOO}PW7VraYlSsdB za@6eRW}ce}5TzeF=`^^j+zT2iiwMIm9qXFPbzg+WjQf}Dkwo^K>v^M5LD2bZZML`? zc!|eZ1U`RH{e~ZsZjzhv3Om@k>)25#VX*9&e65p&nfbphYX63g4Kc6Dwk-9`ma)r@KiAoZ~$_8!_~&S337ok z@TB$2-bcc5&jGO7tN@q5ucMq>gXgiB?YBr7#@+Ol&bUvHpITe^33D;mBpai6A#N$E ze{p`A=Z=7LvHoEi{PW=w9>G5sJP&%nA)I%Fli zAcbw-)VBo3J0+sYB~&!}S)y|eJ-y!dcul8GZN(BNHN($2#L`X5nLLqyHK@+0coRif zGQrJ7Rf?q}s>|oQFf+0bhg0%7=>rE6_V&eEEGK?*rRs;!qy(FnxE?V%f{8NKAFJnl zE9r?j=5n6>wos0)QJ^P5Ff(t0Dhq}L*D+js`}-2M`V?qrXjMOg z;j>^A{WvqHwN=a>@DeCnUF%^5FqqNOHru5JTAVXCe!zS2+)+paUi5xNR=zL0Wbd^h zR!sLQsN_wdG$afDH4-r6d}+V}7Wf%yvL;*I-u^u^I4DIJSy|jni4Z~bi=cMq$|O~$ zD0kw;8rQnqXEC{`3y`wZ&J*1{tn8jpW$De=w6(XN#Aem_F5N|x=^R75hH4ZV{RjC3 zH76e??p|%ql8hj~jZRjw6Ncg6r_fPHv zSFd?WJ?nk}E@Q&*x(5ElrDk8>Ib}8ROn1Or%)Ki9?BZq|7$r<7UD)zL=CcubBhH>9 zQ>#G42u7$gzOS!kN9KSG+S|-NL`;gxtN8Lx((!!B4Qm&L$YB>2mUE1*qT7EV-{7sA9_I#GxQ55$|K3!B<1&Sy{5}Sc)|FRSWn_{Yt3JWxDi)Ur%@3lIGsjyR7{B zVUNWkPfMB4wVt498o`|@NURog^6PY{SJ(*d9Hm;&9cR~+lu|D|v9(K0>}la5AKvp} zgGjH_J{>qAI37*)N}r;NFAgP6EL%}sY@nbV}@udgYJj~dt_egJH4 z07a?OY5w7{Q)JD3N!((oF8{yC-89MQ*}hD3n9=T^%!A2_c{Fq=zS@AjNoSQ)%(x8T zDptIh{Tch7lM0eqTMLAY@k}M~PIXhfhi84EDX`i(Je-366{z6gT@YPb{%a+`0=LR= z2dkKfXQnUiT;5g*vi@>pD#}w)x0W_11p0Xjdt&69#yG;qVj>uoPu6AGwVuEA>=`w7 zWp$x!vSK4HIXtBLgNoYRnlA!pXJ_XP{!u-#jVZ+WJZnq%yL!2gmWBgQiFLg00S+x% zt3_Ew26>o3uFc;~f&og9D1}mMU_(PgHBZ8LY>NBa`>E;ayaVn7fo7;5 zU?2COR5C{_usARsmnYG#YP|R~6;3JmV_21GGXV8uOidc2XqB-uJ-1LafSb3=BPydA z#kIH7xT6O7zr2d_W`Fsj(QV6J`=!aCss~qE%gRtUnKTvgd()%|&Cf9(B4yrV6quH1 z$k6NZ#Qn_z`j{_ts_CT(4R|AEKNO$H`Lh4Y3W=Zs`L*q2cZ+BqJN+R|^wPu{6+OyY zN>lH@-R39u(qtN?N(ARAe_XvfS+laX7Ehml8QB*QRMBY-(*&4@aw*Fse+y;NK*jqPtq<5%(9+^M=*6pIU3e{VahK(6J<%xr!&)u zy4^!rxsMQXkJq*_R;Mlui~y^2Ja$KE*|l>?m5Rn3T59MK)3Jr zFI?3j={J#GtCE{d8MZ6jhi=twLhR~T;}aP5ssh;^o0R>mYu}g2!}5MAXXX@3Z;9k_ zyEO3RRQ$$5*)eSI9E`fxUv~#wVmA%(pH-)nk2`!eCq~)Q+MSGHIrDc(hycYZo8z`t+NsMNKewkxRjv~Q;=Wkc=% zQcqC$$zA0L&U_3>Zj!-HQG?K(G4*lmUN&oL10Ed)3GM8NTusTlv)N>Jw`oTc@&iG> z5{LN~9BsQM32K#;+`y-q=pl;4@k+?@1+hsJKGI*xGSGo<~xMcF2 zuntqnlnFPx-w++j+eLL#;3z-coUk^vss2wvhDsd4&u+Q)XU?FNkyoket4`Kg7#(pm zXy~_}Gx9inds5#@I$4V9djeh9103UcK2*DRb`Mm4|L?a0Xh?-?&vma={nEL|E~8F4 zKGH_+b%iqv7Msih@wS8V^(eSM! z@{imHzM5Zthr)=0%Q{2ZKZLS$J$#YYxqX@qDU+CquJzo!lIlVjiK24Et!J4rTw_Lc zWxd0d`#vAi*JcxH2@CXjj%Hi^#k5Kc3Lv4Vs$cedTsCPZ7-#fNrQiSRf*^jeJe7>$ zS-k97DWSZ|#FPlU`|PC<$7tbIydcN*8Sc8b%In_y+Z5Yfi_b&#>z8$+($ zs>6D+Wa(CK(r1-zf()^+W#k=VT6z259;8uA=ft5<+S2an=38*J5(|w*T;r)w#wAnO-4t$SWR&Wo@ldM{|lXt)W~>7mE9KOlHn87g>1#|i|$&jP?X-EiCZ*~)1HFg z#z>8h&0)2Upx2JaJhc1mFE&!21YyR>60lAeb$1U;wI_tVqk`;uZ)>@ySy0Gextt;F z&KFXKSo3=a1|tjlpo7RhMGun;-gKXz_MWyumQ7}hJ*HE5X0mb6jEqtooR>y5?>Tv& z@<9GSlf#LFgCptt$(@?_HZX;9X!cV{%dV`+V2zl@3HR7XjX09XuJi6U2M6{Tp|snF zhwUeXjGDjfWji8%|Fl_f?fh6qi|Sxr6Pdl{oflwr`^@E%!zbzA;tn5Dq^2#kbn(Kp zBvla|s%iSz!E3~Gw00sG(bUn=@oodA=42Mx^6vg$%-X+`)O0QAzCWWX7K`W^6g9B` zy70vowhF0}RvwIK`b4=7X|9j5k-o~RtfYh?M65tI;uop0@g&p$L2rW`6{x0&1PRqN%46b@Yu7dG)hHyCdiZ>oztiRJA{6H<0}1 z%wOP|d;AloVDXlBC~9rc+k&ufut-gOW5>*+z}z4j*(?0UB5Ck6IWna`uK;UY_Ap9n z(^r@;ef*uYk&{z7-yjj~7wk7|Z72u|THbg;=;zkce%Acr;x5!iQw`%^1V8VAQ1^u3 zP^cOkmmXyjtmHtABtDQ&Ueu+?7#mZkdmjqELJjkT&XqQli776mClE;Oi#lRZNBHmg z-5&vcDW2z(+VJ9H9M0A|o`3c|ghdlsD~c#!?d|HaGnONy1YRs;`5Zz|5Wf7o zutdVmtr~Y41z8JgZx^RbLIF2+y}@^Lwxuh_E1frs0RhhpJP>X()wa+JQ#N^yT$BlT zr0YzwX!lQI3Vx8(=g-6_CZ{z@9k=RY8cIQr>crt+_@-^_`#Ch)Z#?R-6mZf;OHySpMPE2HCS^^DiqM!E@Apx;#Xm2T7?-q$j?+4}+HF)|XH+gMb}<{NuaE2{t9Hs7dNM)3 zT-1^WrxNBv46%t*`ZIJiZ}%2`__LyK@ofQd>f0ONMku-aY0gmK7#K!qr%*bZhL5t2 zh1JE?8f34@tWMx_`o{07Dosx1L8Rr+v;T+LH#WP^aVZkzz%c4kI&r6VUX@298^nOG&jkHyU z9tGwWI(S0N0};7MZuxJq@nYp`F!ep>8v*>Ub;^5Efc&jUgO#_;QL`78ETTxLNv0Xg zsX#ue>Uv3e06V@76hJKeMzK%g~s!)4-aM!(4D0{sPYh_yv*#x zL*-uz@-mV>S6grPG)X7j;3nZswA3KZjawiKAH4mqdKsFoMT>uzb1cp`C=g+LdvV}Z z1^Mru-qD47t3VQ2##;bL(1neLyDN_{N}5p8hTNYl@=w0XBjVC$E7POIkjV=B^R;ZQ zxJ;)ABRKGFV&KDrxD*^S`HLKLV~7(Y1#OAUqd#BfT4q2`_35h>!IUTh2flXjE4jJB zur(d-!`9f8{!@NpYoWKZCTWVvJpiuxrUz!{O+nYuSMWNIal;#c{-kzE?LY3M%Bw=ZAjp9Jm>?Rj?( zm?aR9kn@sF+eyd2TkESa0Bvun8?XD5P{%8cm-CE|$a#8t-pGm^?krVu5qZgcsz)Q4 zj)C*2{P%fuEz63Lzg!@L2|>Zx56z!?4Iag|Cgv2u!_sH<`J()B|NRq` zjzIMaA)bqCQp0lY%$)C>V#t;6>OQmYI0y6khGRM4BxUqIZjOj+WapD5(9$OG6LFU! z@v@_}IDgPis9>h_#*S1T4&GLX#j8u>u&9guO?k*k_71rBTrnCN9%aEtbcY5PZTIQD z_iJ4&c1Iz!tu_8VVu4aHf+9)ak{;Y)=`~47*ks-2e4Q~uK!n-D?@yf;wVj7$g=?CR zXDy}T@ZYtY0OtPm6r>?!K4+!Md+0b?7N z|Nj1qmDO)>{a4(*0z|n_E*h&>Io6Up((9$q2Pkp#Zj_EJ3VGhAhta%^%6Gy3T8@8n zi#EJFZahe4mc5qx%=0gYRn!((II8QRjP_LLDJkxZ9iIS9`Lm}0vi`pj8{p{lX;L-U zDg-yEoJTKDRO5Bt0a?#3)Yl0FYTv28n;f@YW0uaq#B_BtyYRU=wftO2QV#mVU}#ZI-uHN96f~?EkIB?7B$L`O=~i z2V0Ib&jWXcWkE1vQ8%lZb#{(WVpONRRwP+X)t`9oS2xdPnHmiZMKI8^xH2{#uGa1? zmIEgBxkkpn+I?}#WJNA24(4vj%B=s}_wnyMbg%`(+#4qYo;grOL`JSS*Ht->1knYo z;4AjM@Cgju-rErJOiFmKa1UQx`KqyM*sE%38AcNo#B}-}dH-MS8!hux$-yk{xroGo z8S44InAo$cOZvF(>`Uz&>NJIk+8egq7jyHC_z=bk%B&{BpgsxuD=WB_Wdt`0vi=n0 zuk;Vr`9Gf^e%i|FHBhzAav9)DrJkB$H%uwPo!X)e*YWC>(?< z)3~@AUtHV02N=lcSPC@>@>eFqVNek=QZ+nbbiR~w5U^g9L9vyPv9o}BJ0A4q0y7C!q55*<-56(Cw9+F z<#XI#^&f^?N0*#OC0?nhkFYP=1RJXy^*{HIL@4BxP2)SCZa4e|@BRrt?_1$%4Qo^z z*w^m}Q0S!1_gNbW;W*WM_l?k9L~V`RySQxs&3CoE;MMp6kcEx~AmxPbmoCTI8IJEn z){hv#DEU{#f(_Yb?C+yvpxiMJAu^S_iVSG^0wCSe4mFdMHVzIz2Zz#hBi5+s5d_lZ zKJkIG<__aF0|4VAMtLXtmz9{nIvYaWVrdMv2d6xC2Jqf0Q$O7}f0_d zvAlOFBK$!j?)v(5He0O z{PH6#n`5&&umXNa`W7D1%&cA%m20rE6!I$qO{5-}PP$jP6l)IH_iS5$ig z$i^i^rK;}jD@&H%S1+k7hh`^AyKFvFdQIl2N(^k2;R)v&SBs zEsVZsBJX=uZGOy)*1X~O1H0YWnemLr9k#4-a#Fic4nss9FH=aWmS#-|x<{^kpvnn^ zjez4)YVZeNw7YXj2Wpqp%^?|!+nBOJ?FkZ^?0&I~rJ+kUwUH4SUwbxtsN&_WR>CU8 z-?35jP0(yVsu~>wI{01e&+^j4HM+4IfAg*!*>!H`5wh&u+@Sp(pO2IT#$*-3vHkp? zxTlh#dNoKj-HxOAjUe=qyQuVnv=R+0&&|mc_^?m0wI+QEaz`=!PxW#=FFg6`Pk&zU z4pkx=lS!EmUddF(r=-Jw?+E%p<^Ms}OrT0wr5@n@ZUs_p*LH8}5djsYAX6^y-S7R( z&ZbBmt#}(=?(xtqk?U=jrc6u-LnFabG$ai=c{lF&V&zU!dJdcb4vMH8{5X&X(!XKq z8im>Kz(;4#kSUOlu9wHG#XFUw)-#h%Nzc^4XD6p4kZg!1qo3rYbm1Rbphuc#Nj~`Y zEMu`C(ZT<^u<^L>v4t4A$S3Ced5&W%FuaBq6`jXixl`nn*Q#6?txFkm#~q-+*{?Ee zN#AtOPvZMX_2%c|!WccX4$~Ki=F6FAg0NG|lknzJ6?GeuQ+8b`KF9T-U&aBc+Amu! zMVc<={^UBHVhd4#(Mm-Zevw2_MGuxXHTf4Aud;3uXG3yB6fd<5^$S}C2%9;E>4|T^ z?-gCi7tCujtVv57YB+r96w!GOfcO@SMNrA6qNAj z{r>U#1DqhWNi5pQTrFurg-F+l^}eX+Z&I@&$u^R?Jm zT#Am`Ep@5*UC~fz>6N>-L>Qle>9W>+-_n1z)%^M?YC!QY@RQoVUh38E1k;}0M3vdj z3VH5m%4=ys&CTtVzSbx&f?iupZ0rOsh9wWsb3Q8p8DIx3Oh(v;3olO((HgS2?CbOO3Pj*c;Z4k%^u)}5vdCy-1d4?J#l>2;` zTl`L8x!Rp({qajw!5BR*ul0{zB=pN$G7-xGbWBX$aV1z$#WM09m{zSg& z+NMpp$25=cu7bexpPTak8_cr>zSj;bQ;RJzx&_uY-_%;F&3h?O2W=l<3xKAJItc5o$;IfrH;yv!&&RKGHSyUk3 z1BuiC@5LIr^j~mlcTABHy1GvT@MfD8Ub^`msH9hxbyz1(Lq68{Zx5H-Z=A28*No%X z#@@zY6xGbf0E?{1KigCKq})2?BS&Kp<(j7@7+YH&!zNQEurhhn))Io%}oh%yQ)xG z>hYoJ_6SkWt-PH*e=88-e-_s|Q#Me0f6P8V*RHjFad^hpqnz17>ELp7(+4mv$h7apYKE9^b#K^G$k4n%H*YbgHp{OAixa0~zMcHHY z$l!J5^aN&F4ui=Yd;$Cl99q;zq_+a9vJD&auS829 z%{;UmKYHm%uWTUL1p#g~DMt4`z9uH(F&P3Js6O$Eh6)DkNClqOI=e+Myz}{31bt2` z*L&)lWpw(~op_7N@|>ax#J#Aqq0f6@MF5UmQ!h2o1)9iY+ZJh?IMMtVN%+TJX8rmqSv-Oil zzrA)m+^RA4AWe_mkO|xR4^#$2u|?`uj`A1IaLNbC3J^L2j-r;YNNV2<4r6+s%&5gw)wEO;;2<`B=(Jqdei&wq>J9T7MW6WvCF%G+p=80JN;QMMR!jD8G7Sf2kHiIU{>-6K{+gO4~@QNwPKgjdCFyxV)rX9b)f<4yVJ&IN?}#cn_`U+Uz) z5{jO`;)~N6yXkG9wasq+x7%a*)#8i3RR{JQb1}7ohu2QKRg8FICBh2&B9UsJgd8rY zo}_u-(iwA}zc)r6sZ}ZOu6l7EwJU#mcAwXJX+2JS?)uEo2_n3XV5SifKJ=O1l(ItJ zuV%P$QXCBpqhj&;1hK2zn06`ZS&o{gK*fiY(7{6n^aG&z4DKkG8~(v1X#XZADz&-u zNyD-4?zu<}<==M&E^h@d{0Zey3pNkY{S^Q}^pQ$sutSQ|Tdn5rVAvR7!DYrgd@!9q zRoTb8IdGqp1VMP+A42Z%E@^VF(lM*u=43Wb_WrTc3WK4y_%9MwpaE9bMjD^mY@c!h z;(FH8jK7LdJ*-C_(4x1*dc_`9Uqmi%e-F5yllz)Q8r*tFXx0t-viT>%Q|OvA@!_44PR(lNCwV-GoptK|*$yWtxRpOgKUJ|>Wh+0KEn z;>YzIe^@+Fc*7^f>amFmzOzipiC}gC=%Tg^jie!bN+{w<{E66Y?b5X)94eHCQKhqPiBcr{+4v6UM9 zi{0=~A&(~t#x@!D(Wf>;bHGqFyUALkgRi__;=ymco5w5{`Tcz0M^vY=Bs^Y>Gnh~P za@v;gx*3I%VCxb@oTBcT5ODnpB{6&BB;+;3=cZ$cCmjj{H`${%`O}~a*~d7YEmKj& z&B#ooH;H((qr}14!!$r@*^ZN|X&q2V=cS{yWl6a3)`^3HE_YdD3X7n_NlKyqqp-pOhO}^=-L5gJ2Gg7$^gXf9x(-l(Y7T^Vhzk@_V^i&*52oE z_>zpq<|aw?I}-a^%7y{)Xb!{SIWTNSuC;OFz}+5jJF9ftKqR$sFhz~GRBMF=J~ypB zD9!t;SMecLiPiB2x$&6QN5brPaCWuKxnN7^*Fq!RT4qP`%&lM<+Pe)UZK*?&>&-K- zS!CKa2R%R6(`LNl*=fZ9F?fGaA%bOc^d2)lZcR7;B=G7j0aAL;Ro?Gg#(Ls zznZsO2%CE=Qr`YbWrNkMiId54rBg5n;SP>Y$d4oHO})@ z-LMc}?htU+m6wn`(XwF>I{G`0?BUC2Za#O9XT>;;&qrfVmF;rH%pyZ--S*(~5pf zetmv;5wIkP=q}fGy?{ew`-hhIGL_3F0l0uOuM2yb+u)Liu8hZTlpgPI7U%a+g5HMh8g2ezC`hBaPW$Wz?s0AGlGu>Zpa z>i5n0Db9q1zy^I_xzOYmYV&P!MqARIqbB{sdl*)e8bt|!bsMprzi#KJgP)!oLa|u-D2$nU$$=m+p!YlD?-g6$v8AKJ3 z9}T8K4+=mhgluR3kZW{+VCwRx?2r&z9=dsR{!&@bZt78P#w4X+P#7)Ggk1U_DTp}S z{o%IpNLc$>>-(2|y^#=!5X)HP%i?iVe1sd3BajQMS$uM^RHbjDyiz&nBRqsnL!X!m zpm8b~(}hn_-H>JUc*y2iUSj&;yKF)7_mPXqMIO)h%srQfYUkTFX+CGgdv>$mv_yBb z+GZ^qlKH-YuRAhQT@7K=1=LzZ3hIoiyXV}zZ_LP0UZSmEic(48Br1TB?{~TT)LkZu~oA}nd+r)-`4Q9qI&_8 z@)u7A_Y5A^Z9bJAag~i<&RBd3^<%THOpW%W1j!J&SB?+aovRZPYb7h-HW5L3kVJ-4X1BNAv za~$>#Lmv$iF<$7k*}k49@Z|CX#=Pa8@&_G$J^D5v?s@=dVLR<&6Dp{io9gzieqK>B zPr}!>KB&?r&i^c^&(>8WxtKxTC&m241!7eC0F}ViA>M2pqic z!Z;6vhQj*Cn9;YT-!RNU_ny8W-OBe+u?(|i6q4h&%chVEfa*?ki(XQw%vmxPg!YVV z(8&KkIN%s~{kj)$(VrYAkl6608 zg8-aXT!~S=^KmD534Ol*60f>=%tGuF4GFV6kDE7Rriz#v3)812c;G)m|nBd*{dJ~c!oZ;tDL^n;mkMasCdd53OgiXV||TZMhJGmSD`axmYSbs zyY}%jYzFP^U5`w&(Bz$7Hz6-C=e;~P3-TV57x-;(3Z`s+^yQitSFuGF+5#9VqiF1? z;R6hEnp-yx0G(N-u|%0F90xo#eXyX}lNQ)?10`CM@U{g|#B*H)`B(CEcEnFB-P7Xo zO^f*tlKYoJ6fqjZ=M8zwqX$*4UC z+LIpb-9>Vt>`NRg=$|Sz$4sMkMP%a(F zQXoG?5LoFKZ)}eact3ts8C^sYp671N&JSXrC${A@b+&D^^u#Pw=J~GMh2Ss4mN&}A zjoN;;QpFx1!tPMA2SK{)EQcF`M`}(XB_Q$RPl&1TDH?jH85pc{TAyb2LvAasb}>P| zn4wQfk$kd3abz%J`y8gOQ{2*Wu?zl+L=lh$%Lys%fn&`EbVi@r2EL<27CZyDqsF6_ zi`m03yrqrH(U+%d?^la^{eUF2H}o|mQX+9<_0SMsLoBrJ$^-b2(`HH}qZr^MDx838 zG`u5cRo#4tF2E};XFB}CJ&XY2S5aa3^`K!JH)vES>x()8tgY+;azr6TW;=e4#qdG# zlaTprILV?i{yCR#&J$1kbDJijfHZ^({EJAQGNpTNzOsjDULR|4U~Q`_JcTLi^4){b zYx>KQ)~(g8om`Ca=^8!;Sf4mC*cG$8;6%!L-Lig(j!w%8ZZ6w81FLy-jzej-g7&6p4tS^Q(RiZ zL+_|d2V{?B(?RX&i^D$yCV9=@s3qb4KpkVqxd`WECxB*IeKb04CpdqWS!fAkd^sP*N>v=!=cfEqym)BCg+KE~g?qvX8(H<**V@o7ttOe^Wr4m$V91dO^5uCy^% z1Qh4;bGzCG40z*lLPCsP+5|Ad9vE18f9lWJn!5R{y`cLucY%v9&w9L!?dK;DT ze(@g#C<$MM{|{%k^*E_-TpaS3CUbsJuPD5Xa^|G`ZsS#x7Js!=@m^J#WN93k_e z4-)RR^7Eb|ZeEA3%5A=4#-39;di)5q5R@yTqf8U+hc)rN;x}nvA1mWNw7%>d)m{ZYXq+3ncELoBR)MVWBBKkhi+X{U+hzv- zL3rZM%XK8CN-L>#Jb6=0Nla^8<>VFiJh!Kmy9IpOVE%)ef48t`i<=_Y%^9a z!I@pMknE$)l}cFc`#+d~4xaLz#1B5jYwF#*&YcSYNo8ZDZ%i?BMjr-wZ#t#;Z~uVc zgjZIiAXj^lMUUwlJhc=Ksr$q~8!eS~gEcfIS?}UTKRzk_z)@=q4TRl2xo|e+Pui`U zxFq#58K?Jij3F?20CKt;A0e~O>c-p~2#;a=8TX^1#;1}(FGL3xJ}F-8T9e`*%XbhO zjdIOTV+n=R+`MVt91)2FJ_;(*t^OFYpi5Nj^McbCc4d8-rl_c?VHsd$eGL)5ToE@M zy)h2B5P6^;lKv=Si?BSb|JIr0{PKlC=S)&BZMM6Wm2AY#`)_}->)c-(A~QIBe5~o| z0y#^-z&OA2JTd#d60p>?bmN?wQE@fINY{Yf`ID9Fna>={eQWC}oTPYf91|lR1TdF) z00pbug@$sT5@bb#jPyov-Wly}Po7z`y6!qOP7FLd(B{n|yvh$94rjEO2d0L0%V4(r zGifBfM$;``>}!bzpE9;uQxTxVnPhX`)d=d`tkg%>lBZz$a*C15oUg1S6@@s6Zr4WF z`XlZs&0q{u-lS~-@hS1`d#L~M>_y_?j6I;4NR@;lz-P=Bj=K)gyhLpW;-b}7t93m5(_6JSPr-Sp4^v;+)UxUAJ_ zvdA?Lb5zIl4p?W|)sLydwimKc?Ug%c1mn9mG-vP6ok{Jt)Z6sDCKMvN=I@tv2zk0p zo#eKiB*fOBvs0|$1CuD3z+FoJ(Ra+OH|DN+VIdtd{`Re!2EW;0@9G=hDU^nlB-YJ;alX=i zJc+xQ?IN5keuH3`V3c3IAM^*;#(_C&?G16lN-C?yV}Xvv-on7nyK-h!ceCq#(NNN} zx(#*`Ss~d^D(+GPGG|Rcodl0Yw<{YaZ}M3yH!emuGE>nvK<^r^@r3Hf7B|#j`yrNV z+utQ_tt`QEvY^Mwm15kIBo9(4($wuye=5<};({FVBwRfwi_RkaI6Xo9ds4&J_y_cP*{ysVG?m zOLc< z0#ZC9NSm9fX6ANMQdsMl1xwN+zw^fXyMGh*~{qGyB0o2?G8y%_jMogN>L32cmB z>GQemHQ{y6r^vF6Iq2R*gR&@Wp#x}ZJ(ytM+ z-}?R*(rbFxwg>g^;Td4fjtRb7>N`8pds0IwNN{U~4h1J~L%4?bZWc!i9|IxYq{2cP~(IDArW zwV5ES->u;I#pe%#r@LRrqJk_brk@_H+CAsC3^J-_iNucN@%7UagCh0DdmA?(Y5`92wEqw;V~2BQX|c zQSskm_Pjgk*%$>8f!CIt-+RLW^b?5zfnG{MHbsHnM!+WtY!a^X3 z^OC@euEere63p-w>WAqaZ5vqraNh+Xo&iSW99AsdXzU0=2YX-LY$xG)Q`+7S!=;tz zDt&BY-gXGb!hvMT(k-vYEaSKA-I^BF3G4%TuU9SVUtS}XpJh`}Jxsh*e`*k6$n~x@ zVQZ~ANYcY7*-nx`ve#4U$gNYF@Z2H2wQm3Ou9FM%_ABwjN!Be2YOy)dU1hr%>K3r& z@xkuF#{GCbg;Oa?7Tyi_A~70fV3ON-qW0fP;#{$N1Y2$ zhJBK_-Ww&NM`mR+WK-&}CYoD-#I>{))C;G~tj%@bB)!SeE9tM_(G@ZJ-Vy(1W6u2C zzeH5T=P=mxblX%#N66_kA)%01S5Gg=6jcUqrF+Xz`QLGSuE#kHm_o!@MnrF`nyxz3 z1fBMi(?r}PhSLR^w}#VyoM~*C`B`Wsk&xtQ8pI1VZk6mcN@>8geoQ7xr@&H^W@pLn z(-Ko=t=W0$w}#W=H1bsX!wETUyn)d)J}bdn8#CqbpE1^6YRc(C^cq`vX1fasK4+;* zRj8*9ygu3`uRpS#B#;a%Z-x?Cmu73gjSV_~6E?pBpk4V4z3Jlr;p!~|ntsE-Q4tgn zDNzxL4MC8WmQLwVK#-OeDQPykySt@DIz|pqx|`8Ga^&d2#@X-xoaa2}ocqo8W^cZ` zzt?r&pSsp^``G*|Y-{V5CEirx*wJCX&3 z+9`Gg_NC5#;83)$qEn4mCIwyveqRMfb0)LLa?Y(H&L)U{hkl&AA86|^%hf^1UKHPQ z#c7TCI`8MJay2lh+ebVzP#-bW5&$31#HdZOqKp=vMs-{*Jf0Yd7j@I%f>RP5JA{s2 znQ_%#2E20|6+t-pWaR_&<3YxlKr0T=$;$DP#f=6zL^-VU5GJwn!1H8wm7B0Ziv%BA zHDctdJ}!oK2hLH`ypC&2OiTd0N-}3+D^)Qv4ac5z`O}T{l1uk=btlK_c6Kblj*8Dt z(-;#S6-)SwHWE}W6f1P&H%nrNj4>A_a6#WIcMkMuA4Wm^W*#3-WQ>UrJ-=}1*8!kH zyfFW`262s1wO*Txq(jZ6yp!Lx3MDdAPUGq4MFdzkWdeD4-UAB?x_I(-%ow_O40cm( zh2L`Mrv9jSQ#AR9opW^P?k;M0RApfJTqu3r`4Xx!mX%m~X0>(DJmrKMW)bqdOrnv% z=NvsVESu3KRmJ{KJR;;}Uyk>~SI`1lo^c ze6~kC=~Vapf`rk3w^=>=Mj>-+nf(zI^^f=3Db}L#N)3oKl5zpFdF`1|9zSz~cnLlF zAD*Khq;c0PfeBEZ^ETa3LtRN=2BN!z){@hPJFqNr)2=cfw~kQPLie^;3ct@C!nnf9#F*_>8hp{n<`v_JeQhT`0-PaiqJ24o%fsJWxW62xt_0q70T5{LSq%nm5U>O_~r+cW_-HiB?ADF_j_r95L3_>q|3aI)3{*-*YQp7T*(QU;0%roDj61 zzQgW)k-3`EaW{>N9B-scv@-heR$bItI!6pF7n7Y9zsYQA0S2$Q4UAmuFeWQymH^kA z24p9LA<}NuasZR&=oYO%UrM$AXiR8vrkX>VScis`YoXQbL`2Fwjn&_6_G*e(I`0C8 zhljsUx}E$L@zll^(6=S(IdNuOP#~A+eOB;dg5E+^G9*E(j3Yf=FK#DSgg#arS??vY zbq_C*U`TdqYx~y=>sHpP`rPIaY}ETML$VRESoFQwPlqn*CON=2^a2^Pry2M@@)ZEk z7&_W|fK+^hnJOv3qNSq;kMC01VpGk?J=;Hg?BL_Axn}OTYCEi}m|)>rFI;}myjAlh z_geZz_ER35PTcUH(o7M{`#X^-q?$`Amqtk031y%5Yj5N%-7>eX^yNTRce`W6gUZI&e^-%f7vcF6YM>qr(%8e{i0C z!_As(jIdp3I8H0Ir?;Izh)QQZg~H3_OB;3#d~?%!4yH7U+2;3R(DS?Qz=3QB8(xve zA~UOM2R}>3n8&<|v{vI5)j!p|6=ldzWUWrNJ71_8v7KDx*@azdgCi~p58$A~?qp2s z_|3|rC|sg;2YjZ^Y_OCAJ6m<;T=>Z0bdKlEZMQSN|I)n9z2G1Ns`2@^j{n#ala;pR z2STUDzU!u@89d@yTzUZT7FE9Qw~|`9+_$7FQxgrXdoPiJfU*a!)%J60VUW?&Ux3f^ zcb@f{?tV~-E1T6RNLzMH9X@*RQYO@QrBw`}Kd@e-335Z(FYVK=42e8FI2UW667CR` zTimN>!6MZFTgwt4>Zza6!L%9kDnr4T_(=nS@ZqUbd#j;x(_V4rf_#;?=xH~Fm?~%M zKMJyTFG1-}<4s=h65H=Zf&tdeMAiWfasVu4vFN#mB@$Bc^v_EGhrNUPDo>3Nn?9fU^d zmx^dxai(BfZ4%m+&zGunNxk6QV8k1u1QOD{wywkkwUTnQWt)9Bt&g;At%-aF`OQz- zAAA|$T-Os=5$yLqNanTc;GU2Tntu+jz=YZmXe@IEfk6!FDsM6tQe8LS=~bk`XcO0Q z8uO;W1)M_{;x{K(K9c*%5#{Ay%t5Xni;Io4va{j==!x8f*;UuX3q)t{E0MY~Y)r8+ z;Vr1hJb&f;^5;xw%9?BS6vjBBU3lo{sOPBo;%vjCbgrUPzY2f%gk0MP?JlPle-eSs zuRrOwrrE9${ZhxC@Lh4SYF{Ue)5B-G|EX0XU5Lgj)IZZE9xwYIkJ>4Up0ss%INbL8 zb8St}3MnGz)KZj_H;NkkrW0#Pn_WRw)pcoNmFO_n)E`e%ArthD#A36*zFB}cG z(pGNAmD|(TFIL3vkY`_mWxHIB+18o^`}YhOM((4LEKgjzV~2_+dXfJZlHj$xI`VbnDB}`N;NH^6S<+AzY&#Rj0ylmJq)M( zSyW9sK=zjC?o>Nmu|mCyFW<>EM}CX(<8geNl_zPHoXow?7uJS}u7&+S?3+am)j((G zI-V-RDt>{0Z&Tr#C2B(xX7XF`0ZpuCgEd`CiG=P0uyM&H5xS-75O>wFLyI&#_9*bW zT3iKQEjcDW=OLsTerx_qf@QOds`;#!yV=fH+n$DXK+IEn3sz&He5F!3NJ}xqGno;8 zdLFR^TCQGlMVMf%z_?CmS5J#?K(3)7HYfWZdQ%`(UZ=|?kdU*zl0=DCrKZzC&nD|4 zp%ALm5p+5iiOkQ*{otxGnv)ySBBLB7A(zlz(CL1I+PPqDrKvXl}^TqKWR_;t_KP zlC8s(QeoMM(}y|D_&V6Qy0bO7r!?PdXUHlldMC191aoA^1HIZ<7I&u}^V&N2Xnb^S z>U`D8Ro-0tA|HwD+0T}6l)oMAxklx-eT&4KDiQQrL#ZlqqQG6$mkQR+mc~nWot^NG z9q-wJ!{ZO%c0Ol$+nbol^D*UKwcm%)%1#r3)EGf zh~N2ksIMRc1@*ywu}eSp9MD`>Utf!SjoYJ4Eoy@M%$P94j&C{)=jMLt$o56JI@)`n z=|qkmg&xy1`Y>xaQgcCbuFrn~ZXM`qmI-{}#@HtXI(9u2(GLXg0lJycXRbVit;e^O zjknozN-4_N*G&XUvxMCC*549U6Ipc~M`3!8Tcv!~a@%XXXF)4#7V=c6YmD!S za5Mk2{N?cYfjhZeh21$sLce8R8`)&>Qjs}x~M3qGm=cJi~q!t1>wD8s& z)kI;(wxOJgit0q4L(MiviJWn+c2tZ5492B5mxc7y@>#)$M*6Jzb{KcC8$!*@pWi+4 zJXp6b3#>i9ZEoedF*M>3gx8E^*ZaKh)o+vGdQ@sForB(Qj>b&(w)!ARrUu;JMOkvP zDjQ3j5M3RiRx7fhx38|`#hsU8CMb?KD*VJeZ^2Wc4og~%QG%C4b-Nw+C?~q4Hq45c zWv=gSZbvDz*ryP8qK?73$~o-@I`m?FcKO|M%NED&w7uRXyDI~aht8?N%4Gu@iOKcO zhU(t?xNgK^j7ifEam@F6IP*VTb>@rS1QXGX0B)?VGU?ED+pBNqXj?qbNSDmV=3~*u z$8$(3tQ4ocF>)lw{XF2Q#5vb0`|3qOqa91A{El9Q?^QsiQ8;7Y+EH2v}jOQ;K>*nN-h_XP@{%+YnA$~qRr z!H1hWzL*_5H4mXV#T)yxiHb?>xqXbAMJxS6rTS+O4u!XyUU1r($nZw+w!3d|AzL!A zJfeZ3JUE?`Ybc`lt(cKs&~(6(6Me~$GT3m8eoR|OC#u`5D=fI@5z$AEABKA>y|5B$ zYTAT<{?O-7bhA5{wU~lp6pIX!z8WisJSIXNg)5r1<*gp;SfCDA2ACsi-Jb{Kv)tGk zzy?)IrxP_QdMvCV?}+yj!7}C_EjWIp^CxGT^>@8UwzhK}L4{lylp0KIMqFkaey3g- z%THpnKnS)@!uUw(+#z}p^o8_A@jXo6J0Yy(ZTg^sKxXp9I{7>=H~lQF_`Aj>uYx6) zGh(MH;@JV>S=tnID6@srJzc5R5VCV($HLT9g@kS{bmMKV`oQ?#Us)cfg;~PRN=NMo zHG24~qu^}tqRcddsEM7X}_Kh16wQHGa`Bi2xEa9m2SiJda#q)5X2C6>`4t);hRc15vNL!Vbob6;#f*wjn%7Gi3g1@to(K1 z)e{ir_T6JdBWoyxxZoBmi{j6rp-bemoMF4rh^3bA7=x(aywA!e=72{ZE@kN~GG1;g z8C51;|9hurJjHLmLn%IcA#75lIx?i^>IC5$h)7Pcv!&tldjT-(`C&6RrP zL*G)x4&-&=M`3Z4$UiL7;6#OEbIqH0N@O%9Y3NJ%V)1Lj8D*ItUn=S<7Tepgaxp?X zHVc#bxY$#VPW!4xgKPFHp7i>sFCH`I9;g0W$Dw+4km{2xRK(K*iFqlp@ebQ`;w3Pf z5~%}$_;6<5J9+GoNJZmv^^KaeyAjHcH@TiCM9BEqJ3r{=p#%R$+=tay+#OG>JkLAD zpC0Kw&vJOxtNgQcta~PmZ6-B!pD)7xs$sGby&5CN8Aj_J;@wKQv!$m+=Q~{D>*h^& ze}LROi<2y=6ph{1l(t*i*@MHp#M(LU=ZX3eh~V?dNQosScf?u5q)~KuhB__8&660^AJb|N)6fVo&g*iEl5Dh^%C1&kS81zAI1BO@)|_6zUo1@sh6O{gWCf z(sb&&AOqpnLhFAInjN+>)`wrDwo`%PRg@?mY9jWgoCVr}yoE+eh&9pVK?UK&grx1a z3tWk6jYC(8WwF&8A?6paoiqV#{yiIStou96J7J5w*+0;~^y~&_J20w3f?~|8_j#lP z?cq|TKUV4a$8yBkj8U0Y{oUPkH<;u5xIOV?CB5ai@DmzE)gu~=47KUga!bL6l!K)E zj_GQ*A$#Mpumx{-!*n;|-*Xo8vL)1122>K_m+bqzb)%=fyhFTjaYa$h9D|Z5uH(bh z+8CgN?eu`yv%a~;vEw0UT94ZvpASqXi*qj&8tk&2#p$8VmTo1NJ5p^&ZIbA0;h#Hj z?icUC3kRL<@DOVII4 zrEf?h^I?}8kDgkE@7yTbM(@?L*k$A85VAOud=MYN4gtY4Udi~vnE5{FWNFO z?2M|-w>YQU%7ujBo4c4x?&~qttdI#5daUZTc|9Q*8un7ep$(>M!>-Y3W%>2{jMNpqOH zY+6aPLhT+wpI>I#{sB}Pk28QFJBodjXs3f*;utYN5AOz4mz&>rly@o#97wDKtKjs^ zsV6+;Sq!p`9dsZvGN2r&wfjEoF2P~tieS%sPD zc;oq(KWKD-I1=c4FX6qJVopbqE^#BcI`_4@Id%CP?!(F#cyG9XYx^=TSGF*s*6Hl9 z|EFGHH_hA;lUH=ucANh9l7B(eT(oHOhhvNjm5A2A3$#A^*2mWhJODY>ZP~_K+n2WVt`?|daH+U?AKkyQ`5{EBD z(0XxWi~p5?uuXoqJP}eMVmAf1qSVRWT{LJTtpYGzAu>7&XE!D()v=UD?S;wrCga-l za&}G*MS;vjX{oU~Ybq+5xS&gj9(x9zT2@Yqrj=zBBX0TP>^O#YsZre?iV6Guq>yVO zK@YNIuVXXY07RbnNw>FuHF(mTMI+v1OroNu^pI3o+G}&c5BAnO#*aHzCK*60ndWFz zT5VGSE6BFnZMJMUEwm!65UjWvr`^jL1D~w5Z*Qy3-pL^E{fzInjr|oj)rKZvYuf zF2pa!TuiOtqH?3FF2?3LgEGrVN1wJ2D?ucdTl)t#{YIMH16pH;;f^^VM~1VIP({xD7}M7t94em&XSivehj#=rK6_{P}6+cI9e8d9Tq2(O4efXG5f-l$Irn zgX4G-6Y1`2kj^nwTEe-)5luKT(~kR}{3ToxjwQ6c!!X%qC8z&Eoo-Og|Ji~IQb45J zESL_2L)eo zt{Vfj4RHK`Gf@J*sZ{1Sv#=knG=(_u7qaB$G6gH+n;}M&nNXR48oJDQC%q6t@f*LX ze~;4ru67;qf*Z;Y9iu|YT^^d#(*2D2@V#`2P$XmtSfA3_ujim`ZdXx`4AUC)APzUL zWtjrVuCJ~671JM@89hPk?u`{e?4|EDoDSeg(34KZ^i1d0uR3h5rH!v^9h?k|?ps>l z8ut%2pY04UlHL5C!t`uvuaeo!S)B2_{}lI6T53|UQI4)_^L&kfnn2Pe{0QN}`3Fu$ zU!>6^S^^YRAY(1n(t}aI=O*LP3rz`4v$Lj!IrJb0|CCq0IK=dy{03d;IfUi^fV}C8 z$xcX4PIwwiGN`}eQneEB;7eXql%h3)gXnX}C&k_`M*Fe4_;%%{gl(g3<_j>yP+_gc zxVWV=nWvEc5LYSk4{JG>OPcs%aM|+-tM}l8^<2oV*!{r+7rRaW$|zeWJidlK0^xIC zlQxBW!ry^r(!HPK^#XGeb?g)m{~koRRj`DavK0Zm|LinvPf^=Rzj7EXWD;f4*IR*4 z_!{LD$M9zUsTOCFqZ*`C zupSeih=S&b{!Rt|UPMfLE-%z9yRYvD20o$!01^Z7uZD8kC@#y-+Sh5NAht1y$Lb3g zSXq@YN=D*b=B4&6mX3P#=J>UoAdiDcwdT_5jc+@DoCgjL`Ty)RNaX+QK@kGkm94qXMVqspxxJxqi1T6&X;^5#P4do-z_O43LhMbY&mDYA8o zL{+O{ilJaQcg?J#H?2c+h}}CJlTdk@q6~yBd`$sYA~fXZZy2j~jA9!DDXN}ihZqk> zp~+JEY*L)p5jy;?wbHIh#V((8Bf_U)ArAyrWvfG-;JMH@lIaOMgua@(jf}L>U`C9^pcz0ON#$81`uKCi^)m4x%o(uN8-#7cyKA7HaVK)TP*;lP$8mkCMO;aun%qK!V_86|pxMi1Vbc1i%zQ~Y zfen%|Jj$Wa{53f*UP`FiH?|N`k+h$HQgL8)R^C$lk>0dF9wy4*M-XTpEk5JgN*ct@ z;M1|s1*1&$|A%un$-wCJ?VBVr7+U!COdav@enkYa6)?qhxju?ByWkS*zxf^6O)-Ys z=ck@4I{(pW%>OKm_jX#n(k!%o=v6|fz+Nj6i~Hr1>q01z@0aW{aeZ%M5yAW?Tc&hm z4opv0vbY%#97+0BWcDLpadHgb*@jK0F^LL7svDHE7f5O4MQ4G?YDmk%la-9itk>Kj zBnxA|F$In}TY9vfQ#;w}IYPnnlKRHe*d`QeRBPsb96*vyvcxTnm(|)Z@uILGuxb_! z{98vcyYoYm1R(SVn+*{8^mm)$P(1p;7JYCwws4Un(E8!$njc5hfXqd>x>x7xr%eL? z)auo}PwTP4jv(C}7DG4)fAXgApxJ&Lda{C=$mFv2&hzt|70wqi3#mTCetS6w+;_j< zO0}~NS6;pm00P%${IS{sC%@?$^(%U3qBCSLemf9LPSl2T*BNzkr^6{)Laa#4Uo+z1 zk<&??_lb5b$Yy5}A%b+Pq+Wmh&75efN~TUG7vv4IQ6-|@qHFEXf2jZ3-&E#4(JO|(rBT#P|3%Jeynoqz2mfjM12`Lq|uccfjd0z`TW3=swwi~ z7!{;Z+*~TdYL+~Ww^V4mu|Y}OZ~J+v`P9wVGsdzjd*1SSLbo5^<&ZLroCC&)1Y*5; z?W2gtf(1$k#3*;!OF_Q_Q5B-KWlJteJk!xv7S3&B^D&3QPyM$${}9f*jm5--$FStq z+c7q$6d0p&2b6Au9Gr=3UnP)@>zpwaQtPcGJB}GP8#sB}$5Pu#4eE-3bG_8m;UzqrX>z4dNg znR*Q}A{bTA5w-67e;Ze4Ss%tj;K#UC+F`OCEX!zDRrIpc4@RjPdR zS$fPE>XRUUOaVt`*ja~L%H{OZ{zHVD=9v`DxSP$g-NQVj%s0o?Fi{2akq8wJ_?JKR zt5&kKA`odg$=C4O(ZHwbO?u6yuA2kyT07TPV`FJP4`knpv{-6#Q&H2U4tV3kagRM4 zv3SuLb`BY`{zBZ&*>DJ3(Oyj%zNx(0pf+;pAN?TtOFF1J1%Rh0TIrNtNsG;K|4JcO zvsNUZ3miU)>YO6J5t0}D!a+KY%k$S*i=af?yDr`jBxU`POmUYndm4EWLN4yH{+UuB zK`Z?gQ7`!%KZ7-`kbzn^DK~JA;c! z7>Xf;dNn(8V=SAfKbu9H0iv#ljWE-(@~aecF=aAMZ9s z|Gg@|7%0oGVAV&~&i~#mO!cP{Ph1KxS`Xpra`TFDU=y;M*tx0{Rhg%@G@4cMW}@Gl zPO8z$`ElP^K8vP&36~qH;og3MCzQt_*(CL$`<8}kM}IaW&AHK{nzv0Iv_o8czZy5w zT{oT5wA?
o%c;d3*yy=b^}ZdAJz9l>ij4DmT3)R}+_x;Q+gc8gn6q6?voH)pM6 z;V3m9+*e_`E$oo6l9ei0_+(fyI5=1<>U_|oGQ!cHQ$t=@59tG15e$4pq7!eoXdS%k z4kW7Om5TV!v;%SvG^v^Zku}!A43wuy0fm8g{(LqWsqy7I4MBHqumEyFdpJ)u#n*p~mY){oe0K#6<7O zxIW?jeoS;b=BV;_;MZo^mF;f**c_2}SLO0io$3@VSdNp!)GSPGf|SQ!oI~Dwmn;33 zM2v?;)&pT>Yq7cKhjnH=;FBP+p!6Se`;As*VlVp-6-CvdPRq&v*lMgVqz`UH86`6r zVQS~c%H{c`$FESu(IVN_nL+z?4FIRspPr54jF%!8{VUlPX(3Q%g~C11Uj?3sJYR@6n2rPU66c;1;uuoYOwR;FQK$jkGaL{akVFEyCH z%5RA1vLnJkir|CkzkWhvNRG@<{OtE<41>Q!XyPA}n-U|u+sq0H3(0DA18AySyn?5X zj~qv~3Yr-5uK~Ga-%+`AWZRLAw6*c_yo*a&8)`;Mk}Ds0a1uJ>!9L~Z)1$QEQaLHb zX`scorexZxy1GUQ4&qobjfksW42}5iAS6T1R_aHC7PBIUgfPz=EC${7^m6AShe0{& zY@#?SsIyFA%Y{xpX6|S0T2Yfd{54#+OMyqesltX1bzG%8X;V+E`;b0T{sr3XfW4l4 zei8nPPS=h+N+F;=Ph51H3@5XH%Ly#OWS#uz+2c1Q4J+f|XWK9E2c$)UPJ8QZg|oGU z47|y-N4u(i@Z`%Yyk#ihlMvYI2N1j$c+^)Z@1^0x!j*E1O^O;g-SgV&Z|0&idaGu*>LkB{|*6y}1{37m`N`6E% zgZR~?SFfroF!;w#2Kf-xDU>%54IYu!_`+8fD=xKQ60sr@>*ycl3J$Xdti>&TxaNKv zD-p8$Fsh2kZpH}}dk<`lnwxBh3lwe|V?KOVtG4`CRP!Q-uwa0~#lY+-5Pe-}>S+X# zKIo12Tc?i#Vj#V*%r%CNAYg<@Owv85Qn*#cWLuQUf|C;n>+PJ zC(V%jQ6-DWP4K$+J4_LKKhAYiz91)VBP)`(7Hj|`5V!5dedF-++ju2D7IFDM>s#o5 z_mBdy7l(usP|OF^0D10~(#MxCQ_LMrK5tuES%55bm27=}QJh=0adNoD%?z{0k;dcS z{57X?dXoPzphxs9qe<4fP1wYpTD^X8(s!lo@f!k-$KXN>_zP!CCJgwug-{L1CDY3< zsZOYIq>=VC1YgU*ftt#SG34cTyU*)p^X_Pd=ffg#sBeS|T_&5-Z5bWToUuBZofI~D z!Fz-W59hUh!c8dWtGp51H^|uzdcoD7Z8HNT?a7lF7Zjai{S2zJv{>|YbF)}R;PzXW zzg(SVp8xN@ihF$e{61Ds;bbXkn-VRSJy)0A&g4@*Q<*35pe27%|5v3_g?t$e>3De5 zd95DbCzz2!Z({i$e^j!7VU*|RKBqW#+YFLxV{p_M!*d-((uM)@Wvnke$) z)!b+0+WD+R0~lHy{EFBV6do{ib*keucli}c*wM(z;N*VMH6P6G&T^H)ZpxWPWO zBAwV1*!w*ffBP?Ts6fH&oQy;6(SEDxZ=Nc&dx}Q#g*V)I; zjBnh9_ULkReEm31eMUbqTq)K zwQ~^>-_Y*n29pbpHWt0?L8&#|8)}G$P&439UEYa!cXUH5FZ~fZ7@9Kh8Z>OlVasS{ z7S0MGHjfM#;Ut*d1_P1*yXF4(=@y37W>UGR8HwFp>|*Zb?+rd`Tw&ZES(Ep7KXu;Ttjml;Wd z^3IqZ>3Y#ix{{sn4`<&MgwTBIO-%zI^`}j8^a)`rfxw?P^C$j1WZd9yjNzCa=tF)0 zPjzM5lSIg3MMb!{K`5M#LBhz_fUT|p$Qa##L$6a&%lSq& zhQSudLeED(QGR4T7)E`@sei1Qsh?~<2=b=45lC$#d-7-N&mX~~cpy1__TWOOtw7ab zwdM~^i{Mw?o=+!LR0O{KCjS!i-X^_-hA~aatdKd2_^0_d18vwKR{kyZIFx8XPP^D@ z+XC#SrhSqA7a9_!!1}$NU)LZ*koqqhHn;X=`F$W*&4Zbd9iB2@5{=Ums^Db9!Xp>A z_+U}Sc*1Ie0-U41k)>`s-PuP-1aowTCO#=~vkNj8>8K(V`^3?zfqTSz>4!Y{HtZa} zj5GL|*&=>5(FZeyDnvI+J`k*LFE{MUjNQTexh$aYSqLOAxv%4@vR9Tog~Ceq_!}pEY0}51FStMK$nCY4>3m6dP(QvO*q@A44l* znfw2}eN^(li3OQFKeUFwkZNo}^WV=azLGtrj@PWn5L{VWg0gdR4h`ykjt~Zg4)aQv z<=v!TBg~gz#QJ?xF*Yb;PmB$Pw`!b;x7{RhLXWpb4F6=Bh_Xl(0}@CTRj3@ccC$n9 zid<|Gnvq)y*$V6q1Ufp~g*`nhH#-^;HMoBZ6gK$|@ z=9wmtQ}u|FiV;$8Y>NNsg>npjs$15y?8>_r1xkARr6iqk#ldw-$gHJ7ueN>12@P(u zu-OGs?Rj#hrhvO3*yu1j_Bq>MTCACkNg#aK$!NZvbf9jPdTS9_R&HO8&OBsSG5w0( z2sGLi>-HO0m9LzNCl=$dp1U~s-TE`w*_mI?&hZ1yZ^y;fY&#kfF{1w3wULu1h`xJk z?z;LQ`;{hW<_82?XLB%B;g3&_&$126aCVyHs-j?Edy(@An?V6yPrNg7^F6YA^2>~L z@aO0@-`}0B*DdQyFdwbupUa3G@J-OUi~vKLvn~VbbSdz?p`q^Q<-N2$?oHL~2K)RJ znLW`|G7wo68N{PWI?i&sA?mlL=ikU=!z^6@SEg#C;N0Jrr{>Uc(mD{PRCTW}rrPXH zEc?3$S>oOc;<*2>0{OqLC7SAD7H6IBY^C>$6Ix^JFHkm^L`63~<8$$=v~d}N>dNOt zmz2sDEIOwx&PF=J1rW`{n<|D@mxs2AF7jV@YepjpRaGU28EN8i;sYD0oh=8`t}^3U zgso@QMM5>|TGl_M>12MFYrhu$W(Xub*`A1$bBT}rBxmoeQ#F^Bl{5eLkb3q3BdJ!F zQN4NFj_(4Oac|`w_p^y&o6H~3Bfg5+A}zZ?q@JpVhd+zPD9$IWxqwGZjLoWev>(}- z1$U<6sI@n;Y@pNEA44oWHi{-oFCTcU7$Fa!31D~&@ty(560FF3;MFFw=at6k_lkY* zJga*D{@bQpzUUQw6flIq@U1cA2)cwKLd*SFXGsqFrstqgs!{K{yQ?R&)lKnaV;r(+ zo`39N2FrA1*cxX6#Yc;h`Ny?+SV}j1hJmah<)lk8xk0LLD3C&?gc^jkaWx0Lq%v;m zkIyG4>R$?!MpF&QAr>mnrj-z-uo}8V(`NGG@x0wX$C?~M?p3aws>WRS zsXyKQ?S=ksRvv(q4h=(bc$|r| z<3c^lyZXEr`(@Yn8)PaZ?INQ!wU`E_rllp3<+lw`8avi1VU$%SQ6ET<>^bts>`^st+!=viGzi9QJRVZQjQV?k{dk5Mgj}bKHyjJjWP#e z{S3sUq>BL7r)%z5#eT)N|8qBy{0oV&3Gcrhb#FI2>pUdOt~MqSW^SXKKxBiUn}m`i z&t`#-fWaqxrlESGHo$*C!?c+xHi=_b=Wp^2u{gaak z!^0d4B!5pt(df~F>hWAnPb*dNryu*CK4S~yvd#_uv?=xdvJfR5lLZ@UGPzGyQas)~ z+))tieI+*Tc|OYDn`-8=1|>UnbIDX_+99P5e(!>qkEf(=q$%&8t!zJMI4|cnlss4UD-L|(gTK724iwtZp zXxQ25Y5<`TF`*8(HtdE`**IkDcZs!%$mqOru(h?_{I|)Qv2q&YKIcuBV0?dJ+!*lx zZL<&KXKCA1K4Am=&)X$pe88PS>Zvr%rgZA&wMQQu-l2Mho#jRyr5tLR=yXk0MlU4J z(l&F2h#~A%7Qd9(*8MV;IGZR58i`Jt{aQ)>;hJn78}yGDh-TbB%)(D%I@@;yeUHTZ z2Y*!1(ZAU{YFO7L&}4u0JHl7H3O95&TIAf-(OQZQh0?)xN<{*xp3I?zdI5v)>^Jm3 zprhUjRq={?iSb?|A&#`=`0@lc;*s*2g9=mxRM+_Zuce*lf8pJ{v%)^*A!X%l?nl6< zvk^88{(j^Q7a8VfoP3Ql27=8KFEXaFk0$!| zF4BkrT?rMz4AK==f3()1+%wb2>EvUsS2qe@*@I}op&lc(#n~{afTpg?CE?(Hbp&DfPHT7q!sPsia56fAuI@?@@Ti3Quw*isREWDcgem z>%xgprQpj9Mm+ly)<|&$ECp@>wXTD5fl*1faZI`A3*h4wF_6K-6jcHv`A;*jKTyf!lA5x@QWLfy zwKNi-1z3Fd)YEQye8@4nxt`qa(Tt|auW!QrRD1g_3cPouZC}cW&wd2)VyE!s61sjY zA^W++AWAvUqF_uv0sJ~ah}4~{9K?DaJ#_PB_VY=;5@(w~={B zkPs`h@hp`aeSja>T($6ZJ)L4I60`hBfB&|5vq!GFQ%-nz8Q3gMT;O%;F}q*0@sN zlvhte1pD<@QQBvht%nVZ<=Ovf_Zq-HaCskD43g`9au7&#Nc-WZB<6Azvxpo}_tE%o zv`2bYRy}go&^=r9_Mi^Nw7k&jUgfoh3y7m&R{NU6<+VckbpwlAp z1v!$a2-inD+uP-s$I?HTmphyX#5ZbPb&jBr;bF12F4=jL}#c zp*R1Hz4ki3@;UBpx|>!t3xJKv}$K|8# zGGp`~L;PIKd5Oh62JLiv*tmFIoAbEAxsTR8jifsEqxa3!js$v20@4n>8F6T+G0T!T z$ExV&>#VlUa_^xtSJ;EeRA+k!GPx>E)q9&ax8}6q4m&27G~@0+-xMQ$U(tQ2ui~IF zTC-H_=Iwy*Dwo3MontA$`zuP~oJhkP?wruRBc^dT?3=i~Q9nZqm}hRjLf0n&KGDV; zB~DjdDLZc`vFaOpB=d(~#422bb15AyOEArpbg=G;tkM^CVC)oEE}6n@JV%PG!(#yn zlO;ZewGL=0F>zoS;GTa^xrzVTE6U!e)R%521rn$N0r9yd^}BBM{+qL%5g#fMqwBec zn<2z^iM~kn0}9C;=i}vLpT@lqN;-)!H=jzb1{3lDOlIU!13Ma zaToKmk$(nkM%vaCZv&sSWR-USyh@K(H#x4;?SHcKE6mVv?qxtLE97td0L1MZ1MS2GSSsVJm%=wnVUrD+71{@oJkhJ-wJ zjnS-e-9L#k3mT^XD#8`7Hh3^x&Xzi6ot|JPx(4Oo z8ZM=uKha_+Z0ayZP-eI8aks|tSPkuE5vjLXwwYY9$ZUWOFL23w4E%&@&z^O$)tET5 zcfMbLK2D7&#}VBDP6H$QjVt)ID%lwd&VEJ2C!aG|XZo!jhJ_X^D&S`KnC{}XMX+;J z=`|tsEM`Q9fqAChdW|tM6?t2Hq(NLr$!&THXAYNur{@gupPEq{wZB~3Jnrfbn}|++ z@f}N51cB#+`ICo!mn%}egPVI)e{8A7 ze4DDRZ?pTVN>^;IeD!a@vH?q%aJ{H_kNfbH94NM1Qw; zKe5s4bE<%c^AkhZVQLO7@`7YS(|xYzr@IBQdW$(9q*iwi7gsS2QBhH8qx8Gu+~^{V zJRPXpe2Y$&w2&C@u?4+eKYpncdY7zuSLE;w@6B%jmcvhd=z8+0I_J%yMu?-I0wXCr zlljLuuKe)gxapBpR4gFrfO>^3T&7WZqdMmHKo`xX zF|i}S2{DV+)kPDTq703563^R?li{xJN~TD#^>9{_xc3b|WpSa;HYj`xpHZM*=f{}u zq7S!!R?w2HS`Kk9eBL}krAc1X)Vq^ZL>pp)Pkp-9&@5MFKQLKxl` zNy`)0LZyEtFKY`OXES@?_=GURQ08yG@|T~^-`$gp*63|&|-Q+ z=uqF4foS{(fzHlBVU1W&R<68cT=^a}?bCeoypVItnh0m^FyPcHGdn$Hevj(5eGF_y z_8k{D?n6043V&x1WNRN%oD^Z9YoM20wDm$)*RYOE1-db}<=obT3gW*Nj~4YI7L%5w zpZz23@HcSGEoH_js7U$<;%R|Mj>p%)i)HJ7x4$l$Z9?4I5}eATGae~NC)L318w_NC zCoO+JWipE)y?I0~r@(1W4<|ZHc11T9g7b{GO&aN|7F_~s!GD@Fn7A03&qPo?&3iJ4 z$3fYX>Iw?I|57d3%VV}%2D+M(qPfN$HM7S_@aVb|s6`M7TT|??|BI`)jB7J!w|+~Z zNO33Rjl*k>4Rc{dd!r6F6C@j+Y`Lh1AZ+#JThEFM_2m7d^h|&`z`@@4h zM$40c2e~wUE;|K&3&lNIM(^ZgOY|EZXU-@%07-T(YOKT(i*eh(So9I zK45d5UABH%85f%Vk8w$O1DFrXI97O@6pvg#2}>i7c)Y9eDPvU8`3=Vr=6@I(px>SN zcQ@fyKmx$QXqP+Fd(S8eh*6B_Q#36r0jY2@6rXJ0;TB3Pkp5+k3IYLj~Jvles(fJg7r^b^|-GC#hF>xu)Q zNjmNtWp70)3C+IlIVIK?OTm%E3bDd*ge_qfWNB+@ztS*bB-Q)B$v=7dU!P7M>B`>3 zR0ZvSp=+P5_{18tyHqR`q%b?;GI{m0RA9FsO|0v`9-?~96T*IxyoT)W$vX7E$f$J+ zs!c;9I}d4}3&?n?e$2apa)sR276sp!e270pqQ9CI2XAt{UOVvxomET(uEZ#yBVV4{ zMpYro=bv?ijoN6mM==3gq_{p-e`a>2z8BUamA$K5Am37l4-jWLFqC6&#_qm%NI2QZ z2BTDh%xyK=aK*m|9palEuU26?NZ3*Vu(p#!Aa-vHl9GNy!d5AV6@tmeG;$@%C`)X( zlkcZSlDBikN_)mT%vkMO^kRV9^CHk|W+DWkIC6ns+Mk zUS9C63=13rO09SQneq#5A#SU|6>$Kx9!#S>WKMA@$#j5zwbLmfgZUte>OzOd>Rqn zXDzGCr+o#hRtUD7#46|2g5axag9?d3XVr4^7h#Y8aEe*|o)QOVkrlD7h$H11lY%DEDXO7iC*^~{K-;|c)A%4|wp>g}|<{edc0uAGCgcJo6 z;a6w3tX3;!{L;vyla1=$uA}qhU+deQ=UkWVX#bK*@=Z_9C*8O23WS5-hW-uP zdp{j!Ua=2@%R~?tCKP=k_d#|kz{U6#G!xI&&;>gadp+7TpAioKYfp6 z%dj#wT&bD&4|?TBFMTUG^FBWqz)1f|LG}j(kP~2M_gS#4B}wd$x~la6$vE!AV~e5} z@=tGsBK7I%Xg}4T5CHPBC&ib^b7X)2XkU*YA|)PP9qLZKbg~&2dm+Vn{{&nbTIapd zsVPMdC0g*L)kQpn6S6YRzFldwmAakg98(_6sta17^xb1hLK0iE{8qi_2(HkI?{b-L zu8x9N2>S{#`tAHYvgfCNkgk(Q-!FySdMpiiov34PK6)NXz)xu$1JEX0fB!9lmV(eL zY7$J88XY?%g+r4JPXO+gQ6}N(#?X-Na(+*yf(^<;JQ+!)*r(BhitL$r1TQI_ySxM) z70w(9O;|*ZM}Y#QLJe}ba#9=6Z#c}l9|G?-@<5##3T(M2-uYDLOo^AG6DE;=Idwc#FNq9QNei z|6VA!tLawvX3+ZXGkmal*ky++t^Ln^QqWX1t5AnF=1`-~yq<|(y(moTcz`DL9P#M} z{Wkl_&HwtcGek-Fs>|%({x9Yv|Hx8PItNQckCGZi0Lkm^jfvOZ583@cO@@Nz){y5b zYkUW$HNodXl{~kpqz8>P0@3Y_%EuX5?vPQ{y<{5t2@+P`2sR}?f2GzvyiI&*VZ&Ux zZ@=q}4z~h&b^|m#=J|sL2kJCc`4R|3l(kn6;&%!9h7MvqONa;JF%rmm0)IB49@x}L zm0*+YkcN!$;l9`mDV7wQG1Huq!&T=#oZ2}B1i zrCzJh!>)Cr92jzdq}xF6diokY8sXF6{E59Jmrt+6a$lZbsxTu-<#e~KM==F{Fee`1 z!`&XaBpQ!sjU8HGq|gly-ZT0?eT7~Z#?D_zzjis2JWCR#r6s3*rB;`$_g$kLQr0xp zG+|iJ^A{~gnHxwZI*Pxu-T#(!TMMzsoNb>83tF@1-;C)nD4zi~&yG=!!9(QXzm~0* z3Z!GwVMG)fdP|M5ca@bRx{+OF)90NpJCjS|5W|p@x9XYE0GF=s$(~Lxfas6hQy<5r zolQLy&LkDc)-?y3VPO}4%mGq0NryO<-lRQSiXY{&zjBm6ZK_(D#v&C*^et&`tB|Nl zF9pg^07vJAsQyT!XktXh3GBXyPbj>l6iOja>}c9=Z~}fq=Q9URM4J~`%>GdPN8pB? zu`rr)af<&do-L`x33t^7)*+wy!=cw44^GRB&$#pUJm&=D17H+UDH@lNwx=<^iM}e( zQss-AMfx3nsyr&wLXrOH_m7ODbQ#~s8MLP)i%^~{&t+ktkB6Rxoo|e_NY>5{N|EU% z1}i4nkj{K;aZ)N=0#Ik1Oe@lS8g!m{tm*4xT~u!AKx@q5Y3($GdfSHO+bs>hsmjjF zO|~g7yVU)0%?GhCY!IKl4TtzZ6=DiF@U^8_GVr#JG6d>QaDZLm{^o*Nx?4@n0Ed!N zH{$;7?N=sKJ#`BNx!LE0n{Ycj&3T;#h3ICg0p%3?`%?&mKbq-YXsPueBDnL|^dI0BltJu}E!H3``COM|x*OzZhn*vK2WMnT86LTZbq%Y$_d6<4H zt@-W~-1ZITy77*nCG^Dw27J-P*X!^?cF})nJW6Ylhqnx8Q|o`vyR$YJ*^t} z(lK1_1@oN5!PWI0bpP?n`6R|d-=rlVu-@1hJXuXV05Wy>e^(XY4nLr{=k~ap=Vs+V z_g(vTEo)2C*uk`nD4bYtK!JeX-2&XT$l}Bj!Q#h)kAF~gAd138iJt0^^hMv1S;FcU z0?VXJ>)T^z^E3t{8O_^Cq#Q&F53VhbKdZ;pT_Q5v#VYCt(pWirO!=*1@Ljbr|7#2Ar;!dQ!`0DBrLaVRO7t`)Qer{H z7jrh)aQYS@nn_k60#{0`^*u(weuf6aYg=8Y_OMCW@wH|(6gmEP4{t^8#cWEZtPrD{ z_G>@lPK&ke&)y_Q6G(F12sn4S{i;l6MM70LqEWQqm(3JOY%et>tDN@i{;2F6M1N+F~>tQ%5k5CFrw)ZcG-vs)#hKQZ!oJ- z6sH0{F!^}0kLT%6N2r^D+V`ZYnyUZEKO%!SEkvbWuu@WjxCuKON=7@ma=zPEmE4CZ zji}0Gc~B}pclE;hs({aCcfZV3D}P{%IqXNQT&A2v^TrGQ!Q7k|5SB*< zGLT&+C8~8=FGRhtM`tFe$W<|s8i!&8a6vDQgM7sdWT>aWbiW!M?#*yIL5#%QMF}+ zkp5QK5b`e~E-}$G=G~YSjY~s|VUlih)y*48_cl%O{jp38DI#ukY`ijIjxED0L4@pE z#Dx8=v)6>?y>MqX;#YA}lQUGjK>(;ivb%j_w#qKHeBy3mWRbrXk?V=v>)Dn0fco$Fwg1XsGY@(zp2{Oi3X$<*+hG;Bk{X=Iki3Af zTC5F8>ZjmmP1CjoJzL(T!vW^{GfX8QDW2Af)aa4wa4tt*H@?$NiT9n4OhxD_2m*7D zQ8rg^X6*}cnJb*F6N?Lw4kJ93)Hj_Cy245J6Bv2Xf+Tl2qz_;D1EoP~9l}7BUzI0y zWytLCXxywP~6v%WO3Tj}6ejPWkG_^gi0MzR4aKk5D93A5rcAlI9m7 za?bPYe2i!Da<)#QTB$AFm3SylUo!)ZfqImSLQAOU8$PL;o!wY0S(7w&Cp+rvN2x66 zR>sVy;YGcTi4XZIz5#ZF=EKC)Pfha(55C8eJV!QEfui~M62Z2XaR^wGlVw_FbdO@T z0$Jv+WhR+nb?xj6f!6Y~-R6V>xID$c$7t64%4saDVY(;-#@NQ)lI^=|c(S*(r-7k? z1MKVvP0WByV|#i6Uw)xxEBoh#h$Zqg?*YaP?(GV+_iJ$<$2`bWSI6{EySdUO;KKWu z4-n(hRg??okeeB~CcHDF_WDvw1GS*%y)#3AwK55o3+jGez4&oC z=reaT9_8t1d3tu9nO=seaJ!#z6rpJQRZY0p+0wt-;|ycpm{U1oUh(sxho$@_Fr8R$X6vA&ZM{8x!=`ogAf4QoPo>qcIQ*}v&7yBml}FQ~gv2EkC15P40cGkq(N)Va z`x%7}j@&Yl;9z$Ht9&dyUR<|{GtyOU^|VAxty&|-+hVxl zOM#5uXZ`GC>~?Rjx1kqzE)9#SYLysg{baqupI+RBR}AM_QS1umX9fp3T&E}p zNZM2;$l;d^mbi{fbM=@BNEZC5DV75Mwop!GD`)qA@32_4jCFwd5urb4$!jahS*?PT zv6s)(R<*Jh@FBevESXS{@Go9i!Jl(`Q zjq4Zn1w_(9rtpgd|40HqQ3*)WgpC9}+K@+a6(t^RR=|NhlldIC_*jt|5iflDEk_}2 ztQ60OkmSqi1fA3D^D%N*LReT1*6$bTtJNy~4%W%J)ueZ%@vKWOt}^KL@}}uELC43v zin9+7VUZvB`T3lzwpv77UoCM=*O}CgoDMf!mI6WF6op^DcDvoul|`=0huV8%$<*Dl@Num&s~&qdj}AkquxLSJA>@d{5l+eQ9oB zxA~six7m?K=yDU$YUX{U{D|Mqp_90*i0uImg(0Dkd94_9nSxu=g}y@LNOb@78f(Tx z%f^{7HuK-|0v8wMVwIb1CugTXeoJxCSFPi}{aR+4hvhX5U^^dHfq;Rl;Z3!naUQ2^q2;@-#mGx5=+~DDbRCT0Kim{8{jSDNqXPcuW=(d`J6kOdm=2M{ zITEDVub9)3U0{z0c=~M8AxS?f&IwZCm^aE?tHX<|qd$HW+fV zofRlLD0SQTonuXs4rDiS{u=U*uAXFeUCPBe2O1d^ zo{kFm1tkEgwK~aZvHJ|B70D|5) z#=wYajz)wbj*B%^J&6J#R$%DJ~lA8CF9>Phq^|J+Vdr z%=wB5O$s3@T7Qzry1SulMr~Pn&*e;yFi^UePp`XvELosXAeS!3z9}EGj0l_-0fTKI z_z<$K_oERb1w0fOu2|r7o&c>lo}pp0Kv30t=Hx(jmpP!FD|Sp2p+iX?tRP>&C$Y7V zJbuw{fKr>sC-iRb(Y*ra#uJn>8A^dMBADVgMiEveisz(;&$rcGbWJM@{w!A>XQg|g zUzytMI*xvu9jzbSmq0_E7Wblmb$%vADC{%uv!}B%5zNA$UAF9-$nhmmtTAd}_6-@! zsOiDKf<6cY+Vg;30cT*l_x=6spEGZ7ul;E*7t)|CqtBP+mUARcHp1fN*Ut(ILBfK@ zb&T-cU241iyC#i^@%eP>5jzl{i>Zp<()W_O4QQiTOn+5TqxhKKr(3I#R#O9w1SV-V z2Mk!}ueAr95rmS3^tw>oE5H;i6*o8Dmo5H0IPkj7nHyQ{E=scWVab4l!4my2F=1JcMt+cB)2C?Qi1?lH^>cj2V3jtRLV-FAgxaBneYrgIea>!o4 z&cbdfO)z@aRBv|l7tTX3EH{5ValQERk3_2$wWXZ_C}FfQflRe~XS|X>Pix0SWlUAH znqoqHXS6C~peR?$w3{42hJ^rSFBQpVybvZe{-RIa2H1J?sZb$?RxZY>y^TA*14Q-F zUjrbu7Z>OVe(@!FB@qt?TMoRxAz@uYEwji@j1P#EQ)Dum(|SKgm1|YCX2f0lAO4IQ z6~%Wqoc9hthff=b)~yYz9i>t4#nM2OSW5VV2)g1Vm%P zBv_*0LNxA>j*iI}QkB4=1h|l27B$f7kiT}7aac`>B_#AE*5)04j*SNXr|$BGOa#h^ zcQbG?vrTnmme(TA9%Ncd-dQpA9!tf>zQLW6;2bd>7{JaxojU&(D^b(e#X#Cgmc;~M zg)f7zhq7_S`I*vF#}Bj}yK&$14-WouDx83**^?sIR?~7LOO%x8iy}b--o|&ax`4oT zPM)tW1RXbeg~syK9Et=HY4u3!WRc{rJje@@+w=Ca%5HtTYIBOErXpj*pz7D2DJvgh z!3l9I&czU=H925u2Lpm5&)?9!`}(uFpQFNfjtPPzH_*~lXf|0-+)ZPvBnvvjmKzVF z-?ww3a2{{lgH=FB)&>1NaV*)>QXgEu=&L87vLu6)ac@MDM$cW;)bsWcIj|K8xM;IO z&}GxZ$q5#hk$Qv2L{Zn4rUy7|X2AF#9)LIlUwlOLX4Jd#Uwf<4(oVgF_NI{5%df~u zy^tEK+QExrIe956;E}+w;{blkMy<|n^`Ur}>G83K?3_ z>mON9F}dHKwEB;d5R5zwoq5_ zIbHH!X9G3YmpU^;T|3s&lByZBzctAqLOGufAi0yTP2nSVb$Cdd3=JYGWlUAp0Ui-uh=A;-`rvz ziR1l{FRWp9Z+xPvnp2b!h#+wv)yKVe@SnsXkpF_rIM$wj3N{E`{`SYCyZTf^0wm-X z0(JWy!`OvBR#S8z&YH`+j1T^i$C}@ML)uVU5CeB>l~hcL2aNy|9Vc0G!aSS@cC#Q@2CJ>Il2qCvP1x18lPc5-O3oD!OgctxutB` zaq0?2rha`0d+~#>sB(7VlC-K5Pl&(}15PQdejiq(XYzpq&{#qKp*?%J%#QAWc%Yo`pC4iLXkp=jliwYL5j|8YycWF8MSZoW>8W9 zkAy+6fczk)(ru8^RAB@gA3_i6n!*W-Uwn6N6OP|3?nZA`TM=*D=sNyYq~HD-A|1w* zD=x{AD07*!mtMOmvcfJHyZzF1Oiw@ep5&w;_p{>;yj zm$!JB`cmopc(JhdZ8)m)_IKxzf}EW8q^w~5P!{Xi*_R4ZHG|+oYL)f-pFvxffdBPE zUJM0AGWaUgS&%pmmUJ&N^plF%vwz7gYP>!AP_Ky=m5)QPxE%l8Oo#qh#(ky&5a$n>U^BQ$?!H9=eU=!F%}jhutLk3pdvf~KE%%4; zDHoIaYyPx)iF^L4^DkdQdiy^9!nW?8#ses<0oRNjNGv9)=T6o)C6w^*zh)8E%ETz( z=QtB5X~ww%A=Jp@<*+v(*&v_J3kh)oCkA@@G`6Fw>tAP>N=`5>FQFY111&-$Rdmk= zY=3q}C^618MIbrj#R#8##hZ~dlxe2*%tB)ChC053XpQwTUpvq?qzb>jyRzz9g``#el2 zqP#r zR2Q0an@!VOBMrqV9q*&(NLeklICju3E%>kOx@+3tGsSv~oXDk>D-Eks`Dkc&r7@tRt3hQQa_mym zoHztg98CS;+Wl3k;=R-> z%9J+#{gUpV-ylkJgBQF07?&noo>bZF8ZOQ$F707?C618|_z)dO6)~wwbgjFt$S`g_ z85>llC2p=QKhwjQB_{Y}kjwxU6btPSavaM1a=;AM)|dVg+6qc=lCejkw70#2Q$5?c zAy@scR|^BB0!YEeg zHuo}T%hOtO!&Ea?qY%6MSA7O2ZMLPx3Q-HzqRB%GXS0H4c&1hnD3JWijNQ!DEh+y| z*<6m(a9U~#?cs%TyKCkzR~!xI=1JXKpwphKpw>@3n(&8tfVk&r(c(%Hy1{7%JHlf& zrqhR=tNEfPXd3+mKw;S>gX^*#7T}nCu-D2!?)QP8X)~ zf58>KqF7R9Qj1fABe<)auypfdHP2j`rtR({*D=xAHSUxm%Ssc@qN|o~2Qi`@kE}m_ z`fe5}f&39U!UnN8c;5944=@X`)fDeDm}|~?c#mbBQ{CKbFl3+Oz@#Nw1y!LfsrD{i zsh-KI;osNp$IyH`D*b!hbERNq`BaP5Vojvu1hES(4<0L0Wxb6Pj597mn8IqBZaZg+ z?kn!aXq)bmJW&%9kyb><^wBl|DJ473xAAevCVBho-V>5jil=q9$N;& zjC8=Y_pdG^BjIO#1-~<{pNu7oXnz;)9#5w{{pj}D8#0g;|1dT>nx3|juNV#a^Os2+ ze%c0?v=LAr;n{gLK<5`4uTy8#MQW1ApYPfBTWqVrhbQ?(BZiuNgk8 zIx6&ANNg5EsU}@2Wh6~FGXM9ja)NH7DQ7UGW3XL&kcA(UsY8D{7R_w95*s*i)n$SK z;LDg;Rt%R(lGKUuL{51=UHapOmF`+l7dC~gG$`+UZy%iX)QQhg zvT87TMKntYgJ!N@fzEMN`fEFVsdwsi3i^yx>3~n?OQ{bpc_EP`@ zv5n0V?#NWg#7rZ}eInFS4ZsSbKr#Gp;S460rY!`LN)!ii;*8{7^BhxWvATAkM@M*e z>TZ~X0#Ae3eqJ9RXa7Ys#2crz(xu8m+hQO}#qM+7n=f&f;gOe1kg(xj&|aeKC)Z|& z?<&10D+vGCTh~^IfLdP&Sa(j64|F%(6wR8ab&PNC(OBmqKqEXO%01-HM21F&@kCp6 zZUzP=Q3>jKvqwChMXp`_129hGJT*z~^OKA7NsnJ)I~;NlB@^DSfkN3kJ8Y1$XXu zm*1O++B|!?WS-WvPf+(B-({y>2giE2NgISvZpn{$z-ym4lWNxzIdJ_=rSzqi@|U3 z{mEs!86+9PbPurC^OnZ7$-0$0FNw>$Bt|jk-DBQ*qx~YPcXMAUN@M9x+*#a{xQt$bDm0`{gsr#R61=x1Av_~?$ zOV3%YC2{8H*cK#(+z)7014qc=D~x_axzYi}Gt;{<^--vilCh{Q0`MpK5O+l?)U1s4 zn4|>m>s@g3=MbIe69e%ggq6@ahPzT8%E(GkW~<*JH&VsZmtx~l`S-vcNS2RuO%Y?RdS2a<6g3l<`X($Q+6gve6ui{Ip;+}5V zIncjqqVsiy9^e2b#H1T+wI^o|46@!~&(?2dBFT;t8aefyRM zz)q9!a*#ZQ@_9W;Hd1a8%*t$OLuNm&r+U6zojCWCKqfi3YZ}qK5cZZbBf|vYkSkkp zZ$D_R=^x+R^azd5ZNn%Aei=$MQlhT~?w>pra&xc`)=64SRK&Yl%wC|Ct=lCu>qr4SM6zJu;}Afb^d}NIS#3*sUePzC{)jyXf`{=IQqKUGHKzL*)Dz|hhU&HLx>!VK?f!Xet7s)XnUZ{KQ!8DQFE@Z!P;GgTED-#Q-fRERiE)s; z{TA9f{1(VT!03?c@UR6a3W4%X>B13>vt_S6XW$z)Mwobb7gXFT)~>6uPPrJw&Rw3` zVM5*HphABO6Tw*kO}zkQei|B*K8+Gv=Aqo8v?qnB{v3pa?b38_R9EJ4*OKqkE9ETV z46I5n3M`q-{cgX?4q1a+q<2H#PYpeBP4SbQf7y~3Ir99Jb`+$NfU@vgVbhkr_|)Fu z`*eRY>7u77PD^8WFO)8@nsaKm1X5j-EZ)Uy_R!JO!q3mu9SgYP}J7h?UQXFN!t!b zyD}%B{6}ugLEtlr*p7^>q(oa3r7ADJ@S2!{7SNC75B|w3dj*53j0kcC7{!K(-BJ1B zA@8EAV@^F3gq_&)ZrFFX3GtdrfW&Eroq+($KH30GL(2s4baR%iNTCp8OTlE8nWr=t zQ-N~W*_GL{#usszP7#s+jAro{B1U6Pf+AQ7(vV23jAb!?m*rZq;-)ALbAwxQu|F7k zVIOR&J?@2mu&;V#S*ST%6GhH5qm>;>SkDZdyJGCdhBcSba0O_08`m>xknuAwI^!(C zd7eHkL1^W$6 zypw1Lwp?%0kXv$b=>CfxPDRCU5;9wUB8V~Fr`Y$G8W{d- z`jOnuz;qAGhHG3CAB26Hl2nD3@`gH*eE1M-2Q;5Q<3wmDL{PlmJA3z4y~;xCLOG<~ zLGGTaxfLR88}O{L&_mgdmWiq17O{w!GssN=e<0e+!W*0(E0w)mN4U&e7V9<&fdZj_ za)olG=v@wbSD!fBA{uwB)MWLwjI1=EMoAP~)u+jm97S9Z4!O%;jl0|5wc%1p;Q#d`xdQwiStPWGS>+nq4qxS4QT8^j0 zFcb2auK$*Y|L5s~8+;mXM3pys!5{Hm;&Gz3>NAz}_7zA*<8?dm?Y;O;OmhWc<2fZ% zu3IDZ9x|647&=ilNOK_%dlbX)`$x-6@sv{6^r)W4N@PyM8EZfO*}MHH$k$H1&4T*OZ3dE(V<*j^lVC%7C0> zXNdi7V0Km8W?27D6JKcd$w6%Ms7PJ$nW=9ZAHQN$DrBvv+w1K=nJiMpI1Gw$KGUaB z1VaS}F#~AMmA;T*!cc4rv0I`T`#B`@Q=u9+XHP&t0v&scUaFMv9KGA-pqTGU&-p4V zd6e58`DjQ|%VhajdIW1s($5VH4Dfb6%ZX1+%*fr@*>M{MU=J|1w@tJ?8s{4Ef45sY zLC=MaG@X{PbNe-~`dqYhZfF||`PFoz) z+<|{YN4V>?f~1!GzY=Q8!aI9~;I}2DJMpF0PD^a(zf^mDTQ8Qk*GSB^PoU?zr0eaA zqR;;X{Rzl3xSXjCo*{aeHS=h`73ew+xw(Y$p!^IWkR9`J1 zFrfc0CNA+@J;+Vop1M-l^DlqOO-%Cq(2bkM@}>kbnsZ z=nb7d&GKx6&KyrauKH%Q_osEsc&(#uXyEi`1-TNL%I&3Q#hsSy%eHmCXcY^CU1Ll@ zDssabz(6N>tyWyX%gaA<*H@4&?XA2o%HVMP^QYHhbk*hAasIt&3#TGBwr=_C7$K=b zWV@HnEe<@Y3brA{?0}8?Td^1J!697BTbmwD*Ae+bRJTI&rq6gv#PeEg zzr5#a{s%u=A{JYAOiN=cZzMe!WlyuCFU!`*cdk|@(69l-zl@7lm&igkBw%^5 zO%XJQi!zR|0p8sI+B^6w-uF==jupZ(oz9D%0vCn``g2`x#Yo*pOvGm(Th7`Y2!q=E zmxVgYD&1JJWT0Mu*X6r^4Y$`1o2l0Mew!_?bdj~lLccruDYjl~t0LuqeP30HGL3ec zu{CvT;hu8lI3wht_!B$QKOYJ?^A{i~-^0f=W39cP;>*TJ(d;a72rvZv$aR_JkBHG` zZ)^b)!R}5&)~21D(6bej3QV*A`@YCp){5oxHaBk1 zxbwY#m&~se!bm@fmad}!rkV*Ft0kgt^x2Us-anb9Ei1!!#|K{?4t(>C-Ui}9drkBy zY$XH#)lW7v<_vhtcMayv}NuK7DEcE>vG%GvgvWda}Kyv%{ki64CgV$7! zpIVI+-!9FFeL9u^<$3vUo;cOb9#S<6D~MlW`zxuno{4r7y#HBPI5=J4#3Jk*d)fepjXPs!Jy-qMN~Bxd2!-J#+72Tv=n7wz$ov?`k8${LId>T)5R2v zm~ky>Ef6g77SE(Zts8c>z+cHtXsN}!JYkRXX%Jgg7DoYbEPtaG!jizUlP>EZ60yu) zEW1|g@99!Z{-DDAb1353(<;1F3g5vdlJK_l9}n;d z4xU9vbe-p>&EvBKQWcC)lI__v@0~V~Fw*-^Qg2kkhznlgQ_m_Y8u}(g9)DA;eKJ(; z->*m#gUep^Mhxz zZrN_GuGveL$VHl~K(K~krR6~ZiIwyL$VPGRS<X*L( zVp*Yktbu{=KC|3A=aGG3D3m=*n%S)`j<1{Dnp{U5$q;7jo{=jD@2z9CU!-QCQxH|i(d)o%?f0H~eJonn_WFG!*35$w0pR8kBN~LTA#G&pc12vs`tFS9; z6PY08r()gmBo{d;9{Q!!FmKAw2%_WKfGhJ>f#e!rkuES3?&|JE3`u^%6Kge>j&BIq>^ z@0HRCx;T7UTGO#_2m~p$PO*Pqd;dm8cfs1RRH;=+UV2DsPa+%>56lZ0u7G_k)-QeG z=8_EF@g2v1ZI2`&;p^{@Z5qb;(-EdHX?ZY^vfrj##{ukS2W)Q}k9wT#qStrh(=)+3 z6*=ox^r{}BG&Ve3F;hHaCJrtM^$9x$y-3}9|5Y9o=GBfN*&se3xT|V+p|%kU48lBo zy#1trz7EHo>Xh@1n1s*iS$R`EGffsM2#OsuP9oDb9(s{U@FAhUlKZ(HEob_}$;UH^ zaJd5QhwK352s`AfRaBJYLTxw<#(@=&idx8fw?F>+IHu|fil*Kei70Pe@-*SLyUH$G z%(if3#B~deS9KhcnrPA-F0e{dsrCL4Si$Ur1%E0Zr78FTD`(&0GO^$Skasq-_Z2L&_JRjj!wbeXK%j@)dhpiZo>* zMn4b{3D~lekP>9YzK73fug-!Zj*G-#d<}+dH@$?(Z(MW92e>Pt_WHR$kn#&+?J7|! zq^eS#+Pc5GDb$HfX(c7)713sYYl1qiQsy+zri8>yZ`&vX3??Z~6PAWChZj^6G#0&1wh)*KEB=hrR}qQACI{Q@YfMU_~+juL-yY z$?zZO-a*1Z`YbwNsSqCu?e691ek`;|gT|THN^<0h1f2Yt&<@AK0GOt3H<* zb;o)!L@}JF!gk-k5z>{FG?4Ls;7CC_7u@qYnbo&VyCmGnF)h9#K`~V;?T~2o+r1k+_Hok8qNAV zx`>VdwX^I2ULF7+lo+c3SnlSP!nGCXQfOmR%keYIz8Bs>%hH;1p zbEmh86^W^r$)~SoNbl`}Ux-Q*8a|?BLn9nm~GL$;79ja>FEeej?xUJ zmU2P_P7kxCuhhikleu5ATQ)dl!>Y`*0embD+Id2!r#oiusrPs!#$Q-YS!{r{lNdkg znGL>_LIkkekv;$uBP>eL%;zH)5Rs@bVCN-H|0k)1G~dDHx2Tz$f*=>XJ9^BpIoS8? z)wnKP(+--IkRD&gv`6}Hk2y&0A8VKTP;3vk-QdK!U3*hg#h_+#!2YrcXt<=*o-GT6 z(^6&UY#)0atdi|Xl8+16@oRoHceuXjx^9s!n9~R#aN%tbC-ApF`o4j*1~4)RQ;_Hi z)CMszGJzBIRh_zoPNvOFxGMPe0^~3BD)ptd)wk{%y*eaVk~12lPLIENogQMS zqqVAqA+^iFn4sfbhhpSm8Yr3r;^z4pm!Mtx6LL3CiXU6WJvlu5xwpDz`^I=DTep`& zLaxQ^Y8lZH7`sOB|67z@N2)L_u#jYPB!YfP)ej1t$^ZNH2OFP=8J94B`|J_^V>7fR z$F9ckkfP+L-ERp@kPN^qznWd^=48amkzD}bQ>ak8+M}xBxqY@KSaFbh+ zTKwc@$Eyl?n4H$p%(YN#X0e{r6qj&=(4$fMenzDyc`({y5fczFjhconZOHNe;p(lz z+6uR>?UqucI23mXR-m{Cr??bKp}4y{!6{CWkljUzZ1PQ?B zlMz^t0{ZApOE4sx4A6g1)z91y=%@0ivCIKo&oBLbg^yM(B3~RGiyE}r-&ax9wkf8i zu5M5>9fD`IEQTDTSI_oVFSjj5p;ecQJH~}v>yAVK$k3s@N0A|cZT~hcg(zkFYJb*~ z(%%&4>dlney_|ojhp8EbTh_VZS0P%9+6V;DC@niXS;Vnxy!{azqQd&EKE5u%zVwX_ znxu+_rWFz0VY_Ss1`0=(!jd3vkzOU<;L*)HW3Sc1Bn$d16pW*?=-+g9Ovx2acdzeb z#t+>Jn-sFH(4Xo~XaTt?!HxJ1UIz0#A|0-jQWL-<&CabM)e`**rEkeRWjUf-TNj(P zW=+tKRDt!EyW3|Ts14MlmmdcvXl*I+j?t_MmzQ*vhk~u@dX}TTrzP8}NOhuaDX1dz z^S8Kv`i~UyKs29j_PvX~_}EWU{mCKJtHz_l!N<9%RXb!7PVKD!NH_U*lE!XdGH*HE zN7xV;XvyQlPKI<=_h$@vzQe7n^K=d z(Eybn?9D;{|CGRfaSlIzXcY6MlvvsuAG#1XwN!~$&e%GGqG~r>=+_oBWH9MP=F3kz zMY4X(kNzVd#H3Px7uwHvVCw%-PE3e9$kUoyBLeinfzzvy3WmNr(1(Jlv{2-rnPBb~ z+=AG?uXH4y$u!GqOGg*hffP2b!<7LGrS#^6GeK>%s@4QjA-J<)77KwP-J#CzhUVT- zT54BDh)Y^pHnescoz#>7!zTSVem@52e6IJ`JN$U~PK$r9ZeZg(^TlY8y}H_mBrgBI zjSY1p8rna06y6SNJ1qe6hrp6xuTVUKo9K@;+f#&Qvfs~ib#=MrD5)JWZTd6Up{PhS$`kKIG)-> zIi8NrVRfl%O)F{v<6*au+DH*-@EpjA0t*sg+$aLC#a+2mMeem}l-r7rSO$7G*Q(Nj zCbC8I>#7t2#h5sNfyy_^F~gfP(V8AHH>xosbFDU{lvFhyueDQl$5+ng(rgsUMb&=? zzj?55F;Pj@PSy;(w;!S~QKYWrYnM1rHS17_bXE5?=82x3<{~8}tEGfMKUgUZO&m#E zgvGdb->ml!&qF73tC)1PBnAYX@^PVZmq>elRCWPce)q!A}P&I(4*NK^O+wOAL6`vTz8 zSpCK0rQG%vu*-b!X9*-_G6!sx<1d>n?x~T?dXGDF;Ciyhb8+-z*TSIOFk7rDP%s-> zUq9=5^7x$>!1CbOZdf+y|B33~4uPw!t@{0y$x_<#n~&uG&%NLuff@-dl1-2Plv;Y4 zrf(fGQmESnn5Ow(=%R7l2%LH|WLR{_dzY6i?prR!H6-N$3;-)p@bp+*jQB4HpItz$ z)&6ib$2KX6fIs8%Q_!<|NLIaCFv$lZV`Lah^x_Rh2;gTs;eJWd9Y+&g_|PZ9R&*hC zBhixDo*w`9i57J!sp*^kyf0Q-npuj59I$SJ1n|SZ42)}P4^(HTK_g1BWBHw=b^y<{~@W8z*> zPWjNxLYgLM>pmU7bH$!ivPYxi%h1j$cgPLNJHQb_1n2*wX|Zh#uO!`tDOvTw4uP5m z+|_(ZSlmP%kfCfL$`z7Qhma)2akM_OAwzJ&hGa(Zq^jC*u0LvnLpxyxVwhdP#=!ww zx0G1uZGIr&>!aI2oIk8GnE>vlADm+71~R#CO#?{vjpwqloEq+L|!4#uDmg? zFTMwywC=`Ko;FGbU6>?tdFw}snz}S+#IT>0`fqKhmgE+g1YR4lO-QFUMMO5fDj>0G%x}~;hlxj|I|U&Vm05B+M%AbuB&9{ih(AXXYv)|z!xt08 zuzsP^ltg+1RLmd!$Zlq@&+O zxHfejcHR3ekrIt`4I%S{{Jrw9XMbP5lz(HyqNvoZs~RbnT6~_Yu~?ywdy> z?o*VPuFGNVhqJ!8{C0K~c0*V3FFhVYd9hqBCNYjG(pQx#f=FsZGr*b#Ap8d?nQL9! zf0lYVs3BzR8eyY#X$Ya3VmhqacC~j6?p$?*!BAoGlxGT?RMR0b95Ni{)VH-le-%u` z5}^F8YEn#l`6WIk<6=PmH4pxFXOjZ&6E4h#FYGCmYIBlLi|;&p+ME;fU%<{4HhbpI z*+roq`65(=dbcVMNa#OQr^s(MywGHe!I02NqDFC-Mq*;aN>5b_&EDXHmZg&N6K;)J zPurwC3NdGi=w*J|N~rJc@Yo&V^kzZJtwcE0>%3g07WLnFb?0uVr)6b8hDEn5zW~dv zid2WO1pY9yI5>SeEY&(}a$_@RH%tP@U#$&lJPa)d0f!d352d9vFDMp$zXz0wWjVN2 z`CP)Y3~y=cb{ux&8&&1?^jeVVU%;Z)Z71}+c^H%t#j>#5}?kyK9p2us_ z*se;o!NlaqA{Vf}&n9PF3t7A^zQ#4Wb$!DrJn?=h!{>>zq3aKolS&)m z85V$*u*|GL-RGf~$Cd(|E<w167=g*y;EeD&HvpOBYw5f;>GVv@G!lHIO742 zSZdV3aGJj~9xao|IZ=#mpQ;j43+iPl3@zS=E7JnzB060$hf#u&N|9K4nXX-w4KjJA zBT9m4UNx8*syaY$I6lD0+8>RDO5*QW?+`cce9-Dd`5fwNiIRNwvuY3XmIE7Ub2R5-zW6(wOsHV3#4vd*h0cMbB}`(SDWsD4}_GHuxVsI0eO&oz1+1 z*3C&;&EZgd4j6Qdb1x+x^ZLGl@5xk{@j4w>4AZ7J-HyGIm~_ARvSdc>7?sN1qpJB* z>JOgjXv-#g^5`}Bd9tDv19a3bkoF(G?7PCooFOG;o?*`&m4C z;RitW_c<4T#z!Ipi8iErDWPtrent{9GRWN>h@AXh^5Q3EQ!i6DN^ATv62^mpQ>o$E zlpA>vm>`c}hS(cFrPdw361L_>n@O`#lA{8o`Nb?=>X|ZHVB!4J_*W-(SxnP&<^hV6 z;!&DUdoi=Wq$&i@uuLFQ2l$CLEMa9@@ILT9k2;hlzuu(M*KwyE6AKe2@$z#_S#5Oj zU&&RYXEotxSRDG*k-W)A&{wQbOq#8-`>g5@%?cTV-YW5_w64AGi@X; zK5RWz+P_JC9|=HqUnYl7UoM6U?wcOqe}*@1<}ti)MvW5G0`_k$j$*|b1+dFD4wR}m zd4F>B;A&C+UrigXGsF2_UmUDYDSTLjz+*u=WYO4gADtA9QA+&0Wh)a`m|xf!DL#U5 zBNLYz*J9OdNaKP>=(->Uk6t%f?O;2b$qLpdB!jveVEC@5CoU5gVWtit5+0#@#?`~c zNbI9W1JRz2}#-TIm#6)#y!cvS2 z6a@RHR?V{k^kX#auiJt#$;hcw{KS~P@XX2zO11E1cx3f97L@sS_hFb;6q&)&J;rv+ zu8VHe#O*@)?K;CJUI=uu++r0Oe>>R?N@CWA9QF6NR2K5{bLHMsL3%duRQigcYuObY5Xah)i2BXfewkG`D-_iU& z8_fTRf7cOvwtpOiyg%YG0!7=GQ3Hd(u8V>IDmdw{jv~#jMT+bndnxxUa#?t&N=`)*)=(lP7mk_*k+gws6UZc6}8nyer+RHfQMUs3aARq0t22pP`cGeMY z<&_N>3+PUvt(9VNnk~AlH80hFdyM(>B&3kczu9+E^7juJ450&oig8A*rZT!8dP`=}zF%M=fXIXMgwvVkzTXMX7f&1aTpy%Baaor!D14qmVV5Awofk4U$3WFgJ?{*s&}+ zCLP4iZ|aKx>0i`FbNseH3Hd#} zRv6HAy_x2KIlU|driefOBerPcrxBpaPE3DRQDC^jkg`yqdKwe3uy{&*JPCY^zj%nB z9PRL0X9=5|pep+xCC={;G#B5-s7#T#OEt?BKc*0SezTCm3AX&zdl2ep92EOnx2~z_ zL-}ZVQ#cWo>fxc|W;7}p)K5x)whI3~i^B8`{&#foYUnduAdMEo*A# z<828>8aRw^gXUN^TrMVYQ+S((q+}&Q+>u)uB#$cfik7)mE}++GSc!C`PK?SN1ySsJ ziS*QlLEcjHWudx*g}UXiMOewUo}uAvXX`jFMX*aSETrHs2}dPj*h{wTwLnLnlM1e# z#v8UgYjC@0(zXBCy@Pi+W8W|~8_#9ks3}>dc8poNq8xrYdH0lF$==Y4XZ!d` zy&`bUkcdxj$F4;cdlH1SoT7`wz21$1a%=^!Ny0(+IBJ3ivYuk-LMM~A%W^50r3ZHt2oEEY>>1CZ+G?#_=CZ0C3TIjMWLFXDvA@Rezie>=|_B^RKRU8=yg;uT2}LW_vV+%Nv&6_S!T2?|>k<3pqQlLo9E*+qbPzL~E8=77I zBlZ>AP*{x1?H8NoL9*OtFfy(zE=uBMCO%N<&*j>tp3o0&<$ zKhwp;=^KUnY0R}6J9aYlCgb@KLsiDxaj#1KXH70-U-Th}>GvT{7A;3E6!SUO2u?)CZ z7&rcR^fQ(JO6`+TPZ(HgS*Nax<`;@#L;k}FgdC23H(~mqyI%r)+AL|`9t`l`ms#ey z`P2GRguTji`ip^f{a-KC^=KM(8~$(YB3WeUY9bH#@0t)asrDSS$_Y`on}i*T-v^L- z@3a)Ud5ipbrd6GXk30FrD`U4933@(T|BrU8-LnT7q96izV<;9nC&lPYDX~}kg%x>j zggdtsi{(8EL)JLSYoy$slPq`$Ea=q-qS2ctYNT!l?Cy`vSO_uheXAoNipdtuWF9>z zfzzi4?G+3%FuAOp`MDM} zj?qaFfCdY+@blhpv3@whtH;H`KC&!JLD>GHX%*WBxa#y&xfGiGaP=xz#wY<@im90U z@BCXyK7QekVUIzLU$sC~|9Xkxt-Co;P417i3vI~;Jax_%9;I1Y%3ApSL;3%dxUgRX7sQ4ayjUE`8a$oWyq&a7WK#2kbX_Q zz(&1oQB_dkg%sBbuL|&~T>WNT%*<9hh~vulWf z$BU_!4h{<9+A%d@O%B$iKP;ENsg5|2obw-0vrKCb9Alew&RXtJAw zV}L3mKf`w0Is=bX&ZZokc*7}un;5;io;-Dg9@;Yv6^9YRKZ^q=G4^8Yj<0{bYiK3|x2hQe$}eGh zLT<9jx-5twuJ{hzh#Ts}S)&K`yS{2-xK+T7zv;s>TTbHo!v+1!HyvmxRBrojH-2QA zcoJ4Rlmod~u83*hrmPd!NvNOX7-m0hS8G`Quag=Z_;}XGZ^C3AclWUX?N@>BKb!my z<@f%-^gXj3Vuh)s*-1&p^aM9&HtSTcX!BNeEwc54r;Me;cYIW$%fFV3q(ze^Am_dU zB`6n-^+mf@5Lkxd{qjz3=zuItM=RCWexz^e87S+&hj4R(fBVo}uA&e-Qr5NO>3XY4 z3QGvPI=H%4BkT)`!uiJ~`gi(<@j4uprQDUaS@we)uxxW-i(kG~6%te*4?NI*daU@r zR|B-CpfMTD1Gg3D@0HL11y;Hq77o^wfc6u#F18d~$T&P!u>JTZ!vX=zw3t|Gvp`Rx zbYh2*K0eZ@lZ0H(UUG}_*geThxw4>r8nbfIH_nfW9xM0TdkaCukzP<^Emcg|7tv8jzF}E?r=8?+VgL_ z6JZ~u<38u$rKV3p1-&76Acns$P1B)&ZhzB$ez=;2(lnWbGoFHWqllpj+gq9ZwUvAR z2b-CGtEic7luNHdS?`2~EXh+5Wcicf>zWU7jdw%4oDgu5(22pDm6FJT+udmd%O3 zi7nkF-#?|&5(6^n73{bLr#M)Zl zQ#K@f%~lRk${w+j60F`xaQ^bcJ^{7;RI*=4C@RaD#v9MjpuBO2$$6f<@c8cQ`GQ}o zvozuJtC65FMb&-ubfenIliE4{-Z#vNBOTbjw(KEVQ@q>xa8jRvh{1SG=X83F|MKu+ zsCZxZSgW_HTHocq-r|4q{&F%vN$mFg>m7`vLl2(`!I}$fp%cH%{XIPNa;D^ZyM7Xo~=Mf{gQXJfmgGxskdWS z`4>)sw;UGkla<`yowqxN@crk$MDVH4i=KG_7d!P!Wf$c4)6segJ#q5(e+9=`ZwUl! zb?qZ(pS5MGp3pi{oQI@fuOx8mIL(1|I-OG|}6E-5AD`vroK)tR*Kl}ZSmutlY5_BWV( z>L!BVbj?F=mft7)_q8WAgC>d4xhf9_%e*vUb)&7y!pPTog=I8$7y*p(Rcp$8+kZ6m zb~FsM`-4M64W}wA1`WE7!bFW&Z(u`Yv2kphovhLUuck4W4;2VTqz`C+R1=f> z39_3*C+$L$4uYQl-pTvpcFQIo)XtYjsYqMrUdV-(YV zT^zYF@i%u9k0Sj07zM;+xx3VUI>&{prU~cCuR9Z{Qa2O{+E^udeCx$uS5w54J zlc?WhoSmR=H8%B?lFq5-CwF<=W?6>T7l)2QPuE%?(X$oYu9=j>OZ@+6VR2b6BB@Hu}t;q7=0EID|7PewCO*wGOxAo z|923FZP&>WQNrz;t}Dl3ShU}PfEdG@=97e_fwuNt=~L+IQW(?AtoTYO%x-u#=gtho z?O)yQHmP%0UTk{NC;n)lQIZXQxq4WKQ2&GBz;ZWE*bM634WBQX#Yz9$dZKcc(REE; z*U(Z%aFeY1cj=MF%p8}%yZ1}l-=QnLc0ACJACSoy`A%GDYb$8j@;TVz+RxNf49&%Vr?7a^hR5msrS_HhMqDVYimmFK zw{4-}tT1X!WH2&se7TRo=5S~tD?=Nt%P}W1)9sn__jWVUHp2E~d=?Yp6{$eUa1>N! z)m}oO)6>c2iINbXr`0(f(A6;0cK`X7>>te$_La!IW#`Zb5$WAM`a}S=D6+931Tw8H9T9q zU3%&#w|U5Q2a5>&TqROx^f2D`9T&t{6niLZ+ZfXyk{K*mB0zfwOxQ&Ss`xnO%+1={ z2*owF??eDX1oJVw%ds`SBLiDeAJbj;pq$3QdF2;d)`obmpOZfVXd7vgw7Kc=v1s z%ZV-jjQ1{c#l%zWQdyAdnh(MBUXl#Q#>5NC6@=KaYg@LE4(be%2%&G@UFS!rYcowd?B2@``2Fr zik9l!X{a`qT^S{IQ?f;HV{q62+u+imaSSxmLMOQ*lkXi*`ZRn$d!m)~cVMU6dZmxSmwB5u zxqbh&VyB7Qjs$D3>patW) z9}4;;*80c_vOAu#p#X7*Wc_xK!o_pHKkds2xG~Z9T$?o2#<`r>I$K*04;(tI4b!tz z%j%csiorS*;krJ;IUgTV^uE-qn&x;_ueKhZKby5Uv+`r&IpTaN<}{GiFr6; z?yt43;djl-_@9Xxy|Xx!QopxRr|iY#fZk_+dk}yus{cInir)Uo*W)V<>vLMgn(*SHDLkqxpzi6I46wJ$P-2#6#fonQr+LCQDJAdmS^Z;PdWdFe7xys<0$8=$5aL88=W}TyGB|1dF51_Dof)< zB8nwv!A^fnk@bm|>99e9WD@bDw;G|z%XY}BBd&ru>cbrWMug#1AB~=X!T!%&xvoVx zc*_C@a9R>E(|T`-5d_u={;bg9_f7@gt4tYD6>2r#zb(~awMCz>n38)t(&q#_3x4?MCc+k_ls(P#iR(klfIyYNp6iOE!~-oEztu0Mmh2=@ zo}Pc9(VepMMN2FOKsJ=YvQ(C>;FgsC{Tk zK*xb5idQ)Z14A87abu<8w`lQ8{;Bcy12v>%8Q_Xa9rQ{2?>_~@A`jL#P@}g^oka5+ z$cGxE>v_WQwsRPI%_pjc{9b8;VWX;Xre~Qr8Q2v`IAk=bwsJRf z$TuD5w!24&O=30(v$pcLnZZbe&fS?x1oYc1Wq)O}Sk!T~Hz7aY=SJbsKiQ1Hdnmp2 zQYX5dm!q`a383>vEvJ{b>q2Gqd=XtnSRgNuE`;3x3*ta#rIsnZdtzYCnM3-&isS!O ziSq{P`b%(jhq=grJ-i1Bqg>%zbI&UpvzQB_6 zPqB5u!IBJDSAJC#jlJ&_ufVHYLPn(M^tB|I5bsys-Qvv{5C;}TO8NIQlxShoG}pOJ z6vJ(Nb_=<_Yr^)+b)TBs9aq}kt~5Cf+&JjfdW_049P>M_(ww(VP5%kk+Arp}VN$@y z&&mDC*7*Yv{SLM>yLT!c^6Rvd7-#h*72<`3#bUp>_=CkpWLVBoU`I?eXORZ!Yb`sNzRZ&sQt`nU`Lzhi!<>qfPAmCOz76LViFA>XL)`WV~Rb4mO{8M&S z;+)j5cd+@Yp^mC*acBHTYqez8O7cO&Nm@1Yf=`$iu51t&Jcy?4TcYa;{hc1p;_}B9E{95qN0#PO~0Lg4?t87h>dklkb zkc*rDyZUZSV}_#-pXc#n*f-vwrZ_F&#azDN#olpC!H*R!o|czq7JJ8d6RqT(Co|H9 z0qMP%*H%S}f+_49;ST8bB2!VmRHxEr+|2YTy{S(0O(z}i3u8*Fg=XVd1T8WfPg#mo z6e|=&Fw=IyzB8)FZ}!dNl9uP=WvEv^`ZF-jChX-qlk+yy^N2YeY~QGNcuU%LyG)c> zrU}i)nG;P$n61ixM=qXz_agyFz?lihZ=AKXDy7|lwwgEf9RQR3gq&>f$Djp>TYi{c zfCpRQA3%&kn+v%Y<2d^S5B{WeNm73=Kcs!c(p&PAdh_H3+pm(juyiNDtK(#ydm&dS(!K-p|B!1pXWS$7c7>nhb;mEL6^rCpxT$V*v#XD!^4zD zuk>+Etmf%yN#0_z>D9RkvI@2zZYjvFMn*aK2llMH0ajKK3pwZBc$iL#j5-rS;=;mt z{ruCbt8|XGH-rReUv(D1R}6ru8c+0vi!NR*w@UYW2%_GdTr5-i>J1 zk3&W585Z^p=!z2)r~;GyF0Or)vfsQK#W%3)H88HMgf0_Yu4nL-1&mtAf5h&h?9x3z zz7Zu@F^S-~z>xzG0~fx&JF*I}`%YLl-S%6ykP3TW!hh=oFzGQ=N!oJ|tjO@z-VX@; zeHID)-#yO%I>rt0|6Pi|va6-$=#c}A6}{gaLp-?G=rD4V{ktbiVRt$58r#;@kFs0VpQQ%3rmqzny)Dz zes7rN1fXP9O19eszLS&tZmk>mCOusjOn=Ad!O)_weNhE)D5}ZBm%#!qBrPYU`DqP} z-AEL0OE?&k$QYgpB4k>WOxNop*%nTjRDUH6E+H2 zG*E4u@qA>n+~N%RGqmzT%!bYZ2{K6WpqZTZw}&ucf~!&U8O4@_jGsgleakC)Nfo9U z-sqo%`|7XgmKpIUC1!^sGz2L0=DC2spUmbJxQ6uSi}Rtks$|WY^$lLP+=P=COvVh-4F!m`3|HB1D$R-* zrxNy3%C_`5Wa@rn&P?Ta1gXHegqhCTJPvC-k98@3&K9fXcXb&t>94&T{!z6TpX)Wt z*Z}C0uzXkSJ+YK%($D^{*8wt2p^RhZY^pVLha1QDvx6ZT59DH{s6>A`mhWWm*Ky5A;2V0=%Hy3Qig^ppgWG2$d8KpR;ep}raxcGh3e4{xVM z?>qMY!jn%zoh8XT6Y2KG3NJPsH$Lj+ir3Pz$X#Xl2W!b{4+fJd*Pk&3QyHzt0BUb+ zYQBh6CuwPXmtmf)iIMcU-PpHyN&nihpplB53C`c5qIZ%l5y_qZr19l0=vzsML^zfa zv5eEk@jaCq(MP{P6c*aUe{z%A$YzY;dR*nNwN)z2L<1m#-AY{Y zsbCl_x~YQf{dt9`ZNvDOYJRno#KO!|Bm?xX1)fiWG}v51{eb~LhGvgmop6pl{#=Fx zN?_*wnEPNMBpT)HNTHV@WgU&;!k;0-MLICG$lO$M+&gWhN{@G;v_c<=T56NjH<5DO zBPag+itI~3`}qYjQWRP?*=i)^L)9F6d%eyVHAnh!t2&si|E&CvK(SFVQ#}Pbd66fe zb}TVPD*0ETWH?H%iQ7lI#>N(pWa1#^S|%wheowq85e8AjyO7Mpp_D62CAY%l23vI; z?X(2ma5cNRW_(1S9Ja|Xgx!NRw?AQGS{caGCFs{76NG`LjG7xqfE$9GnaIhs54<8+ z^x6`Y4d*U~ZBld``5p@(zy`nq+Ro)^{+`x`K0Yma$h1sS4(i`?z9Zxd=nxhb=5$%4Qe+tTaMOsJk)g~5;t!!~qYnM#0@s^^8Ac3M;5aAt zlgQ^#k+HZfsS?7WA_L|p(@osQ&BcZv3Qo0&EkvV?7bHp0z|%h+!t(BJ_^wirxqM5i z`7Cs7T~fchu=JXj^ztdl=}@kj^hKR*H~eqCposm1AdNdmllb>FZKHVamnU!60=$fs zOF>bJe!>S|=NFuS&$9?0(Gxy%m+mY2cYA6V;SO{Nr#w{Bl0P5t znUR(5kl}kMtpd>YmQYbBCSGl8uGB43(YJ*!g_w-f$QI-xN9KgJ{fTf6Xy@oCqonkH zDGePyIB9I^PSHm{YmEuVlf>&=A|cCwrm|SzVSc)1t5=?20x^9~^fB=IBw{+VzTR<- zD+RGMD5tI+M2pM(k=tm8F|*IYkd4ML1eaT3LHRvU`&ouVh6Yr;97DT*SwefZcna`w z&zkVyTlsqxTd>fjul2>Og88^<#fjANUT@)YbCWFl@HPl;@v-iwr@`lieKE>vaOmWO zvt4m3y4H~9ju9tr?-k~x-I%H34#Oer4m_Mr?x-NYl<{@g2t4{X*(TdaJ})Vy$@x*< z7H_55X=tM_qCphSr)j3Lva^A9KPQ0acuov_y%!CsDE{L()reO)o#X@ z>aCKx=}CubH`|M{wp6&2%_gkQ=7zt>13=OoIRY0SW#3FeG-J%7#`VQQu*es-?#Z2! zg`Lam-G35HVr49(Uw5C4Q1JZBA^b4_-{L2wYs-{>L=4jU;C!=StHJXtM`%JDg1 zxw^Xgdr)4j6$`}o?&#?FkAR==BkHJD+(EU0h+%m7!ua20YG9DEcdyOUGKP&Qd{Y>4d$gopfuj_+;XY)BFe z%lz-{cx+aPTyqO(4;8eod(v*IQp+c+-Mkui1I zZ$>dM%*)?``qbNmTXpwT>weQ)Xr|#|b&&mhAQFNw>5f^tA-XgZK{gxK0;ug`LJfwT zhaYq7a3aJAptWJvr8M4e`!I1uI537fn`1lgiTfNBdN)?tc=Q=RG)4}h&Cv&LE#M+$ zv~zY8FT!cAcYRuwKC zliE|~Xb~-T70O2i@Ki#EP~CXi<+MEJYW8@*CecA|u89L;nV!D@;28L; zrBjXtL%Gn|NlhRzH>$;vr%?S2t6hVxofuK&=>^M+T&fBN8$^2No$w01e@9y}Gvd64yEp*xV#A?~-;@>7T zGKlzJ?Wt$UXTlzCPk*NzA{x4+sNHV7V%4mfh_LHX;@(BjajZ4D&wDTNdASjtt(raS zK3#i5YB@&gp}}lqs+L2;hNDiRsNe|ayc+bBn~BX_IYyT?^6H+mFY%^qb5ZOLZy*0X z+~yvplh?3r^wl%PZ^BDy`+xZ+NTFca@%Q|GVa6W!{7a}^F?3!`HB|fM?NNt|NSyzn zR?PL$K;tjnMr@|I>`$|U4$M?tIH;(3E&GkyW@mrtQzN}h-CW7UTeeKhqq#|Wn^g&p~Cy%9a1^Cm}>7Q^YYQ)*bX~+Ee`I+e}^ya~vf6?)W zmszm-0(W+ez1ATALD7p#Kj)8MyC%zak8N>5{F7b*a9#c9@bS3QgYKu3DwLIgzt&wnAf0NI9(qUvAUsBEMutE5FScj3UDd$U^*m(cQ*Ti0z~F^}^A~wqB=o9E0e#Z> zG`XY@RXC|F1=O9NeSTvbhwJP{!!od`S`9s;aqW2T_;`Vf`;31#{@s)r8 zDgq{x*`gy?u6FECE6d9@CVeP`b=@}uu!zquU-EIB-U5LL#eZn$vwDo0>Q7unn9{1y zzt2BkR1zX&@aaWeiPS`&IjJ6p{rBVueDvrqOtFmNbJE^t)5TmszOd=wfS4E+V_W|6 zh}4Ogt9>li2pr1Z?!6fJP>L!^M}{xg6@2Xjj_5ramES)WUdP4g@KhY0KC82_0`qX%oVJ1zg&JDFUYtXGoX7(50lih3R@@M&lC(}%06l_|_jJl#pr1}m7x^)tMr zXp=ot8{_|$njd-pT;2cP`YOOB0%V6onemA~Rp*4K@m%v+CbIKxlN346OqGJE$Eeh7SM?kL953Vt&< zT#BwN$j!qOXcEN2lNCia~n`IF~$THDu-l0xJ+M&(P;* zH$k^1oZ^YAjfT{Qoc%*+<0(yexLm=b&6xZ%5T}~v@Ds#aaXBiZ0IjjnyNRN)TYlzq z$88tH#m z9)D7DV=XFX{L1tH5%rZ}O}>A;iijX3L+NIebT>!{j1*8hq`SMNMMe$jl5V6K-5Ur< z=jcXq43PHh_dn;l&im)(bKm#(`^nfne2B$DR}kf93|Rq^$K1_1h*K#~9du{&ir{u4 z5nMq3W*%1|Y-T;VO>03InBhywzO`%FVPi7|5#oHveB<-9m1De_QS?_ECH)I#6t8f1AG5#sROD z>~Eg&9x#5{Yt>BV=YGSc?8^$!agQH()3jMu4(AggVSR2XmDs~j-dDXA1!XdWi^>YC zK|-te5&c&vM+JcHOx4zv>B~DXCg-6Eq#3eqVG02jlJTWkrF+~!XH%G)G!~fwPEk)# zhw0~z{TGe~TMfsfY3S4y&R=B0!ookwV{DGCzSria@D_xPT{vPrJPQ}``_pJ*&};K$ z?_In)*uvZ&5MyZ+X+r|x-gz%5@JuFGms~;T*9cOU$c}OR7bUImIL)4{hj#1*d1*9=al`8To{BR)LK1lX01S?20g?rGvD?7(ppz<*ZY`e zii?W;6z*1S#G2aJl=^n6-RD%tsa=J;^W$)vTr@#S%k)&jJQZ=reZl?aa7yjT)S(+_ z47FFf7|2VhX8)`5eNu8F71!G>JpKta?x;AO)m-)<%X1aS zNcQlHzVY8JlTw#s^_C%}kh9mKT%P3DVcJ~Qy(B5VZ(Y(|D*akN^%9y*mkO^2H;-r^ zFe4`g=7KJ);iX{~-R`)XckL55kI&-AQIskNYkL6Ht=giH8bp36v)~N2PeUP8=KQXB~B`2gY`Q>}%LHqvg8#$nASR^U8 zKw)*K9QO|;1@!D)YTzA%dHghjk!YZR9@7f{%>@c0^og<*Kw1Kgz`c@;8Y;lbviBdJ zN(wfT%M@XzSrMvnj!mg8kJ0SBF!P3Gr<7PKf5|j5(nv?O_>#~}CkL8Q7?P+-7S?=j zHl7-*PjMU}1+ob?ee;iH7wk=c9ytS%%)g ztgbPOoAUnYA$xIQ6QIidWFsT&K;IeJDvIbtSd_==?bJhcuG8^vMmcN6MWBA z#g}m67`;C9sV|Ww1}ZZFTsE0PclfH`zf*%1fEA^L**tzeea5Ig)yF^qVI#;c47L6} z%GmnL@0S~&aF_d?lh$EB@1~m}&=-eTxa`t`Vo9Il&e`4G=zNDfRADRO00x5>OIxJp z}F>gtj;iSVEH*nC@y51@h&lFjK{=NW;5m6N8o{i zq5>}$((;el=g&$pF1yq?!yZeCA2;7JY>5j^vO56Hy+H=m=4l5+NrZLi*eb3=xJBzWjTn^$Fp z()l~B+%)(5tT$lsYV<<9rqnFiGiTw%0N}p zojo`ApvOzsd64+;a?}tkjZxH9I(|oZb81z9#@~}dxZ}V|#Ost=gmk}e2SMpN?{g}9 z_(}N3&5<1RZvT~m&)V0lc^lWmguHj~Vs3cJvS#4Fb=I18q&=7__(`kinVa;#N3ZM2Qx2(lHE_OV!^n~NG zD{WtnZ@Z}vY$4zJUZ6BKdo`qLuAX(*lcsfeq%Cn{3XLEBoBp(L{tG|e#c2ULYejq0 z>vn$~vTS%I{deG%^G%MSpd&o1Wj%Avgd*lVF63{JD&g2BwW)u@mc?h3@xOCH=uNlr z;k8tE-S@{JF3q3gru)}$-Qa`gf~FD@(r)vnl3z=^gDrdaptr_QzbZL)L`qSoR9h00TFP?TyTwL6}8{nA4@2wA;o~}4Iq(O2_EJ@4BL1G4H5#z zsyK%Nzkk^}*NQNF1%f1rXkk?EJHjtwax}jgnNk4a`gm4IDuclq$EqnGTO-$#;O1M9Z6k2wHdGuYbhWBPc>A9yVDI9#&7@!+?d zE8A)5A{mIv(2D_#GphdU+-t|^?P9OpRBfE`=H)Xu9{M@$fnxUcfiV+bN|Ow?{l&GMz?Jz2D*(z)_d zSyQ1cW`n}+&zcla>Vz{k0mN5Ttsb&vH%xRT9W(FB3RF?fy@YQhi@tuz|Dt38d~ zxJ}7<(>gCR7+7wpx@&XJ9P?}RWvd-81{qCG)F?0-Q;^gxk&aPAhOD}s9En>FVo11T z?j3^8yemY^AsS;Myi}VmR3$Q~`Tm0NgoOp|mWRvPIxozv?G0kugvc4gylg0TM{>a6 z5#%1yvI-X@0q|d@8Od@M)%6S>3N(L!GUXhQM>B(@>>=@I1Ya)jF!Hf)@34voj|f+* zC>1THUWM~IKTGY(pIcvVeF}MJYwI}Ia8&jlKEjuor6w7-Yh!Z9w=KNK_6t0Ns}Ie| zu`8Pu5fjR%XmH{js|fwY*>*(QMX6+Y?rk_%*x6~^goO|@a9tU3`R;C5WPGH3U>MJh z>;8GSICKZ%xW0Ni zz8@am@W7t~1&@xW_`?8o8h=2k0^hz~_tVMp;B4}oNa^%}5@YcR3eL~Ime~9j{QI;N zGFwYd3vJ9X4dc1;AQN@8KFa)~Nv$zrG~|bH6H^koG>exsII!wjXAbX0jz}bV2%}Jy zOaD;0b~+@jFVgEK_7(cD`-#xb?vc8+PY0HHmE?%ykNZ@>0{6bV1uV8a?rxxd3s+p_ zoq{DO=kX0o4a_i6>15fnPEF3xLj!gvFUb`fwH4%GsaF6WiY`52EZjys=yLpoJ5Oex z3%+7A>r|=G`53fydNl7pqdd<4#H+IYBIa0eZr<6!yQOYUR2w(WPjL6p!?49*&zf@w zugSoxLP|OoF-R%Cxg&Rf7?%=|y}*SqC7Hc($E!FrsFafTGH5rx=j;v{%)XkZ^a&73 ze_xF(#~N90_7(45KHg3J^+!~CO%H%7Zn0artU93-pKFe5{#l6_m6-ATqo&t=bKCO( z4!Zs8G7nYh>SI|aSnK%9CcE&&6DP$(A<#JWh zc~m&{a+kHYt_k5tS|Q#mb}ka;)ow5{-X=~c?AUs_3w=J4^Rp`ID&6GwMsUf|!aO_T zKXOhLtftDEA?qF;5dqMxCn>T6aS19hki|x!6ak`kN<2I{AdME@I5IV%!a8_kMQh1p z>OjL4hWjE8I9EJ!lGo$oJ5Y;5)Q@@Q#AUSZ$ZuvsdyGpO^_>Y^WR(JD&b@Y^_QT5C zK90!nu9E~(vMMxu9Wj*KCa-_D1zJ@twS)j$E`fHox1sX6^t3pcJ69h9G*stY{QV8M zd57HFtD&I8BwsVb{$4cbPw`=N4CCPGuy9TN&908Iy*Javc_P-R_0+yJ%b}C>cn~hb>zH3+U7)C@FVqO(!qVxgos0W^0QbTA z;ulBUyGXC(tHdB8vpamY5$~7TQoN5xg~}m_MxktkQn~1m5IH1nfKl+D66Aw8BuE)U zF)H5A?kXFdjebOS!xSi{UP60WCCQws&m+Z*l8eZ6sCqK21))pj*dj~BV?-9&@L~C3 z(QwD|kcuZBS&+R+-&d54kI14w9SZ+&2O*8T_Uz*2L|IeBbB-{?jCni<0RhX(Dr#uv zTb>lPO$Lq!|7b5&6g(0kRJ!2hwtvM(5F=s_b!T@-l#egkdtbQyS#NcHosL0y=7v|2 z7r%R(JWj=QN>VWVtBD?lK#M@R>DprOEQXahF%mO|(uoirx-L?u;ipbJezL_mF%wvf zMSD2bg&S=yrc>q8Fsc@WWtpfn4FImN`u!um84I+Meowv7JK3zz$(8r&y8J2uV_d%637b&+ zPBgn66*<<@Hg=_;=tJpfyt30y3U4B*5W+V@*p67DO|uI^OMI1g1r(RJEhI#;wbG7v z%T~!86RtKJMwRylTiOnz4*4c|^9BnDf6k~cW|A6`yb>%lh~HhF#N?OQLOL~vQI3+Aj=1bOI}SiM~>82QFKnssP<734$D_1H_A)Fjmt8L zX0zakBpmo;<;`Ziw_H(DdI3Vsmb{(5rz#Io159kI&f7N3P92}MNYCbN=_OHKZli?o zKoqqSHFP|faut~!boGfLA3kWwPc_6V-w!P%QW%3(rp8iLY6XGj(B|S=qZ)1$z`3b! zfxwTx$mVXE?)_6%G!R)q|jri}-C zdVA5)#0@XCd=0wuUat=dXv&?g@5&mpOw8CJ52+_eyGmT%V^qhdOprS0XOnli`jc?L{ zUUYG)W*n~CDf2mrqElN>Uq<@CO0tGjOle*)gh=EswE1Pp6ZJ;YFV79SVJ~S(^euwscl1(sX zmJH?cxFffBNqYAsXdtqq{jsUX^TeN+irqZFaUjrQhZ*_xFgQ3mlQ8&DU(g|6C+O?V zpKWHEg%+Uv@`H1pq)%6N?B(v7dC%>~7K9Xg>_N+)iz?jdwis3f2_OpTQPRY4^qF2gP$N!2bLt=)IbGX+g{T?@wTA?5r()(@za54x2*(DuyTuVs-=xSK%9FhaQcJ!1`TvFj8rN7R&@-kIs$^L}PbN?t z>Raj!h#YuA`ghq}(LF-g3Ie7BnOXT~?pB!;@rWN{bAS4gx0S1zO#0FC0^H(haQ^-N z!A$ODIgA9vTh0h#wogQdxo#IreN1NG^{B{EI1e+>T*ewc4zB=izT$4n`LNU*DLE|S zRBACVha?4U07`@@)B!1YF#%3?#{hLsZs&Za&R(%ZvU5=2 zst6^{b0&h8@N+)=T)Ew3p>+Nyi$AMgY-u3RmDrLIHqp^6ypnSGwK~Up$VoS*-S3|{ zk~rSxcXCDw8t3dE{87*iU@3vIc*SYhDKSq>O_a6#JO_(H1o7*gor?q}ilR)l##grD zijTF_6%ED35aOP=E~IM14V4YrE;Bn$Rh)4UQ;r%-vV7G0+h847@;7>_zZZCWvEVqc zSzQl5Zuy(^Pxar@gsJ?l$kels`&*NEQzm2Bz{;I$+Sw`%{B2E5bPq%tz(#4-Z8nYs z8BUR<9%myUxll-Y^?#{djx)Uxa%fc!qFg zL`y|URg{<^%(*kkURfDqpa(VbnO~O1N^_cM4UsG)<+!LoTj@wlIOwVB&^-kil@@>- zfUjb(y1+hOG?Ot7m`3U|{FSZehaLajEIm&1Zcz6})m=1rM_jO*?Y2X?pWq@t%x=te zrh9%*p+o9WsGuhUp|J4r$_R}-scQVJ1g0EZ{tqX;S}hjRgePB~zi8EgYUkGFM*EFi zt#9}};rgz`lW4@CRI>QI$=Jw^{gWW{x)5t3@(ZqZJG3w-7Vd93Vs7T5V)XWCvu@4_ z()=(x0MDhI7j0hpArwQYLs>(j*}B{%adxX_zeLG~!{sk30ElI_!wl4X)fvN1Dy+nW_G9wwh|J|!>721zP4Zdw^XAey{DmFA zMpeja+^jz-chd<~p26u)|8-v!YLN5fFC-|WH7_J}SZL8*$zj6)sWqus8o6O-GR4&3KsIB@z1XK4h&NeF|2_VxO{_6Z?%^qr5J zoH+Oh1eXUaR~6C;w~_>k4iZD(1HyJCy!A!chqWG&!x+n*&LqN3Ge=kI#u;x-d!FzX z;deNGktcE48ryqF&)gtr)MgV9Y5`r;e&+_s2CrykSv(X6@BPN#KdzWj z-DV;SHOJC*j$Ma6a8|@L2i*}kuGGI7_9c#r_VYL;^IbKyF{JblnE$*5GjTNOrpXd^ z9DuFjFDQBRV>vF>npmMq;uh#O9NGdVR+ma5Xve$5FI)^@!3MXveL||J64Pkx!n0jn zdkC`Nr8j{n*4w`y0>DcSYHIlVf9&C@oRoD|D6CE=FMn@^Vda+yIgCbDyVerI2#ldO zQ>+X>)AB4uP2WR{zf)mx2dw)-KAY>O{xHiqT0r=zhqylnj*%sp2{h=-scR!NSNPWa zXlTmc*mJv|@Nwt1Diy>Ts$ODQA+wanhpsb@f6feBv@R>C>@cJ{;K;s}O5(7Vn(5in zF<7k_b(J!m5wRrO( z8Hyv!Zlr3=T85+T658@gNvQ3x!6=Ri7m;g#Ifx>s66UH|v4FjIk(|mW;pp9mDaW@m z=~jaBi^C9rl}j^fUEJ7m2d^NsBhnrt%0f41FY@=XzaHMxwkbMIm%HXUs_NOt*`sg+ zJr2$HTEl?YR9hpbs%;Oyx}Cf3OFALHO-{~+MYe<~Q{7a&&5GjyMQ2%vSc_%=^eRroT;mSmHb&L z75IKHQaD7)Q{#wB-owk~7T;k^!4f5Z z`7NM9nVHgg|4*Qr!V-1znf$V&gQLCOdxrqwxeHGVCk>XlpNBGr9*j#A+6%3%l$32* zlZjs$UK7w!#fGzV{xn>RjXzPBl;b3NyPlF3iHu5vYYv^=cNEzB#(_0z4U1gLC-wRo z;2LOc1V0(&-h1p0U<7Gqq9Yz7$0hU4kjEriCd(@(7WViUoGs=DV2P)N4->Pv{h6`L zK0fWA=%It5QEGn4VoShX+I{G%J;&vijw(R^`)k1`+U6x%R(3z;Otl%?+Qe#|4i%0T znxBsiD~zg-1QL-`=k#2tD!?-kU{LNGODfiE-KmGAQlQfDwR?>lUKx&}c>;wKCJx7M zPFNub5L;_8+Q@92ytL?@IYYn{3dc1Ssmbsp5Ix|xuhR@rYf^fzbe8mvF&}iU)}kkF zm4w&0nE5pKB^g2!_rN$Z&Wr@EeV>0oQ(D0vlxd4 zvFnYl^EOO}@>+AdpEzTg(sRe@Zpwq$QE?A@!Q-z`O?mFTx1U8ZNx3Im$@Jp(&dp~# zX|6NmFw!2>H||{>Xxf^*E1NF=Tgx^>nT}b}XbUC{&P)3_{W^pdK8UAsn+o)1NsUI; z0VF=0<`?r1PcV&dQ_)8#JOdn~fiK}4vqNsDP{yR2c!73Kz5W!~RR$ohR%7$@Y0CGh zrf-|8Ip|yR0(P}c%udFn?qUIxiR2k&BIKSH4zgG$VrDibXBwKP-1{QfhDGFt4)pyo zAi;S25tQTee0xVoRRNR0R|Ge&UY@IV{V)L}epT+22h4mg7}!!`BDRJ2H#ZC9S2w-? zGaKdQAU-+M)9?pxxYs>gD{XGq`l9MULDz=TzfF8{aWbADX8gD^Cx?0}6_an8QE4}N zVm2{~TR3!TR3NPQNnkORHA`vYw~|Dr13_1Ud@Y4@)gK`Yk<-N0${%tl_Z8RHpG3hG zdBvn^+>fs9mj6v`LHAapUFVJeZq)>w!aM&;f4QS2@!OY?xEQkVy`F?4_j_5+u9G#^ zCpP*;+|Ds?$1mCI;Qas6g`0YyV|+CH5#*6UJ%+w^^&wzMW;ce4NVro6aG|O;ZneNf?Z>ByCm79*g@PpeSFv^ZEkqWe-(V7pGoiG zWUivwuzomUgzI*ob*z5B3usr`SPw?AtrpdG|ZF8^!UK(V%Xcc@3b44O(9H5wO@d zN4gLn;L5S6gGAxjW~+Vo?0J2gYiH7A0Wtl22GzFkT6P$VnXg!z66n z0(zSM%y=Qk1LJTf!#T70_{+D3LVv$i!FS_27bXzlUciSr&;0fVeCld7TRS_g%`j3- zffA*T!9-R0B;~Ie;BNzoN=Pbi`|nH_U~h;A7(sWCNuh0P=PX~jJs8W{hIXAzPnXv_ zs}Tx0=|vwK3Y-7^T@Af}7%y~(5PBakf3Xzckag-SnkgjjbeQ|RRf2DOY&&^eY)lQ& z&@IiCo}ZpBq|lO(`q^MdA#9u^Be%|>P8EQ~5>F!+5Qvw9l)=jrjnG!i>sc7mmo$`m z<9Yt^j{aH2Rh}LoB_NGL$UEq%SYs1ZSdQ zvTl6M*{fh)l`jJ;X(gwe8__#iuBo@v{yBilo*^v67s|jbjJzSjfA2ZM3lfKT%oH?Y z;-d;_1*eX545AjR8_>O=CB?LZ&izcSFi%yvb8rOTI|ku0Od;;SbfF5HaUMD7>rv|E z^jXz=`{SGKXoKvTZHq1-_Ki_eRUtFOp^EVI2aDuSr6nw=l3I0eWm;Hb;`ggW$D&=@ zk)j-@0uoyRz+e&B!XQ@{kX3G}g_!>17;Y`8v|FB9hCR*<)K|kuEMgL55Y^#`wh?j9 z;sE^xH$E8sW2FhYc9RG=!i-Xcdm?xQU;91M#Hg*x^xQOhcY>2gg~@5g`X^j>PXl=d zGUb*vBj-3rW2hN#X2Ypb_7iyz&Q`@{e}cNIfD#Pj;pmRfGBx>Xp>LEksT;CO)hi0( zO=}f|k~Rh{d6I-DvcJU)IVwo=Qt8UD1S`r`G^;PQagA7$)6Jw(hv*&is!Fcr&1*mW zbI)Qp1eN>HQ1w^9S8}8Gr5qgVEKG1OZ?paC1FuRWsf8i+xM+!O+5u`ZPDF8~wPIq)}Dd_zOcUgo4?cM=;b3v}*4p`QLKm%Ok0# zCXT+Hs^+N2^R(5(nUGM)R0GebY!#IIOSn29VM%nEPvuw)K-#7@M~||Fe4(o|8z!#g zeLpprEdy6!!86MbexIbJY2_~#y@3??jjy(G(Mm)mE&j!#^w#aqs3;zO+`*z_$70I1 zmW`qK+)v|J^eM9VTSLu&_(X8D7X9qS)q4HN)doc6%Iq{(a-l`T@|4S{-X?9qCuU9k zXu0llBX&T#4*lsaEg$NDQ%@UYJB zP^a;y-9V_y=5=w4=f>XJazslvb8HqDZb3C$yd`=Zn|FaVuiVuJAF2;f%+bAedIyv@ z|7sW*hbbSH|Mg`{mjZM}nBx7%VL^yXhoo?*uMyB5TgW*fPJtL8Y>h1gg5%OD{YmPH z2InSPyeY|lqCXw>m)gNgPn%z5*JVZss^Uyt!YVX@VNy*Wlex%&fU zyzmOvcC^h!5+>t6IY^xMOSIijZ!}h(T1FP^F%IxP!j0nXVrsyS;+Nc`Y3ZJGPa{j9#8A<-3o2_aZlaxm^~u`_-}lOiBt zkNBKQGQQO^)XA_VJk8~Lmwv^*H_=p`B6^&CBaXDtXPpTU)|NOd;0Opz_;F0`@J!Vc4@!h5m zKgTmz;6rnHeZkhEv%=PM81Sf@rN+_jxpeLqqtQ!JLM~y5H+ynkK{^HMKyE!Q99*BS znfi{z>g4ek3!F_Z_c;&o2^qvka=-ceRvu#)Uu6F~@dIJRo~93mjbozL8!S=lM(e0% zh*wwQUOf$$&I&2U-Eu)HEGMhO(AiKDJ#F4&fm*+%=A_#>mo}lzRp7ZCrBuXc52d|< zQF147`=x_sz03+f7UX%y{tt%KDl{GjWb!47Y*h^t?t%3119O$@Y#WoP=-o8m-ds2~ zE*cROCi9b#7Rx?CzB0@*Y&D8D9r#{Pr$2ao_OU7timK>>T`cz1bI?V6;MI_#=zi=r_@uMe}#bJAj+Lg$+W>bS0WV@seFe;rSmN9E8K;m|ilq@J< z#aVj`yxb)gfw1Bga4g~U^z-ueWh0 ztpl}I8U2DV7Q^Mh?vMQTo6`YsNBU}Or+(+Z_4At+vDs&)U}9ood;haD^TE81UBv$C z+*hA}mxA#Ly$39c$VI~C@CTPagATzXwvv8NPHs0fmmkafeWyc~qa}rZx&=y};r@8& z8|HSuuZMA`lTNEudFIZZ{Cv0x_uZ#tK~{!%aL%3DnR*8gXiXd833u-!RT`slpOJo; z0e=2xf-ORFPh+0PiGIyS2jvJQN@4?Zdk6WupkMZcWbGGU4{CstA(Q@qEC?A`u^==U zb8C7H#vhy-Q3;5tO!O&UvT_ZYZd6JYMtOHlu-l%F zP?J-RPm<@uOyT~Z#mBx+$N=n%rG^U4=Y*YWyAKfoq78V5b(BejM}A0i_p;iBWW0Qx z0{)nFp&c5eH_E=D#j5P|l0oZ<2czvY09u@Q018y<7hn$+9UF%#oz&`V8-0t!!{`#g zc*HnoBCnKa>W5m*Il62Uy3h(ejLbO3cKid*G=@9z-0*RY<5pqag#sDOq(_#S*M=)N zOT4$Nsr@#d9?QUMf;6;mmr87!9otKgnyP+Su)bS28r!v(=dEF@CgP%kaT`gR*@uVP zVc$0zRZQ*rVcv(AM&G}4MkHaLg<G}6y6;{ zm@bMg-;Q1(MZqi(GD^z9nTzkvkxco&vf^7)nmY@hP4iDHPt?&kN+WWW2S3KTIy%a> zfY>dy64#68IETd{9THpddr~F*b_1IoadQcRl9b4P#L1`Qj^=oh#-^f)xtTAntQ8iE z%im=K9B_lLN<#=Hl~mWB`#)h?l&o&bP^5C;@3Q97s~v0BIP9hFrcgB{#NBDv8`Xu` zf4OX4qaKl8Z88kQw78gKUJ~y@&P?=oIXSpe&#p|LHh(uZl~o6`(R~5?eQ4 zK4>kDalcx-At(tx+2g9n(mRl-TuG?vBwD*&u(!LQ$l~?vdfK{s{O?SXq0Jhp`z}FXqO>Sp(azms_p5oidfiB!{>21Eg2~OB+C=3=j zIE5bb7t7O-q8cfgLDNKF3wdf-4Lz0-4?2s=K9Q`>PDyP>PTL?S* zajk+0!1r&jW~Lve3*P)}Yzx6=EZ-@b3S5+qU}D4W6l^kb(iXv?PX1CvGOk*fbE6Zn z__nxIKPDW1+VrNd_R^K^ssIw=m`3lTB&8Mb>!O`4vWVsrX)KkZy)G{y)(|bC+y3`( z2Zj$d8<2F_yDKdvn>ZhoFFjs^3nKHd(#sek4pAFbGiEmQ|r(fkF1TWWif~k ziBMPbcsVV~=B~`i=8ZP=ed=SQVSS9XRNkkt!Gf8LtzLvT=vGZV9d!%!ngf7UN9y$m z!y;%7mCVsO6b0#y>acmE3i>999uqh&A+$xn=l0~-$BWe{{gb11QsNty@qV0*LX=H?%Tg`fV|I9EG4+A4Ucv^! z>L6P(%oOPMWvJMb?>hQb={ojl-ahEERU%=C-@-|Cx|^i2!E`VD7-8VL_bD#&+?ZpR z-9oU(-{TQr#c=wEn_82QkS6sTF4MX1j;JXlkPSU7m=EqrxzgSeBy5pB-oLC`w5v&I z5kbw6b)C_kz>8hW!UASrqFuaEo3 z^;HXFw>M|l3j(8$!gW)AI_)fN-cMZa{EC9_bk`A6?N#?*i%VMdPA0o=*vfiqbzfv4 zcg%pnP(pPQeKr_0)jMGJ@-gwlXDKZrqbt1^ZUG__NAI#aD)S? zP!L*j6>Yyt-fq9m=4P{bpw|5dE|hV_uKCstr=;#i_Yd4X)w$RkUenZZ z_jJ;hJXDm;m7&SpR`zfQ(%ar&cC%4A%UmSj7O%vHIZ2hN2gRvRYF~$n+KU+m$;-*C zG;^-~dG#%`>DuB&Ue5u4(7CD-_sEmy#V)?|AZ-f_M2pj;gizJmSNVD((|@-78c4ak?6}%xEmP<5gOEI@k*6SydpV9!ErcqXN#(zuiz3nQ*}pv$l?o%SV?4^V?h$52Ss(VLC?ZZSg`LVYELS9G(Ru3w6b$-Xsp) zZJtX1kY8mF@rd3!43%Ha$&;**U#-cK= zCt~eibKpNbJXlrZ{@*JU*>4!)s6^|haNSSI5tmbxK##O_k8xPh;i!11=*OG1>}jeO z&vq@{!srrPE?8RQ=os5HbOOczzu9BQFwv3Vr}(zzd~AK{Kv5rOHrFVh`;D33`<6du zO0`Y!JMuCu>AHn#{?_g_+q8YLofLs+@4c#ga`q>FZ@34++aL=WaSQisY;i6aR}+U8 zZ$dDn^xn-uV`@Fsa4Qp6ZaYJ4;nqHfs{QJjT1#!5dHpG9mzSW$1`D(b`icCx*mrdC zl(Mpfo{N1ZCz36XKhaAl(@%f<9Ed7O>7k^}n?vnDXFaX0wa^lF`lA;B%a08Cpv1B* zaxZYdD>|bki;tjR&&PgdI&Wuk%y%?l;~sC*2Adm5zoF2=^pFlqm6@7ch{H0K%0p8X zUsk_UrCk6oMNFz*$jByK)}|TNN)F2d>U>pkl$}GE%rbvl7PADBQIl)piq~e&=GTg8fsY)vm+?BjD~b(G3S_?8ua#CrR(Q^!Aw;6`Yfj}$hRQs zmi)hOJ?+x@qm6z9(D%h{)xN4gF_HZ8k(&8+Y94xdh0X(Fk4m9Czovb0ire^K3JM1e zy8Ha~68q_L>@l;B*m#OJF?-IQa=WCF2vlh^?2qhM39k4u++a(AEl`^ z#=ZL0PKoAao^%*9X{&%>4I^_ZeKhz$&u9Yre%HketVLupy%)E?|N^aNRFc2TfmtENoT*xqNC-hdjYIZ^J4 zaB2^rYBXV3dNFnNt#(kLJfG!YKuvn7{Jt!RZXFPe$4SgZ8ul?pF<#K^UoD(c@VwbZu5m!7wIb$z^P z*JL;5{0P@)T^lrKI@f#2l|E#Fp(A?Q;rMJR6gJ+kLRhJ>eRFaDM7;YNGDk{o3Xw=I z)PYc(A)hmHa|H-R(?D+m!#V~&3K}n2FIoQCdps@re>pp5T+s9lSv$0raWCNO_g(~V zHEoOZFhHMF8I89sAe#)kwq7{_JvlZkx^mia==uPpm=7Zehmnv!@A_10+2C%_cNjfi zHd1}*kHVJb!kydoeD288n;a%SC`7$;R|3W{nh%NkUFjFxS6~tL3;Hp+JT5>zDFN~7 zyn^vql1pei(QcYCSzt~&) z?#2c@CyTaQei(x4OvgD{o9HCF`1(RsPl!0O3{64a#na?KZ8yMM?B}vtWs@fsA!pWl zbMIa7NTgL>*XJqG)N@SRNOjKoeRh47UptU=n}~NrNj7lYvKIMa!syrJLN;U^Zjy1_ z(JTD+;p2p%z2Bn+NA5ei*XW&4GM*(jSmAK^T;v4&E{ux|2juteEe)*rj!Q;cn-PF~ zO+YL5HZSg|GW+5aUMok-)96}fC&Jb165-F&QEGo!;*y(($^IDO?2GB{g@SoCX$*O* zb85X2a|UJV+JsG;qiLt+ZutjkFNKpxuWP@ghWMJxOOix*2C6fIm`(d0e~Z-o`DOvs z?(v05EN2Hc^^nT9^=NMO+exaV7w3H;tcoUOcIS(~TN>T?F@FU_TS&@Es<_$xcynH4 zkQU!_{LT@JO18P>5#ft-tsp|W;!HF4r?X)arI1d_u1Cvw+dol^mxwLbdTlXHF2Fn* znmdl``nYH9db^-`K{(EkMbqyn1wQbkK`z+mQtzjc`suAsFTdUJ_4~iEf!uTp@87i0 zaK4b(&cp`jhzC>H) za?$LVQL3K2VB?kFsfKBzPt*L)jnkx2vSBwVdN|ZDp8+mt%8_OtJiEynME3^%JJPx7 zJvFs*6^r#gMJuhhatPg`d(5H-T1Fw)oi|6P% z)(&Xo&CkIHPbg^>ZJ~m*A<|*SPNlX1e-^5t2$$m}o3|IGw09qFGlD&*O>g^bCl7wu z297D-V}E+*3abEE!+!0K6A72xi!u}D4-w?Ls z11GY>{_0$@C_ZOA7Tfv+TZ4jl2hCh+#gN~o)D}dy{MirATT^*A{JGVnD08YdKW7@j zm1{zV0LN!})M0K){z+ew2}$i(9z;mxlmX~$7y**mdnF}4+J@)zjt5o`97+8ms{L2$ zs%jz+hiGba#q$09*8GQ$(LO;6-2#qj3y zLbL=w%Uz;yK+nQr#1uR`WFQ!!&b70Cyj_xwr zCut8hTYvEeMY12A$65N)D#fji|KrFUAxt?C1=-=>+-BtU>p4Joe_}}8G~Io`W8N4c zFoUguhch_Z47ClK|Jw~Wf)nj*9>MT5Zj_K{LlAS0o63#bIh-q`O~-7w zB)v2_q%x!O_U^N7?(6d!T)mewQ`fX-er|u?xn7h_{~6f5=|iW$b0FcHPOBjmq?E_6 zPT#2)Myxov2$E$B=dWkjq5UnBmaycht~(IC);Rw4k`eS{{7HA|ufNtcl>2k1I~Tg* z-CO7SXw<6;y?J*7%ovt+$}n>QUVswJ+&W74`0WHDl{sGLj1FANZeZ=s_+1{c@mghS!T}4>fvk zh$uj2O`l>HoWkgxV-By9@MeHiF0pToAqB5~IsPa`+F(+um)88U47Q_E%hv?kg=G6s zPN#b#SIX|>E+62*Oi$s#n>JWmbsGDM!t(`3hPWzoi%yNeEpSPuKJHY4ovn=+zzK6$ zysbPE%_TVRYV^hRIko8oBrLhj_)uk$&0itooSb8rLWfkWzGZ3%W{V3GUp*fBeb38n8vlvF ztRHM|lMe0Lwx+Js4u$D}!PGfwo3yY4ejBfv+MgniY-~33zmK6OZE50$_BUGV>FHt~ z@uGKgW9h>Qk9=XzT5@;}z%%`_8}gm5w}{}*4;&w(Q=T0Da?@^qy!`(OV*iV+{4Xn^ zw;x5JGBu>Kr{ep!#=67Bl-*e``JG(4DtB$6Xjs-9Q(X(^x6|x&`Jq#}8YP{nqAh)Y z@ixfyy4A6gwKej=L-e(>lu>IPPDta=r-g;uzC5&jE{@m*E)3Bg`uq4omTvs-AB6!! zpv9T%Ep;Ql0ZWDkEv%;AvXRn&12s1qEYfxbmfQUtk&7N1bGRp5Hk$I<#VUyyBU#8vCI!50kl$nBcP6x z`PFFMlM`5KF3I&vezN_;{{4>xb@H;i)uS!tpzW9MRq-w@nqOml6D{KBC!-)6P?h>( zTlS^5D_GUKJc=q(Ro+lLr!<*yZ$et+8{Q~6&XC$>_5iI0DN!09Mi;}B_VkeTG#NQX zk9=E%JYW2#ymZ&i?Ej(aE#snWyFT1oM3ItGI;26mL1L7U1_h*H=w|4KLFq<9Qb44o zbCB+ap=;;?hK3=B-g7_C^X~oIpWp+ZX1K0%oolWCaquwsFNmKg0|M}8Jw0;^_#!X+ z$fZ93Ts0YY#6?0%(kVtpM)m>$g+;Y5)!k;wSYmI%(dCC|S;s^K-mJM09= zViq+%BQXTKS0TD8QeFirE4-rOV! z>h)Ap<*`<9T}KJ8Gy_zOTXexhlUp53wm1th+YlX6(#pIZQ{-9t!TLZuCM+wWUfjh; zEzKiS^ay1o&UIL*#?oRY;$iLYwOl^mpkE!JJ>0Ipbnmd-C%A79x1tVnb6`>lAtL`c zE{Ih1rLpR-SihO;==s6>AbL$T6(TmI$CB`36^23O<@0`AmA7rC(VP;zJ?=Q{96mKx&jrx2DY9wKm&mT} zcd3Uox~kQl>b1IP4<$9J48Myfdp|N_^=Wg~pyYP5@ozCBX{>F4o|L7H&A)@X1H25% z%zSFPqb7uu#hHYY`u6V@7?nlVAeBq~3bWfwx&#DQyRBZeQcLGLA2k51akyAC$x>TB zTM2!ZvwpEZ`>VF~%Un%4S2;ONX2<+|BZvrb?L`y`vA$9>^g0y!Lowi3&yO>y78f27 zC*I%hD=JOb&$Q&()l_P~~+tbUa$A{B>@BYA>7u*C=ae$j{ z=*A)em~a7l|18evl=g1B)ZpZvC*WE9C4spEe=G-huhshtg5qu={1HQ5Ci7&-9vF#V z9ey&G6Y#>o7^#Vx$!XI+le*3e>}_R5VGJ|=U8lS|g#qJ&10StX+ekLwIaKxakdFC5 z8_&kdpr=EWDtsrBy==AN*+kbr*%JKUbnX|A*M(pj1H*2eWXrWz0Z$)&_cfJ@%iGUi zdoK^abGao0#Ip8pc1s)gNT#+Bx1VH`qaJ|ZR}giGiMbmst2&<9s=-S1J{18R`Z%|0 zR^tI!x#nn(7`b{Rg@PVlmm_$9#vRrVyQ{o>xDvM~j5aMdh?7zt_4UVxsei!7JmA;m zGFZsf$IECm#qL2spY8!e>MYOn90clIY!zAibD@daYhU>`k?x|x3fVAfztg9F7zylW zJ*Mt`$OJ}0TC8|L_khO;$@UBD#>q!asr$bMyl;72HiPHA&J2)4s+y=B;3Gk@ex=-7 zx98R$lf3tDSE2*5OqcnO|9cck%&lQWMQ6-39t0WK*CJ>;bHJyo<5`J3 zEOL)GC|YmdX^<4xD-FNMw!18||M4SZ73ZoFYt(zpsP`ix;#bHMp+}QJ9i1go}i1OJV@T|E(VB8>xoeb zZzqSi(DBzuR_k_n@>#Lp zv0)_G1M!Sj>nK8zMiEn3xPI+hIBlJ3Y$BsmKCd!XqejKw-y8TP%!b|?bMKF`3 z!B>+G5Y(B&04&fSlI+x%-6QD5e2ej{1W0alcsSqWlSe!q>5YkYXNbC<>)kIgEzqdT zR#{)YT=Kq;-8tBqF7KdrlhOkNZhyep#}bho?ADBh0%1qh7ORb>-3NCiSYceR+6YPC znzQSc`2Xp=wm_^bWoKYbH#Ox;MnOQ1lUNti7B8yR%ExP=AYLP7K*N8!^Ofx zyz4FcxqQnJE30utJo^9t1x+NIXR?*cJ4Rp|6KDECMf0kqMS5r$6q)8jN{z2-QL(FcTrHp^0j_G08aPNbfdz@7MX?ZxmHw;TE~=RwR^e0@4|8cxYr>LKD$CT-M6yE zs=t{Hc!sWf013~&hB$GjK#afN#YBE5ANH58HsaeG-_!c<5C9@_ z0%t7A{dW9N6D72FH-Qg?;72lG9Bcc%k%ZLugm=TkEsg|W_|*gMN`MjT(ZhP4&Agvv zMVmW*#p437pNe}w8LKYDL^p%Q^=^f3z47>;hgHCJrT1C3>U{O1)j12!pDa5Q;46Q2 zHM9KWu1xTj2vT#-QO3OA^KOaf5#YW0cqZKQ92`_McI~qJMaS&8Efd*x)rKVwyZeLR zvEM=0en0Hpu(gGP(%lfQ1Za}AT^&08=HUuGM^vx>5rGp(o%_ujh=w)i(2hS&{^!Dj ze!TIWJ1P6ZvQkYi*X5}J=<$yJ8^sUK0e1EFjVD`O8qh+`SXO1{3BiYL6>)4_jZ#oW zA$fg3jAsUs+d?q1c2VV3Hsp1*Ea7WEPU6=BzcF!`4_+KzQVY~a^Www%<%p{rah4-( zFp+5}apLG`cH(G7|ER^-@7{b2w&r|4it`~`6Jy?j<>CyM^S+HR)BFt`8qkeN#q(@~ z`8iOthYk#l(Kdr?ESa134R5iU7n2!_QYJG6?rbmEP5%*0`i2yxf4h&te5DX22CA45 z^>BX>H9ZgJ|0nKCuUyZ#i90^8=V;Fp_}_xb=VNI9ZdvmS*lRpzsdSfhITC8tIBR8P z+(j7dhqL+WS&lR{*3IYc%g$xRm~^L0Yi9^jTO)i0kN0T-L#q zfweMmP6%ht=d6B)GOQ`mtYOx)@N78S#Q>T2bCV~T!l3suGSZ=t>N9OvVIR}%g}Z6@ zP5mj}X^iA9-7c20*6FpKEvRejmSF8>zd~MKp7r!^%NPxftTCU8=4T23Ex`VakJpcA^_%7L7>uOyUAF?R9THuFtPR+jz4@Yaf5BG=GCz+6}KF6Y>eAf=3 z;_duUwgC*|SR*&>ey!VZx!we>GFe1@$o5pA`4KQq^Hr75GSC)*_Y z3hz);;bUv6I`wA#Xwza2z@EFqT9o+9xrc^XO-=EE~H*^or>2BwN8}?pVAKz!M zODh`x3B|zq%gLWk?Rrx)TDrYDf(lU*UWwJxHMUt#PJ{1IrO#|M94 zbC?KJGhX?8e(BzoGs;M0i^(!IaP~Ch3#W>yuV75}6gPY0Y_EdsMnP7EYz zPqZd^+K_@jK)CX_khXpnkdxJMP&WO=xaqHh{!DJVEgw(i=Y+9C@q{#A;>Xk8$~6W0 z(3LSZ*Jo#|_{$X?VCNNs78>9CZDYZ(Mw$Rp^@p`#)N0^;DylR-@QFGBGVkkS0{^4X z5W4%ZVgJ(qlBF;~f9l)UX^zFou*s1(g@pxi_P$jWjNja~ZnC!0b!fztozYlq~wqEdzm?Z2M{7PNkqT0HFGfHwmnc2d~8Ul&hnU!$Sbmw4q zLcE%4HJVAJPF7$lTU3}`O*DOFjQ2iLF7|sd+7J~lt1#}opPNxlzG3Eyl^Ut;rNtD4 zIVgta(It8!MMFcv;cC2DN#Q7}pfS~1y`VUcx(kG-{%q$BR+gwIm19BHtfQik$lx|9 za~^dy(-*FiIHyD57H!)44L#|RMDr#I=L4&HdJr}lLHK~B;l-?I#;oXYA(fKN_rDYV zyA9Q403FZgbuLtFLXR<->uN@S@-+}jR9Y5NDTfRWm1B%?tudAi37>MG8_COu;~d5e zH}TU#VET#iYd4V=1ZThL&T6j(r211$B*`l_^{U^TMYu&$uFAbS)r;&L7XGUB=d+Z7 zKXK((WTYbVg}0s(Kl?tn-Sa5A+jrTC7X@X?B@6Pud6R|*-B_-Z-s6R6`Rt+73N^-C z+NPIJu)Fkj_kQ=_4rQnhB`dUSO2Zf|1p=k)m%zhq`$luY_o)XO3)SWV!ezkV@=Oua zHp9_az)c*@*rt*4ZUpVMtl ziC;V2R|d6z&Aaj^i+=@Kd-{k3tO=#o?F3?=q;cf^$tmc%4`O9{c7rK2goA6AA4O5mm$+UrA&;PNroe0k2LH`deb%V z+CDcoZ*Hc7f;J0I?W`HudDZ&5H337YmMAVXVJyzX%vXDehr+Cqe3DDCJD#Q|9m)RF|Au#i z1~!p^r%XdWX05fz<>SUt{l9B|;*<99fenu2osOH7MO-}efq7818UI?DP%m($M`?=K zP)S=%x|x{HQne|nPrshcluRf;D+ArVW+Ay(l}L2chL71SBdM(u-I)$KOAz_-Urt#S z$zm0+U(#FG)x9-?CnUST^a7Rp{>s62_sDRBh?WD)@7~^9-Yfp|vu6$QTX{j={GaYva_Gr8_1VT6mY|ax4V63%0;Y2`850~ zrz)0~St9&WQPq*3(Xj=EIjm&e;cb5YoZy|Kqnp_#TJ>rQ9&Y)bonQ_Rw~V~nQ=A$Csn;2SdFCJk74mPwfMq2;&0w?RXq zaCrfxcPAQA^5K(z$|1GAHaPVIvXn~07A_x)-q4K0h`Z}Ynf-5e@I23jO`J@L=>WPN zZKI-{8}rgyX1gl$)OMSQg&e2~NCdc}mTAYa}yNpoC`kTh6a=h=2Snx>GQb?9%nP>hlAqrQ%FoNvv2t@*Tw zcW=L|z|U`uXCU?FJvCK>`}({(sB^B(OQbMQvJt(tR7DSd3A{Z`MRqLkuAnY+y4!^K z@P3NMy}zP$0K!7jJ2iKp^=loLRD9rVHZyzf?#qhe9%J@>)+%F%*`}z z)(3A-b|Nt@+wLgcH?#Xh+8!i-a(MpoG7uMbT8ivZq3gpins3e1$sQHer>t!}zFqB` z7!>st21)xteGgXZNCk@MdUOKs$P>|RSvH={F-aX0=-9GCtkhSYz-ube$WiZp*h+}d zgdX)iRoBho?L<1pO^(=;)f>tA_O=Q7tN(Oc(QSRwOWdnJhMx4%9U34?*0EUgv+Ut& zKH=bo*wlBq=&7yy$w^*3ls?EVL38O{sV6pkK~IoE9X@m>2iWJ1hSTAs2?`F&zJbU- zmx+kTvi2BVh#E%EyAL!)?qeJ1m>FC~dtVb*kg0!iXpDuPDt1vkE^cNx2)zJDbwzCA{Bi_sgEwk2M?sh!kHoVkR+e!5h zdvNKB$s3Pk(XfMB3;hDxn>=u#ql*5^JiwI3u%^na(tTRe6zKXX=;BLYW;ls@H%*nX z(spETveO2Cl&W=aoLGOR1=+oVXM#muRzA%=`#A!IbPEO@p?+s|wdi4G65P&!KYkug z%5ZP72@6U-;QoBdf##g4IMmAUi^HCFs;FAx!HQg z&Au6GVOEW&K=CYnA6$K_{A`mV9c=7RSaxop3$-7=2gbhqM|#+MwZ86Ah7zkcl@fQJ#qmSe_8S{SjG z7y=`VpkBiIl$Z-C@xez?p9|0s4rKdqUj6*^yKndnv#cgR zFt2lfN0pM>vKpY^oLF`B-?>FL!5TwQj$5hALZ~$Q-1B+?9=i$J**$W{Kv$)^YnnN? zzoqEz_C|_Am~d&_&tQ-TU5G#5%<;UtKy}(5dN~O3+dcbJLXq~;8_Um5lLlQMN$jN1 z3_?0deD>}b3Me=gVi7JzHkz-4AwRTc&SlIZHI=e&H#u8lU`mNQ^`Mj{$K}`R9CT#Y z9@~=bMUVvVvRVWg}CA%2L5LZb8K{b zI_rC6=LVM5nQjh_sf2-SO0CMtA)G`3F*r~I!f+-xN5F&e_L?k^+y@&?r6=^2w2$zm85ze~T#k!x5>-Kl5hRx)jN&ZbEEa@`D;e0|%gW;Re zIrgfo5}))`GSAKa%%&hU8PpGssAS7z#s^0HCF%OVnaLc zCQDXi)l0aQ*kQxEH|Sx;bha{EmtiQMC-*%wS0N*^*BQwXo^<^gQl`_R&#l*&yYt;~ zqd10nkc!z+G~6afT&)gP%?^Ei!&f1TTfF&r7Z48fPuiP+@0%^|9JnC>Lx$hTG8rRf1`x4ibdb>7_QlvH_npj zJHVf=(oWGM!TPFCjal)f_$j72mA+eC(F5lBzcy1}Jkz3z*Y}R)S1gtk%;aHsEzF~F zV=%(C(!|7Co|ZOJw^+f_YU2|8bkrH~tV>kZLy&-shBg7xv^Gr1{Lmj9{{rv}wfc+l z@&3OXF0{r$|FHvV(>>lf0q3^JuwOGDw%k2huG}l} zB2RJs7TQ#9d%s**4`oeZGBMO2oSIlYGXCBEtX#WUm2wvql{4}rcFWtv;V_#nPF#rh zM+Z?7vZvrI>~kHUceT(|Vo_B;t`fy>JcwFAF*Vs-VTpn$nXC#bsGl};FLF8Lq+L?- z$LFv!9dMTPd%VRKSKdx&G}mL=W5SA5M-x;`;R6;^FP?Xwa-z^q#~8P#PnAN5?_v}S zDC_(y0&Pz@C5+8FU2PE8Zp^#Zv)?x}0k3+{kqngem(n;RNp{fKZ9^P)IWEuO+Gy<( zcHiNSTs1WDeM}lxSIeOob(ERP9<;%AG%Hn=lJ(nookmK-JqPJ`I6gla3N*x$bAt$QRr-^YrqQpe(qqMy%V5n$u#%fdPX^`eG z1aB%<1LER_*5Y|ld(o9Kr4>mj$F-8C$ZhJ0`Y3N-9HP69|DWBl+wIxE<}K3;WUN!* z+(bb_Xf@zXVcD%h+c;Mk^BJ2VO2aK`{8>p@CNF+!W79u6%_N0PvA(w1hSRqL2MNRz zEwLg_TTChvNwXPsi@uHPo;o~ts_$yQHh6M`1hAqZ?!{X=_h_7qb#?KDn(HlcS)LwE zR^t#}3e$raDB#UErZDlEo|82D>WQ2QZ4n8tx(0qu))ERTys17bMPH5DjKrOUii z7bW<4ohzG-nGD(f(~g`vo5B23((jD53Fi7%d(zH?bjFC4N zx@?Duk$fIGH7t#w4~qeGwtLbNXN1d8CX93RlT0;~(~^e=nBE2#8VJO*%#|&H?1j$R z>h=rRP2F5%*$6da8y$q>(FB_dzH3c`v3%9i%p9?%AKIsAhD~CaERZ`X)R>e6XD8i9 zgW`I0U-j?w4&3K(8e?QT4MIm`{F2d9q%bjpHI3B?zEwU-M8i0!t=RKve5r#v8TDbX zxw-@!Ef$R{1X>#6>kU7MKBl|mWdr=u>9;H)LZx3EV3m#oA$qF=+#mHnG(~fmR}!dHrF>ZyxKJF-=Vm!7nKn`gh^p(=#?fd zs#KMi_$0t!^c668eanA$9hLey)7`mwKlIBj&vO--60o)IW5HJ+&hw)ZGPSP3La+Yn z2atHE=YE4HWL_|3#Pv4vb<2|6`JObE2=>KHj>-Y z&hMg;1+mmc8DM!^K)QE57b5%P=g)HJ23vI{{=~4N$)H4+>ITt|ca7U=9b@#DtNtEk zWZQkxF65wXWUoy5J0IEX@YlVe#6CspIkTyxz3Fl2*6x4LuV@T1KyYv{8s~a*bK~wJ z;~3uSPq0q<7TsO4^FBxjx11Oa<%}fNlYJL$&5`1rK**OK1Qz`JhWXk$n~MbKc-kVy z6pyBT&un+1`i{c5p!3Vl_5=%v`K*V#7CdsuyE5&iJqg>{;WOzE8by>BE2`&}q+Q#e z53NJNf{HlvqO+@g^`>=HfWi1K)E@jjwHp6Z&*;lo_+Z=bBDgy65O6(#?rKHRySrZr z=0)ewdsEl+T~{Nqlg8*zc4mEa=}$R#tXg9OE#q|OdF@%}K{(hF;IS$|vA;BAW^8!7 z#y9tw(4Inti#=!e{G|fZpTprT{LX%^A%9ZxG5)0h=q2CkC$?gJKZ?OA^<`l?$kC}; zEb(cmgua3J_oR1xFBNI*jzYW9_6AcXGa@Du^v*MO5ApN>u045ZNOo&k7ad+&-NP?C zXbsfiQM>z6him$*GE{7{4VmC6PMPUnB)XLf*=qV!5!ciaJVBmhCEH6sNKX zSZ%S)?L7+=dW$3_&@9v}e#(8ILoEF0dz`EPaPD?%;1%jGP(sT%2;QS{-wH;7QzW|9<-ww0HOx1f!;H<8FTlBX{oRZ{(1 zQex`?^VQvmCo{5H(8%)Vj(_2lYMCDT8?-z#{F0dfw1EFT2JUIB6cJ+dqNS06HoDZx zm_Pk{&F_zlJk(QAuD;v`ldsYY>LDzOK0;Yw=k8^|Mb#%!(*}uJ;3!o{EILe+9X8NL zDBc@l(AcMt?UGkv-PfPeOxUTd*8YO?Rs1@~{Swdf24ia0F^=CVn}?6JPR0MGlY>;K zfTB^KpjIQBIOq`4|CZ^z)zD}h9!GyT4_yxdz=P1B@<99QR_eh{h%A^D1PCoUdKWwv z8{2q9BTfS(sCP#D)%vydv?lAizTpuaQm$AsGNX04i8<*w})k$f0tVJzWMN+zs%rS3QPE2qc08uWVXMC z&>hY?!VRjAlnhDw&&6(K`=Y^HN5zCRTT;Z``TXFps)RJAJ!-QahhxEYtDpEE@(dbj ziVYO$_l2)d;v=p4266W7C$;u0OkqRLT@626RK@Yd9B#i!6Zfj_Yzc^M;)q#HQdrbb zSk#KOehspqtv~k$XVdR_-(T@UlaX4N=L|gKR5noLP3kC6^)bfH8vJh8Eq*BgA#i3w6kYMG&R&! zaL(!iEN;6yE(_pg-~J*wezhN(3s|va_oZTgnjPQ(dYbaGiiiIau~aZl?CYyP#&%1p z7N0QGn&gS;?J);%3Ag{i94=GbJY24qkwg~;uQr+C#|vTePWLoco4s5AGL8Q8{tHK7 z@VsI;1{mEwvnX`)Mz8sQTNWvE^OrPaYrA8;T4R0mf6>|uo4)@BZT&FXyY@e+T!;cg z$fFB_N3@OBZoLP)*{`&w7!th@rI@aqc9Kwo*yA(aqR6u)n`daMs?3t7V2M=JWI6hy zDxxsL`>1cK{B*eP&``B1kkpr81{d;>;$Gv~wQb)^V+_st^m`DSap`&xNOTzq;L zmI@dN{%S)*!;Q%?R@w3SnLXHp0&@KEpxV}yMb8!#Ly#_0j0FQIqQyo9Iss20OzFw1 zau7*C9PwlzF0vkGkGg#Wlml@PBmT14t7P8`qk0FeK%QX{LY0`igo=#pJA{u)0sAxG zsxEZ#NJ*S>PqlG5YgrN?fsf#SUwxn1HrMx8V#fWX!qQ{pH~$wPpv|Ug`4rJYV0dXO zw0fOj?{ZBgT)N!dr5o{2D=*dLmUavO(z?*b?1uvI^O>XQCk@TB%_Z46 z21`Ae24!^J%U}>j{4ZEmc&MuN8l^Z50f*b?-FMbYU#1I=PD%AiR(7k!m=jm5XN>CNR55iH00cCGN~01=aMID4!m;Gd2mCcr&LGW*>PC^vmyX zK}F3!Ad!W`XOmD%RjfUK)aF((?z9U}il3<|`8-)TVF34r17?O#uYfP!4wgciMe8yJ z=}P>8*(V_ziGA=&vG1e#FHvo7i{I%mpFQh>=eYi!2vj5u%sHpjvH6 z&y>VZq=(6vxK`%y>g#VM^%WQWiz5_X88^BrEr_TAMp5I-1y0Dknyk8n-p@@B=)+Hh z%@0$$F0#D;6$$94MU;*S8L_}#E9uDmLE|EipnaGTN%{mp&^Pz2jh+zWN#Z{r54u(p zpKRZjdl;Pd`mYw`{sve*aq2;3p6_u6gJ%OlpT6|)Co}NQ)?~SqbG~d?0r_x$sx;g` zep%GYPa5W2wQ&hCy;!0)w}<4%GlQ30Vm@g`Fg(m`^az=4$7k^{A&NuggOpTVlI}iZ zC`{ITq4wHV%?^`J-jx5d_u|mA4ABr+U3G6>KmG-DcU4ET{x!Au*^9+{%j zmtd!W&XavEC@CQtRUNf)w3S0|U}R)uYMFBr$1+kXE1+}Ta=*vJ&5Re>M<)?#!+Zwj z_5Mf!Xx3EaBwv{j_D5z4Ww}j@tnA@04gaJ@%1hQ()_j>yOk^o%pK9X4ENp*!sUM%^ zJD8IgLnlWu%)jHQAc3D(EYs6fn5#JNt*wpKkdtH22@dl+IiU{XdGmnS=w-WH!u)s8 z{=aTQc06zXH~JF=?w!BdOoUp>L*E6$Fw>RC{+f0NysD=1dNvD9{0ah~lU*aQdD}@~ zun{kkBQVQ#Xy4DpK07YZi1QT~`N{UyaK5d&F!WG_LuKC+COY%bKn-ae6z5?2@fM`K z!&edMbht#TToR%e$Xf2f@tK1GJUi-aZcW2+p*1RL@72Xw_Go50sdH+;){1ZaP9&WS zN3$zJHgC*RJ3*H^(wllvR+{;TN^VJlg)yUkM#jX_WXSfmm7uUN{SPJjgow9K$YXm5 ziPo84=PGEO#_n9|*&UP!8x7EFEmV%x{>Chxh1tmK*OaI%zQ$2HLHc*s(Dg>@sB`vg z&68qHse2l#1U9)9pI0?kGUMYTD9R;Y;xtJCoWg>94%Ii}NT_b(H zPpa5XVp@*4B3iC0buMBgq&nbmI5{6QRRsy zmJ;w;C%Q1?rSmJ1D=)7<7e{j!V+h7g!`XG;h(XroM+T zNV^43FF856Cn@4Iz>twj;8zqN!QBDL-$rZ1W<4DQWfR!VderK>+(oPm&oQ?&JmxujYcv z<+I?kp!Pk>JBkXksUO{0+}VDEnwp00#3o-D0m3-lpXJoy#l`pi60KdK{!_;bib^IdG_kZj`U z@x|j2zyH1yt#;QRHyOq;8af`5Z-6r_oosoDgr3{m)te9LziKek#A(j_|09gXH(5Ediu7nUK)TVj z=pUvGm^VIySuKMYj)EUAN$U+7718}%TWqPW6#IRoMr)acvx&;Ae_gsqPPLB0OXl5! z#822wcDz4bvJ`|iIJd72h|gmrGK-Q8O!24XRbvGp++`mveGKS9cDb|f(hhZZFI-wB z9CIezVc30Mw+RlvfkN!o_oeq`%R%4}@oaIhkV=4R*0P6)XQ9BlJ8VrUZ4?+Qw)gsaB>h(o`fuZ!m+LeS__R_6I9zkeetm~;k^5M=a@w{8FPBwsbw^<(Y5IjhP+xcrFE`p(^Zt{O7!wq1dfn>`)`wD&D2)6 z9J*T>c<_OF;&Np=`d?g_(%T9DYgmK5sG`Kp%;a;%$bR?s#{v<1YP;dj-7$?9bcjU9 z9_xp-Oa6%qSdMR2VJ@%a8GRZ8tskE@#%22Ja09s8hQ1ZE{ooqIWbAVgSKH8=?{#_Ky=&K}i4F0!$3HVb^$8<>KfMf%Q!|rdOZ@x&FXsm34-pgwm|Vd!hgQ^LVZ(`#}pg zI?_pX8_KVj!me)jnbfPT0d(~4vr5KI71FWAZVH|0*sH@l1XW*{(EP0sFl*?{s6C7s zALFW>j)SY#EP2AxHauZ0fK}F>m=MY*u&hdqn;eFPsof zzB;gB6=Nl~5@R~h#mY7xY?}p(T$JMz|K*2&*_QHY$g)GkFCs3(51%G_3n#mjkB&Qk z+!6j8-JZ`S_A2Y4DsDt(*n(FTe?m~{dB#7E@lRACgu;@CKN`veRe%yAjc*v7hEura zAx=4VntvB|^x0nHo)k5?%y@{vXDY!$phi2MjNekPwoT8J?A=Q%DGX1Ub}vMSD_yCE*r_B|qI&J7RN*E?p=Hl*O}n)?1d z&}{pe4oRZdwH&KwlIH`$L(ycpKE|?L?fehl(!|T&C;s4%DQ@v zRr+tPFH0Zy3&mg`olwtYPzlq&pJzXVtSz>zAlL1;ZF>16&vN^yUH+9})RK}T<{qy& zge0f*@MThZ59=@^A$xbL55UUL;`_XGpBt$^F(#ZU2l_8l$I9D5^~~JXP$3y--xd?J z1tzix_MwN6iw2tZ`CJ_LI5wU_zKmb9wv-zeFKuKIq<<|TKE#^ng@ z7Ci{2K2;rvVZ#7JwPR@@gm=b<$`0O+Y%ZP0okAwve+pE*wH6Rbd!p#E#{}riqnif0 zxV&Z1Y_Lu2^l`7Z+{W_@?wJ^%jcB%eHvRXE+X12<;=})7W->Js1pw0G33z0{!s|`W zyoyTBpVhA@6uXGqW3GP}JC0*AWTO1cACF1n^h1?72~7|9RZU-Dy|a7m!xd{|WA|Rh zoOmz{GjTAj$NHV!T*5dmJtc`i7p{o(3jrYCms@U!0V!htOBG4wKK{ zeE17R-=Gu@0I5`6Z_n8$94iwOxiCUI$H<>g(F=6zP4+zU$fYC{GXAIo>5f|wa1E{t z8J(4;t+Rn|<7z2$z2QuH_i2FPn0iR}yZ6V;cqB8o(B0|B`tQLb&V6TCmK)EX4j{;( z1B zz-4<*=l!{)(3bb=7r^e0O>(GHcNSSwaHl`!9R=FIoYT7 z(L5GDl`#X`(yN^R@D{R0u3aQ>qn_HK^YHsLxq6B<9&H>4W@{G#(0TV_<6VMo}6HT#xoCxg<2rvq#@`jg_pH#Xs;`MB9IZ9`vp z=}F&QJL#NZ1HNhr=|S76{*pHwf4;p{Uh2i(%v3inPEp|3<6H`-77LoA$5WkOb-GnV zeopVcg7DTjAOUnacf)`_9k4qg!NX=W>e3nzOmN>Bj*RUuZtu6{*&rAOg6y+;bpW?> zsH^s~V`S>1E63!9+qpcTPXzF2dxs!+kb2l}f55CAs}u8BO+E2zzimd*0h_Q=q_YWR zWMsUL{Z^v`QQ?8k{$F9BX8d*}ReP@WQ*Me=>9>|e>p(a5m8;uF9;uVKVdoQZul1$# zS5{U6r>-1p=Wwqz+?*TChifeK8k#R2;O3zJ1n@Zb*z48qhSm14rM`g$eeOIne3{40 z8!6s~eCEG#2JGv6s5_T^UX&g1Djt9$@rT2_ejOhOc%LBqk*$FbuO6=b2+U7L=y!|M zH!{7blcgB+`UNPgkZU@Cyi@DPv%qx$;4KlY-zJd?eN2@TrMkp9Q??|ST7B7#2XsAT zjl6bxz+{~4lu+@wIftW8t))UMS3Ssm+D@`qeE)m#gtDIaRY)dT)ssHg#yvu}Rf;l5 zfw#D|&t}4aY@7*}k>&dHRnVVa4p2mCsP3Ojv2TdD^t&kmF-dqu%DjI(K)87OjL1`2 z07CdUs2=zQvdJB$6~HG$w$)^VU@#&*dD3pTF*BLsR@tyLBqY=u>9FxP@TYUXw7Hbc zJvo%?vS_iL6R$KPN%O}D^Y^mGsm3$s+e%WqA87M%myu2vjTL-R6gM(fd86oES@!hs zYRVz0X3-gZ5j9(|vKH_&Y8UEhfr5o=&^czBbfT0(qjoC!c?k z5BzexmojYPi?XH-q@F6l_g=81+BCK4OX0F7WFn!AF@ZPG*hG=?z7vg1sFimfZalc{O(SA+RF{Jm)}@PT)^} z#`62B{qY{P$qI-RKW-s8PC184oZ&5^;U!Szpf;Y(-Xgje@9Rn^*nMIyXc@C$&rt9z zQRj;v5!8N!1UVG)GMZGgp!pasn20&N$zx}!0oMSA)&hhBJ107xQ_m-M1w#Ul76P3mZg!j@4ui@& zD+}=4z4@kenq>X_VFA`&fp~09&KB{Qr4|gOC(;Inx z#wwHi0dfNIvgsx>tdgJC7}C5j5_?b3fo9rO>W8HbazTkI9h7RHG~^L$(kb(m%Hxf zz0uiyQty$Q%Y3=G_@GG02>^CJwlpS`(w%-Xap$Z}J z*KIGUlN*!G#(B=5@r8#};}bs536^jF`50cvn>nmN(dv!hSP8MO^mz&b;h1_heC2X4EfFYYTSA_obWDGQNr&WGmJIP)C9-I9vFR*2{D=Kqjfmg z{b+wo>JG7T-Y#J>M()`=?|zy4C5~paOa-$wl=c76X~z>6_GEYqoXqetjN-UD>RM55 zc+&(D;cj&RT!MD`&ezy*{7IC3xR&j;W<5b2V_f3ZkRojJA_DkHHBnuile7VUL77feqo9O#QnBYTFb)+p{+yq8y}qDS)?q z_8?5@nv8IR%%`JJuG4U);7pq|T*&{!)LTZi6>VL^6`;k7l;9M1cP|=R+})wLyB7)W z6nA%bFYXe&XmNtO2fp;)`;70+I6u#i?7h!gd)b`Rk2kT+vIi3|Uzdh_qqVE4Y1w*n zC|_&HVHGBOhU4bRJt9U{k|aFv_~*RvyWkR^YM<@~XlsehazGPl^``MbZQo*zqp}2t z@M%OJ0?g7c9>R^Y-cEH@3|Xq*$x0Cb#>9sX#6?o8q|(L7kkZEI4STYGJL$ll0<&*A zgaJv_jjx=rJd(zpBHCq(UW8P)X4oOt1badJ_FMR@!EG7$X_9yX)EQIlSL4!hR9y+h zQFf!e-TFuQWpV(-MAm<~OisMk z=^h$ZsV(j^rEepPZHWn$;Df<`{B4-M*w?-P@Rf?q3%~iF zUr&Bh0vb9g^0MPdRy$wN#MI^RXcetw-$+7U_mv)Zg9NT!!X^Z?k&bcxIz{kAoPyrP zmvl5X<#D#2M@ItK?>l3ygjuh%YaTOWBb;?Blq0hr$L?%y+&J!4#A1rzN(Zx2p4%$* zTT`>WKQkbA^R$72cX-{9vr{k?K}@t`%vODMDO*IjE8js3_7PBDt0R5eA^4vVt3(M+ znzM%)rNhEvzebiW{_#A%=+AB`jqQEqBiWX<7mS7~M0)bpT}{?*t@EzUD~w#@qeceX z6T7UFA7En)p1Up3O5JRX1?4PcI&+2R4qdLV@r(>sRiT#0kffE5oOh8H&Fh2YtWH^a zbDz9x-B%^nFIGG53E#;NfXC~VBql*tECpPB|(B&V-;pv%Hr(KS|LT2A%DD_8|gaYIb? zwvOWhdE%^wqL{l8l6C4x7WLiWd!Zrc#|NK+5sIg~Y|xqb?Rn8E&eYhdRiupR2!{g=2nA$NHbvqIBfzgKUmT!y;U3ENee2-V^0hx$G*Agdk%q*B>3b#p^$_Une#O7l2*C)x^XJ z07E%qV!T}?wN|<=x!ykGmRI)dA?lYqpo5t);-X%yBz&r76c&;x3-3bAi<1R*F&b&| z1UWN=k{XeblsSIVr1oOBJGil4D7BuPr#FHP?V_M%z<)7Jnf+`*+iqUkC<(QzI^5$v zec^AJRdwI47dI)H??Awu=CbZ^Vr=S&f!eq@8!adLmwC+I&5+X`s60x}7ds6-oIr&S zO~>eeo2q?LH(mytSrxt;IN2dP&P)cZQ}mhf#Z)+@qKu92%f`f`RP>Mix+jJ`}>nc3Wx`<#h=V`D}2_+}mB}dRVu@g?rU(8fXmA_rB z&ZY4$Ij0#sCf@190OJN)82ZH{SK>Xd)n}seE_56+?ZZjm=&mav0LtjL7T#sH z3zDVq_4H!$qhxKqz$+Cm4b^N=mlhlcs73Ma1RGc3teP^YL`P{eaxtFRYWOv4*ss~m zE{uk3QJt;6VCV7qGCG7T)~o01WnKAOtSX^Lj0`31PaX-hk1J=fT4ZA_kNDvt_D+qx z{ZDH)T}X&aZo`NZxPsCHHkE z^`94`Q72k!nGqQLhs?xQ{4hTKBmIM=r`^gi0|u~a3`X*Q|!1wd8 zI8C9$?X~7O&JLyaxN*msCZYEp$K}hHnQbxL%<*r{`_r$-h5}wcK0(GAf)Nnn67TbxG5Y$NP(5DkwbDZxVV=+>iLzgC?x_Yh3$0tykNKZ6;VboGS-{ zPtw7wU1;hj@ysnTLJ>uk+<(!6FV!+m z5bd!6`uMNPPSl+Ks7F~*hzHIQSlp!0(ps6$2>pWlEibe6vZ?1dFdu%_MQRf-Sed)x@!6m*z5i zrC{_?;fAHgG11g3TmS7wF~C1x3J3~TzH(@z-LEBPckA5Gi3(*ep0(o4IcuPGJzW6j zSMS30uC1*U`QuV2w%4nPMSf5fQ*CQ{98R*k-?tCNWlb7Evs%qY=f|e<)ZCTL-o^O7 z1|{8G>zdUbwKaxvr=00i+`d5iguynQtMFHoF*-2$a*dMly(+j#V&ZwHU9^oA>fM2< zh@lAb(}z*^v>~J4xAHNjpTayegOVmTON}`XF4!N{6{9s&d z+pTN1qztW_li4-5TDJ7aH|%R~hYot;q*RLaZwvF*pCwF*vt>Tnf;hqM zT|~`8NzO)&mT;={G58|Sm)Jw=N7WLRf4`jiZgF^%)(v-XDl1uL1ng|fe3w(2h{4zN ze&bCe#iI{-D`!h&jSh$uMSJ;gbDT9{@^9wKMDo6Hi#Oy0;ObV*R+y4k2g+8I4iG#3 zQ$H@2g$%uq*m(GS-El^6|DZdiUs+w8<%x8(P+2bhW72=zWzty4t*QB5;9-|QC0AkQ zwMB!!c@<~JX4nk1P~Z~YSIWNK2E0T5;!T0%A>_B`K?SzWQuMfZ3dc`=_^=Z;`t8m3 z{f=gnmItQtYn_h1AwH0#gJ`4M>JxXz(aF+0X8(nkU*v}@xxdBhE{W?bvQb~r*yo4E z$h=>WTRUuD|Ho;Ugyh>yh>QDsFp7XEyD+!9T3*I z)`Xky&hph{2)Rc;fl@2yJf;%F!Xnu!f^L?ja=`lm0dm2~mU9k5~u z0b-sdzudQ_X?p_b626eaYKS+1j%#Z+WZ$HwWA>*Q5d;#V&1NxN+wD{ihfk`4P@7L` zUTj;oTl%aX63lmYap1;`HMifhw?RF+x;$!)-B&AnXg8qOV>*A}p_d0=Ik)!$u@a>( zd8aaD2P=rq9OW8H`UZ}fj?CVK~~(W^*L*sFGa(=qh}-Y4lF={9Jv*tifJ zG^YrxIh4)LN!xAD(~H(Av}PFo{aedYpF8;@aj z158$YRo%zVYRgvsKk8PsOv{D+c6bZd7UHJ-5!J=EYk1OQDkI`m8BTW zN77G~^n!miR?eB}2JK=%@>| z3QH7l-1!KL47gT(pH5)S48Mw7ud`0|Zvy<&oTPzfc4mkn3}L|gPbhew6*18$F6OvD zVRzGzZDKxVdms%xyv2_hNoEw=Qr%K;`Q_E|?Z>q8WrE`YAl9Ck_}gcdn0_zAyh}E1 zgy$&tUH!LUtZ+9;z3U*e{{2&u9VP&9E z3av$o#?uOJL^e!=CX_bFlq(Ys41KjfTWcL3IBqu;mG~%8ux|OirBa_0=2c5}r=*$O zd*C_GG>DHTB7jT!$IZ!PVZfB#dR@`6yQWK{@%uz|O`X50zFKYcG{lsWi7)B8Gva-FMMEl%WZieqO3A(U1-7`8M1uKXwm9H%B zEuk$^_#XW*L4ZA|{KNA(DPdS%O1ebV{j*oa1B`}o+`!RMsZr;_(OX0e24TIr9Ok9S zvAi0QZjt%&zrr_tC?H%?Ptf}X{Y)i38g4P&cmL-$KOh1e1j7MwvI-cw>e62GI&`T< z2B-xRB}^WHN*G0E_z`= z#@gI)g8kLlNBrLFo5#qP`J0-HHH+iN`Ym96d~}JNSdH2)_Gtl6i}dh-cy#ezP?xcA9J z^)K7}{_*NG^>Cy8{DjA)bb|0gbHG(LujrMD5PqX;2CqFV-SP7`AWC|KdQ$>U8*9>z z;M4DvMr-;-8OM{+`&Ks_n48X$l)4jpl|~yJlKBBL`aEd8)IJQp<4G^0Al~^}u*~!0 zuIgfGo9)fv_gBXhTsbb38Xavs{Nx~A)wMaus4*I@MzjX$=SCS+Z6eH=hjibns_D_Z zih-7Q|G+_j=m@DDjEn~6ANKwV)hGWq?)&JTi{;_>M6fZdZQ?<^!Y|~F%B82&`Zt1N zeeq?>SHO2=gff$Uzo+lJv2%w|9Ppr5TSiFaw0L+5ROk82B+6EFkI90*b}c4b^L}CU zqSp{`j%?TnxCguk)OFbxXEJ9WvfMp6((bm;G6o@AEPgj^JT%zXHGTZXOL1wQulnvf z)yOaI+pPW7b7^O9I4_mrWCfwbm_u`}QV!hgDOoF_aze`%9@&({!8eUo-|>}^?EN2> z0(^8MQ^1i$(S7w*2 z7LgVeGT(Fa2%0PLg{gIZFUeTVDC-#bYx(j59nu6i+Adi9(~7ai!kmO~C*P3&AYgmoSFjLIJeD*HX-Y96v?%D8EwzCw08Q~V z(9NWW-{%7h1DR%mr6B`@+8<%-dHBhDQ>?pI zlx`brGgA_6Yt`B|8Pa-u8nf9~8q<_jiK#CoKvZV0+RA@HN|wwbz?YwSNbDi!HF;Dv zX6<%#zO8kjK`h?!aHjJ@G(UeNP|6drE&^yMiG_Y74wc3-IfKZuCQ|A+-w2vJc{5v}z8O>4NM znSZtI&Hy#YiaD_!Aq?g(nJu;HAJo{m-37L1A{(;$G^g;uZ8LIJfugz0g-K_F zpn}Q}Pp5HRH5bC8ru9MDIF3m?kDv)r$#rq2kqp;oa|OFe+XhavNwB(cvLf%k+~Wq( z-{6GFmp&w7!6lV3msu?RZaTBVKAEJ`pMekJRad4t^6*d^!rQvlx* z+6qqd+S;wwmR$WO>n`L0Q+JmacL>sEppp}88Ea9{{MeLDW6M&C;o<8o zLEaX2-!x(eMxuTg;ZDZ6sai%iZhDRrym@k@;c!W8b&H)438>7|ThCqwevo%YdNInMmCK5oJQ-vfY(vitw;eJ1D?f{px z&u%quNVIlw#3de(-e>m@-I0-M^6uQ*2gg|3T26_%pZtPjtQeIr`RD*!<=YI7U8kpy z)ZWoWS@&Q~D#}WgNjHw29D=5dhzQW&iBYd^@^@jpIRWx17~GTrkzQ)&g3{;qSTpn2 z|8E5v495Za#l;_b3=~eJLH~dZH7rF%hx)FHQS*;NuijeL`V8lpD%ER^>*`}5pCLxd zsewV$j@`NW%ql*p(v|VE7PMu~`_Qn~$;q}M907-OW2gEtuEy9mc=$@15K|u|spd+G zmD^gIE?YhLx%~awf~ANTWfg?EIh!%Uc6ng#q?>E?B0GV4JG3ObvN~+)HdQEJpu1+N zwnKv@Ev`t8;?kX|<~AE8{&vqXtYdV?>jgC+M719Y(*tfFqwzB7a^uUt3#CQlej4>P zICJslFA+)W=!M72Ryv6f+@0SIuJ2wq;cv?7Qx|VRcMV>F$IgWNQ4-;UmY=V#PxAat zNY)wY8}-PGuQRSgZo56qEf?<30io~z1FbeZ_j+_fwd?c{vh1v9f|Dk_PSWDqW^V49 zx9U%{y&DiUMXP_Ybp-nce|vp$uZ3GndPB}&@dMUzS<6$)uGz5c&sR@%E>8sXuvK(Sdh>t5ZAkoNs9>iyk;Z`MPu3lEe- z@m2qR1;zQ@r@zUig|U!$@32oQ21&Y}MV>g<)2AEsyKoI<8N+c&=T& zqQrd}sac;cCx-w#$VAZ24syOn!6Syvl^JiKg$p%QxzL5``sCWCZ}v-Epl`lcK4F{a zVzu2#(6Sn}*rwZi0s^rpuOY_BmTaEKRH-hJp}L2-hd zgRk0mINVVDT8we`?vXvrj=gj9J0LhCsaww23&|O_8;@4IcT} zYNHyaFH0}M#PUq=7BPNlCn@ZrkJ>Gh3%mFp1@9&^`2q9u^B>{f)yc=B5^xPKyQ|Dk z8PyKEH^^G=PVs+@9&upaz;mq&4*iyx1 z;o`*hJOx{s#ZMDVf>Z*FsyFdHP_Tl6ItKifeFu+@jH=??NJW_=RPrtV)R{WsKU_)) z34jzg_;>n9?j{16M>q=EX84!Un9;S0Vjiy@ve)19(e)uCdM@UEM+Q7PTys2ff@d=r zOftLoy<+mwnPf0A@vN#~R4Zh|t!px2ifrnV_PESsJ0)pN5LfqT{EGn5;oQF4a zDyVNA7;&TM4#U51)(w7HuIP=QCaK@okEUnJj@g864AKOJBX55k=_MSe|7IOwjq?A?Z+88(35cYVISgMWdq{I$OzIXze8z^R`$KH0< z#2W0|^A!BC=CWvD?EDZry%<;W?Hx&{K?cM$)sP8}?`msZF{7&EJR8~J>xP-zo$Ly{ zReWX_7g1$IgK};)zjB8Z+4j*`8^j|rgZk)W_$)?oxE~eY@|ix`M4Db4%z_XhWz~{ilIxPhsF3VX~#h!2u`Zb((g6=_7D9T@z%tp{O&e-K{t>j2AaY zd?&-nN8`8YJO{uZ;8ktW3#5DIAp>81g`y4?@|ixLLnVuR%9iCeccm3JY~q573x^hY zl{F7CnCyb|v?ZyZbq+X9$Z{R|nu?qH0M4BY#F@f$BtCwd`5igrKWh#?)+)3) zuWnjM?nUsZlH|rMicvHWIrO)L-#P@cc@8sP7BpsJqy$YhlV7;t}itjNyc1G*j#&u&9m&GlD8>hjX zSY6%9iK_ArrE|mN7`Bj^LURiX2soM6Q+RlEw6{XDUX&ETr9)nA+@?exvoXQD=}Zu?)Y4P@YNuEeyzs?d!RD=e_Se>eUP@ z(6rT6=>P5uK_6;y*f#O=0LBm}z9ZJ8a8_cxrRk^c7pdg`DZg+MD9lMzo27KjYzHc@ zMUiNvW5Y@?V7pgPR0usp0AP2c3sJtI%=vv}DJo(J&jyqkSn`J`K=tAdL0*b1;}35- zX-+jY$@B|`4?tmhbq9r!aBq?FlcgT=@IBuyl9bLp?@DpBSePkeFrwoQ*OtP!`;L()g)-=87{PT576R~tHC*s6+) zyF(9|uQ#7O&hA!r+Ga5{sZ=K0awHG-w^jB7q7!>*P(@?JcEv>B*Z`*^n!BplW52Rk z+R8m~5$V!DN_Pcy#8DQK}Qz$khyI4#d6P+G;DYoC(I=I#q9ohke;72j&^AV4l0rx>OsPYNX%xwBZ znPve+#aI{42VF%RHzyF!f@g*GK0kDMRjN&fHouOHU=n1a_q*DF8gt!yL3yfy-^$Nf zF3vU?Xl;7EXCkA`z8fK84`kQw;%0t!H|OVG$w_?!OYC590Yz6Yyu)^HS+rn(n6{AehuBzyaAyXSiSyc#ci`k3 z*v0?W6>d4LP{aU1v z6}HvDO3K0U;rQZr1R-%FUoA8lRg^r%o{Szp%7RF#F!sXK`$!a6sQ$p}-9IEpEYx#< z5YIJ$5EM%*D4 zvx-?%I+Ogf{sSc|HT0YQaI9hYpTIUFK)BnS;ctNul$G`u8llH+-^dOD*&)aC@1k~3Z=FiDFV^X>ZEU~xewBU_a?ZapYcN0A)oH2x?wTUEIJz^nYq0dW$C%WK z`^mvwOx7#4((mY}fE|`lI#};V8ts>>!nDqlhvoC`d@14sYhi9@Yv)MMHX_ZPhvR?N zRezU&=|M&x2d|z+ZI!xrHO~q>Ny8zKG|L2#+`Geop&LwakZ>nw;Y5}IThhAKV&_cqiwO& z`}A>R?v@4W897#yX&=o`hqb)EvS;_2IX^Yg)0oJ%9&hG0dc}5j^nSVeHL990@$TE9 zxwO}E6Rz>o*`F*<3F_yfOxQKU@fekR8Qt;W#{0;$DA`6O;HF?>zUp~BKJ$>9<&rxu zeH7Dqpsj{+irn<1}FJC}fZ3b)|?e7vX9zM*$ zM^Eh^f$=d_xL8?P4;HJlD|{Ss#fH94B&T5IS_N0yG1N5y7_+M-yE8pWQUz`1xXtwO zA%t-_umKrv?^Z8K3uhCe0YR@L&s5i6+-tpyKwBWR3}G>Kq6b>%Vy&XLV;q|#X{>kv zoyi)d=@Qx~EM|npiUWaT>7369Md!Ic0Wzd#wF(UL zXYqC;E}J2{n8zOa9kIX)bYYUsO`=R>s7~+@dA>2(FmIR+aG$v&!=*Sl$BIh8cE{le z5}cg+G9&A7!@{>Ok$!Y>p$s}PG-D%s_I9O?^2Z98z}a}bSie2up9vlID$F-NfMJY? z*o@BSeqn7vB*_rh=;JmU{6yvVRW3?ULWixcWs0)p^{+0h0w=v>F2fe>EMMI%#7$BU z_SaWRMs~Mk$ynd&UTt0sA81itdr31-4RerJOAG4lxO{hZwgaa5R)>T@?!N7G!M^0R zGsGCT*_c3CujJQK1wB9ZZk`fob3ql2yWNZnPFIv(@H&oa8nN8JFo^?}oz5;)TR@wY znCp9H<>Z>_yPHiOg~+R`hc`lpuUy-#{3k=&S-o9c%Qytustb8BhW%bzhDhhHV}h?*Or=^vCICzB`6MT zGSb)lI1-uT;L6*PB8?`dAM7GZuf3A`%z@R6)-`QmX=&*PMs?%*(`L&@R7oD8185~A zmUG4?7LxZq?-#O&(QiM7BPVO7?Cs;LyL>Oprso`A*>@wp!-hdz6aoy+q|FFLiIGL^ zdV}Suaqr#Yg1xS|G&hAB%lue*vwnNI++BBB;2!6?C~P(YSmk`B`?d1C?>}*J9%CT3JTzmOYP~+4s^R(lssA7!Di*{X64H+UOdSOFK-}Qo1$~Uc zY9+K4Hx;=;w1_>?(VfYXh=8tAPstuOr;kpzui)+JT7=C?lVM*l>Qb8veRxC!cwqr29M9j~on8oC zYuOtkP&xF2z;j7u6*l@Sev9|D1WY<{5u_HQ5sU8gp2Ls8l8#^r{1k+!rq~Q4ZiO5 zQ7IH0(WNKXzcqB1XYH4tAxv}~AiWaVPNf|#X!rWukM`GVTPK6jS?4-W?g6@%7gPAT zqB?0ybK%^el7eWIdN(;b(EV1re7AvKyhtR2mS{9YPpwU=VRJWcdU;apDR+BrmWUkg{M2y96BF7@LC30*e=g&Ed)Gvrb5xP<*m5&6l8Y-c3A0!^v;LxpMEgxSz#J@} zS5#9Ah85zCwg;m$8ZAGsdz}e-Uye{aLLtwLovFtS7PC7;US2?tjk+WHc$s$<0k{9j-XTJnzVS0+$&XCh^*^GX5Aj}HWZlT*?hK0J zWMzmd0V`>y+LlfwypCH5tUTdDSkpYUD^V(B-LkA-S!oDPY%0Wdg6mZ z>iyGrW^)adkVyq+Ivvi?IR+@O3%nfVzO3C#~i#K0_15@BX`wh;Vb zaWcm(S(J?UB>Pg_BiCE;C{xhuc33D*Fl&3C{aG+T#;@Dp-`*D)w_SgWB(BKxiDj3O zH*8wowCCv^4`<0t<^@h8f9b4IlEtl)x`?!-a#2?xCk=v&JIBYRh*yXLV3L$@rK85hFeaH`WQ$)+x?;M9Te8p{6+nnHP33vb#p3R;#l4F|nH6ii z6ox`~w7qS3znr)F;3~O#JbHHWNAxMY11I#{>s+SWCHY-jP2r*ec~7)frviYBVjTR} zQROJg@{iB+#n4iRM?DI^>v0M;*!;~W%$*V{UG*T=i+(KmzZV-}kTZP|hw|?y!uEQRq|~Q~38n259aBG6 zoX|UKW+L$L!pt_A=j!bUR!{KRuD7HnrVl{!@-c8+%km~y^ktPIqW)ceu!AJj6_40i z4w20MLI>*pI?L6dznq+fbHZMyNjH!Sa1%uJ>^UycBqRE;8>JUYoAu)OUG~k5Pb}C$ zDXlm#I>EBwU}gIDm#ce%z<)A}X|C&ls-b*3r|EMO-0NOvQ;s(8|Rk>~(+(xD8-%lh{>E1K6&;WH@RSu~N+N6X3ZHGUB`5St7x1H4q{)a}EX1}JM-%CHe_1vv`Z>?(B#H}R zj+wXDf9{qV9vd4Ivp#kJ|9TuDADf&!y&duvw4-2{5hxThBATZv=xVw<+hDdjj^p_@ z1l(GO)ul~IRw>>nc^nL3>&dmT!ZPRa!e9}B=R%x3KOf^1x!ilhaa@!YUHQJ;&% zgV~ZZS(&)ms;|(N*aXS^LkZs#&aV>6vXp58^X^y4Q>2H3)!S)cNN5w65hVPbOxqzF zN~Bw;dv6#g(!Of{-3M%3iydRuvn!8W1uM)zM74C);0MsQG#oZ66~+(jX!-$lAL4se zpVwYUgN7j|K`!lEcOPGK1o8?sWbC*fU)hH}WUY}00?TlOXD}u3;5w!wjf4?Yk7rQw zi$ZODjH-=Zaj@R`vNAU{hC(fU9lLzYEAGCKvg4h%GBbGFQJP(n0S(uVa#al zpInbI&w5DxE&yCfDgJ~5U}8ZAgmmBxQ)WfBmNsuVsn^OWJ|4ZB8=!d1K%+y(Ja-m3 zR|54jVCEvA9IT&x4Ew=hfPknG=lfCQy@bN!ngk$S>L;1hFd0U4PKR<7C%#K^(ap_G z-7OKKZi9RpX4}ts?ddK|EG&l!&c$KyPx9PTmlA}(sgFzi1SQ8V`99MZ@%O+N(x`xp z*w`;oY0#O6JeD$Asf+8A-dPCKqtFx;>c5bK7wftrzl!SMkNldJGyE+1yEKp6KW3(H z`kayeui_xRX)WVe^KE^6JR!52U1Wl0xb&oj-SqvjkuWW-8n$=c=dgO)-{YIK3c5EX zE+1Izzv7fNR}8M_DOqcF!X2Th^jIv`z<5sYP2?%#>z~MbECOd#0%F#Eh{l?*dy|$) zIBnjVP~h5|?;;V}nD-XNY=~(;e=_OU1a1HL`RAZ-Q zWgtZoKoNnwqE;nQ*%Nk%`Z|#B=kXq-${0F^`{oY(c}Yl2 z<%WMsgKub4xQ(z**g}a0p~eg5%k{ApP01~(&-9y;&+X@vD`$plP0+78Ty*%IWZ7u0 zR8K#3rAPld(Wkf@FZzn7ve#ceh}G~-;5wPA(NIWj7HJW#%>PtOHYGFtI&}>ja(S-s zf=GqjSwgZ9uq&$L8r$oDE|nXd$cg0ImZlRE;AAs0uHE~OE6Mm2qF|?Z@vPIY@9^hw z$qh@$rL2#}ol*!L*Q9i2iYW%;s>K=)N*?GrV+xmlaL6m;|H|v=(BWb%6xwq(jL$i_ zY4F5a-uOkUY;w{bZO@mbUK3t+f$c z_kp;~NyhXy_)~RU%(TypLWPcB|1v(G%*#p`w9+mG)+K zGv<6tJAKoZu4l${?5mGUdX&x5<+|6Bx|K+on3$8Z@QyrwV8K_~7ico~bcVpY1R%OZ zV-_NicdIa5YIH^Q3Yar#$=17@a_ zMjloE99)v5BlI9YW@orIoy#WPr$6qKgwLP2xKOE;Ls_GdWoU&^KtEdmzTqaf77L$;|527|&PxS9t_%nwy*#Py_yX2h9-%*_n)s}0l zfTUX?Q@stev-ShytTamvgaeg0JjYy{&lXDk1<-UxE{ei}FMOQujU~~5TE8&LXo*`r z9&m+S_^Q%`@e2p|r~k75meUUfP0^$uD6#8D5LsB1hDwhQmehJkg?{@zZHP#-+VK_? zC0Wof`OP>5nW)pRX1ME#CNiCkU031^nXN9H6Em{3S|AvLECmPia+V-SAWy7&gZG0Y zgI?H&G*H8L?7>=A4`6!^0>}b>weW)mvoE;ITio*@1IjKxh4tG?!Nii@a&8sZ=Hd8 z5<9_)y++H4YsiI{1NXc`JKBIEnf`HBJOwHL+c*Jd%c_mzepy+lZYU9f*aQ!D?eXo1 zbBVmbghBi};(5BD0knui&8jil2=NuO8N zPV_KY2D%$!imo7ZnXfp!p&$F4aSq=zUwR%w{PCFJt{q!`Jq_^#V1vSztKh#V6iYTs zH6jZyd3&`K%ir|BrZ6o)Bn|foD46zkcD~Rb!5E$724YFYO!PhXwXNQEj+2jNCY9<7 z^D#e$cB^>BOcG=YA0{7o3oygB3dMh`8R|8&nyL*ei zC5yH! zhm;G}Xh3NM>+ndr9+31N4Y(zvQUk89b#{J7x#@Wko%z)ufXv@U8Db{a@q1?;7VMP*>n;oSp5bAs?vh_op>Lpe`Jk18Zxh zE_PNJnU(83M?DrK6&jbB7QWPvZL)tWW)z9KP{Okl`p_Uw&CsM_a*K79nu^P1^o5}c zUxl;HAVwbagN=+|5Yb@-Vzffo4-*YfMCMc#lNtPqBIA-*Rz_S(zW?_y)q|xcY}K%p zrHvqW0Oj{Fd_Bt-dW^8rRNNHIkR&zqc(yvQy)#i-0+oSONAP`az5PG~ECDiNF*g@3 znQ&n#ivHc3iWQrXMAv+h`~&DzPEg7V{fDycD1sm9E84!aAZM}sid50bEk*QisXFJ= zArhE{kCrvan7$?*b%9v-;7jwVkRncwG-^hp2!>U3;wF0Su}$D%>e zfef(jIIKoXouSWHH2YBS@AH|(nszE_57fo&50n;aJ+LC|bH*P)Hy$)tI`zb7iUBn5 zz-R9NFa9Hs0RzCZ=r?vh|5#$Ib8u#Vc0i%hnCOZ7i-JQhqxHu3&++`b`Z!4*WrI(0 zDWPOs7-&2<(q=G$sb}S~QlPs;%QtH)1&K5j!BaRCmhcnCADcPla~_RSVnO(_WaDHR z{AF=8m)`^JXz0ZGa5PMwG=Q`z~k#bbyC!za?Y$2>eQa?(Oom^l1$MTdmF zZmoHh?CxPc>g-yG_TMRF2wtPiTZPW%DC=%k2<3y{N0T_pY|08D3%_+_2++1L(1k}LS#d9HwhwZ64dM`=O}qA+<`4j0eex39d|F; z;zRnQB^#0D;1SjXE*F$Ng<8W|EkbW{?500RSiR~fNWnPW7?Hr z>t7s?GD|Rx4A&T*v+QD`G8QZ8cJdKZ8X_SUBi%I$`tK{_pm9w^kL!W(@+|go2PyY4 zqV`V-2$Ul8iG2TpOv99`Png>!!MV1@dG#0nu}6qc+cQN`+5TKMo=++PrzLigOe$IV zR*3pH;m>KSxA#90b*sjU;qNNTRIp-$c@Jz_21#dKO4Nu@b9!LA^ncH6LIb+%#eaHo zut0kSHk82XeQ*D#cn~%N8<&y6Fi;g4iSlPi+{LBw*%CneGwyy*>M+KFy~xmHU10}R zDx|s);il3TmtT=HJBYuY{rxOpyzl%NSHpys)-1e`wFyE1YXyA5h|tiiS<*NNou5@$q4M z65{7Jmy}2iwx^`cDP@ZbEWyJT;lz})Z&8izDgr*};d0m#r`?0dDYuvdi8h$Dn`90yEu!wT*3v33P|;*9?5X0eE~No;yQ?DjCVp%Z1#Li#_e>-aY`G$_P0f)rQi7EIIsm#`?_KD zHF(JjA9DTQMB=g-q6MeL7>o>xrhw`Tkj;Mp$t2|nW5#ijbs7hj+H6Qr!u||T42z0- zGvsB^q1pZUi7!o6G?f)*Qc3*b&Q`3F6w&{(lg4F;%x}iMfJcTUO#*)&L}Sjg3FPKjZU! zmRg(NjX*IStp7irzA`Mz?)w^$?(S}olOKc^s2^7{Wp=#PdU)ilB&&YlWMrI(p@_7 zG*qE&KPt6}tW2^7@+n&Y-PZW7M~c-KtFb*oM(HOU4XvjFTN8=h%n0E(A7wahEomGW z*j^DYr;MUiwffraA9g*EYl>utzX6*jj^|WWk-`M_u1d?W zz}7|~QxC&;K7Ks1BQ4nb@qRT`bXe~6#b(=!!0|7F&^mFyH^S%+leu3$px!w2#0EGi zes9DK0l!zx;>Nj83-fU|qT4ZUgPQi^?MV8TXmKmyuwWF|lOEZn<7laiQj5e1)SD{zk+O=B)gLvzEhy?}FIDIAqLmyaHCaLf zs7W%XP%H#qMI>2czAmsh>SosytA#Lj`)#bF@~@u>g-!-%JY=hH(WoVUu2(~wVrZZ* z5kW)o{db0nO3?fZb>A&;Ldz} z3$$49_^{s?3=PYTG+`VsDiIg?Js5$8O9Z(dPUfteo(8>=u?nY#1*!jJSKPA*>G{LE zx%vXa_Fxzd2m0SfPRR*q`WkQvTD%>O3X;aLSa5xI&Btqos#i7?zQd~V_@oZnrr0ua zJj9k15%2{pgTUoIU2tMn{J*EtUDj^2+6RRt7Qxl%$V9e8=dmBhbx}s(Lk$J?%9W)) zyOJzkAMFjEhECMhgnA(XE~WP@8|q3O5_sm9%u2JTo1numF{()$u@s+!I7q|~;Qhx1 z(2M%bn4{>IRNw4kz?K@CaMb{C_cEt1?TB?QwFb#xvcXJl0sTmEF~*3grTV=m0XiMI zq@E(t0ja0UH>2NaKa^_JN(4CUJmR{XCluX`bJR0l*qdtCwiI0`{@Y22XM*&Ioo1#* zFPdq$lEIR+baVqzKVGiguJ*<+2DRMXxwI?wBQ`e7_Hp4TuDUeEaNSuV(T2qxeVOzP zMX?kE=82L80gR-TeJ&L87A;e?{Y|=`76ybi-;-j=g z(q$gbd=jOwR`xHRlSee$4hX4)3p33{gbPkP;I})gqJGeD6ii1MDW=y8WBb)iydQ-@ zQ&XXc>`FU@M(}dkM5n;9{(Q^nwk^*zfwt6)C-8VfRauG{v%MXS_vnFavdBytXs290 znU)b9Hd&JMD*5AXm+QWo+8XXjcKtP)8Z86HMbFU2gFBzT8Q!wSlK+bftY6BFncM-o z!{4Rw>G|@S->dQt19PEm1Ac0_I^h?4Zrlqb+YJ_}Y)FBDDJIB%+SAPbEQ7A+Dk$3m z)Q2ovZ|Ti$Y%SJB^Hg1$EPl~W{gev1BV_346@s7^N}=5?Y`pa6Cy6R5O7hY_=EVTX zS4Qr-CMXaJWPpcEEf)qC{TB7wMdt~}T1V!zjXYs&4H5E;^Bj_j2RU0#a-^ri3^o1h z2h?-NzKeiLLOyr4I`Df}S`OGtYmCV9GIZ$SFzR*8X#;l-^9v3}REFKI*;D;Bs&Llt=ndYupy@?nUF`C)j$UC#;~5*8QA(bVC0 z%7@2=mo9hO5)$c;L*Wf+*HzQRd$e0-R5f3>=1hFs>SkD;%C=vicO&j|b!pu~2L&VJ zQ?xyTw!_0NyxjdirS7`X1DI#@B0x*a^wnf)JT{mszGo6lls_CN7v5L3V*mX4GjDA3 z>f@yTa4^0-N}%v%pG|H3C#usp=@VwN`CMYmZJ=ZYyEZY_X1qikJN)^IPq#1Rg7(+~ zzUdyt~rRe1R7Zpdg=hlO{S6R#xJpi_+luYokFQa1sHRv4C5iY@_S2jBy6w-H8W9PlBl zTWU78hO0RLxI>V%)PpAAj$2XQwl~V&3k-;foTk26#}FUy2J1VR^JaAWQ||GFw-4zZ zH>|ZkiH@D%YIWBx0C?E;dGXPl@}F9%dD(xstMo1{`G6=M{*{OIN-mTAS^ zlc7?<3W|bdcI}y?supT72A@h6wAR4_6aS1^#7I^1k^V~~1;GM%7Y)t?CpkzstAPf* zesrZb*?M;!Qzb?!v7RLb4B^6pP8aS3EV{v0S64Ti(~nRrjEqT@PJ+xiBNMDtRa|>j zB*_}d?P{D|`MMTpBIRaZJNZc4p(o`_r~ru7Nquis2G@ve|DpOc=jYt7si|uzDx#ey z%PrfC^>veNez#`XE&!WueQZ#_GVVDd_7+s)V#G`XZ(XzD8PJ+uK)g&PyuP7}rj;|r zC4rlcGRt0`Tc%hpQJrT^juO+q6kb|ayxSdtrJsx!ABRDyH~Pp%Q)^lrFClc5;bwe+ zzTsLT+1B=qN%TOF4|e$HSra3>6B8rz#vS8gU{!zOBF#lftfS2;d@{RQKW^hN-3C!O zj&*Q8eE2(}za{;^4WX5x5CNfnEV_~h^$xq5v0=I$>eFxNm;{W|cfw9}@rXkEfkJ+4 zF_}eg34nWAKYcA4+Qd;;4jolhm2~Tm&?m$PL=Z%*!J_vYRw143>&{ z(ZE7t*7$CV3g=Sua>V{Tzh@>?(3~PG^7VrIAn|`OOXwdm!s#Ti+t-*Pf4K$KH z7kA^41Z9uiqX2uHlTmiRMk@EiWtC=l;g+r9>MTb9c( zo=NXvi~Y7>ligXD`R&Gm4A5md8)GdV+!=7qym6s!sI7&!>v+5c7Ot}l|lP^pzX$Y+!1 z=^;UeFe8xX2hOEMV&I`Xza7SU2!(LGMB@w0DSIHnsu7?=<@5nRR_054Bs1(0*I75n zr04bJR`BI&O!et;fIyY~=4JrY9@P^ZQKe(v$FiE8x~YwGbbhKd52etEZOoD~x<$uPdD6_YXvtF{1z zJT!cYE<;x+&%HEa%rboqSx-6@u7bqj_%)-?=4olZTCt4a+d6>_=aN9b7Ju5ju92JK z1~QMN(*LW2MF#cS@=|=fn-Tm>#Cc9i*->oi@z2?exw}iYsr$ahOD)RxxV`h5R_Pti z$wbRQJ0sT*$?j7>+t0G@vf`yKdu3Vr{7iY|cN*Z+W9d|*yIv;*Xyjk7BQE?V)B0Tg z68r`FHOipRGS12D2q72+qNym?0zvE2aLK`v(eg>~d|)JMw}1^O5@Oy*lBpcdf>eg(Lh3!~w28V6<}%$62@g@}(U(27>Q~tVP3uUM_Ry zs!iYhYT7^+a2b3&1+kMI{Rj!?qd}!7KAnY;dvK91Vd%maf;x{8s4lUjq^E;FUX;Nb*G>ZnlU!2kj=|(rHew2&Ly71L(ZGnxFLKJsu;$y zCJ$^6hd&Q6V$>ycw==r>GyP=ROJBk8=0EL_Qo~puxMMg!?G7?`oiM9V(M_zpsq~q> zVhgN#BFDHR@7N8<=@a%O?Sx^wnc}f*=`UI|P9l@G?(i2UQ*U0|i?h zXcF>gOZj5dud5*0i{E}Ohhkiq%Sx{OP15>3DB0g*GZ} zuiy1oWm&gD6v?=SQt&zLC^rmogkHJSdF*gBnGg!nPfiyK1K>rz&sN+`z7H@~LPsUs z@AUK3SHa`}Pf`7u*08j>^^Y;01rB|@rSw8WNK(ln4HV2XPQhHxg4kSUc}x%OXdL`|ut;Jy@HE&RRi7fKTQ@6XqEsi~>`=KE}0i>mP;BpmvWSq=1v_21WDl&Hl@s?NR&WuK* z0JhWI?u|b>3J_nCllgZ8HJQ;n+*9&WPRM&6n)6T(w^M2)l6%y*z_k9tF9M zCCNp?iHavxkDIO}I96Y14OiMRFP=)p^bzEg1zBFSQ)dX1vo@v89R-AEXbbz`h5GE- z=Hr)p;yLuxIjkl)_`#$CLH6(LNO%gZ82)a1eNuAY?C*SLthAFcyb+HhOl8d)W&UBM zspXqIAtu8H#MC6?hxK*~+M-`nGit_&O5hfErw7cPVSS7__`$VAN2QYAvAPpEaDuyS z9=hY+dCJ#iHo0~SHDiOIS%rce(KDCVoY|ugPNp4&_R{Otl&Np(K~K%B*2>>x$g%L9 z;~UL|(-@|WQ>Ya%q-TN4@iTvQhaYQ5A@$r(EL^De24pmt^Bc>SU`O@UkS{%E(yOt;qBe)G3$#*Kq+0=9$ z(yGwZoW4h3~up*PGe{O)7)4-DgSYZ`t zn0Cd3Z+>oII@Ti0?%HgdL1)ZX1 ziVAk-m~XuB?*G;o8pT&}brL8^9>5o`qt7X-EaA1WA6eFPM%Cx7Vo7uJXuig!zkUA3 zpFo`y82JkMo!l*CX^CR8SJq-E;1m@YlV@foYxP_qnyJK-hwF|KQAmfWvFo`ur<3w# zc`^ygd#wZd2tr`KaUl#l3*k^CRoPF z<9l-7NbkRAMgZq^)ES1&A@Ej4_-0b>{3*+Rd07#dg8_Jk1gx{g@@v4 z+pTd_-y%_|aH;kxB)5eqVKJ8K(%$?s1o5Q+w5*{Q;CVahDVVMPf8_9x8l9m z?&qkQT{N~dLAy)lu=vp1I|~>nGdcsqWQid2qQu|OabbONX8Aa{kHAeD!eB2*-$x3b z81AzWw7`vm&^lghM4OCU{=9AtCQmk@D|qoxE=ZUl*yi2?TDg!y6#4cfsH*DfaMilb zd4Pj-PtE_=go9rXo0;b8PorMWYm8`pJ{699eEkf&>T{)|o0`K+{pW1sR+MHFwE6*h zb|@?En>zu(r7VmzPZaB-U*+{~GjV)jVd1388;&{g?#{>1cl#?r_9;Z>_GVTDW0#Gy z5yH=di-n(3w$KX-3M>f)pkiWTCI*mTVHla1lFuOF-H4+?NX~h41}cc@&fzv+Xvw{q?IXl*Q+#lx0_}8RD#df zF}n~tGAYB%!#t*a^iK;^i}V?D79+n`jTx{RM&NHa_>X z>q(H&mIzW&=wF9z2cRK5i9+0y(p6z(243eC|Ij1?J{w`H#J|#7GIW|sGV`4QrDz$s ze~8C(tu~sodN(`#?31{yc@_P%*FJVhD|+B=QeGrcXod2LEg%^aUDx-)A*;S-rpKrB=2obG+ zFWfYNSE6lOo*B*Sifi(1H||Go3waU3g4X68RlIOasZ$po%^?G z9}uVG5e9+M1)sNy+s{5WT|Pcv02z1+=%N_t>EYSZ6}-F@)*~V!Ca6ItvC1&nO`O2X{3v@ddGa@C=tSdH@oa2(z`>Ch!JCV zf!5h7lhdn&!a&(;7CdedF>Mhk!|$r>S64yBZ*d`M=zXtA+bxJ?j%mxa%i~e6%BsZs z-veRNc~Fm-4_oe%B(BXEv`4p41fs|5{pnXyKVPUi{c=;p9z?Wy|J?GCLgzh_?!W)ao zx3?`B-?K`k&>?9sB#Q5+75Q9((Mmm;IKHQn(8S4;pgZU%G^U@5Z}guNe&<5e=-UCD z{`Ec|iOse_LL5~(ihbgHa4EJ$7G_18t94>p`FyGMblAgJ4H_S=KW7tv%0#XzGrTH3 zBQSYO3;);<3EN`HUaLrZEHL_C%87NfwxU{~5i+w<{Y`-8Y7dqJ`H@VF1X9i`OYjWu zy%X_Fap$cc*%JwdeAzUky+k3*2opEEY)!-S0g@c_mjzFmoxyX7P}?GU?dN6skrjUd!rYbm2S~V5t$g2WgX&sti@=Fh5x=pJK?2 zq;i{a=A^WD&sHPZ;kux*2(Q>ANe&iEM(sV1HJq9n8{T}QV#$fo)CH0tQB$^O< z$94ghw-k}t$PaQSeFK__$Ds*6WgC4VF;Tof4UBtId4_SSQrXwTo^z+zw@@azZwGpk zuGIF}WY+{}iqG)jAv;IOz6JIel%6$%y;XI(+(H0RGwf*(3qM4^acwNDt-YHa*l?R{ z-!^oTKy|xOl&D@?E~q-5kW*5$gU@k+)?3-+RyiJq*mNdW2L{)+v1^@5YGPQv}g3zK{9z3uC{gMEzgbIM`hXa#JHH>r+J#G zG-zSnGIH&~`+e$wfALn~6d!(%Pns<%t{41Vt4F+Mw%qKQjd_l!PthQh9Ld)4b3@{1 z$)`lc`?)D=?yoNjAla0B6BnV+O=aqP1^u|}7BB?^EHa`C(Gyl|EPLP4+@uRkwDEm2 z395*cIOZw{Q@(~tyAEH}{{wCb_{)%aM9HglgXt6`LyQ2Y#<|7tcA&t*vGBgq?X6pH>m<~-H#Z$24}|%bbp5ju$gT{*i8n&P1_`<80|R~iEuB9jnDaJC6JttM z`V8q|TzR>hu2;t@y6CdVKnhwnlAW%6a1}Tfqv(;>Y&g?%&PWw82X$&pTQ8I>ix=<= z(Z5v(lFc|S0tLOH+KZWw=6`>RtTF+S3*Dv-itaxRPfwuZr-$~+kK0xVh5m+b{H~+V zT;n%LT%p&3w(ZGAgfA^6qX#`xsTbxcgq}CxepA242`TjHC`gwp?9C11vtp6DuYLAi0E3&Zj6U=IW7lZ6D2|5r_%*{pY*Yo!K zyVRRz#d8e||8R!Y&qxJkjQ5|PPEhzd{QBPe_+(PNzRa`N^w@`tTZck(Hl2i=0!D&u zrj8#7SA8!$bvM3O6XDMFnMBF8^HV5)GrP5^_}Q~e(H75oLa(br-h9t*_O+-PxrWCv z_!A2w^VA-H9la3XB4h0nDnwBkAcMWJ6G=bqhy~Gr(LRhz6UcAdoy#d-e};#P zvFibd;d*L=)9RPDv8XV3R*TRcH*5kzqSFzJtup2j#7!ToKG|Od{IP~1e;ARRmoi^} z1ohyYTCX>%3@3Avw_OerdYrzx^cB+H0atp_yidXI6r$npMg!rUiBEeby+^)kX=Aiq z!?s__e|Wi_NUuIgT#)ih?Gm+qHHZLji{Z zL%no#ftWaj++!8V+`#wX&*7)Vs4S#;P^{9e!vlv8iVR*Ru9)9-lu@i#a4-)qC`Ny& z2(gjp0K2$eTMk2FlOgQ)bV+gvijkumKu(j9#F5-g_u=--`QCP((j9KOP8DQ8y?OdW zO98&XTPDNnm{~F1_rIu}{T8)fr>rvEE<@PC|UTdJs@ zFWr;l%^U)ydg6gQb*rROY#?HdwklHt)+D~qsDEdkpvC+)obPPn;ci85$CzY<-Jnc- z*5M32r?q?zD;q85xJHG;WPtbs#qCD2q|w-9VGVWCKIR2$%AZ2tb0Wig0-d}`bR+Ag@^b&0z`V2)?=N!m--ZlxB;_qsTvdHXB&Z7f)yLG7j98lR6->pLiP!% z<~RJ0o|RY(lRG5QphE(e$!VR9mZ019v{NIQm`_%tgmD);ZD)7y&kr(vSct`7&baf` z24zAon_Mh8`Z~r{BpeGOj|6gho!cMvEOH5hnyzL2ACiOeXDDI`p_z`vUd|Ia10Fn< zT>Ho-$OG?8m%LX4n)ZvcBx{Bh#Vf7XGR&`tq{yuCI$`9X7!`swP&xH}KYxXm$+>Ny< zAQD;&t|f_cd$Q@-AaUb3l+Wcp547n#7%Ro8QfvYW^nvt0Ijx2Wgfe@a z{v0Gh26;tX+)@r=hcm&_;#~M?hww7y>L#OTCRT}s8){u#8r)j`pc}@f4F?G|j*K|r zDtMFk8?guL!vo=c^l9@d)^Dy42#*a(63LL*4NX69l92O7XTH&g_ZB zUNF6Ot#`-H>nbFn`QIAr(SLQS^~W_xVvX3?0}!f3-@m-vf;N-o$dMv`kTFap z;aqmU9F|)BKt;N#p#d}g%HShh_ZA#W`xa4#M5889Bj&Gdu3ITe_HNCa>Q^qdojmb^ z*$~IWV{r_|zwjS`5aX*{q7jIA#8QWLOZ5*B*-g9YWTRL9&iIb7Sc4IoZ~~$0YMNpF z;-&{cAikK4c6aR@80lCf+l@vT;n#jkGt}<|7}OB!9$j65VWmQrgyw5#sx00;CJ;I;JUj8 zp5|6?BB40H5T86uRIK&aIpW=IZi0IKvXB8ts2wHbKA5lGz9)Lul(YMtY_!}56&N)= zXlF%qotxa?CC#Wk`uFZSMWVxLk$c+AX25-in=~@IUT&?xm7nQldMM@g1kSo z9Xtb7Sp|7Wp>$KhkOY?M(W<6NLfy007>m_<&3g`Mx?C$8UVrUh-~MqhOujdU85u&U z#y7vo(fbm}@{+g;P<%Ct6_YE`ZPtK5G<;@=k!7?8ix!@j)+??~>=w)zw|Xe`qvWey z&UztCQl{-&6}$LqOjg0zti|T?d;1$F$SXwiciyeRZ+EPGDn}|`(C>0y=v_O5tmgzJ_3RHpZ^FVS8&!eTSiaJNbVA5{N;j9 z1o$3>Mj{J1J$%^PHhMV|4yvWV?MO2t!3}wVfqHvyI7Nm#0;K2XixA_322GKfl_^C7~!bhBcdGd)Snky{R56(Go)N~Mjr+uPS=!RIIKgIt69_R(Tz&S->2 ze>d+&TUN)FugY%UfZ@gt`U(UV-v>h3tuea#?=1fKb4q$EiEEu3->b3wtV#;=I?L{U ztLn0&vSz#}E>;6XDc)uQ+&#Y}iB+xZjF6~W$fvkk-DC9cr!T+9{T18%R5@SCN0py6MPpbP#=6opK8Qc~g|;U?vxU;nhrW5d}`)t*$YIk+Ei zLKi)`fQi`y0q^4VYORdwEdMLDCkfulfy(0gD?mYllWpN5WKXHs*iMEp+><{6r`gIk z7AxtK;XU*1Atf?0G9kSAXG9E;1;kk%>T~p*PR(od^Be1kRgsK`wQNeRRWKzg;qwKe| z;QX6Tz&eZe{{hb6??@_?!9hk|?_}rllaj$a7tLVEl^w2EdunrN%xU_4YoMENc|5^d zJ|o?;%M@mXAXww!U@RKh{#*E8$^Xn^xnwkJW`h3e+6gk%FghltGmX_?Y;Mly?@qN{ zN8%k-3I}fkyn^;=B#k-puQnDEl2wDm?|-;dL0(K{*z^E1?RTP2E(nlt( z6poDI!LX7wDsq3JEc6at3iGcEqu#R)v;kd)0ip92!TGS^DbREI*vZ)MG<9Y>*-0_= zP?%{2%etU7ZKaZf$8GS7V;oCY#jsiKp#$YVtM#ca+s4tG(21A63pjiv zN#e4GKbU2ev3!D6Bw6b{n0{O*NC>y12)F-58h(7rD&;F4CculvwPO+@F=B;_M=B}N zhBiM!@382F_%f8-PE`65a5sx87I=J6HrIZv=RzlYSw#VchzfmPSo42=7|s zDk1X*!9whi3z1=X+cghDxPAwZiU{Wwub|gY^ZE=CgmmSsz?Z1?WHo&9S>zR{yWziW zP6y(~4LHo6P*D?{J9@7l*9M8BNEjG4Hod*gkFGD*=6}P!N73ip zkCkyr`_)OM6QnpaS?x58rPy@9?BmVad-3e_t#N+V1ln_yZBBL@40@ERs8r}F`9&Cq zMo}RFH@`D^~_zsTeK`e&g_s|G|=$|XL1>#P>K0)28M-dKuj9Qz9cgQ=2vl_N>^%$i5Cq|^kRABP66N|SV;qkiK3%`*vY{=YDTTZYk) zcUu6NLAmszm)G&jwFcRDD=H;fw}cTHCM1~qVtgRc`;TEMWX7JoeYtt>`#^y6c)n5!NL8mU979)uF$VXK0iNqWBhE?50U@DQaSh2ZZYtfPxn4|DOE>D zwMpC|j+;uZNGlFF_QY=c0pe67UXK2JEM15#T2zoWbVI}~+%<_*TM+fHu7UjqrZ;m? zhAK~Uj^J_T{Y7LCeylp~D3!rctuf<479oyQ&WPxaB%53P67$KopF}8GecCueF^#>Q-IqxhM$vCZm)`RI zKo%72)4ecJB)_W=F*Y{k1P6ufpNY{5(#oScg73G~au)N~Bo*Qqs{!9UFP_xLjaZ80 z9weZIMAPJ+zrJ@B)DRNNELbB)dvkO;s)mIE0WL&?LVm0)3D zXvne|m1ssnTJJ?FOZTVRR}LD61E_j#p2)a0`Xjhm>Ae~e7rM?U8LEmo2`WAfapE!f zMnrB6%XME)c~Wx@I|^`8;VQn(RxxK3riN2O$)zu)kV1j(_fGV_6cbF4AbGu@#D6f& z;WC8V&37y#VNcwP2Giic)_L}GbKC_G;1}PzK3UQk=)ho?B4>KBrg_&YYSWH?wAu{a zqr?pKEy;&;>c05CD?^I)a?ODf6s%Rl;^SP7{J({5>V`D(>I#UxEv`O@cV!!ICKzL0 zJ*AlZ0(y~+>rt^|w+-1)a68w|7bX+R^4xm3LJ|s%N|6sDtGhJWSQl~B37~qsm1aS~ zGu6GKcmYA;n^fHMm6GpjKRJPyt9u$_JD{_{1gB)eawN`;XP&Vb`%EV>x5vXaSK7A-~ABN}@bC7%sm zNE8Ga^y5Y>EnE>%Ad??Ak9z`z*axNv4k=qN-{>3K46{N_V7BKbG{xS}rYuw=&H1?M z5b{;FsE8h>48AtH%1(AYJcdFw5vE`mwT3v5xPAr@ipLC7_f4sSz*M$i&VthwNFY!~fM1dolqMC<3AFYvR~2AQuTGL4Db^;Xiq@X+_tDUuo@$hGX4ZK*whQ!(27ON6 z4a=FK_|c#m>JQ(lB7p?smBk*JgXK4p!*XHO?u&?%`-x=z9tp#=g<{d!X2}yAMpVbb!qKoXpj~vviH{2*huMt zaJ-ichBFm6^Ik9P+wUaXFG4W_!|21OaK@6dtM zPz4ilWF!r_`K%p07s@h_W;Q&m>Q5!9kv$a}Q8q!`!;PZSJ;tdoL6kF^R0*#TWBhNi z;NBLCXYq~pY|uN_x`JKYqFWCoS{)C5->{#DS%U$a_(*bs!6B%M3Ubhz6e)G^ED&vs zLM5VpJhG2kA&JAciTp(x1s`_yX&~p6N%{R&j4<=Y=ed{XQyTMi$t%!)v4Rp%fKDkQ zV(xj)oX~C7=p+8F&h@>deS$eYyLQB|=+mt#%8Ro!^+TV&ls%h6!))_;pear}FEu%m zR~Z0XA1jjXO8rmSQp7Ni=n{`0*7%IV=;>==1schqf$M3hj~-`9!K{1aA5DG|s;Ws9 z`Grpg23Zat{Ep^0_s7Nv#NEjEs1!|LZGT9M{$>OEgueu1uzE$NkpC`OxYJzk(&M<( zuQor%Zf(4iV$r*x5`FSv{cG^dvXMs+QDH*=zGS>!cVfA9%(;G{h@NPyx+48yVoY61t?p9A55mpuEQ{8GC~Oh zDLJgZ>sv+IBlO>h7+jrWlo1w)j$R$5X9*mmEF8%QX&%l}xextxsx6}wh#K2y!c9${ zoO2|e+7lY$TNfZ}Gx_6aL7BO4Dc{Z7F4Mk9V%l@ijiVfy)oBwNqt)sjhriCoyBU`A0yFw-t+KaReRf;cu<;TV z7}@h^Cq;$K+xFn@e>_sP(f*jz)&2k&$~00q2Me8a8{Mt|A5U5kyjKDn>sDVZ;ld9Y zTGu|bo^{{4E;=@@GmN%{^a2iD?(Drb&z+ZmEhp^=w@dB>?Kky()is(0#fd4i(^E?CaJ@bA9wfdUovdHCz26d2HYTR!? zS(wikJT8GxN*#+6-U%oIMrLAeD!Zmi!|rf@@@0vaq{XUAg6+zUY^q|jB@Ho4Zu|CQ zIr{^zhSGiBkun#r_;{OUD8wl9Ra$1??DZ7aPw5!`pTr)ChcJIUhf@eVl;lmcrw?Z{t@^fk>Lf3tO|1H zaSAvv-qMX{G`{BlA(Wc<`gEgw&Ise9R8^x?oQ8K&+bZRpNxJuHTYU6`L-fsfg09#X!k2mQG!ud@emPoA%c| zXhr3-e!{8jwfQN8dV}}Zvnp*hZoU2883~KqA0fi#q1Ay+UTnB z+Pd=Eln<2#fDA9Oq*qHf>27>$7hy)_aW}yEI~S!_XknZaGGW_|>m(f*ky&!Tb1s(16-qECV)M6n^xJaB!uHP}GWFZ0nj{I0WXzj& zt`nGqH~vJTIRR0Gpl8mgYy8CkE{;*6pYG(H=Zyiw7#e5IB#OxjzBv5GxcykM<$&^I zK`jdId6Pr%Q|pjnsOrFzhZNokDLGKHr0I2ZN6m&JhD z2Em%6t{-2$HC!G9phg?eRkViK4-n(2nG2u(gV&BGENObgPa^gmTe@=%-Ce($zx4@ z!(4lIL9t8OaE!PwrtZ&Jb6inoLmeT6Vz1i59HvyLe+SS9aa4pu9wWG<*rBEM^oUOW z?2@xUMC)wca9Vef&vM;sBsuaOcQ5FMK{C`Q8DtT(BuEkPcf!y|%x8e%9jn%wfr!jv zC{g3-aBr_a>)3(mJ-K;%fcGyg6-0jan!4d(-i6e`1#*Tyezhp|#^+&}Pr8T&qluLf z8{7S5)EyYQZ-tG(X>MW!H{y3AcPb{;P{tyxaruD8;j%hvqe7|r(|!US~{Bmv=}QT8IH;)UDB`&jITyxdDw%rL;E~%w({>@le2NzE}Wdg&aZV$ZE#0) zY`%U^-j8;?!k1Dn#i?@rPmj{1m|?r9Vg9cvK)S_N!~cD3QA=wqS{Cru;`}9 zoV`?%eZ-v&x4n+yz-#QkTFk5K@>(^j)5b`{=Pfv92~g%)1Mh%`OD_yRj+Dp#zOWJo zm7@nO=|vUwIF>y5{E8-cv3xu@yA4n(J;^s-)?bWGlsC+yi!^2PxH55z6c|;@~3?BeH4Kjoi zizZ&PyD-&pg@SIxpm6l){9+;V#b*rEIuc*!K=MRqd{n8fs&&x&0{`v;LBD!8m&DTv zPwu8+EewndZ>_h68zF8xfv`;@BYKB(OqeMiFyFuYj{xNUL)_&2Q~xDmt*ukWRJ8=n zNGNO(72{S!w39sG%#K}(lKnnE?Uwx*3(`j;8I?^#2{YYgs#51R zjHVv{M;$f1$OE$s7#JwpYpgh)R5K)*3}&@J5|+THMF3of?g5y(Hz+| z2rOx4w8+Bt$FKbSc+3ZZ(NRVhNKDI#}>Gvo(Dlz@4aD+H(*^wb-( z9lDeoI=nGWW;wA2g|jf`_nd^l_cEk^<)9)nWeE?MW!e>ri2PF{2^Nr(t<-o>mFl~Q z@b0;yTW4dN*pf?Xh2i9Z2+m{SEr#A=4u5IwniCgQ) zuGb00ak9D2U({A*A8`VCS&>VchTl(I-nmxLQO?}Jc2S7UP~Mn!EaBqt9{ucm-xtc9 zZLn3KOB%#w#E>t{OHtOD)niO6V*m()$>C2!u4#|ZpJs$k9e4GWRLYVuCXx9@YI`y0 zomYH--|ATir^TkGyzxC-RZoNV6svD~Eh@8}}Q0^a4^cP-EPaO)njeMcbofl3s6 z;r|iz;wvDzxHFt}-ibg#DJCX{yLpsr%_tCOMST5jIs;lhCIfkh43uMksg`d-q5hmM)goO*Qqc+a?x=dMiPvvQ^JEVXJ4-ozX zc`jkFJ4$7glqs+j789a=M$^OG*vXX z?C8$Mk?F6uAG95qlCn2};{T7Tw+@T)3H!dKyE|7xy1P46T2eZs83Q)J81_B;}y;^eNBq!O~h3wHYM9-aT`84C_E7)VYLx=V%YQ@zR+*qh9s2T^v zXT{TlC;%fyrp!KVy-M@3cNH{UHH^v@Bb(R1(<-jC<7HuCtAtLbr|qOYs)?+wM(XCU zodHd*U~!8!NVoTjbFiZUwhj+4X%(;;VkuZy0hj0~=9cNDZ#Nf#mwjVH7o$$lN~isNKidzu9o?(!>Khn!KkwCKWX>PFGE2nCS`k30-vRC*v^ zh?v1^*9l4)u)SoZ;9yFdO>C-#;Pu;6*?9^?>WtAY@>-^UE5f{h$Y^>jw<3Ww+ z-+XhVXsc%aX8}u2$sAA`E#WybcFI}k%|L)AM`3*48@4wl7(>mqSjv5%prtVhW@!PSP0ckzw zB;q#XMz+QTgW6q|NUDh zjEXk#g~YF)Tm*!gx5p{fmTQRk-3Bx5pmFr#bix8+xssTzdu5hdMUkkE)LlZ76#PZR zhXgAq(lDxIQ62@~mHR};|iHM?LSt1&kF2;^1p^#K!v|_6aG$R%5UTwzLZ_QWOx0Q8Mpy-;0 zw@x?{)@i;++BtiyfAgbB52a73WRtni(yh7+$3?4_aiLOO+=Z4REcCOk&*AGA!a$Ya zcWd#&lsK?+sK6L-{xm;S4;ji!F=oS&of|URz@0}BOR*PFXtG^^8~7Jf=pLOITU7QQ zP>2~dj?&Fa^iQiMq)F0cmHi)>WE>e_;`AlzoJ3>uk;GZ^&I%Pi`r9`(WM#J$Z=8 zxlghW@q$Xbo=B0y{T%?afC`NFU}%#ZD|?jnxOnu_9I%)oKQOBcNB*Ko_R~P0&`XlD zrAG_mr%(4XR7?!Z87-yoEeb=OFWA{lJ|7v6gEOm+AWPJ~%Do`tCxK93pWov`Ijdo3@ZjL43UfKN1 z&fw0Pj<=>;z%w2tJ7*#d0TqO_x3sfaw~jqCGOigp8O6KA*m6X{oE!_BdZ5f!{6c|y zR_VaQ0I^h1Y{WXa(b@4nU_UFf#6z4-U95sw^S)6@AnB?ZkN>#U7-<_7%O|;v9o7HR zD2p*pq=`A|4KDanj#rq){UKDWiEF;Xc%_Q!Xj2R~be${kSBfxrk?=yDD;)){qBRF*JnrDVH& zFlyg>ehVpI&FhBWx)U3D#(2xmeMODg=I?1 zuQuSwL7q-|ILed3z5&js?0_&4+!3`dycw|G=t2n#Ul2O|zOfwxcp}fT+|aJQWs?#X zl^-BK`+e`eUv|Fb;u8EN6L=#1gg+4eNil=Z524FrUrr&;moEmAsIm4$?m|fscejjM ztkF&*-TjPu#)6jnSh{)bY6^s!t12XPAan=7C`DERhPr=dz#t~Q$pkA+%c$Ec()W}~ zuk!8+kKv|$FZ|}CqikhXTWdy=H|Bvun%B2zD8sI z)=kr=9bq*ynP^X+w^GxqESK-|8c4e*<5j(doSaCz=+#c3zQu!0v8NEUe-0ju!479D8e5!}<#tVcIh}f*ke$Np=|i{p&=U4Q_n}oTu#PC7)gm__O!jifk=v z65C;byUQOh&+iir<+6j8M>)#Rm5l*l*JnW2<7`#=@k%6JS$~0j@AG-@FVcPJPt-AY zbOUFelSMo$XI|A>5m<^YIVrdD=CZ5GMbKm8RCS=;gipD%AefpXs{W8=Oiit*%{nAb zSP;;JXBL_MnIxe54!7yU)=F|Vh|TitdKUeYwj(joEH+WRa%JnBUkeWszke|>DF zKaC-Za~)cja!^c9t_2Uev}qo2dyR*zwWrNrSakwHbGtu}D%)IC6W!`Jf_*8aaH`0b zC|dZ22HOuX>lEeN!kSeyXUGR~!8?zD^yqUCaGEQ*OJ5bI7mvmXttIW-mZKL)Gxq?) z2FaBD%5v)$@oK(xMAkW>qf(0xfNn*1PhP$gEh@m!U}J$%FQzF1q*786%X$=53%7$z z_fYTE2_E_WjpUh2-~D9Du6j*B%40lwOP#28EVhq9Tl-9n(t56R_@Oz@UNW5i+;VD+ zJe>>}-=f!HNZ7OKgB8gna`yPf9(D`$QH^fwVV;nriCb0rV0^;N!v={D$e}Q!$%@Zc zQy;MPbUJN9(boa8; zjMsyyPJ0BA#-U`t!fc@lQk+%3L6EjXb>c-w-}vFwTKM6j+il}9?kvJ=JyKBm9!p8$ zTttef8^L?y3HSK(k?+`e3sMjzuIo8+lgS0%H?*+lLkIlqaht`XYuq}Nu%X7PVq|gJ zK=MX2KMaJsay7wqww8jUdpuctf`z1P^uaLc;B;f$jSKD`O^a}kqYU$Idx_I|z?Q#b ztLiA9C*`JE=#isvPvaR5%d;<5Bm$Ab)2PMm2oZSC&Lij;r>^(8Y{8t82VkhgUwzSy z;5?{Nz!-!x5wUbCc_D$glmX$>fIc3bgn)1}BV#-8zN1b|juB za!wtpB1fwOt3AX|)26+uS54z0!+ng&_6Mb}TP*8rddiFKR)rShg}sEVW={pMo$E;O zci+^HhpM(m+opu-GwONtplBSG_k}*WlYeEbHHit8ygzV*QidI%in>*UQBRtePk$B) zRc|Z=15GHmsr3S^6%Z*^9M80RV*LB-sU-}e04N5`;z4aeJb9`#fC2mrMt>6bcSq^_I9s~s?v=a1EfB~x*CoF~WW@3kE7>|D3k=c1D8im-PEuB8sO?*h6l|4Ynp1s0<#b&1Rk93af3zIaDS zlw@@kXWhftiwY$#5e4OHl3SOznM_P}0nQ)sR zB{y>Q@`FgiY`_mh4G+vi`T!ZF>?V<_*GAMT#vdiN9upFTASVu#+31Z2`X+U03- z{k<1;oi3sDg-b`_g?GspjJvvedLw~9F1bU$${wpjrRPXfvpmnx(MiLGGP*qLtCd8^ zFG&&s8gzd3O0=?OxKz!7r!1Gv$IuHmUJLvQqw0EUTzQlG`v2tLZ@A#*)SV%^ZS*R5 zdRwLPefW;&7FUbr7bC0H*esnos5F8#M-tlsUoR+q$>_Hem^S4Ut3qen>@t_l+z{=m z?Snaa6=8djB%-$=4!E>c!Q4_L6ldz>eIu{uhwkq;wwzt0JQF0eoP_sH;0DEa{T3hj z7KY&U-eV=|`2sa1U*VjVcj^@yiEst&;YuqWyuz~q7&l>AAA@GqgB2tr&Xpa(lg-H^ zAEAK@S<0}p+z_fi30@Tb{Hi!WjDW_O$QMT@L`%v?qE@d>0^#;hoFSVn2s%ECvDE*X z8_O5@Q|a5#^?qC${{KYaGdKoA2U>Ot_w*SAM0))%S4u4}s!Pq=Vgl0E3r&WM`~atY zHa*LVbSFT#p+;74iy|G}@4E zlBe1k&-5&?40Rb?C`dO<(=!MaIRhX3%_O^|*l@M<&e}aHu@Wq}5bjj}`pkqa97GI% z_yTexB_jjX*Vmg2fr?p7qoO}$v!Y%|eWF2ZPq(^S=OZ7xE2G5;368B!PD$D?A6!0) zBH+oCmjmc_;?1Wz1{K6cY_ipJ?7^*LKj#xOrCUdLIitsxp*{?eiv#*pQD7fzzoGNf z(K+Ks;;PBZIY=`)sIgR3%le*KP_tG=$%^pbwLmTvMr zZ^nR@=j$Ch`twigGdpso2XFo-nvU5g%dK~E>|Ws)3(nqRw^?{%ql%F{Fl@Z)vkxCz zm*W>VmptVw+IYrvTX|dXTs@VoKIMZATM_Vy48W|t?M{(J4a&*&%9z3M4cDsX_T9lr z?YO|*RtBbzW=IrOFDKH34gZFg10Gonm}pV~od=pY)ft%CS|@W!G*&pZZNY^gi66iE zPks1nY4AUfP}$Fdl0up*#5b7lBKA(j^eF_Hg724q4`%mT~oi6{!Aj z_adZ}(%WycV1wtZE{;J-8*T~{0?Cnz#cF*XMovPa+oh8`k!Bc)J*>2?;H8>|^!&kt zjP5VlHsNdbWE0V-b%X5Nm0;0aFuBfFye|~*@GKz9*~;zDc&{=m{0Xz!hELa z&H@m?O!;{j{tjOV7<3xJDq4@Cd#6}PfH+vVJ~Dt3f1E9ODnoYs$8|Cb7gmIKku!11 zc0YgPyJx>G@H3q9dmPpLF@O>_x4DV6_ES|Z?*YbDecOW|aJYt@~v0>l@H%oi9$ZQFY;9~84V4!qqzKo0RWzW86O`%4^gJiAGeW*LllgIWF%I5 z0l}B5<2m2(r*-cwD3hW}j~v0>^9j)0>C9~D7fl;p5CvP{SR5&LR~Jbk0NehfN6JcFS7SLDwgjc9U!$UCCD}(sjrA+by|8+;>W^D zlq(Np(HMK>+Sa^siEL~r3xEG@!f>eTAr1NmRS8D~js18zQ*=5e)q=)}f ztau?X)H({$z-e)!L!#r%!@#E(|{A z0VT)o*XWtzt%ayCx%Hx^f~0-jdl`2g^1`fY%jLAE5?%6ejb&|mT6kULKb^uvq!iIP zdaU|iLUcz%1K(0pI<1d61*;?1F4#Kg0UFu#yue z$keD!k zW?S8ZJ%dmX2e8WXJMxInN7(U8njtO6_HO@_EN}*2!m09Xg?GVxW<0_p9HFAI$zu=G zsK9xoVJm%wiqc?Om+Vao`M2`H&3LH)GiJ544i20{)>vnTOk5ojv`NjVR|{djH{|hp(j9VG3&C3;rFUGGi`Qr= zs=a$Le^fiT>R79A6xj;yf`(K{ixZUqYJ+)$*a+FZ%y*K-7_oCh&nOZMT4&;Xv7#&{ zV}G)E#zfUi((vymK(~GZ%*~pOIK<7HMR_cq1o`r{`t!}N3WavLJ8*yFFucFE1%O(_T zMgyIk-wfnJm^fC}qEU!E>+K(v1ln}sv)a*@pIY5HyqE^W@piuIMu5c?^Qvu@TzgRD zHL!f&VmXZh!fZAnT>oy3ely16{mDhsbe!l34*Xkc4v|}r(VSTZaWNFBQhsrUoVTSK z_SXMXB>YogeKHcHG=!5z0q}q{PA;= zq8IH7n!s@291qP>8|~W(9ggposM~XIb>{9Z8p>Iu-$e#%$?Lv}ITWwil;Le)HVL8H z#|i5$q~t<5ZEo&WWKfPq)KtvX%K)tJSvswm#A$if_Rd|D(f4V^;pD_737;4S9DC;X zlV~fy9N6q#uQ4j7^QI&Kb5W)LLp7-{Q z@4r!2ZUBQF!uv5{tF$mdBo3w&>e^L$RqfBGZI56PYA`ttIxGzIgK}IiD{|O|faasK5I2Xicz2~mhVx<^r)Ql8i!=cD}ooWq<{7~!IfAf z+8*dYdHd-X#6ncgpdRk+dqg%>QvTNt4U5&93hU(>cvVAicCvnd;J6Zr0DiJs@%}YC z_&rC1)l6_JN~|Y2sY!BF%}IAcC@NCqcpKr4r6bsK%@n4#ht)@OltAgr9yo2vFj-Jx z=eFBp9ZRA@R)_XRnQFf(cxIuenc!~`Z)ufgLdVjET#abw0$jnR@tZ7=-P2y?L{NwQ zU&QoFk#aVy0cr;b`Ix8P!#Uc4I7kE<=o?qS|{arDBbN+fivoB}Ln2K$!;Oz!O z@DUSW33>4#pdcPTV=e&sAQbl-MaQO-WtT!%8gr(uXA`Bh$E6Ea2WqGkLzcRgd?%@F z?X3Q9@ez9ifbY5@;CW^*)~ht{3R!wuithhJt`J|kUEVdBToDfv^`8QH3zy%MyhS5T zuN4he*vsut;~vXV#hqF-lY+BVbH-;o#D0CO$g>gn{!nCh6b%Fx(MSHdDfspcCwqxw z=e84KGiQ@S#5?Wfj;qtQY`E!#W*!qO7a!J(oQ>Ez`YPw6wuxHUa7>#)loP!gtfR)x z`3jMgs>rIy0w=;dEjHT^rYAASN(V$$5G}kC?lg$@#uQWkGgDetU?mVIecrEF9E4!{ z*9~K=Lnd++m#bBm!@WCj_3;pl#g|&p?j~`5HO#Evu|iCbO95_8n9E z?#I!$ZT)xWN6!#%_~n92_eB+K;3f!O=cj`_!w$o5O*9MUUjNK}3}^rVtS{sE88y$av2&rH%g@`+?%YbPp6uXlhsXCqv0$aT*e|5@H?)4O z1s}2vkqp@3l`Lg1drmmu?ZalE>rOb@7Wn)2zG=d-b>Cz(30yT4zgjc5pnVb|b`p)2 z{f2S+wxohsL+XYF8!Iqz!Spjt-NT72arc9;#DyuvJ0@dbnOP7`(B1R`+#7G@tWNle z{m2&27(;uSGT=aX#qC1lDOPyH2dlf=m5EgPf%DLg*#Gh_NpkN3b};(fAM|`L-Er1S zR)1f|4bp-6Ij%oZyp0S%I_Y|%T=zf6P3=5IZPCwLCGgVHBEY2)BR0hBdNEbN!^z26 zm^2};{QJVu&I<*62qyEVBo?@R(T(XNH+NRfM3cZ(7VTSE{F*bkoB%&2_y@G38lr5` z`wP!m9trY`t9n}>d{}^2;zA<+hNoKBV#^Hk-yr_C@QCi89*F)Mxqo}<@5lHBTi|8x4e!z){!)FIei6n=Rz1;?uz-OK#&{} zUYvpm$+q=7YNV;k4-vZY%*?XL7SmMWW&AWnmqI_q?_o%iQ{1Ynz~d zSHIrUjOqzoNaC7~YA#@BV6+Rl_c!se$VbyDOuF09Mr1RDYV^(Z(PXCEDOlxTs&OO# zZ!cL)P{84SWayL+uY0O*dCM=-ifr~#+qMy30~1KAbed-U%-s^@0x~yKe@GML{qk$m za5-C6|Ln^?fcF}g6Xne?{E%@@S?)n-*A8TRsrFngm;qwv z1a)*%T1UcKmd&>!afAF~!bloKnYlhtn z*(Q}3*L1ihtV zr6q0v9e0OoZk?wL9rZ1InKI-=%<51h*G`m_;czrS06xFXSP$GtA`}jE)r`-Ry-r{* zWj$kJH0qCE3h%HZs@6l=rnc15)tWBaOpy}~Z12Kpr_vFPj)1rfgzKbKe|p_aTmk58 zNq>>p6HgVn!YicIcYOW=aXW)vmEmvM`Tu4q>a!{_y85w5Hl0eU_O zuj@{px?66&^l4bLOkc>t=~K4Is!%6jHSa}HiYKr8wutdX!r)n_Mg?r`BwbGNg=^r6 zy2P17VOto-&@doT$C2Lrpe^(ulh^7r|M@`~)A#vdU)o;@3hF}_Cl+0#WOZiZCAer( zRdZ)mck97I%B2s|MqNJZxg>w^=_2Yo43u zhDbl3vj_NqaY|*xNY`$41MdFBL}RjQmaspC*{;9ny13-@5H)>5Ve@*#lMdRGOidML zu-J49xMtrNm;-4~H{E=G__LsVmJqZahaLNCJ;Z-cGBR01GGXPOWYbpq5vygP&Afrx za(T|IPq>Q*LyN}Ix2&Y7l(vgRgKo}~xDrB*DJiH|?((m3L)Zz&QB80<~Lx6=U&LcK~PmKC^XSEj~cP9Jwk#jbChPS{>53YfnU0CS*=|KnA zA$rCAgT`RbtRxZZ>+7S1L4yC9qS@`+k)01D(y;&KV!*|=JWk$MX-R112=LoAEum)} z;+_vh%QlvgErl{6d!B{;J7n%o(TVl>nsKVy6%<^~WWS3YPkoF}{gA+mG;WL4kRt)z z<3T$qsm+M(3wm>&J{w-hiD%!@bqq46o5)x2$C;ax$|U6}6DqL}Fsq9?x);2VrGHg@)u3(`^hyB+iY zPBe6Ig>2K|p;PAg*BOM5|L&jQ>FKDMI+=Cr*1VUyCe^76vwa)z#IqB+y}zx(!i_=S zUmf~{k)O;E!|O3ed;5@$plpJM|K_0|I^jtX2-ME8OW zxUb>uOTh((1N?d%j35scf+%RWHuM7*vY*xv5!ox_7UbFMZpzZ#5c+|BL*}uU$1yKd z`wx;0J8_xPlo0mXL;psJzl{3-mQKr$Z-zkSLOD2kRV1`Pv_{*>bcW1YlXlXYnwodB zAR7!QMrhvR#0SrpTv7kffsvKSxeKlAo*DU&g6 zq(CTMUi3H6JFR!`V#=GSGb^txk6P$q36YvO(v>C37i_-+EwwnJT3qq4EM97osppLs_P`p-1!A>+^h z&G7iKl~*%kZE(e^TyFmq#`mGZ16@r0Zd<B*{HG|L_&idzcd^Ydpupoz#ue&5LOv2!Q$2~sfiQ3v>iUaEALqaNc?5DIF9PG z3_pG1_BgcmegMB@8$qo@zbLnX4v1`ew-(I(L{Zht5{?^2uhK5I(wzFSit4FDO>M)w zF^gTd_{P|hUPqt7IFMk{GO}-r7;T@>*OQ?DQBOH_D92 z9mO>;$S?FibO5%e;p?HCdzx7TzW4ta3*>uW3g9+r0RbJva73svJi+d`z$GB~DD8iO zKtAZc_8jDWBj(4=C=>d^|HPz-MQg2v#V!8a}DOo`g(2GLqBTQZhS|7X2u5aY6Z7P`#bsq_xQj-8Lq|kkxIc83jV3^jsgE9 zEGOEIC$zc)8=kxl{%qn>ZQO}|TmbN!R!Du1v^p&!7jUir&*~#zq9n+Q5j82kfT9rQkj&E| z^1*^As0i>%x;myioLJxh3-uun!UAObR^Di|YUU#_$SLVMz z40U_OPcOgTykHu4e(oW75s%~5?sfDoQq0t{-DORzc}$2frW{Nq8YcND9)vws)VL)yMEz2_~V+ITkBzuX;Ave{`hER{q3X%Xj~A829?nr&S ztG?fDm^Nt%rF3-_7!(gnKgW!VXSMK=W$}@>sHX}P!+ssx4MHm`Q}f~71@FeR(P(Vn zxw*OWiV7`2o1L?BKRn}BaW<}LqUe(mxVr-2xBhX}%b8W^(VggRZ8t^ASGvpVn*y&J zE^Ip@u!9WM!(Ae+b$4bLpj#Z4@YcuYi?R}NM-dtZ-euihI;^xNM zySk+Qa>f2oo_zJbqxDq*gYEF^T*RZ>?g%R|uu2RrTI@w&&{4a$B0Rq9Z&k++d)Qb0 zXz}?A+F0j8Q>gCUj>a3^PAhDuKZtF4*}1hbZ)Q^sSnXRKOdoSXmviRn8}8pbiBwpu z(JU11&+QZBcM?)u8G&ou@wN3=!ygiHe6C(&U+C9{H#(DD-=;)%G+(HIop+cn+e^1g zbrlyc$CwoO*ufsYB-fn{7$qvMG7pRFr(~SUp8}*!SLZ^1yl3Z?ZYScV!PvQbrMq~! z?RVLa-S$=Kk30q2ANHJSf!*d7i1=dMVrw@#dkO#FY4#G`^{oKniS4uWC5c)O^z7&V z(@!G5I(#p9KK;=VTuGGnfDDM`r44omJob~B=~(!7OXMXC8pMe3jWC16nB$R@vy)x~ zZKZb;=fo|=4S?M5123mLOVdMsU+h`QX)$ew*f^~;;8}RHl5*t48He>cijB!od7U^Y zEj7vIF1q7CriT<^%<$M6qToBpD{IPc6oySzmO|D7$(7rC$%Q{l@!jKY%cvlxlxjpx zYe%INVyCr=rg*qr_E;c)-QfxH!^J(4h|X-q=Pym)^f{v2Rm;L^{3MMiI-^M_9rJi4 zIaG348Gt0RY;O(;r5N%+Ed3cy;?TRN=1&0rV%F4IM4>Bh%HDw>y)6xE2so7cH(WfK zNkjH`%w)~Bd{n8q0qy^dtPxvkABc;a8$R5JOn20&)pes5+dtBxpstzKb-49_q^pA!-GMpAvzEJDWnAA44)#hMrW3<+wMOM7ThpgKW}84AJ%p zd-bVhNd$JuFG4XVJ8ZfXUrz@lCQ7$9CGp>54QtJg@ex%0N&I)VXenU({u?I7aO;Mo z!PAEKHs`y;r?&xc()6<>XF=JzFm=qL96NBtRZXmToT2L-=+25G-H_9qN9L-LsIA_wc)Qk-1E+II39{D=!ptEMM8z(|wAZ67NvP zSsu{D{*=-THK06yeOx*kmWQ&ype3dC)vUsx6vOOD@5928`t5(q#6&cm#=kdJ6@S6E zyL7tXNFh|T6xlRAz(*9VL?8W1)$V(t&7>#|g8*qFK{|ypBcWpMg^kFjhsXLC{*hXr zfvKc2t<|p=waUXZ068sLzIAqzz|cQtHr0tl7xo8hYdZcuw1roeP%D8ogu1W7`8R)fw-b0fs)h2h!dBT=qX)qQ zABZ#P_dZs=2mLqm{`+pb(*Tw@D~8ZzoVV+|p3LEi&3%(MjnHvEb#pfE`kCrR`WpK# ztt=+JhI`v~N!YX-it^f{UvJcVmph&I06XbD_G z-#w8HiT=S`88g{ktuSL2y$e#k{_s&V_qUCw)V@F+>=A(SFO2?Mga{Q&lQ1$cv?Q(? zxwpDN7&;o1z#d27_PT!_a}bSx;02PC2(`kS_pGt8ahk?SajJEZ@{`hu%%)BhD`7KeYgFuClF@o`#0g3^uLr5BT=fqKRWxItep(p zuRqH^^wTVWW_J|mvqMBjT_N`ypU92_Pwr1|@jCI2y8RIh$HjhM91q`@(rgvMA-sBHDGwnD)3X14{Tor@2+pI9ISCD!=V)eJ;{9UOQ(!f% zhHmmj!*IV^0V^UkuHhmjGUCTBVRH-RMa2Ci?~Q{*gGC%JdNfAuvcucJj9e1^H#Ptk$d(9ptO!fhZ|Lvi+Hf)OX9~sfHMBXl3B@$#2mc|!_ zB(TSg)dXPRd5TX{6`@(zz0ilgclRt$dk4?qKzIvaQ)U79&)1J;3@>mZUFZq188S!q zll!O$z8YiXr-N2U{;-O`&Y7Bx{RbJi&8KNplI&^wA*DS*TaAlbl~2!a?F@58GsCHLjnrw%o{{@9LgogB}Kh z6uiB?*`Pz4OYZMcH$lw8VK_dQR3GGxd*o)DP6th~a4-sDFdvfuzY2FcAA1T}rT}4l zrx8S?^LT~@Mqpqdpyc2ZB-H@{OW4>rWNxWa;@wJ2mJ|+D&_z9Xu$Wwv{R?K_&? zQ%XJl*4SZBt(&XTucGklzMHE9yR3cJiB9el5?HA}OUUSL2m#_$y}wkb8=D6&qwRhf ztTe`Pl<1LJ?JWdHyo~tzdOrq#Dzl&{i?s4HrOVK)jBHfAZ-<1i67%l?N%ej67wBRk zm|rHRu0#K?$Y)F}5Lc#05J$$XM;q#<&bU4GmRa_B$QwUi;WVUTn0qYHUMu;I21Bi; z<`nfI`gwB{EI{KY5u2{-ZMo+!jcCh;{V;fXF^&Y=RJ)jqqTSpG!CSq0DRq7SjCH{d z=$&@#j@4Kb6{pa%u$aMnBAUeG>g|4-!Ljq(MuY8v#$nrdT_J2{Z0Ol%%{Nct12r`R ziQmzmt`43<`IPZ*0*`5a1w4nr21z2=bYL)k*siVFK)2-6C+rS4?toG0$ZV%B!hToj zCtPaZLAZ`t?HFr+30nTdn}qpbVi~ z=VkY{g8{FAbL|b~W2lklK+X^(YDMZ^>*K@j0c>WzvwZEAEfDs6JXnnPnOGMW$t0>} zhu!RvLg+{`c=>8_=XU5LM~-f#r8t#(8PNu8Kp1R0N&E2A?8$oMrq>)qm9zQ&!6_)N zEZ$8*`3v4{_R-*|IRi2HM@2Hy9!!8^==DU;4v$ycM-kI5;LO%=%pe-41Q9aRw~%@C zZwh=g{~NFHxo8Kv2?E?EC2wSA1l+eL#@{ntRtJcXuEiQigos9%mS|Ru_-Y*t{Q^*j z^OJ^rJMz`sof<<%Wh(>u%s*%Ybf!Gq$7@EXuYPc!oi-Xx6{|s|Kc6*{@1s`RQTuy2 zL+3mF!QPX&hl}fpUw(V?6!yebZ@-;YWz&qT7#Sv-_C0;!VLKTiohef>8Pf5C@{&wv zGx26Ea%Aj-1BGHE*eyG95C9{|TUiW+m+_+o+@tSl)MuNWpG` z;+j($XPbq453Y)eixq}lM8XPr=*8#z#HVmnG|XoFy?lg>yX3X~f7VY=6l_>V5dz-A zh?>Gv9x!2_+**a(@ z-9COVoff?BO8u+}IU5+lfCr6Uqgaj_l7G);+X-cw1>;N!OnyMb569ZY=3l6_Q!+3W zDqhl{U71<*v3=%q%H84llSxgrLw+4MmEZ(zoSeKyt}1D+u)-xP4Q?S~$on@N{zW6> zfQgl)K_!XSm6~*{yg1&;236?JS+NRZYO)Oe1oGsF=apAMW3$?k>)=2!`<&u0S#moO zTz$rZ5zc?j{_iij2~GIhb5fmnczSA?m?SKi`s3h6!Cj6iwit8QIZ{*8>H8`e2q+X( zJoynZjygDF(z9fGe{61!L&D=G$+>E*VXfYG?-Vcx>k(PI*$LJid8%CS_zV-LV}3RK zeL_6?dqeiW&+FA4h{o}y&ZVI`hkt2mYlqbswX(_QJ<^45WuB3rGjR|6saO*6C`QQI zDPxd+7j>0`OJ`}vLo`hB`Fkz%iAMh<#mtZfv-BtRr))kiyCK%R;PYzyL~2JRIq%BH z4xjmaYkOjiA5%lG8c+258Os8-1A9?;1|lUYIqYJ>D;wEqe++s)4n_QHxBdTazX{Y3 zEE&kD4jUR9wTz9cZFWeAiOu0Aq7GiPL0Kt%ELKZAi=!J}h-eNs=A)zSg&7(O^$QA! zT*MjrmX_8O0bDc~rk+*e$!2;XF+}WINk2oZvxkP*A>lDZnwdvhjhXZzQXjn{lCtz) z)FrFJr?--6V${2tWFrNd?-(RQXCmhBa$WNAy5fyf_4QtE4CafKe4I$q*m@@$W-Vea znycUS|Gake{hnys-SJFb`SISJ$20P-ueLw>EqO0*ZmdSrIY)xr+}!NEXeWn8Yu<<7 zMj$vX>S5{srmr^1jJeWqR+w0IxCkEy{ND--%Rb~gmrVo{`VM8 zzSiOmw%m}_28oYe0!3$w?oD?{Y_1M$`8*yEl58cmygFn>mC!eMKdMpXM8yx$l0Mbg$$f&BDKVEKDp*Z)6 zIT}u3*8Tsu`s%1Cxb1C`66uf{x|L?=E*X^;B&0z?q`Q#@iJ_!~p-YgIZUz{7C<$qX z?(XmSgdv6%!z&Wex7IVeTk$Y(=B=jGMdRxs>BX=W86v`w!AJcT7rF1 z5solh=MnA2V4jd)Id?_&+ptq~4M&^1YAd`Z;h>c2eLE#t)U<03^2QJdF^r)1duLv{ zq0Q_f*qq%Wr=|h_t9g6UP*}xMl6%LLJGq1mY9lFVpaXTJgv?mKh(-_m^Kn(;Q6~lR z`)CmJRaeEPCNPHn<0dP}^OMViyv2}moVSvH?amWzt_}0voy|>YG1n9iaC2v;Eb@`n zFvvtUtBRqK_}+;xw7RCO`z7QhO6lTHOs_SkIpOgDZHQDLg%AgH>0Y_W7OUNXJp3E! zI&$@@MBPp7&7?|oNOT1TcxPwBlZ{H`1|2%T^r-WB(ig0rt$aOmEz)fv0Iu!XDV(|~E?lh{&KOC*cnqLlt?}SoBGGtRYh)UZ7gNa66xi`VEw2lSi(?74zD?+({R!jZbS>0mDY{LVfV3xZ=G&{FvM0iM##Ki+r*IC+a<_4k4=Q1Sl9VtwT` zMgC2;KR^r!VdZi0RMU6Y?t`$$^YgFDX5N662S4toc(v^={bTljMhaVY#s1|8I^TsV zWfF6}R)T&$dBL;7i<^n=3>8~EG2f*@yLP)*Xu$WqHX0>)-Gke8cyr+QWYM=+J%ie7`{r`f z+rHgHN!Q_J((~*_-TrsaL(A`0D8%nhA54#r z7MGkKT4m6^*8*sbTWauBB~Dny&lV4Q6c;azcDJKSK3V3Jlqfd1h>D33M&RfYz$pZa zT({_(S2v+x1B1&S)%ZJSJYF?ulzm5Y;-G$!z9Son8)U(Fm|x$g!eLt}u_!!j-0MgC z?k*-J5VfhBpLB*i*GD+{cRzW{~RLh$mmRV!cKyrPa*0x zt2es10lFHZg>KwmXB^TOD7{&}w{vlE&2DL-_PrDLkHOVYxooDX|8*x?pkjari%S@B zvSb%>R=_j#`k2}HyMD{v%D|bdjB^*7>Hia@MC!&f>g33_q5kebGT;{XVnvPQ&`Ur3 zv@W;C^3n3{+9llo_Q?z1TC80c9R;JiZEeSm4ELP;{FhgIa}C7y-m|lZ$OeriCvokW zDaEf=m&Pj}m+}A|EK8sGf9;heUD+I03a)u_zq<*`jZwKBS%%3-gfEJSIe^U`&A*{! zaU++wEUU&Y-*j|s9e-l{Z8R)X{ZjA+2H;Yd8XHej{fQ8D>T2`h()^L>tt~&T=X-Ki z4U_+&bu#rHNQj0gA{ew^1~YyHi@MQ3>BV=?1RQONy_ z(4mmgEko;NNLx>x|NRq;Excs*K-6!L9&Z1WM>Mzd2M+Kce}!L0r2%>rMd|gPqaXOG zr-Ru{J=U{H=W5&t3GBKe_8U?(+^qd2EqgqaQf5M-(e3f>zT`sYk`bzH8+LQ9(8ZpRp2}R@%#@EFHrq+jTV(EfKZ;@`aM&)M>;A zUo5kGbKIo!bF%wS>5^C0ufEt2o#|qvouY`Z?1Dy)bFA4)|79k~B9TuPe1n+P4vhWfli_fL+lTy^;&nPxAzzp?wS-R+)hLi`b-z$b0`1(DCWHQX!AMij_28B7np*ur1g zVh-PpwQL@BATXRfLm_pKGw*)W9(I}GFDcR%cLDt$&~NQ5-T9U%JYZrA0mzp3MieI= zED-2&`=5%A$Y?+_92;i%_ES82jd+Ujc5khIib+G9y{Nj$7SB&K%2V=M0BZf>OjwWt zj<2RCMu?tuW1QSY0r%IM%{CV~>db_^cWh+&6NN{W|6T~>2ZvWLl)GUak)y?8e%)olKv8SsO^77^PxxfFf3<;4S!b!CM&+)oi5~;GtNY$tpg!alJ}h>Q9tGU zy{Pnni$UGy>bFNbv|aXsuCfgpO${EL(Y;Z2SM;9DZfwQ3(EnZ3Z>#UTzKwx88thyT~LTJa5k)F4za}2dQ=9 zx85m~fLbpEeD3Y!vfX3YSJb)s zbpzm07eR9~?h+H^E0@el>} z*+04L40}Kii`(MB1H+XoZUGvUSmD2Q$R9 zJ)d-n#D&Xnmjv8sNJ;Zhbzl~(KR@8+eDSu8F}wK3v(|rHm83EmaF64PZwb#H;vj_m znSzPJsFrqQPb*q;1A0+eaiDfJ!LAJ~Vx2Tt2|{Pp!S9>GlTSJG#F%Ga!LJp38(~Ed z%{m+Vj#uVo@(!Sryq}BtvfnWU>47DMP8JkuJ90!T?UazfBq6{{;?k% z?XG`JPPFRsVa!oFGCOGBb)+RfDX24rXY=<*Cl(zddQOzcPDd&k&KQ-apVURs3y4Kr z3?$v?k^XM;n*1j21uZQI9xSWG;eR4k`Zw~T)89`|rssAY*jdtj-}$an&!o3WRz0-2 z{1z!hA0CQ@F(tzxosy~-s#5E$37PMs?-f;`%6@}^;F$*{RsOIw_P!foo8v1%4ZlC0 z%3;!fLx(cHc(ZFl<206LL++z;0d@{h49>GYp%<`Fw4B)1t}F|9aSF;48bFw&T17Ty%n&W=`Nab@ch;W^jliR>2N zcwiVFFA!S1``+47T=}<$ClT%eigcoMk>wr|jh0Qm)mmpj?27=j3 z9(`R4*%b97@#X!>qom5kqD|U?4DzY(95?NGvccoM&x=2^PX`X8oUH7_S(+id>2Zb3 zN;sOybcfl1IDwik>{8E;p9UqSM0*5m)MYQ>e_PtdFFwZpvjh$?y;1)}Pi1@xHoeHS zJBk=ushH4Ej6W?G5?GYq-s8Y~z3;C!emUCPAB?=!1JcOZo%zi9L9O|lU1$v@MIS-G zFnaetopasem}ouLvk|2XmIKDU8X6wQMHO9ySDzCVq(uweHHyV8-ckwDf&<&?iY<=S z$%8tNTTQT@Li0!YGxqDq9zQkfB&R$k7hFg0cOvX_VJ!?Y$aeS$6unMR5FgY1>xC$M z{y%<@JdPe5H2h5nAIUf%b3Id}{3ZJb2L9}po4De^U-}$1p#39Kw6cw^BWe4XsuH95 z^cL^3MxVow7ynB4YE$f1ymk^jHclg|-!X(|CCJLorbk*BC5#&r(UaUkeGpdXghB<& zgw_%hejtmMd-)oV;U14)(4E1=L;byOfOt77y}!`=Sy95u_$D7LvvzX8pUHpRsNcPI z3dQx{BmPU84x|3t2d6mz3z_$m)a!G(+927@>Sd248Zm__)gi98z+-DtQ@@B94+WI> zZq1*G$-!T%-z*COm#t>LP!H+WTMSX5ecL7+`YxYZjmzEY_INzWAS~ViRRt|Qh1Z$o zy`aSBy*osug(I#gm=@&rizGP4Mke7CWs(w)V^J$0lQ^C)s9O4R)<+27 zV!+n|q5rt-ul@#V(a1pUzw>>^!yrck#Sjx*@)W0W9j>e91zWD+;^44J^&nLVOt_wr zJYrJe>sFFqh@!1^!}Eay3yZ zCOF-VaI7h%Txf(DC;E7M$0LqZlh8xFW{xy*o83q zGgz}IOY3S;HPy9*mQ~z`(vA>teMTxm1O(_AfyBBE4Lob#ivBKlI%9Lh8zypTOK;3S zU`6Xcd!WsQ4EK&~nvuOSO|MV4`aO_g;wz>=B=-0ntjD2K@u;Sz=0)k^0qtKgR`YYk z%8CkFZo5yN$9jtqZ>V~pU^{5=C%cy>uo90SH3U18Dl&)#-zOHTo$2vxkVPk)YAtvarp89ihwQvOrvITw$YaBuY0&J!Yi(_vs1C+; zy8;ztPA2vY7izXb;z_<^&z%%XcY;22UkM!DeB2xg}B)y-S@>9M8mf%qdXWgoRg1&|`SXeuVWW4H-Z|F4e%SpABj4CYh0XAE3lPuFx?0J!)3VeB@u(u=7`YxRhH*M?-a&(T|$t zRQF098>@!BZ%~tXh4y8fp%q06tY@o*`>!q-4av?qmV>SwkUQd#u6@GhA z9A&+#=@@*y*xr_NN)7R(%b)sTfu_FX=|Zg6#6-I0FTqYeft&v9t>jy z{-aL$=MAr4iRd=%j}p}w#X+Kkqn$$b*w{FQNK#^=^y2F=iOby#iRQ$FJFw=}*F&H_3YFQn}r3 zTI{SXAP8x2FoT#gXEOesA6FDAcg>1kom8f%SO#aCSd91m@vn)QwQj&yMPYxNhAQuS zP}tknLSuitzpG`>jI>OZ*)eTJ9htprh^QzWO-;=rv%>KRWS^@dBR5N+e9Dn9(RymR zu0>#31|QDT$NZ=YrP$!x)3(Y=2|!)*NrsLlU$}SM4eG8-fH&s@>R1 ze09(#=ds;)bF{nQW#xkGkBu0)Pd>afgD-i2Uio_VKtwiO#Wb#RPM_1LWZuoIFj8bf zUwg7{oVV}1E`aVY^{^fd4r^H@a=WEVJ?q&C80bjNZnhS^Qm0JE6VZO5f?Os5P4IEn z$vwB7;#E2xfOlc@I(11{W`B(AmfrMP%lr4c{x zr(ZJ-C0=iT-F#a}HbUXtk$Px0P+h*H0|hZnF}XvmuCpT=ri8WI;^!)cN~VZr;q)P5SdFe z)VL%1crLrMQ9}Sj=!yR&v)}O!%%Ri17;`LPOHNmvg~1k-I4kYxwWSJPg3vw?0q|U< zfpgMDsNA>r$(N%NQa!4EKHLxkBXIDz@B>9S(oV%Cstha4j@|<)AGt~W$}7Wn1HF|b zOHTH4LaV!1&mtas}-P z$HbA3C?uR+&;a6}Zv>sVm4)WI-=0wUY)_SFSa$yEue#8Den%lBA++Xv)v;${A$eB) z*5|M-ne8u@noPtfxXMg~wU)RXMRij-TGrf5g%^fuZf@Rxq*O3op=1>!J7`dYQ_Zfp z^r$=gmXpbpSDu0Q@@c>NyLeQ0E&BCA$m2Q_2AYkZnmDfxZ6qZN>Q`Lw{g)XbJSOqL zbd~#6%oUc6=Q8(4**g(G%>WRJUaqZ7HNWOOUYV_K1eK71_F8q3e&`p*jtJ*D7yL!{ z+SHKF%?`a~^v2oPuNq%&m4x~r+cNH^oxwixO`-(bwmr^psmMv0@2r;OVwql#y=VDJ zJOd={MbV%X@_@SUs(Cp*9(jMueNsy;|H)MJMI^ucYpH3Sy&Zmg})+!nRs&rr&ai7$*`XI&Er(tzr9bId-CC2TbO{YquEi^(DRHZz1!1aq?(QL z`IAlu7H;mIQRR%{YNpzN0*jfQHvZx2l3iWht?JLynbBf44rZ{aG0X3Vj@Q0h)lMF@ zTGt$+p_njW8M_8d{7_q=8zLn1;@my>SGg_6l93?OjDz3!Ne9=wbnlw68O26Kxx_^q z<}Z6uDoNkanVAorho#hlhEXJ3pBg(pn|M0-2yXEKAY21tch^0O6UB=z3UBcQyJq;- zd>j^RblWI6;4TKQR9PkNTtW+_#PMdOt;N1ApM5i|!zr|!;%rKiyPx=4od6--$f&f8 zD%h#aI8PPU^V{qq1fJP|alJU)g*NlVxzC?%$qesP z@`Fv@KxoDvpFkf+;Y060U!M%JXJ%DZ)r6CzcL61!=6rW1NSZFoZ_n&Lstgy(KByl3yGrZ$3>}ndoXGo__LHRY!7gimycio7*dPu`28B(vhLC9oL(-hHXlXeIcC&!CqrBVg994R@;aeQ-ar z@Ne}1ujSEO4uj@LUtdzl@e%Z3B$XBH@DNAj@p6jr;vLmvX^dy@V9YgBX??6JNXn+f z!+-PUOKgS^UiCU$IslIB%a|hMFS%aUj4s46sA2bz#P~$aVEcY`FYW!~9S2W!&9~vD zRaiPapWgJx!cfSGld4Io$<~Z-AW-4jHq!3M4La4_+tGI!$+M!e!j8LaqGEEJr91MP zQ%hXWy9ci#E4HrzmEXm`1l<5$U1aoTieM{laCRym)T28vi!cuXe$E>g=Sh1Hm@H83?3H59nk6;^5*8+UCIG zrY+I+vtTsbF?krlseI?J{v!%gJj>jSf?LEa2q4yK2iL5`gr56S?RWT3m)+WUIM^7` z;^8;W2n+ivf9&7bJuIbNR|>KiX5E;AY{6nIQyqVA^*j=MWq6`3uzlSKSJC#fA*m3l z&3Aq!Y0s2^9Wch>S$zKfMZg@DR1GXQw+Quu&FZnoa%a81xP!z4%; z&=Uq-MwJ-N=D(60Rut7IJ9qUyFE-HTs9yFOxI(I$HiF<3H;uNBEPsP>*`&k{sK}s> zh49POYrmC;J&h@wh0W9t!kH9T6J#uwu#StvU1dpHh=u5FdKHz&Iw$nv@J=5Rw_R&% ztP-|kTd$;RxN9REWxze>R|#=w>bj~pKu~zN861fKD)x3P-w08wu-~PwxY^gs{7o_G z33L`*t?aNK%X@8IYjA!1UU2fL=KkJKo`LZ6{QO0-U6fA4| zeXJE`yF3SYTXaC53TbE7zV=R-R`5mgS}NfBr0S-K|G?0-qlLOx?UCv!@#8v|8- zo->GmRml~n-I5JNQL+OPtakC*5oaCYxJ!peb|fm_Lt)|UxsY{-j*s00UlQ&|e6fHi z33meC4IimYM5hF>M|CtslsRA4OeiVN_w|TBCB}=-!~n*9(Vp6ZxEO@;v1uvkp-mOs z9F4U4a6sON3wN8S`M`uEgK4E2P*X$9dyhr8{93g&fD&eoZ$QAU`#g3QNoYE^<@ zV0(}sjoK`#KF#29mXPmyGA@4qOuIQW$dP7RaDPwvs+mTtbw`qyc`YG5zb6m>(9=Pj z%9}LOw#%bBpc)rHtw9ND*-NAk~I3$6#vf zc)ih9Yz*o0i@7z{a_s6RmSR$c;cmo@dskcXQR@lT`n*_QEncj<8@D+V6CYZx$j)?) zJxhx&Nyl9Gak){-I8wKv9bnfXoDH{b65^<;JUawt5J zk)3rx#^Ql?k7$peV8wC_wf#Aqi<&*|bCZiW%hz=}e;;%wACaOoeXPPYIo_6O@ZRs3 z#%p3>rz{$iq0hsLmdJQZkwQA2IC^@i6UKt!-9#u*rIxZRZLdvsdv~{qf0~=yfNl`L zR;tFmtx5%5W@H^*n2Js~Qx^6-ee_#y;<;mkn(jL+5Xbj))&a~&OLVQo&Jc31G)gu9 zJiHp1O1sl#Y&ec_R;DQQ$B)h2#a4(Pxd?jih}`CWPRs%iBbcZ0uxe|rKcwE*kr3j& ziXwjArE$3zbdlW$#H`~g31!bECpN$mzk^Aw6c%t`0ftTZqZ5^40GlA=qYknFb|eB7+IZ(lW4rs(ptc;SB=V!%(NEQy+TLnvD7 z!fKi=Dg5*eZ-WIBF+z&Y{QVt0Bq~DlulR_j+05V-E8>L!%i(9kKzPrJt}Yemnxka-Osv_i zAqqMmLgaCts@!-KInW{MD~Mp(Da&AmU|m=oD)G7rZf)_UPhRaBr5a|YgI#o^pV{Xn z+ib4vZ1ude$ZNc_sAwJzDeWA$Og%0g$9_FKsqO}~r2m6=cj`DIrCWky0{r}0$e!%c z(b1bbI~uf2$aEX)hP|1}*a|8(cFw?uE=L#K&=JpFa@iS#8pOOK&%+ZeVgBf+6uu~$ z!FVrxm3y8AH$)s-d~)b!^IH#GWG|jn{{FKp=GAyhWA<}14F9XioC=j>;sxgClJF!EF%0%Wi+tnC zc&L0je+D?-Dtf^uN~MXwddV z`F!6A6uCrdYaaujQuP+;N3?luoE@f^biKwWhscQ9Eu48g3{@}j^Eo0w57hn_!{|K9 z+(~Ua&_p{@mQo)wNk0U~=>>>qqZYh!caVZAK_#c4PXB$t*+dlEaSA3GjE(?)t!#Aa z`LIeK7$_pNoO{rQu}~k;Fy&9aV?o-fQLEO_wBXBrTtpQy_@;To%s=3{mPD+~R9;tg^#?OSBz1o>#)5%n045v8p;U`!Gnccn#kovSA%7_V)H2(_i%~bN7~^)s zq+Z9xGXJ_}+!FECmP*OpGA+O=L6R}t@)T!L?9j)Y@9p$-oSmjIxD`00<^{Z}5`>)U_Sh>yczQ zM3IyW+)@P2(%xxLE&SA~ERt2m0viZd`FqM@4IMdfRzvnP z1-Aevl_4}GVn^Up4WO}b`~atj?|p9wDK6t?Z+B_mFSfy9Sl34lwasw?aFW)3zoc1E>G=R5nOZ4rg$u>dQlOcT#W@txmiv9 z&aiuy=wgI1PjKLC?89@hgU;_FU;8PrG$`y&df**W+;eQX1+<9A#W9J-P2 z^L`R6s|~+Es?%#)O3*P~#4AgFrIeZ{)vT)wCh=U{IsxAq8sWV?a{_fM!{4-XEym=P zGT%LAB$Z3K-dF=_tz@__1av1vW`D!#$|Ypd@7D1{P<2FQ zr)JIFc2_Trzml52(y6zm=y#D)5j>@1uOl&MzUm$Bm3C9dz-iR}sZJ1F-GOQ;_`QOD z)h6g_8P!g3_wdmSjq%CnD zIyunjN-2yJ94P=1^<@psdhu%Mj~+dozLuBKjIuoxA>Q)ztiCpvSiPg2nZa4~wiV_; zZSoVQh2qXL3+P&JG2hG%B*NvdmCA)?lkJ7w3<{GY*W&EL&0B=0z+fJqgP9Lrl}myF z(GlmzT6)79C9}}ii(w;4Qw|7M(c1gGI@;~lYI3VZoYsRMNqV($xgmK|96+nXfX6j5d!+9+l$x)$$P!u8t{QX)1%ql#m7$Xy|OJU|-X)LiM*a6|}^L|zp z#O-A?f?EoVbT~)eQ~0d)OOC9uuwMx%mD=lf~Oo^K9;; z#<~1knha^bcep}S8aGD<>7h%ncrFn%=P=P%QgBv0X3#~X#a&|aLLvIWsV zfhTTzzw`M_EiIl1e#oOZBA<6)lS4xf9zX<4?F2*)8_a~TIe{wt7fsMiMP0&Bk!4vP|LWe?5$HJ5M}S z==0~CEguK7c2wfp<^hk9R8A9l91wNADA1KFilTHt zE3ojiKs>loR#E;c7lC|9e^kHrvdz2qV2$GB_+)^veYpxwGgFRwAW-(=Y?P>F;?QWJ zd|3#Cq@>biOuj7Seykqv8hHJy@P`6%4;nj7$a=irS$F%F?(EdQUkRPl9eWDG;zhM- zO$<1mo#yRGD(%wjd1+|5-9pMSVb9~pduL&ZdfQRWP0UOp)Nvizpl6&VXz%+pQ$U79 z(5)1c;yZ>}OJ4##F+|mT2YII+>Z&JB)PRezz2)&h>TMjGiOmwe=sR<7$BGRCLu+xA zI+=`*CQ9Kx?;yk^m zM5z3$aw$G%$@P|NlFlGs{wh*kFonhAg`Itcl@8@?9dbESN8yDUjJRg%ioiS5L4cyi zppFyZIuK8(h${0~TnNcKrqkwH^?tJb_>zsNr{&_|&3&3c=wa^uvBeU$y%83yWHH3N z{;hVfdYCBr`(>uhckFS~$Jp&#uaN}Xv$2nb13`#S57=!|gxMW$`i;n4FM~AKDDad9 z+z|~4LH%&%q;cM$wpPhDVd9-{g3AlP=ld_|qi_RsNFM4v1kPP*mqS8D>v69br*sIu zz#K0UQ+r*#4-ksPi!|CmDmO=AdeeD}|dKhMi2jnj}Oymq@o}GSQdu4;H2Sy;bkRmO*=iuq! zG&FUz`I>h%npvE&oF5wSyuq${B9VVp#9Uz^1(}xC@G^CJx|yO)vR*ri#_SajDU^(? zOs)FJkSG_HLKp*c+*qaPb!#|^{GEZ^$R|6ei}5N4`!>+)0%C^<6);7I2hO6QFXQCh zxj(_?9*Nund1q+zF8)1jSL^kYXgS1lBNL@3u%+uld^#Ouu4RDTpQ&g)9!`VjN+ki2 zxhHBry0*~SRp!F=WeWuU%9Q?G*FQIw11XCPH3=sc;wv05y8J)p8TkVjsa&Xd7?d8F zbeT>Z3jKT?mHnSVe~0p{|DQD1!7=4Dvd%b?X`Ig_ZI$C5Z|7y`*s2TcX=J}(=qOmE z8J1l(xAonzHshJFKA%scq5&1-F8`K)$enkC$v}UScH?ds)cnJNhDrQBjtuDQ@|DOp z8vU_~bQg)Ocv*NbfHmew(U&X?9C>l4EJEJk=wx&0V7YERW?YwBg z6n+rAHi7X2&)kaK*VnV6629Lm%hpd`u6?~XPlmjdRE6O=vrH!+)Iyo&r=1%IRr9|M zu5GO~OpLr1naif?>r54*K@!6EO^w5!w0Nf#=dx>Mw$=^nKCBf zyah0bjDMc%CX8X2o31>;?->y%co`g`B>D_zyn}gyEfc%ZBHNxPkj0-wBHf>XJjW^S z)+?7(1C%Qn=7v8LWjm1)50_xEV<-{az*|NG`pDoP58{0Abhl3&> z<-6-fya#46%RX_dG0rN%9%Yj_IpPVFu-z;?(ecsQ2#6Uve8dpsOTKIKGOG?dpiB$r z{CX=@&{#ObY@{PcB?_f02$jh!o;#leA2Y6kEq~zEq)o6QniubgjMEOIXFes)J`b~O z&_oa3Y{IV`L1A*~>BZ=PVK=m!##if{Pw+5Mpy*KYp#A6q4S=kzoh{KJ-_u?|i>A)*Wv#`{l<|`HD{p`Tus}GfS#*$+>tn{nJkKzy5B+ z+b(rV7*zG6-LeqN&|_M3iTgN_jH`A-o_Fy9dw%@2>xfDlRnkN3E9e*Xu*D(Ke6d$| zc>5tvM7;fSfI`(fHLjqS$28;xc*&1BTI!$40nQG7Z%WXp1KIcwFZxj}lmtSeRQAlc zL$R`o`;%+(aueOWjdcWidd@b8X zdAn%!`B(}=A`3gvwVfejfAeYX53xYHEnII=w%iVBrD%$G!f&ZE%oV-(Zyn7uo{psC zWcKiKW|*usdJOip`NcoMwb0L%$fDPo8nU875m?A^G~+3QbSR=A7N1DgZ$P{g!|2k9 zCs4+!j+b>@*jqA*Q#3Z;EtK>FCk|ebXT{*ck7t|wGre?%!>vEGq||Nid2F0Ts%i1# zMJ92|6^{mm7SL>iQu^*6NvyHBUYbovd+?p8OJt+9w6ySS%^-Axu^@e*Xlk*TI85*n zdCTgrN6|Nwyw6nK44GMym_}ygsJUncH8v)dKCGm+B=RFLzba(uC|-o)LjyK-W4Uqw5)*` z1*_H`F3y+?n#sg1w~zDMb5Zh3u8yHZG@gePCSRKYW*q|gZ;cIv{Mvrt;_vRiyfc0*(qPxs zDEFi>z1MZ?RF-*WRPU?*l~j@lHC|u0%+w`wA5ygHc&A2J#;WzHCrbs6EtYms_Xf2_2l@>`LlnyIATJA)NT zvO;HCv1+&_BMT(-Mt&2>FDDi=5x>B#A+}hg-}Tzo?LzqR+jvlU)A&Du;Zx^3W}}Lr zPZ(0!2Q#*js|apZ4v(GmDnk^mO^UdMS;XeI&5lVj_g#vwD>S`LMk<5K#EMle!IT^_ zWs$;O=eLCA_vs7E?{?JQKS}r4Liu?GR2Oee$x(XOkKS2q9v?&EK_xt@iptPQo*xsX zV5^?zN$e(mjmb~@J8a)gs)|)548D`+=87-q_h2-dTup?4nHM`%?|QjOhBJnt@*pej z^p^N{m4RqMpqA-(6#5B$Vn- z=^DQ2NyJ!`dp`sQTE;7A`3m3fKA7%kaOWB?@AZaLwJ)$j0-SGcK3oe+KASIUhiiWf z#g0Z*o*w^&x4~93b(=H3ZM{70N#do!`m>%`3xbY_LuOlfWxJktyx>5`;&qiHxgMS$ z31Ye+J{$QhX1u$A3JYMdYRSVy7il*p+u}V#5zm8i$kU{-n-s)c@#L3pr&E6-@peQg zx#sybjFf6r5}e+7n^1lHY&eCp8c&1I4;7xkE=eazKlSI2P|x7zE|&)JNH@-d_Gs7E z0<)c%9*@-7gsD$G&2XWlxT^5sfTNBSbB_VyoJ{(x<3mQ+koo2wOxq)8_1J zh&#=u)uL#rv%Zi~{Sa%YCYoC`;TV5%8pz;fBvw&U?Rx5xHn46V*6Jt}WpQn57qkG# zj!FOKa)@0x1RB1c6O6iqU4KdSV!rh2>TJ{u8pxFuirmv>zzRe4Fg5PvC z8L6kWrXr4pzpz6Ol&NQ{UYBE@YbIyq*-f(sV!FVG?P2ZD>F3N8mF&Jn5WN880x9p8gcH zp_TGG7Ih+24ZfknxFt(i8i1GxMKgYy63?Q;nXx29Ua+&`6>rZ&j1us7St1bZv7ZWN2R=reLd~kgT+XDpvZzNP-J-` zLGqx?RgGd+2R@}23dgQ*7wX&A->i+&NvxYqzGYSsU6-V3o1J0)_F;Q*R08kXoU_WC zgf!ZcrhKOhUcA`)vptMzJ5qdh6_zQ6smOB%e<6Q))9u{Bsur{#;9(Gv|a*2{aY=bfmPb_zG6w-fb+{_ z^Ir0aOvQc)ftYOZhI%k4xj{1>B#0(jPn&jZ#=i|O$EWFT!#OvNC?x0(UpkUzghacU z`PKtuB(M=9VVRgWJVP0%)*W!8bw}%OT5uVT6Sh(|a7cou6s=AeQ3nsi=bQ=hdktjk zOR$iGqiOMJx}_N9;YQ4olOpo17p+YJ}QH{Ne%SRHLr?+aeAZ-Ko(njJzx z+Y<3UUK89EosPtW*!JMPJ+$f!alCS*vQy1sgJC5nTuC2tYV1X=pc5IE4Q;lV=C)QFY$?=9> zvESqlG6@|PkTjHh5#AZPW~l>(a~!Ux4aq=yJ&yaLFuGo*Kb61NM@AL-Hx+JcKBu)* z3LU$jDnC;OCrtGHc<&9+BJt!kxu=}-7&1-V5ap4^Ke&B4WqQ9#kgBq*FP;`mI@ds>DE~6j{prz^Zu1JceR^avwcBRd*(g)*5xTiVPLZ6=5 zHCiyQs}xJyWKrLZ_UX7I_y*Gii8W3HsEPsYgCRgdyP1&njt{6E(SugJq@m*XazYoG z=Lfdkfm=lI6bJGVCsTec_KbwQ;Yh|smSdi%%9JhZ34 z@D?5_xSMx066J)S7V~x^OjHa`wVg{wuqA_myYf1gd(4-b-@!>GBb*!Vurkxqk|JJ1 zkQy|>yN$9w(sD{eOI>eEg)K+ZH>_NBv&BB2((1!-Z|8|p5bw8hO7wyq-aU_fOdvWL z(=zc~_x!y z6Qhn@=9Ade2`#&zSC4zpZ?v%swuBu1URL@vrQUc=52p+(sn0gID5d>gqm;HX z3SVAwI~ZG1izAA0v1mJ6=e z=M&iu$AfusjwDMuJw36Y4E=2@*U|^9G~XQu1WYRC=-o312i8HHEWeY4O{-5YClhzn zwbEXLNnITgKZLKl2H13NBsIAW0L==@fZr^{XA z+__gHkwx=AgMMf7s7PJ_sJ`3E3KuU ze2u$6*`=+Liz4KD29@Ba6C!9sh^8bAd`y&$a1N;+Ed=9QnWPL@Let-)e;Si-oWvdy zLpcI$bmUwVncZl4mG!li<6bY5Zi1|`7D%!P%V@7B=SOZ_b@Dw)XmP#H{~rJkLGZrq zfn!%4MV$?+z<{>(7&LzijHA>xl+)m!d)z!2&nbdAe+I0;Nf@05%o*j-YmZW!S`14W z2u6=FG32rAdK+Nu2_bRE^+-%6{qWJytZomCU?CDDPisOMtnuVe1MQ@|>G0S-8hK2B zIcp-!Y2$&$7GUNIB$ie}Ypa8?yMyYW1bY2pXbmK{org%Q^h`9;wVn0!kW$-`I+-hLb`_Q6+IQjxK0Hk#Mt)ydpuqIPE`EMri5b4ulU?S=D zEDB#rZF^G!iQDNJD04&KP4V@6VCGT(3){MtdFfhHmHwsgANrVNpL)^$8qanA4|I-e|zSwHaEs9~Px;1xQbND6KNP zPA;6WGvx8}8G`ZJZfZlWr8ZaYiDF$4&&WW=bjU%(n2m_8@9o}dW_-s@pf_T`k;nq?w{QiFIha2;$-^UXrE{IVuLWqikuw|bcDu1<@CaVBGO*By;n(4A)J59yK&S^V(pWP}a@rg`fj>k7 zC?h>Cqw|Jn8-6<2fZe8!8mABbSPx#NzRN3gU#FIVsnljt3xeKw7ha7;X+&vY8RaF9 z-j{`rJly3Qk1A^8e-p8AyRQK4(Po^~axuq2&!j5#c`%BGJcD$rudy3{+!nKA#6Sn#jNRBl&_>Q_QE)SL*8h$?1CT&f*=TjAP9mW2!bGtA?Ibt zkFuPcp_zHfWj=3)g+x5A_7h{r%N!YAZfN`QUQQ||ijV)wko153I%(l5gY>~QsS57? zIvj64frO!<^Kd-|^bBO=7on(f5+)YsfhT_FR?R?FVGJja`4Jvy!7CeILu0rIvu8|) zH+&E~>j#xvdfj!X$jne|Ck<)BINR-dd_?l_)p?kOB8dLE`?sd8;2v=SUzVq#^ue# z&1>eP|Hu{`94x`DYv!ROBOi0-%!D`Ch*$R?K}YKe3?w|r9XCPkCBW`dCy~&Un=~O8 zj;?Ne>(ve%5Alv*I%do$#CxY@BaoVLI!eO5aQ!{l$;wD1zWE;ZAX2Mca zoZU_xj#v~gAMSytya?|sHF582y_hq%97~N5o<0&lUw1!#x-Wz~uBpI+m>>5a4xqQ& zj|cXLux5TS=I0vJ&QRLAj%z06D|dL?aeVRFZWL4(V}e&FU2&i*5X4|CmBC9Hl2Odz z!nM_IytJhezdJCf{<`P#x-c%&K&U@Ny6M1_TxW7Nr(x0a62ydJ53)21(U^%a$=9Td zAv%tknp#@nb@0r+0la)7hMSg^!q?J;Cp!&%d_^G|N&b5V;@G*T4cii#`0}-dIIz7P zJN*ge>Q8jyxh^L@v>+eFPW~gF1y6<-D@$GY`P0Yny~7bKnU#ZFpA%E5UYojO>aS~; zJZ1t$(Nt6xbzt{zeu(2o+o8K0aOGrU@aT)!_sk2hX5NaD0$%#cQ}KJzbs&nestRfk zB8W#K>iuZO=r|gq_nHpFok8+8(Yfn6bc82h&P~hF{^y@#uwWhLuPnvU%`Yn#4tLI9HTqNth+CQT^I1Saas;EAAj~YUE z!0bAT4r3|`i=0Z%akZsE0*PoC3F+|i92kum=c)D-)%`^oJXf9r=( z9@~Xu`x+2ydKIs2XvOsReE|i5_1LrXBw}6raA^H5l&*O<%F8mTeyJX*jmoTEhFLe= zj7-vFZm&$si-O4|)NVJacIMKD^2p2JYD%E*+yckGMrvyvpiUO_fj;Q92h~iXp{^n6 zj@I3-mVR0WRT70$j&zKl54GwB<9V5)prbf6ZPX(&I0NWLGPt{ zIkE@FKrZ5IW&=mIL+=UGJMs_=e zNj{f6T#lS#m^lM5UfK$yHAD?{g5=u?40OWr!b@Kya&Z8_}`ej+O+&PGg?x#Kox*MS%55QbT?L*5E z=&cSUR?UQVyf)Q-?1L68M11uOXh(NbTR`pB$s_cuBe8IbaznF;b!tO$sIn9E4&)`w z1-#7y=|ibO=L2+n>B^ckL@h;iQk(pv<9;-g$at1sl*;8XbofYCp=bi#)L-Ue3`AlG zM;(|%{aKzJ$bGy7>0Fe4BlMi}Di{y-^LX2#=UM_ND$2zTz8D^82w_oWK4$14{JtxO z0QG|(X^!IUHHDZM3n}-+(3B ztw;TmL-hPrXFA}ZR;t45Mt2{Lk@$U*D&t!Tt4EO|596&~e6Rlm_ECO$NpX%d7azzN zk7_z*wG5aclAi-*^p4EYy(IrAdP%;#62YGcf;3VswT)2+CPezo){6)o^UmyQ&vV{x z#R_9%s1q6PO1#YxQ|`V%2j*u?!a^;8KTtc=OJmO8g$8h2))Y)Jd+~=*ANmu1JWRjy zJQY|)?NBmK3)#+M{FSc+rBw0BH-ZD%h~mXy1O7~H*G=ABIyW$$^4k^-(3ML==4|fC zF3v$sb_73p_&7E<(z}lS%P!5voi~+ZayFHR^@?=8a%K_Ub4?-gNQb$u7!o<+{xA-c z?oTXoAx`aeI7+%sj>j`GdLAM%YHKK<%dOL^HijL$+u+YD!uuAu@aWSm$eA-9x0EOF z{Dy8EKi-2s?u_8w@0x_dmTo+?CxBr803Lp+2h*06W90c^`sajaXC2QTG` z_n$7MF;yZqfX+a2FUYr&5gYQj^IB9?gq8HtTCiXNva@NBo|y@U!=bL74fQonBLmYG zt-`t+Z^Vu3)?!W-PxseRK6MFhyy+(LyB^DCPXLJzCWW28=o;L3<4w5!nk6XD<_97b znQ#@tPYUS;zx-2=HZOzZWmc+#M4euf-YiN7%^2e3!t`?Ek5&u}QiDs4Lp0ihy5swC zWbbz6`pitYz1j3IQuE6LHF6d`{0TFPNQ4H3@j(m(LlhUUmItz^1I>Hrbx~wd8qAn9 zSPu*gCijQt3~{3q>qo=x18DAVM`*AQZTk;nPak#K64ba<6d{uam!&mRF{vOI?i@GV znHnO4jo5K;H+lp7!HiDo=U6l@;g6BmpXA% z$2E(}@yS_UY~Im?Z*TP@Lgh5*4fyEhb_|Tm$BJS@y%c#5#{T{Uyxi2kLD|$}Lv8q^ z@=Q$4ccCQ1jq$l2j4yPdz)5jYeeLUvU{8H7ez>(0CwltP95j`4JKeZ$au&w>^yJc3 za{R}aPI@q=jmw};oPib+bcphh>4>90l=@@Mr4Dt-OxJkK`oLeKsyK*!4}Kf__O(E# zh9~OpKsfG#C)$Dl$ye7DMMb(G~^bRz(egqURfzUKUHe) zJa&n`7PPmup>fl1vFDY|2sShz7}ek%w;YwzCc@>Sfpn74Llqw1z)p)BQg~SK|>J+24sudjGo;(Nz1+&!~oYV1NeFZnZJ> zSy7^nISpeP2K523&FH5~ZkuTX!ag*t7WNRa$8 zXRSsVJxl2y&0quJsaD{RfL@1ma)+Ao)mR_5bHZNhU-3u+A3$vy`8i@hTRV@# zsO?TJF(s!uvb;Y@B1|t%3Vb=JHoeQOIg1dVT?B2{78pD0fB-MO%Oc$_faRoqSYO%_ z(-=SJ&ZI2g2nuhFBU$HBo8e_6E9rGk9yy99PVd=vdjGbQ{5ID@r@o*1P)r8ZN7Xoh z-UrGJ$uB8O?ciSMJ=D+VrR|iyWl$Rxy0qI6Ho_HWXW}z8xzGj&@E?bJ(PTNXFyFv~ zhuiRz#sD=F8mKu`@Sfli%}`q`zLAJIxHHR(nVHm&_8G{c-x_LnE2*uHvnmH8*cOc8 z@rE9}(j8T#w_ z^&=$^p>UUi)cFmbVdUTo*^|_A)Nl14#TFXdxhQv}*{3Z<SKwQH#f! z$$jta;-|y+B>gpHQCf4UPf=lbmCMsIFv;+sQuivuYj0u@o2mc!Xy7<##teOh*R>S=;Bh!ob z-d&Al*)iOE-!VLMG)(;`E)O@Q$rAFv4&L-JU9T9Db2J)9m`d*D8`7^0hpw?PJSWqK zxsx(bT;xF&>25{259P&fWKcY9Z9(j)8^j~eHe$=sKD75n)tG7O%v{VWb*r%}cpDdz z>*n=6D4tzH&xxswu79{MQ-u_|NUG0<2tn9ZJzgLU{$7_a1?t2Xqz<8cXxgeq;w;-na)w#X>Bs&c*my zOE4+37aJ+;u0xFoQ6umc%Sw1Fp~{aPYe6DsB1#I%s1;2hbK*E;Yhi@@X>efhM&=aG zaKgtMnv)9hUs(7rC%k_c54?24jm!)WT;5XUybfy4X#mOlr+BDgG^n9!G^v4$}O8;fzMrAjQ;L^?Di*AN28D$ZGJZl-Eb*GIu^DJESWPN|9))& z>gt2&C%-NG+Hu&MkAGN}j~prtsS(LQLq>*%1nKvimW{%zJ)~3eRaKL^jq8B-Gn!GA zhYv0;$N#;1GS(Ft%Ec)SmYrQEtj7aAgLtjUz`L%k#3$zYu$4N7UDS(IdQ>6JSF#Ya-#KPspXg+k5x=e1AU-Ka>z3ZK@+FnINbDuJ#f!Y_BlLjno*?%MW zG7sp;@gETEcc%KF1z%%F72(L>z4+dax$pce*8I&!kn2jobQ{!0P&gGRozu_xFXD0P zEOIC5@_?T2NDP@Z*JIfyzKBxm5KipggFyQ+)c)pM*t_*0>NY)rmd=P0o#FBER&VMr z;OBzI?KC|DNm+Bd&wY>Nz5J08Z|NLNz41L*@>l&%cZA# zXh2B`D4%3n?9VsTH8voPuY$Q~4&pbjLt>m)1ywWg(nZbDoHz`<(~HEKMaez!G^!Ie z=DPX)etAfmjSukUA+dTj5>-BE^@Bh;mD%M;&iLYAa!J{8nMih7EVFZvH_u?=FiO7U zSSGeyct0gq1`;!;A+d4=61S`%eWv%Z<)n)&@MN%L1TpA)Yk{1}NGz_Vmny}}vtKQ$ zcMg8Jz?O*O35eftjdG@U09rRS5{?A){q?|vYFIuhuU&SYZO6mhbiF$pwlQDH*#1pL z#Mg2Pk(fIhiFMZ?wu1MNqGflhY zl7-q(QYe_S=96wuh1S7)+ns>s8Hf1V6)^Kj=Eqv8%-j|bR5s22B;}jI^04K`zp67r z$E>OpkIC)FlKIqrP#x32Jb8^|n_edjd1)=jpf^(Ub^Sshlb$n*gg*`i_c<69-(vU= z%j0r0@i$WoQ9ZH*OoBgU`(Zlvl2S^!wjR;-tfwj(mJ9XF9H>LE?^RSoL#lIG;YvP0ef^-Sj+%%rNz-4CIoo z@im9$px0S)T=Hgcywut&IonSG_g(01rsSqmTqTZd-0rKy7qaKzvl&Hjkbbi4=nXt{ z&zUgkKcAk1_h(JUoz$ki7HUT?$veh1M)_r#Un(T%{q4-o#0TC}gLl{HIC3;Va!AVa zG{{3eo~Noq`8k{hHMa&m8|NT&LZkBYhvA00*7U1xrFi)RXl3PDxP9$-{Pibh;;&Zc zsCJmglsrL*)8{|X$9qHA-4VpL7wYl-XF74?3Wdx^OX(rfUJwQG@24YS6xG{Wuhm9E9DtLCG?N1ZZKzLTwf z=)P=B$_FA%y>M2|z?xfDV;n#D^uQ~F6EzOp_;P-gQ<9zbX0dQlUM<9LwD&r+g5yt2h^pZTvh+_&WmY?xEtbl=clZRnU+Wt5N4 z#iB9|&+Ki-ANO_RB*n+@y{V`aI>~=twO6^9HXp}-z1$9Wt`D=bf#Ypa6uZ61aK7~o z@|!|>;!MP`es3GT{`3j_&)xu*&B;Rlu?~Fum0k=40=W0Z27GsOCr*psl1* z(_vh7Dw1K?sKkfVC5uOuLv}T$FP#Seu4i%JrKizY-=6G{uwmdV@E7DbPX6OTw5uNe zJRh>NysBO=b=c50aQJ0x`}Kce;{y*OlDz~~tMA0xzxx)}ec>yZy?83BSKong#cm{G zF&ITPCBY%Lo62hO*EHLEpz$BIREwd6M`BIWD}Hw|>~B|s-LUX2Y#53; zV9uQeE7S^o_d)3O&E!w-H@-JrMfsiAOZjX1hZ-yaAH3kFKi_}%TdlOvyG+nyq0D`>+q-A5JHVYNI-n5 zBxT5OIBHMeEkI&=F7zXZpzk>btu2@wW!vFw$WN;yUD$F0T7L)0c_WOi z2PpkMXc>91c=!7By17(gS@TS-7fFX--l-hi`LK$7$qy}b=}1%+B;~{KuQwZJUJ#m} zXR;_ye(|Zx>X^f*Q}$<>^C2DE?E=>Y%eu4*iQ)u|J*3kIjzb$DU1v*4`t!m0<1e>v z+z7oj46VMF^qX{ooPMZ_^3X}~f?KemFcH%<^eC z+B=8`8vWSVZ(>nFHi``Ddy$Z`+%9c7Kmg`I!Iy zSeBcKHQogN+|-Z9+XBipM=douoBNEZTVDtF6?qI34h8YUqdlmn&ir#HyYZjLda*kY zM{6VkPnMHLU}ulxV!~sNK%xi#GjIss=&whE?!ywNN6CTVz5~nErDtN5D-+KS9>VuR z16buQMj@4x%bRQXsGdwTn8`^PTrl>x%g08#r2JX7Nq_#A|Fiqwd_79XCC&oe;)vtf zU=tn)~;3$RETb4;{mQ+*^k&0XODP&7iRWOM&D~?Ikyv>19oj(%O0Fx^d-rFeRa(u`8yQ zi>r&|;uOwqZut-5tk*0*zF*Y=-OFKAaQY`g0VYh#$Lhi;o_VPSPjBo)N6N-zhhsP{ zJue$y`rK^%=jUeN^XrN*ZAl4koaI4BV-RjL0|oSsOmFJn3N#Xq%EH{abCt)N!NJ*i zyl|mKH>!5#0CN2h_{pY^aCI;YEI7K71|*;*kJ)dO8t| z>u`{NK|ww|^kR!dqlicQ(HBf0JGU6wjtIIkC*r*~EX2vpPvQV|GMG?b7y1HG7`|*2 z=jTv^lH89m?C(WDbDWH_;wjE?Ax75+EggmYSJp@jN4mm1uMy)5z3@_8L24@syr+7_oJD0Q zB~EmP;HOSuWuXT}G^l-OTL+42O0l-oNNz(k8t{v_pbC1`awN9>3cS>DwBWyAb@YYN zJeYvf?Zo6_YJUf#XdZ|mOm7q(a~LiI6AQfRFGhMIf(Ksi#H2;#Sdpt?Fc?E`Oha)N z&x*9v-X-2_H}q%>e#=0aPe)IG6bYvTMO26F{y01t4&=Es^!md%PUmiq3zG_y(=`J9 zae9Uv^qieCgmT9w5{}|ncLb)3@>t|Spsg1V*T-?!(jpXd2Xr)Eex%b5mj@@;d>xOT zjHt;ZqX%hCJb?bTMub9C=DhL9E6GKqs~P_89(sO!$SR+R3@;5ZR1bvOq^@n)^IQ|A zz57mN=@A6Fy8#*yd%Z4L(E)@=R-S?!ME&hFkSu}ML3-TVLmiYdI1$9)KyodcFSh^= zot}Z_dU_VCH!B+yG&qC`fe?W&ejo!QSX|NMZg}E@e zh^3?lQ*zySiI)NrJbQRlAbp7sw4<-1gF4V|l4~_GsUb+pl{&j5FVmS1ug|GEVmwZ3 z+jt*Z^p%*uatbW!OAK}o!c$nN{-PS`??T+jhS$YiVIbHSf|r-a1-lUn>&Pg`LxR$a zYFY4Q)9@nLg`Va{Bs3qg%O}BUb|I9=L}nJx_!y?BW(2`*KU{_7a77xh>zNl(vf?h3 zmu66YRkv|e;Jqg27G+{%^Je_|;9mF~$>;5YVIzaz4{eZijR!A9^zM!aq4o6BFI~^h zg_TY1m0cDpufAgsP&FTBN%Ebc1p?FuFkod+IG%kJ41yX7x}REqFz zl&*SzFF3kj@H;f`K?UtrI*r!Q6Nm?ggYnC zK(@<`U)1g#J)P!)L)b(%(X+er2&~DoC@kr2C_r^W{RIxgt6~DA zzdn{}h?*yoTZWT#dVty|)_c<1L8?~|wI4jA*G|Jr*K)H+)EtgN8NimRXQ zSKo!DC9knc?%DcFBjKIZTi+`KN=i9+)?5t8Jg&%K8uI?huIV?z{_KK zHW{^>?Q!ZuQ~%JUXR*uFQARQi#}nu$eJrKpIHg-p`X14eWf)I7Oiu**NNw|}{T^O2 z-s`?MZX%b)WV{lfkN!qViWt`WF(FEU8>nia>%M1Xo{Zd5zmYLc=o^Vfn6 zIIQL4Js#43#L$_DB7^SBqyz>{ULNa09))Wq85Ohs@$y%q!_rVn=TSQM(}Pn=X(#AC zTbBq?%VD5`>d{B-cRz(Ipm$$Nvxne6G`3NDl1pPa>iwgU%F#o0o}qg%$?zhc=)rw~ z0o+V&_ykJ-yk$=M=K7}(AXxe|y?&`Lo6?E%f(l{M0IRtrh(3BB=Fk|ik_N^awS_!3 z?dzlddzME{oK>|zI@v>GjqH36+*Ahk(;Yfm_cr0NE-yZIZ9cvFk^{Dm-YE6sJoH}C zsJRcLJMKU^RYF&H92xl}Bhr%&e*$?l=F@3hLc=E%j*<8m~-^!!N-R*b_tX1LYT_6vsU)LHX+^v7~Af#Mwr=WNL1U>Wox z^HF2V#uh%FHEWidmB$~w;OqQhie0;QsqlX8C~{*;;*Td>n6c^_6HsEZl} z{wo0+2$QonlJJZcHc6;K8RbXknQ`RL;oNx>P?a0S@rD-aDDh>!uBkjFe@!(jPwg8) z$2@(Pm%?##!}0LIWGMgYUdkg~RQaIByP~oJ=&VB{4cOIRc}5X_M#sXCXT#Yws2rSY z^%t#Fb+A8q51kJ|vgjE!k)7pGFGpUX!eLlCJf&IZIOv4qR5IiE$?>G7^fO z{({5T`1n+no`!=Wp&%;G7`<5f!WQzfc$Qf5Wicv@p&^f9nQ-|z!#v>U0-ZJ^DCN)P zVfn-(G4xWWt&le&CO=z_%qjU&oOB1jlTLBtIer_Xph92LoWJ&N6LKdJ(iv>y7RTXhv*n%Gh zhvm)ycXY!8{cvU!!ok}IjFPN5{V_A-5xfjSOD$pJGO*6ssIu|j$cKu~GKnDEAAl=| zI&^fKsuQjczRYr?z;@X=UiIN1UTUF}uF|op1Ma$WIuu^D&#F$jE+{=-%6UdbrF!9f zQoSZ30p4m0Uj7)vsmzTEV`j)>l)&hhi>LBUC#+}6k37@M&HgbeB=6tlP31v_<#5SU z)fg#Za|8q*a~d2sd)wDl5b{ron(n9T>DO#H8dV=@1b9{%rOzAVr-vN{#>|k%1>y2> zdD7*o{K(noN_IAM9HNnilinG;Jo7Z!u}j^j230Iy4#S7+N5>pS#moL_=j>&NONZ~_ za5ntz3PjW%W$NBhWb6!igep6`)VV4%xzl8l4tY{LqtScG@=;lb>LjJqe9Ukhe2wo< zk1PE;d-98sQTL}`OT&Kd82f%UI8k-;UXk=~(r*+PTSFd^-iFvR8}cL1ba``G!(qB) zB$vjg%aP&xIF5AxbiKFb&)D^3r;#2m9S+0SY^c4`2B;0;KVGQ)uTuV_z-Sxt7|y;j z;n4r8KbUsmtoY1*V;<368#FaNSZ(r@V~Aeq}$cp;32AukDkCW6bJRHIbSLBTTS zeqBndNoL${W?7|=5lDX2hifOf=ju)sSNeTwt0b-`_NTDP_>+=J)&b9_W4R~O<|{@j zo#f2ERGp|hUJu7fJrw#cdCci0)3y+@BIH~spt?BQ{pZAJ8uC&&Xt2g*O|H5+CC%hm zJWak7Na-*s)~QfjUnY8c67c2l9_UFwwhQsS9G%i@HeOOCD1UW7`BC%7adCxHv`Vk( zkj8@?3CTGX&c1d=RNPc|q|?0vCUWv!aHQw?Lbw1!-Z|F_D+n9$#*ZJ5Ns}fiqg{P{ zz53m~d$$TRZrnJ`oHk{ zh!jB5FUU0DID%{!0j}YAIF)xE z=+dsej#OH7S$Aiu8GXYtcj?2r%yQsgB_jG~$ZuG=`I^IZ%819P@Tp@)=_marg_rV6 z#jTE0*BO?Toi>wx&4$l8OuF-U=;0cDBi`6TnLU$S`I!CEm1imx_p{`Esga2#i>nVN9~xJ!K!Y&j2O~uayCPL!^*<4;62pYh-aUt zhq2>G_vc?b$Z28eI6aN@aOrSdwyfF3sonN@VexZyrtp^-oPA!B$^9q0FUCbpKTn5e zzZIs?s~k5rt3aL$nK zYGFSbPd1`2M8~8==W8e9nIX#XmO39@QpUrpNXg%*&AeD#3V9f7xH*2S%c=5^I=-Ue z0rp!>+WYrPCcU5WmO$yh<#`aUJl=A>PW@gDTnc5CCgkF9h0FO;d=+t?u4J)aie+Q- z(v>W8Hj=*8<>NeDDvZdG7mY@hv97eVRCQk2kjKAl-0SM-O))$<6@VF$fKs9!GCS2fDlb81#2y-?mLS)HHbd z(lJ382|N?dk(_NO2!bF8f*=TjAP9nRIdaa1Jcf;PY_L0U;DB0E%OAO5L!NE4i^t>Y z_;e#)3eA91kD02Vj)PNDYK5jVEZO1U##6E~`kRa)FdaSThG z-I=b78(qgs;(6~KabxFr&mvwbliWmJ+*mp#XVU94T@yEY&fb`x<;}-u3L|dxoZ7mC z`y#yGpSZDgtl4Ms7dQHjWzG8#5B2)Qjh$mTkDPP${AHclrp3NR2&h(?bw{1G9yp(8-D zW<;&W4(^zF3WVO$@Ngs3KC0J zQ<6IEBb|4&W|xLwmkGd?ay?Dsd+KU6rR+iRY9As(j#Y45% zvJCN}z_ONQh+~iF^uTzId># z#o%%A5JTR@LG=3Ka>0A#@e5U)xN~>9`o%^3`nP2z5Tg!BH05H_uv}K?4i~&`7xbb2 zqz0$Q3%ApeIv-thrweY^*u;HlW6RY@os*C5fXC~B-p%R8xFXsZoQPI(;-{j3S);xy5_kkx~41RPWm%+HNx$NhuToD z#|>i)8V^l3;Iiw}xSHDz);G@>zOOVm_#MD?N&TIxS*^L>k$hiy;c}enkBmC}9;P;g z-BsR<2!e2xVf-7x2S57JkCgRQoVasxW*k~(9vq8rMJ%4coIUSgz3=ANV zNMP^&eM#fs8L%vqI-wJ>a?J|No;nrNr%gtFZ~!g6ek63A2F)5wio;U(TQE(|r%8@Z zmEn>7%#?rfFAd3X9EOf5j0#VkFwO(VWpX*yC61HtO@>W|XG11=UuGDFfkpEdsPbJ* zbgHA)-G9O_*Vkdf#A;-@NX}LO>mU3Hw)J{YQ&~?!eMW`&xR&5FAgLS}egDJ3T6S#d)ZFfpvZGYBjTj#k1$+jZ}x8I2# zy!6LEqsv)@aYa7rTU*z8>kS!&8s^4v)RE8;P9ps4B`(?a#&Lt+~@tNsPI!Ro@0KOb|u%{tA`#3`Mo z>sAo^Hav@m9(xkoj&`GX!X)Imxuz~YZ>>%n2)5Va_YeOT&%Uw?gU%d`FD-y0B{!wJ zBox)BVEMD0)qBzwHS03VmJTT{en+Yz49PkLwN+YwJsx}FIUKCr59j!qC~%+B{fh<9 zRA-$&t$h>51eP`T_k^)W^!nnV)4MT3dYzk-lkzz?uI4|>36~Mvh`2oCv25;MO_S&}oqB%cViZ_zIL2<-$Ro2d68C;w(g2**NNq6eH86 zdKAgb32zE_(z+VA<981}g99hJp*!7(cI?HkA9x5Gb{s)Wcfl~jXg+oT`;RmrXj0P@ z9mJ;Je+$2Ub}O2@1FDnP-&T+PwTI9)5L2DJ&_F->dwX%bz8)Qcxax50jD|{8tMPY|zrX{} zZAUN3(Mh`4M>@N2{~@#w#HlTbqiOGR_@5s?iam`TNRVV>fi4{4x@hTzMS~LMNcZ~& zdePB%0w>%2%BZc;fAL@h<#X5IrnxzI@z*~^Z6~!&V>r=4xC$XXb_9>%*FSv%uIbm| zw$<}dlI2xxcx<3kxkCqP(cBlIHkkZEedzT2(OiEB^-ZmG98m*rGu(@&?ml(jKvyI7 z?>~U1o)GvCGs$#l03YwgpC9@$e)!9$aj<2OIgkJIM5p_9~( zlfI`UO)iYVL_Sumy#YQ2SAf#*RUHUeY8< z;hY-v6aV}m9{k;7%C&})e-sl0LAV+invr+UJ@+V&b7i=7_G15KO?Zp3OlVp8a4fo5 zGx99BycL)`BM;lRY(iaQC+KyL8{hv?%rkqirz?WxAN)9$8jT2L-H7+!u^2fSIhem< z4T{YMoCp=;-Tyy(=K&bURp*hV2T34}^xoqZx48FiOP1Ap-PM+v{lDMaU0HTyM|LdPl71iiX=mQdylJm~=l9;b z`6d*l#vvs&8CjW`Fx%o$Hog!sh94d6Eyx)+39U^Ps0gOwQ=hyJ`Eg?VjG2h@RKaUo zh
    h-9Y|CDRvUY)m_L9IclXj^PA-3B4p1dBWAy9z&~cz+{WXgt0j|zV2llwxr}4(7eK>kxCw8^jFeb^3m;Ucb?5+orGjm~W--pMaeFqgMj$*_9lgKV9 zM&sIN@arcxpxNJzsFXZp#adwm#rteCkdyC1XO9(=$Bz}2y`jBdf-0@_yob~xPn^f_ zb)dH97>rIAVhan98`X-{ukL|0H3#Wq%P=;!6@P!~X>2`Ifdkt%p*FL8R%S5xVKwUK)!$1>H?`=xFkz!EHwA)Uhx%?Z$iC0*K8`!qh1f zfg>yN*ek11UU3{-cT^&yAR9+lK80tu90%evP!i|E+s{6M&4;V8ciS%bT!pA;a3eji z6TkWW?{KKrfMIbVH!B&cp~IP+Bi>IATv{h~?X5xKtXW9021T3?U(_JeH%=47rramd zh^#%tA-=BXChs!IlZOb9V<&Q&Z zv`OR~BKPQNgU6ALBvG3Ck_s?6KVFngmuAR}OJTi4f+yi?*^hVDRbt9jS7OGPT)6BS z>JF{NBhRl!W%V&pCN?3rtQgy#{3agT)CIk(2|M3ki4(}iv=TdB`PI*`&sL1M%C&g< zy{)J?x)0m;ccE}XF`O#p4?#FnvQUtdjm#uq+gn?ZI)4$e97C6PM7Wd|d75|@mD^Tg zcXuwXTQ(O3>4~reyG7mOuXtl?xp>Y8Q5Q@@zN;4h`>p@QfuI-NH7D@$%FW20I2(!W zAK>5q=Uo&`$;J8?p24Prln%C_+LVs*IdL-n1Qk27^7BNVodTm~H}<;Iv1m#*luHn= zFP%l6$ZN%O-SPH2=*e4%s~3noBrXbiM>*bn{4s1fUXR`T55t;K1oiNn`04+?gJ!h{ z_4_vAt-bA-HFF{wH$IG?z9sUK!frhF#H%<`S%F>KcEFTfh8&kg##`#KQMF?=*477* z;Wm)vav@{x5@bgWeY{+KWmFtnvvwd@aCdii*Wm6B!3h>@a3?qnGFS*Mg9dkZcXyZI z?w)+}-gVbK=ly#1&)&OxOI24rRl6S2fD}cuGEEJU2+cftd=Ff2{}Zz0LzLnn5n`4b zn_(i`AEM*Z$ZhB(s1{@fA9R(3hH#`_=8Mv}HjRZEQgc%+M>!wIWvPd&T zG*e+bI!ul(K#{XZnbYibMi7Gggs+y5(92`S$|#FZR5tKWXUDJw-10EpyQjS>I$S>-^bf=+iM)ygeq!z-efduZc2X z)#2%nXII#-NfIwB6S|_Q)X?2$zMZuu7OA05l;t_~;3|=)kLyj-VM|L@DV0LGU>fug z8osS4BD|Oo`Ak`Z{b!-8mz=H;r@yada_Ipyh(?IeU(T|Bs12mW_!E_o_7~yBKtwGg4Z*T^&toGi|+AywRe^GREkNb(1)n;f$xwy;` z54Shj{7{#s6b2H2eMjX2;T?aJ#z#1=c7-B1{2}VYY^(1FZ5X1;t)#&g|n9X z?9kNzVCfC@a-ZKPX)PgAG6b*WZW7 zg5D@KJ<#^tbA2=dMJW)WYVqc}{59sMQk8 zivkW==rvDj0ww~Uct{RXwft@x1G^8!++piS5w$#cEw&aFlnk|irJlx;)`OJ7PaBuJ zt(aWKegGk#;a+v_#rq4a<>nSbq?C%!K%<1X)|5Kw%@6GDHl>xlQR%dIM>`ZEsnHOw z4VZO@l5*jomqpg&CtEbqJIl5;J7;h$ro%Q zVKF$ob#!zTAMX-3SjWo9;*+CFb5|HS$dW&}9ckwpt-z?C#({^i67Mk3%Hy3#`ko7T&`WF>xZ_}>7=xnGydZ8 zZJ&YH>g9?^j_3_$mHs>&WfD;sDZ-mqe-|AKA2Nn(m4wOO&XSUZ>{gg&GqTfYZ`(0jvkzk7b;C&0UR2{wFCVcOq-7P0;d?@{E$M_H1v9c!bjxTHcuSl1YPy^T*9|Xw zep7Sxm*LYyw!@>wq!|GF$~FgmWfM8d==B58)!f-uea|9eYodX*pK7jY-RkRse)16) zkNHD~5p8SmkOU7G3KCx3ge&8P^wxWUA=zn{dsuXMN_0Ki+t^Tr}BGGvZ#JY6Ei&=QJHt=wph3Y z?G{$J59jD3N0*2-WA4UdTS!=wqt+cls$*TCUHu6_qm3i_xG@K->xazTigrMcM=Wx0 zb3d!+b3Am;RD?P|VnD&L@g z?Ioq}>6Hp(?%9TA0ZcNDY?U#vODVDT+Ky)FZ4XAZH)zAn@SSD6j4P|#vmc~uX_F+tZzhtM} zg%lmdg+R-YoXoz5^R*i9TdT9x1|$*^5_%@4q_tuHWkC>g;W&L(1G>emg%m9rrt$2c zvNWKTB-~uUA!R@jO4;LTrzcR7a>iTRD;S)I`y<>oY3S-n8V{rNW$u<+>g)I=-jrTD zp6X|5dmlz8OJV8BNqL3#Oy-{7GOpGv;KUmaQ6Vg8iy_6IG!ICOI?cdD zbc_5nx&irqz&_=58zQ3mm(=LpS?;@evS13r#k;RU+;AEEANjJUh$J8TiiOy%%!RXG z))c4LJHq{O9Kk~Ln4M&4M!t2tpnYLLJM0Q_>D9?1nB za^dpt+5fy;?Nv{;lis?H+t@qGnkJW&%sY%+B9Z^fMSgjat=>ooe)DSM20f-(sHf-e zO;2u=REdU)MEKFOjE2bf>!?bS*a^1FjjDthbiqb|w9U7&U8swH${lh_wllFwbR_*6 zm3>abbEo?@vv?e|wt-^u{YG*!VlwQaxE@_4BTjrq{Vq zLb0l>l?yVW3vqzUk^AE90}KGNjjyC$LTjd+46oX%jH zF)`KbZ3ic_WM|Ym(PY1YIRwPiQ30R#26deLVFLr&NSQi`ctZ331xK;mJ(ujvMY0m@d-%`$#6vu^d$YrsFpqF(+-nfU9x7pXgaIUpCWytRDY9E@)Cjr_#F?Z+yBlZ zRb%5(2{EFk?bQODw@|gX=Oa1q@HxkT7}07QtnP0MPxFw2VYP;NQEwr{6LLzi-jjP% zPz~-Z1kLwETLYjj7p7W^@nV8yc04pr9Uz$}O~BQ(*xn`+oxHWg_q{`MarcAku}&b_ z-y@1I9JKPHe-kFZ4-HdMu(7ZxdlYYU1&aCj_!M*vn2X!nm!H|K&CXI*-0$x0PA@Oh zgQ7lcp?*>UtB-va4+b7Avf7Tws2J!+c~JQ?An0Et zbY10EeFE1qyi0{sKjIXFuhZ#Wi@#!$`~sREfrIfkS>J5}30T8qhr)aFEqHvH!OF&N z_xL-17AS=Wm{}P8L>%?y%6dVJ8WedN<(g45kHWiBZUy2J#^S;%T8rJP#qqwePx1O^z@$hTRp!&K|a+?q} zo(UriWPh)rft8C|jHi95T64wEGDyY_9j{QnqSvYC)!I7>>bR0F%(qm6I-_)~H10ql z@rfy6=H8R@4vC}#pmRtt=U}sWcy+8O^2m^OEIF$8@R--KQwU*XdwkTyos#v-#mVZy z$5zRVj1piy^LZs`_g@C# z?oAw!w0wv8R@)h%%$O7LGXT6dn*Gyz@I1lqJWI8sn8QT(*l? z?d(FjN@R$hln}yUF+{nv82&TcpLE{`>Y{B=fqHPTZ=nv2tt$}wxNwf$NrLvF!jJUw z%xk!eaZResU*I9$YO%<(nXhKRq9M;{z`1iq2)80_bW>CeTrqkKy z)w4C{v2tQPi@oW(K%7nbNAo|yh4jvgd(YM;;uWr(7cFKCMc9Yra3m#{98oeB6lb)U zB1ie5K^8=tJzFN;IAp|*J@a2ZO#!x?_jpJqGu!{c79^kB#Zal6;ohLsCy@jE+Ec%z zbKG#JLObZaFCuwe-)om3TJ6NGRecuU#4l(?Gm}8P8t0la@7sY(7>fD1IG1(69Wxax z%Z@JPR!(ooWXR!htW6)oLnTm!UNq?7b+hkY{lf?(^fLy_y+9M7gM;$6SmeP!=bDg% zNwc|7=q>xxE=Jg=O6F8u`0qNGm+QHX-tEur2O7-;lP|$>8%{fyY+Yd%4v06=KvTEH z-V{#KuxnfxWF&BYF#Toy_9%_(PVK51H!qTQhRJ~IWlr}z(Pck45hhJU4RQdfY-_0I z1y_q~CD#3PaYw2NxVvk!&ZMdpzxq+&~&E|`8Lyty2+ zzy5p>0@}b2>&N(3=0GDgY)Sbt)AC3X>&EQ%y1}gZ(GO3_t|T%gIMS)}_%TTKUlA!X z&%1`Lj`!^YsgT<^Zlrt#$g_ED(SC)4;!AmW zdWcZXr4*3{@Fu}DPEw)B2A@Y4Tq`d*ld5#YLRbCmQM~?nLT-#GdbXDv|6F^y)m2P5 zjvJd+mWq}^*;u#S2>T4aaaYZn8<*8M)J>5{g;*dmwrxyWJeRz|jkGc~Gw7i;X}Rtj ze5ubayXz=Ezmi}n=wh(vhW02OWo2MbJrM_OW8*snqRHz?i8w8yHl1j7xPmFsBQiS* zD6tKz-u(M*CjNdmE|LHEJO) z-z@_&wj!py(fejFH13$2mtBu_vq19_iXB-Lpf%lQ#DKZP_d&h_0?dZo`sxCiSb1Sh z%rQw^!f-z_-0L@Yj4fzzf=#U&9*%S;(+ODaGL|qnC;;wNT??a8q4%}$nNku3mk~x} zV?%P?6ysV;ST>{|_j-Jy6spRrQ|lL~-^d3qnRXa4O^QIW9cxu3BqD+U<-N0aP@!AT%94D`WQd!|ZAG6_6E?Z7 z#JTnx0DI|B;(>)jH^Ug_-Aw|{@)YWtWq^3x-eIc!uIUY&cdSyRREwX|`Iad;DZ9Kj z{mJrW%svIaL{dcjLigT67qODx;#Wq#za>>3ep|J}0VstnNpcCGx|3o8oAQJywHS(? zWK&Dxk&9i^zphZYAm*IVXpveHPM(Ixc)?dGE)HzD5ld)4!6rIo`Y-Zpho29Xv))s8#(EGcI{dpl%e@N;6<*@02FI4$8W9!usTj0*?X~ZlUoTmVj`G;K79OuiQY<;eoE)KM zjNvU)oE^yjHx~^aj9lnP;gUIEhjEYRgT|>b=0}$tn8`8;bd3^@KmhKA3lim7pGN`{ z0WW2mxR6IPEtxY4>-Av=jtqYUto5tKvL^FQ= zj96d)q7Nu3Elo`0bg!YoBVc0-g_2a1a%{yJYP{%=LgjLq1%Dk-qYOBY(x;b;4HoD? z{u(7(?tSZ!>721+TP52jhWHgLdK%!zwRpxKwLYuCFHLc(KoSy+jkZ{|8fp4Mtu%sa zK6m1N6vrYZ?jsCNy5XRh3PRiTg&*?!l`6oBlg>i;6>AWDz72Q0cvd1k**_9_S}Fb2 zf-COa0MyW?8W}8s0b3uJ63#fklx(r_;!f`r-P_)>Hvl-TaoIB~_@N?eTubsvAB&yB zXlU@q<*u49veguQ_*c0y*?bsGJj<_-T4AAtv%m2G^MyJ;e$=YX7mea-Pg{z!F@DT@ z56!`jk-&ku$sd(*D$ECUt*d6Ls`uiE00}5rkohn!UB0(2jsnw4y49P0Oq-XO$qp+J zy3c`GS#~5sV1%l!kUqJK>r)iEV_rwb^UnrCQT267QEnDW3)5lF_G5~;VqPQMM00;A z6cdrPE0JRp49|A3$=VE?!VAEw)lo7(jgS@&-o((i(e#?V4;Q$}gJhYIiUa1@h$iPh ze+ooE|7v*DqVco2`a8v&r7#+woJvRZG)LZE|E-v0KUE3fB55jhbL@y{4@khMGO(sb ziUG96{yTiHe3<;lS6W!&;Bp>Cj96%(hB|JzTFT&;ip1>8!>qgUGml}7a|gl z##^LtQ@n|srQm(0S+*XO-&tqQn zIr))WE==Ob6xe}OY8zC^c$zKChw`J3xB-LKjzrp-qmnP8`I=LIwT$+XBV}PEpND?Q zZP5MYH_XI21V1vY(@)CahZBS$>kU&4GlI1AYfmT=EFLd5_`Pqa)6>%nsDi@!gMr;h4LW9@4a%gwaQT_Rlr)G~E6Po(dpRk;plB-$&9N}{%6fv*9leCU z0ope~^99)bbb>R^VCZuZV=Yn$3*wJ(DZq?>nL2VG`#<+B0KYn37MfJw5`xs*rr`y( zN?)wh$vRS9$2BJ1-lb2#=k)>0?<}<(eaVP;o%&upb@C^ZgUex1iqWbW9v%}2yx>v& zt4W!*jG`pn9T|Sl&}uIfq{{V#i(bUb3s*!8mLeer)|Mc~8p`szL%H$jnjJP)EMHA3 zdU-6c?v(YSLrn+#9xli(FQ*qK=;YUk%b>%^HaAHs8hKsn5T#$Fm&yo1fKiV0NEiQ@ z`1o}mSRq&@D+H}(w54rjIgg87Kf{TgwizUdJ0NlQzQK!_l7a#@=aqFAvPpxczi(Ub>B7g4n*Xs!2dnHaG<;6?TJ#}kh& ziYfDop(CZh0*2}CwXj_&9qL7qJYghv-PVX|;op)0s3y7eeB-LZ>{tb%f1is7n?>Fh=L zd#BlYEb+#NC=6@%ZLCL@q z7e}DR%}K(Ge9Oi*J%UV6I9%M4!YhRK4F z0R~VkarvzEmJE2;g+2bZMN(lhiJIIc+*H3R!KQ=eF#wNTa30a*lV$UrjQwgO{Dx=^ zC@K!m>^QI5bQ<}4De+?*oRUa`lEr0M>vE!)@*^?!Ay@_>_KR#to?XYHi#P`IL>xiw zXi^0xz=M6o72+}AL*?f9xcrz z`UO|S0#^hMPrvEwjK%a0zlhr~Kg+1JKmzj6v3OW^1C^j4wbzk9-GwRKN1sKFVXUbv z0%4y$cfC_HIE(}_cpend1YK)OwW{eLS7QlMj7<^%0N`R}z!-Vl&%(muBEyXN#F|MS zTuL%Ba$Rl581o%oIac{-1}F5M^T1^X^5NJ{qhn(;n=2Gy=2ll~I5^KOEtw2xP|186 z0diPJ>>)^>l;#nv;qV}f6$?D*d?{~cBeh89f2C=&c8;B-z2%}8@GF#T(0Fr5j~-jRc$bm zlLadoD>z;@-rd^Q*LRpQkwEJWD$pzHA0?5RH)zRACCaLTs_EJJr8<5n#)Y*ue&}C1 zu`e?NL-0G%ztv=4471*_#eYen+2^Ww*}b(I3r|s%w@*W)|JFlR)yE`MPUEQ@vms`1 zp%)P;#xX}#f3k=Es|x~XpRjfY%_2FpZ~}Cn4+;iQ<2mm%>&Cb@|9%f#hB1ZHY=Qj$ z_9Ria7_bw_3Y5;SJUzO&kReA$c>VXM#|U#Phs+&^j#whTB4c1bysOsC6sI+S&;T34l#=QY7#3FaSnadr=Xso4b1tgi_W2 z-=8JJ8qh`N(FWNIBW5{4*EONSg2`VlnTy7c{<9Mn78W2B@6`qs_Obt(*zrg@&U!r+ zmAE$&db_8`b`E68bZCtnV@~)2_wW`qz3zWauvNWtp5U-Ik~aoYJ4AZNbHvCLf3gmY zr*UCmVYxbTs1nOs4QGohOAc3pg@^WN|3@$f(!y`t8 zx0=e1ZEogoc~?>&pZ@4vgk$=w%ml%V4nL-=qV*8C8Ds-A8e2E_yhlk5hIDjXw9 zH1MOJ*NeA&R#!qxkJsRqZ)K`#fzw55vfq@F(#OU>%&R8||C6B0^obBbZ;$=!pjN-E z?V&qrIB5=A1xka>?Ne@KU??VXZbc!+1c^w&F$$_U$@zr4&Ba~hk1KC!rE^Co3CV9w zUXO^}bvRb%!6=3V{~8M1xHkj3Ws8iF?d{D?wds-^F+3p4GrKRgc+RQT%8wme?K~zIiH3nMa5Ns<*_` z!l)Fd)c49DJd}wU;kKsR1w1tIBKX!sCap>?7Xp`!sG6BW z-gBYlwM!`VT^s=VH1ew&&i|%8yq&HFO`il9C}SCTt=OBDmx_*s16xO%jdJSsQHCdN z$6+00^4_JoClsg;`Yw+ZfD1$Dv15%EK#KP6z!hwjl)OR-sN(zci;&se&_uDb^Y!im zaxPZ1o-sum#vjG&EU)c)Ag3czM-m6{C3DCqr0dVx`_t^y*7qr5se#2G%K=~#ZN2bk`bop#=-AjFT;HaZ^0}p1KY1Bf;l;+rx-_B?vVqpq=%=UE zU5Vu;r4xBRY$SX~{uvAmx3bME?uDsK8(ekGb(=IV*QRNAXZ;70xEHqOkYyDVctIvE^8>IvBT@Km;{ym zoRmp~l_L^DT4L^k8~bS#w!3bL9ZM9!;EK0X+OoG(zoy2mz24Vg{ug#G;cUL&Umef* z!oZh84bO&$3TrV$NPW|>yYyK-V4K?hfm=%2b~g>UTnLpt$y;CV(d{(d3Kw`TDtt4# z#;>!5nuD6kP1CO0<|b-%R?Num)`k7Ww{>l1X5(XReNy~aTLngN8E9M2p(*n6v*cIU zRuOqQh1yZi(zNpGR4p%&jic*mcfh7;F1#a%43Xt^!^Xi@yorx|PFf8us>j$9epP6L zQl>Wb-)f|LTQun3iVK+w`9Cq}R%j0okI@yoq{Ku^T@4q@u-`5%+t*&xTln6X5WYN3 zP&lfPMxwac!DTeKIulS>z+mU z@2W!bQq-+19R=OMr{y|!YdhRHM=zAB^3CXi8qN45OIbG`(!}6cuf2U;b+dw8ZaQAe z1iCNNxF`_|5sN9gZdO0a?~h(SurLy67RQReKQvw62pO6(rG|4*3S0Y;a(=1sy4?Ti zoXdh(SV&MJRAuVqkDfMA=*)XLknzoI{PhO{Zx2mfePn;{x}I+5oWMQj zJ&ljqLr8(IM1S6X-!9M1$6^tgbpHkV|G6uUf4$u@k?b&$-iuqhy1o3%m+iG%<>j!U z;$>EJ#5h@&FWX-ukELzDrpsE{|9Rm0qnd&XMzNdtjNkJ6Y6idBsq{kY(6v*Sk8%GJ zYWrK)->@M*t)8s_%&GU|$ESC)zmZ#_Z^RExM>b-uh+TeHVpmUCpq+hfvThRYki!Yn ze||1jwGPocbSq-@g|^??l7fqeAS;&V zXpx5@eb}*Tm)+^z?5q;{z^DUS^9Bn8x!&TkF(fjp8D{L@N6#;q&qi9me8G&9wvJW3 zQ6A(+w!I^bKh?pDHD2(LhwTANX>03Qc!jV2`tT5o7GOD1(pVz%IMzEH!u9wVAC}-;n!K-@#fdI zr^mn-N@ASTtJOx@m>dzTmN~p_vaW}(Fx$!fS$|7t$pQwpo2DtC=aje3p8*So1qFy=3 zq=stotF)>$2!WPV=nA@gA}=6V>!HniHbDenHD zmE6w|U!_S-SAhV;k>xB>nGhdn%^%Jd#X43YJ5gE8HQ$0{>~+1tZ;C7fn_-xscP-Ok zVTVzfOisEA>7!D-{T=UXQy9aRBTvurapWYR6-yBsv@5 zB1SW|@40uR@`J(a_RGw>M&5$c=l7Da6H=WWxDj!Dy-Rb{8&NOhz#A9SU@rl|307iJ zBR26JmfohpeDNAbo2nTG{?qe$dXgH zU7bP?8~*&x>2>e4&6k?oOeifr?&Wix687!$>(3Fmh)GtFJi&RliR4&~xs>$8R5mGN zs6y_sG;UrUqPDhQ8`exQvqeGh0W}NYw0;jvCwgHP?Ci>q<|}qJk*8NZWY|lxyK&8Q zFWTcC%j4!#-_ab?YqY4Y)ypFu2_F70jL^$QnK)|yEV5*hx}ytUJJ z#al&jRrUTh7u~&`p=|LL6g1OdUy?tkRj@zs0Sop)ZFOn^X)bKL#R>;06w- zC;g+uQq`sV@mcBU=+3y=YQdqK>wp;@z79_ zo8qr0oeI#1X$Ufd5Kd;gwqZDweBD=#;ZkK%N%Lsr4>HTijF$egJ7Zi?UlBW}T3*mG zVko;3T<^)U^@_h9Gxa8w?YyGLrHmw1vOpVsJYV8lkFWOHl!^aICrSNVzWFNCpfX}>Ya|(UvId?mraezhh*|tX20x@VG(?0v$-tgs7`m3J{tKJzmH>s< zNIbf#Am$GvFPybvVGLnM&iFFRAegntE!&-NP~rPai{`%^1sNzj#^1kowr;~=;#yk; zZKEC&C`l!(UD&Lzg%VGey$BTnH&*LB762ndPyp?TSCeA;(fA&BBWCHIfb~Ka^+Of z@|a5dofEI5`~4*z$R{HcI{ZI~Ey{HIe_a6Cn*l&>rtC|FJ9}kC}Zy^8R;^5Zm!6 ztHI;{cd$ht${QdB>zw(CodvUwJQofAHEpRF&?uTqb8{h$jg7b24UM|PObiSOq{v+4 zZesN@=KX&6Xn4}Y(LkU%q?XG6y*w2|RciQ~t!;}lh11FWumADMNxvr=e3-KiglhU3 zCj9R=1UajRwnt&nDf|Z-XeDEGuju%@WS{Ww!Et>Sjf)>jGWxgk&pyun{l7YbAlYyb zgyX-S>H9!R1!`dr_lgl#o+}{w1p^J`eQ8xEaMs5@?i@5*xpf&aVi{a|^T-iSpdvNP z_M?ki2c?g_58h}AGMX<3g4}(`Y%+?kKW`XZ-Z?CjjHWApPwLEkf~R?QwxFfwTqW0< zfKj&RJPNllI>SQ-BI{A)h4bRGTk`iZlrH~ljJ7zIj=puFIps7%2op{!+L=zE;&;2N z*5eKHmqkskE>_KAymZ(*K$EFA9bu+|jV($z6PWpMJS%aD`e3i6p%Vg~Mr&;)?`9E2L-kkP2M2k+V{FJAY z7}uMGOHYtt4^3DaX?dV9J)+@Q?a0?upb+2_uLOvGdx-P!{Ziid&%D8ZTwr z{+>xta)l!2#aq|tT}_rgUR65R3(rDOk>M;Ah?R5NJpTFu17>jpMRij&uqY6(9;!eEgT+4WiS{_ymtNpxbbdCQ-zu4kHJ zlW+psc$znorT_)I4_$w6$z<(`a#DqSQ7gL+RyXfEk)z^eV{tIAttQfGVB0#?(A_W! z3V3;VF9K+n!*d z+fj;)VA&2!5Wvy3YTW(RYMCWP!xOjm-{UbrTcN!GRUApqpH_*H))LBz99^KOZmjb(J`jl$%O~iDUyO zLT$mZ8wW2WyHt{Y(@NZ<^rI1pku!Ax6&DXGaOqg^Dcp!o3pQe)ql*=X24o_;fd4;8F{!m`pT*PjEUjH8g zi90z)31U8%>pz9$RfCO{lw!DH3*1)^?tS*3ynn0oP48TOlH-6pQSdXb$6S4S4;OFe z+t5WU)AeMj!{-+-CB_(>wbx;HN_#z)YPk2SySe+sfAkYXQOO8?#Jw5jjC)}P5pco% z`t=K6EI=5XpTFPi4GAyQsO`$wT@a?`31ek`m+jQ!L7{0sEo3K*K7O}V_T4ojyD zX9W^5IbmgB_@u9|ud$uKwY;p?yy18}EXX$7p);f9Hc#9QFWbuQzq6oMV-8!HnjUdt zWT-ZSBemG9-~5uk-+b|M%08$Ok~L&duy5>k0Ml}LQ-%le0m9tZK$OFrq^_GVX82Gr z(1I_7K9n|}(GUVRwl7wd@Ffk1at`itW9VLN6AmpXcQ|C#&r1N;68n6zCc(^$kV5OP>0aFk=i!_jaYO!1cwbNckWY z(;Z8#cp8r=EZ$F+{JqcPV~KXA8tXVbu8TEGMUpKll=D?g&TG{plM`tci*bJcIqMDy zkT!vpK=qfQr%ssC;RFoGUW*2+v8@Y5g@q#oFOxEm?3Oo&Z{LLcGlliNd2{U;S!UC| z?jA_Jo6l?2X!A=_YuThM~|VaT^-EVNk!r8Xkw4)#Ay8ThtP zts<6wsu`j57pS280k?B(Bcm+ICC_+blXe4Cze z^%0O4koe*Pmk1`gdZ^FiF_m^nR<0M(g7FcYw$V$lT9{r~3AO`F&aLr`7lvC`kdUhR z^U~6g)Ib1(JOa@qtX~WapLI!2)>H`oAcy9HDH$nne$}ADw1ZVxucCbFHGiW4DMs%O zeC8i)hDYSWv>$VeI!QN3$%;3|(6bwOVFo6|a~e`qByh4vM-|Sty8f2O!L*}Adxb(P zbBp#x-=Oi>Ncu*BwJz8)ZSE2mWus|VRsNXQF>+erUZ>thz!1=l(r!eyiTX1Q9!lj6 zl_}!oh+;IY1K=GExKUWU$e?T&rLHHwJ07ViLELdqQBKUP+8S08X>CMp`(n7P`eg*N zp&8d^Nw#@JT_s{5-9)cLPV=WEtVDDoyfE0Mt(Y(YTQ%u#6qsl#zK^?l2B@RU;*{T) zr+#-Y>)&#Sau9+YgE9eJ>=oRGgLSEIBdKB>c)To_m%Tgc1&ER+j7HbD&bK!$!^+Xp zU+jfvt&F4AoW6tuR<3siNg`u&B8jRDgFdy~?NIrV_pw{|dmit zQ#B5`vnhLXAybK>JfG3^7ji+eGSf&vx&D=wD&XF(v_a0KFH31<;*W)UXh}J07jD;R z(F0W7yHGU(?eeQ1*zgt{#tzUqzEh8a?J12SB&_fcgfaF_yD3L!ahgn}0T?$@0zRj7 zPExiW#0pj{19uWayIezNn|B)O@cF^|1w1=<&MQh`PVC;ym0ba_gVfQr`k{1VC(i1M zU0jvzq^?CVVJxgrd;Q*(EDRDFe$be^U^ACN)06c9y-qhPex-1;NjwGDnh`GNr3t3^ zgZl0tg0OsBE>td=v0qHzdbq zf?KXScB?_0r#lo~3cdkkT^Cx%)@Q6?l~^SGV~%lz-|erzO1VSM1c*O5LGrUyFjfK% zL_7ZM+{d%e4u$y>9K0b6kcb?G4Ska^mVwGlr!`VAhEjr>p}z&nWQ+tI>u$unib5iZ zZHKJPq`JZKnkn0*14w|4h9wKTC>#ch!|iM#F{+K?%Iq+kLU>JF~r9PUMbTrwxZ!lZ}o_Cj6uoKeTNeoqAS1O?nPayqNXa@j8u|uFseZF@Er2 zX%6=HVeU(0N)N$Tbw(;jbks8Ob7iWV@fw=ao|>umEHUfoDKTOv5p)7KypAihZCr88 zeZ;ZL7x}4&p06ss9@p%{^fU+~jK1acvoi&rc z8Fi}56K3gTE44jeknMxhr}Le5`6J-dZT>Mh@RvJD!rW(sfFxyG(B$gHIP znDR{z7ZQ6w@A<5DuId7z~+C~yuL1|7sRqinwxX~ zeoEbONolpvXdy!`k;@SvFf6)Oc!QZzW;03T`3(vZJit)(1z zvt(cN!cnNo1gzAHGdxHJ@BM}%E}u1}`sS^UkW+?jow|bxi7JIRn%=Sb`&CW}^p_?rknEuqWXMXg3=owOH=g)D}*{1?FHoT2LE? z45z=ie;`%ltgYY$*e_@1fMxpc#g${j2Z$r|6;pEgMI%{%48G-|(!j=JQ;Bu>^A{h~ z#3U?JXI;|p78|uDeN}&!2S+b>Rnb>WR9+ZS?sZi69!1r9#Y5Y2X=O<+LPDY$0yT^~ z_uR@F)bo3zqZwszP+$sRex7{&o`=4QKd$t}5rYzM5c&36-IVjVM9>diTUqdg31pTd z7k#~w#PRI{r#avcc7H1LRjWV0@s5nnG0bnFbU;B3j(5@^rO|PBBOD>xWsHIwOdqK7 zz(Z;ig7WlX0-3Pw$1Vnmwaz%Z z=D7q6d7tBX(AHe2LzzkMo~jrSZ>wC2+%&Ori=JkRL{O}c9WNM~#U?k;gK2Zw3)+HK zRoco;NH9djl5VI62MZ*X5!A>i8887VkW_dr#tOwip!EI%h1p=${_>RXb+R&4leZG| zOJJm$@lc?SwvYW?QeG7WTvmiQG|Hs5w8%0?>kywIwaOh;yI5*tbNy6UH$+1zIvB1; zc(_P_j3y>7`60^UD3>d#PRbr@z*Y7uEGqFb$U>WhJ^1}%n0@@25;J?}zK7|{&m|D4 z9=r85bAJnH=RHK#ARDt8ixvBUe=!wkFYmx>@WzAx91Ob{v)s z)<@)j}4AmB#(Q#PB$Bq0@iV7Re`-;w;Cye5RoU+jh&ConZOYnX`5-yA` z9nLtYK3ucf+WB@(MNGe8h{H$?P?^HmraQsB84Kh$IzDYPC)W~dxNz{O&~ z`MMwRa{H(K`wD*Jg{WR>U5f`Pyf`gga#m|vM}sf)rEHE~AK_LX%7-3O@R?g*c-Q}o zoN_R+U;z2~1SDjb2!?FP18Q)u`c5CmYW!{3O}jD;OfE**$G=ZY|GE5$65RTcY`Z!e zLbEBj=)fO2t3T%aSlgneV&4Zpw84%n_V#Cb`$-fqZVMBZ<0xrmPU~a9s5V3OaC*Jl z-$~eyy)Q9?t&)N4%7K17jJ^+m5T0|YdwSTls_8S29_11>Obl&%rfe_baBT~;%D0Ay z;^A(+*sj;w^UfNHdinTKlFXS2`hkTnv-A|O%d{p>d_JetL4o382F9EZNj&!s%B(&k z&Gz#NCt>$}K`yDlM!(ln(3}qt^eKl+`OT5a<;s{miK?(rVpk>+vJ^e|Vnw{Q5sB)A zW-ykqa~t{6Xm6i@3BLld;1k|V*;0H z+zvfJ9pf%qA#X%#XI9Au@6YiN9b&GKV+#sy84gJJK{s{c;0pIZBQG)>+I=l=#hQUM zUOFq1o%2sgy4N8X+I)J+|5`ULpN8;WT)LmEEK&@-dwH+%mRA*;9$9BK+7vq_3-p#gaWQl7?*hNS4PP^`!ghI5n73uHGI88h0fV(7(LlM0Z zwBF8C=R(I!K+%c9>WVxe;-<<;^omFLy|-@J(^RZ@XDodh`9(aT(LKSD z0mR1u23(?zzHLz7c;-wo%~I$;hmN99{XeqaIXbTR-4`xm+h}atjjbk)HH~d!8e45_ zCykxPZEPnK+qUuU{_c6tJ!jqdFKgDyS~Gjk{yxu#GD(8DoU(OBk9vH+4|dbze}g~H zC6G#g702{RSf%rbCrdPS(t4<@+I?cDK3TuWPk&MgYZu% zQLAZ%{ac{^)3yu^4MWN?L;NQ)df;G>($!1JFZFk{2%t9of_$NP=-8k(U>Q z&H2pkD7zsEPriQSFRhMc$t-4-9FI3Jofa!t63T{^2Y!YTG1pylUe#gH#~A7`C*;-j^~Z% z%$8|YNV`lkdTkp@v7%()uVUyWNJnHlIdZzBvG^HBeua%s*w#n=3azWYbl&6Jp-M0? zC-An=-YJE9NE9&Q$o`nBA1ADB!8E1kBj6~LPAF3+neN9ay$b&E>wV{20+j&OsQ!`W zri>{jkwzqK`b+JIoA)xi;Lq8Z(r)h>vu>0J|5#8;tT^vVM2}2iUODctSDkWWZ;2e! zG)JLkO{|UkWbHX3>ARmB;t#NAAbmB$5sjZN>M_H{k{E>~T7Id2kjwp^h-Wxm&O$9L7ur6xlW@Q^F?J^*t{%n@#6jpaTTIsP!o_t226jhYsc`{wtDSbQCarZKi=~7G&D^d_4g}BvU zfaTe*Gt74bu7`C*GL)VUrw%%aLqafs-H*dI-|jQxCff*_*azZ5p~EqV@@Bpin9|k> ze~>kqi?UHoM_8?gLae(i%w>$6q+5^sS}}QBSbc=v${v4&oP^`Y#xCjq;K+e#{Nw+l z+WgaxacN=m$?1P#kljekxQyGApO4ts*ur9C&-CADh3i9kLt>6xU+y!b)t-WcQqac^ zF240NPcYqf0Trlr#QF%*wfQEJO{*ZWA{Qg( zDXmPa@8z#Z*|Tz>Em|poho2nB-8neSg~O`D4~_UyDXMzC<67qfqp{0=n{E z*DQp~dkq3$eVWhN zAw!jzs6mI`+e-EutvQ`3-tJ|n8BWJTi1MEehp@{#d#4XS<3nPpVX#LsxQU084Cv-q zPRkpBO;A-+2SXpIoekUHx1eiNk+iruoVBpCOTu-gmiiMrA3&FqFdvP)ghKHSxy4ZQ zH7Ypeho!W9C~U+=ca8p8H*FgX2gmm!HxVKwME+7#(A6ozeP9Hf0Nh72ljPAZ566uD zVu}gvU|UimiR9lX7%-=yWz5HoLX_UC%7JP@zg@Wsetb9lLbv^q)?puCU& z#fHT3{OP@4!JZlt2S%vGoi|2W18SuZ&W0y zhRodaOirD8zP9@(!nUAi#zj(Tj`;5l=-3D^!eEQu=Q}&BY<{r;Z%Go_aG?P969UdCD|>255Y4CgZJ zRbn$Dm@MxN{A-m@Gu^1GBZxB^rAmFXh;m&U{Q&pgHs5XmVRM*F$%*lsb>GJBA_=*`;`s7yBZ0L8hMI+^c;v!=T43raMp4 zIX*q@9Y+gj5HFT)%PB5B@q>LUu4V7RzMw&H$ps=SSb?7%5m4Y#!uAGx!ntwh{F)w4 zeS5&*%#rBt=CtK|eou^vaWds?(4q#+L0GXRx(71H+{6Ea;GD*t${8S^+`9P0&CPu* zz{+e<8(Ck^Nl8t8+fq`lhPNYR&g0ZMDD8*bb`KQFaR#WG9Acpbu8jvz2k5`6vv9ggtiufl*r! zCv>h-Y&pSmf3XGQNnkXE)tP&yv|?U=fvl1X`KpSp?^Sc|54$T}Eq~+si@0qy)$U+5 zj2+~JzxoqGsAEp{v6#qOEg#(q*uHR`&YlhK8FA86Iq zxJx*h^xEI@_Z~~GZ2Iq1{ zgd^aw`93*KAz8B_2k7PpI?sT7INafzb-uoL1zs<4(ecs~h?%UQ5A+NSg>ljx^CSSd z_jm^xh!ZoIbWu>+?^#5>?N+{ZY=Nh8#{HBF;^8K?{=pL0vc5ZR;J@8BtK~kAtSN_% zGr}T%ljL4q+(Jknj)nsy3qhY&GUMHvFt#|Ml+JZTr{HULH61D1*iNvz-s)L2=+@-7 zAycdI<1n)Hy(VjRvpe%qmr0*5wusAQu^JjI)fbSI>op+@g;?_TC+CI+w}D{8-|3UD z#Jw9I_uN+PD8#RN?e|MLAvguwD9zt(UY+l8=a=;|jEnb}^G>X6imyg_Fh1(#Ubkk1 zjeJm?+qy=#`rYR%*U5<_>g_E6d`~l<#qCrU3#G0dV(wf{fUZ|38Gv|H?CI$lIQ`cB zbtK=7$yXugTE1?ZeZ<0lQ+PD;v!zG%G>di>@pCWB#Pr1XDOl2=RBCnNBF_*HE#8M^ z=MvvDA%)kfw;u*czj>j?FIAlef&~MVBvJ`7d4+_C0r|eU?_kKOw2K=)jsgp`U}g@c z2I+j%?*5k%TDkB2O!V9>sIX0Kky&jFY&4pjNJ9Jy5vV&)O`x}MZd&^2*kbWW+1{C7 zYVj7Bxfb+kv3A|NFAXw8JgCm{n2z7ZHC&`k#ck&!eQ5^CS)e&^_qNUj2#vB@ketS0f+yP2wN?{=ek$p{JsH+nt0#8#^V*x?DfYinv$HA?P>HwTQzTfcf-tho>DkhZyJ zKDWe7R^rid<^8s?ai*Pf=|+jtz(I?>Qx+KC8X)j{I{SoN_${RG!EZ#^f6V6^J6Mg#CgPO)(1{mSA4u8gj(F2fPeWS(Oe zYd&qIpK=3!!^OA= zsiW$ky`t-!zZ|tEf7(qi)SOywW*xgE`+f)qJbxXnzyB{1Hsn3-asxLXpSB+zRq~G? zag#Qc)jZSd> zL>jZ<7B#kRy9#Bx48guO{a$YNE1gVHqdQ8lvBM2177WhRd+m+!-ahNyT>!5I-6)fa zxml8TT+ByQpB*5XWXu13eR+z{%=BHYGX|UQ{=B?vBpvNauog2eL*YvBQ_kQeV(@_A@ zANXR!I$cH9W#ImFqIJC)xksdI_uGg&wR)#@O>%KobNFVaH4|cl(rNfB^1-GRiFPSZ=F@`P^w*F_9!)r6xYH=f*-fmD9**F$1sl|-fY?XX*P|c zUnix5Na>@@^j@Vzu!D?%Nws`Q(TNm;ATR=6qb7UBDk(-%ut-FG6zOM}JO#3y1ZzI_ z!{3teGl#$-Ev3#83zOeP3mp?ez-cQ*L3D<1cF&%0ph?Db5P;+*LG0hx9rN4SQXm3` zP7E13gzTpHZ~0%nb39KMt+kNJ=HRyBKqD1tv_-x(7LLzS)siH>H}=2y1Khaa7k)9L zJBAz>rTd0yZEII(Sc(#g+KWVCX7O$pXT5nFGqW)FkXQL=e$)_ZK@H`B3^}fc<>6c6 zb@C!!*^@Fr!ZrOGkQqo92o0WCO?;ETrhQ_%80#|!H$xR7)^%CGT&;L253Idu-C25y zoQZg%B|fDUkm^Ialw(hjw=&JsiHDwR_e}r}L`O1S* zQPn;8G72*MWUcq1k7?k~4{znSMUtAHqu2mTy8CDQwb5$BTt=L~R{@mlz35>Pl% zYHzz{X+`sJH?z4;`d}5D|4tqm2rlmdLL)+Y$n9Tjn?PjR+nEqgEJp|2glK`B=9SOt z?AI5jaD5Rvj_Xmk0ynod72l_F{?ZN}8**}nd%PLE7{G!%yp_~@?n0%G4uy2=4%OM^@1gw(vfoKkHM$Dh=NXE7f%PJGC((ou#U z>tk(O6(&95B=4%}Q6Yjoo! z>|FJIugfH5!(X)%Q{=H5legL%+3z|qSq1+Q1_1jCzcU^$!{+)N36yxcVk@=Xv7cXw zhzcB_ggd1n1T$`RC3*Y}Jp1e^SC4HG#&tN0Pg%ytRiAz8-*U=laS}0a7^FywI_MDH z(=|L(dw0n%Et8X=z+?Ls&DFNB$%)h^p6HxseY=h000A=(88v#Kf~&tSWS)MrC#`8pH-lDBr1BDac#Qszh5 z{2~G%_gQ-L$dtz&{ggi3b3bXWn+k$P4=I5a6P)Xc z+P5X#b?|wzigjyF=N()E%NwTG=>xaVPNs@`CDiMh`TEOkY%XyrBD{ApKI1l<0;$YE zq~hrJVUs@)3PGuIXmc#Pm*d!r(ZXJGwJn$)3*%YCJ2};;@|DV`#hGgRFiQr60t&ZI zO*(KW0mjAY)5GSfT`lE@FOUVeVbTZbJ$)El@9a;AmQs6ABUgp9x zB!N9Kr=K@5=b z;Xf-lVZ<#*j5*_<1KgKqj{8RSSIRlYRFA?s_0)+8S!|RL5VL!!+bqSBg2sc}w!*Z^ z>=el&K;2RWKfXw$ZW?8BsByv!<(_)N52b&#czqq8+*pLZd8km?#`7|x9TmuVwPI@N zcxKs8p=$Gcp#Q*8)Sb)$Z!7XjBFHv7LE=Y{nf*+rQyC$BKDd|bF*~e;3pkZQV}EkM zf6>b~Zv3g!NSZZ5M;3T%o0VRZm=3`sEyuMg$y2v5P0z$u)Qmz@i;}ddzE+K1oNbWmBkMVko3PFJFj(TUqsSrk` z=ja9t+U-gPF*B+Ag+!`9vU#@V%p*aSG8hs0Ax^Hn(af*$!no_g2F#diBy^Wle6Buy zm+^M`C&11xur9dx*|-0lZ~jFUwlhDYuVkZHvI8Y&2Y$g z+Ge8=bs9o&x@#U5MX>?Fv3N`0S=c|Z6{_3DH)?-I9Dth?C!y+L;UH@1vPKuVFb;}5I)aAlZx zvBV=DiW)(ZL(Eonm_wtlOx zYWZW*dpt8cEJAf{mRVG_+TZ#scd7iu$MZK2qz8 z&n-~49D@HrfqS3p33vebvUc2AyA|-&klLrhg6;ojsdzJaf+I z-y*p%Ge}Hfz6EZsJwx*)Ro+Qe6zVOgKJXEQ=R6|qWTuwtL z7|Cim_N_ghU52XnbDIm95aOYk`HMn+_TUv^ss;UZTuAQP?JoqL}&<^X{DTwrk;RV+Eb8e$Ho0P8v%KJh++Mo>E|y$BL4Y&ptkao10>u6$3#V zj_#tUi|9M`K`(e_+coxU!rOa$!!E3Pd_MQAfRCWd`uo}nvOBAKrvoqX`nctYOd+6j z1e&L4X=%SR_Xpw`OmLBk_z@Kr7Ke<(5!ku75Y(=GV~>t<`_O$YEiaD<%qej{e{z%@ zK+r%{ohRIkJ{OWu<41zzFVI3IOYV3~rzBeWm~o#fXR%E~=o@cbICF0I9q-pA<-?Ax|KNvt2wBQJYy+&!5- z;)hRg&QeJB2;fGP)`amOI0DZ}&>V^F&rXWO0bdN;26IvczbC?-4XO<9#(9n~+4|wN z5X@ZW#uvw25SWwT7zH=d15o0#31m3%5l{V7@pmIiVp~G6d;h__P66bii}Avi2z}$J zfqAvxdiWGoqCN$Lyw`PMzbqd6oAL`2jj%$@mGTpfkbw;ZRNEKf^?;P1m>sa)L)#2i z|3=cMm>#ATI5 zE*k^2RrbZ{MiXd$zR$g+6zsf$Op&%Gmh($$(#I?iafaLz^5u1CBwFP=3T1p9Vk`im zPEmblsxnhp-P)>aV#KLN!jY!!qg)aR7ae++Y+osMh5wT^;mj&-MeCQq(Zi1)dp|m{ zZc{fED;Tjp<8r|S+ROwh3^D^DpI{x`Y{)-2BBn9cr@LI>Vl8o5j zdKJwZ9&i&O>}plgFuE}PvA@^>#H=niKYvTzG!P{9euhc;t7S^$hQ2;ms)B{R2-gEj zcN9!XTb_sV4#a_}wPcBKM?_ygxly>ARUElcn?7)yn{u=_Xey<5N31`dVq(Osqh?FuQZPUH_H&UTiG%_QV@} z_u?Ayd@{UHIl6*DU=8dy!Xdjqb0c`eowlA_HV7t*1W%)9aa386;J$mI;TN9_w#yLpfqcTBG?=&wxT6$^NXA+N zgh?tbTjql7zvfrMI(>Yjk9R$}$FQOY0&IpE`W>ANovZdGwmN{mzZ@IK-B4=xPl$C~ zV1Z8+6T)vxRG>9f@r{nVWZy3(>>*Hv?djCFaW(>_$TrBNvR^yO--Q6%@Oq-bwz*W-0(Blc$eM(e_3OMscXIIE#)_EHsI*+w_Vb(T;8?x z^`l=3&*e~<*zv`kqJ%Ktj?(t#1=q1Q7C>#$B$6#u{>|A6%HL9kM%O`k$Rs&U^^3om zeh~wc8@!zSFWyPd3keX?W~07>j`ts3H@tdFM7INi1=A+;3kskBJ2NSphaVb0}bP5EeQ0xe-+n`RXfN5Djx0IQ< z)Z)Q!$w_(|bp&bt5~{hD2nrgo8Qf_ThW@>~SWmo?_hzR<{}U7MM$%<2v1S@&6yr!? z)ccM0FWsWn6p@pl=Ztax{ii|?f+E~SM~6GRj1tQbQhIe=!J@IO5MD00I?4Wyo3ng= zJ93Q#soZ8=(S+&n#!IGor=I93?Yej?#6PTUytUT21oi48XQ z`thKGs1FIz!_o4FZiGJ@oka z@CDoxji)jWc-tPo5?QhtH43nrZg5S+w1p>nr>pY1Ll+5@ogb1B^Dq(xW}bD#yo`z} zXgdkjwz#j4j`o9U7eRSPTY|5ftO;US9`=4!nrT3FY!LJ5!nda3k^^k`R8YzW^o~4t z=ttprzd@Z$;LpIk((1_Tr7btG1S;mg8M9;*u*c-4DmZ0Mu>uY&D7jAVbjHAT&gNbj z%5v)zMw}GO%}76&n13dvrt51L6I0W_c1_)s?22hpopp6;%$P1@@xN|jNrWOQD=Q5) zs4Vv3!eErpG!mG9BUlo*I&|qoSZbTqyFKPaur4=*)>Lt!Osl0|JcbyD$&L1oOeq{M zR^zP1=qUgx`Hoh&w`T(1uWOqv7BA>yI0+rL6?$iT|HumnIE?mql>2}Mp7WTn)hh;w z1>hx9CoP!QVppU~(Z3Jrto9ng1q()qXPw$cGdhkyk@PL+=8RF-wNnjh;6~Zg~39XyDjZ;8%DeH_`kyL}x9uF_w4n@1h z8rm?ocB?_BIqE3{diL=PQKGfR>2GYy#5cicG+V_#{{kGqa`H1v45-ZMb##AB6k zFx>7J({uY1je4I2ZS-GA4qFr_gy*nGqfEkr1u-t9YU8Bw@mF*;y`RF`qyarwT%5Gn zXLs}BdXn9L&L>!m%RFOa(}!U(l5Ql@l2;pC+t9E$Y0_@|5PTAqM^_1Hc{1fju%x!a z&B3Pw>6iWY-3UKr31aX;Oi@9CLuF&7&Pc&=(yc%8D`7b&C5??K@_G?JfvOrCH9ErJ zij#inR^Tse6@kQ*kgjtAK2JNAuQ|eAW+i1=aLx#(Nv2^}ACO5w| zt*Q|hv=zz#IHkC!GO3|j4r`2`m^t^E71G&0(y7w>R3zRT4Kvp-I#(MhAT^%yzN_-E z`$fgUN+>Bv>i}8&u}C315FU|31*m0|j#V zM}0@)&UAO8-4P&9@UsJ1 z?ucDHtedNQs4uVy7~@zbO`RHX=Y@(5vK5cG2JhKAvi&Z9iScy;>U3f>wz@Hs3+5`FL zfY%HtGfhdL9PekPAda}x&%02-_K|B1>{WsDWU{rb#UR~s3SR`^R+JLIrR90J$U#op zZzRDySYigw)(jbwlVKRA-_|~M>s7|Z&CO4|3mt{&*On-W{TK{cYS1XCSuuQN-+jKR zVpTI>%b&ptfE|DtcM1?M>e7ZBVQ3A1u#gy@+d z%gxO*{Qf~r?Mqh&5{K735Ny6F5&YMNJJgq%BoGiAJXT;P{+hXV>4^k>Z293r-nXBq z$Uqb2moUJmXYY_IScAu;jvC-c>duIai9yK#7CR}cL&-C0WlQU7;IIzw$Zf#h8XoEr z2L8PTj&1+rqD}!d4XWH@G@K`=>gX7YAG*AOC-h%*qh_Uc_(s9|PkH8}KaNs0^`Xlw zz!_inet#y56*=Miy)|u05&!r#hEg5i4PMS))nLz$JMFtVxM;eCaZ!T*t*)D` zS6OgRdL&49Fr3)0fm9}d0s*OT`IWx28@>e=aPLfpF*Zqk{>O_9sLTmq5798oFk;aq z2v138xW!qb-;oc$PAum9srV3b5SUkTUZ3%27x}2#a}EB!_fba5Ug$eT z1M&u!8LwJLnP`MLWnSjN>kB4}98fI8KQnr*ko7h`s`YkFR_?j^d48|!!sTJRswurc zfI!{Ls^)dHABeE=UPtx@bQ45y>+6d=7xw@sTec2j!8g;IbbQtqe4Ur))muWp1>x;Z z<%IRw;3l}Qg&Y*(f^-_t<s zjvjB0obJCJZT76%nwn73xY>Wo=F}0ry__7KZ|&U%`KD|rIDa*-@<`H8n?KT%Md4Jh zm(M+oHS}vTWMkojV82GkcP2-Kp?R_~eq`Z_75R<*<~6FT^^n{R%8m^8zccW}1MAme z9%VfUyaMUD)d2F9EWma43au=3iQ@)7Z*u|rol@a!;hUx8Kx_dF^-Nox=;58n>)%LT z^hdWr0LuP6`RDp4*WrIEW{gsHA0NEnHiDz+mV><~Nlh0%l4;>td7wQm) zb#SLFFH?PV)H_LCLwFZa{U@yYx$`!pnOC0c^V?x(8&4qhttk0ZR1UIn(P%Fhg9dP> zh;b(H{85n%KsjS`+V8qj76}Nsz8H|l>-!kN{&E@JuW{W%+U|>ZdOs+rm1#z|-+sNO z+vT0P`4`u&hsA9655@?nlmrq29BD1FYUC;HIRtcCA>@_y6`;!SXc ziUpF;EK;GRz|2~?^qnR+V2qDo#;`r)&&a{~j)K&latEri0(QN0wiJX(L~Lm`98Q?7 z>ykcMziH|J;(ZVvjFUmjA&ZaF+*N=?2jnOzhQo467m?ylh zv9vL@)^}W%*@CjwCM59UPxhS5k5J_Mr}2E_UuYQ##;aK3ZP7{IUR$Pb-)Q$+EDawE zE4w*Kj0)0EV=KL+T3k^zgYIBTZ<{t3NYCQ*4F_LdosX)`f#%4g(D36o5%x(u+meRnVPaufL+O z`bj&Ey^o|IVJC{IIkTUT$aUNPD!>paOmfc8TKtiQX1Rd?fb#vhxoZeM&OGKZoK6?^ z-sz{23=jO>DX~qR-!g@y6~!MTn8H5az~hCkNzI7(;?D8JFN64c z-Br53+BapuZ2`0#Ukpifv$Vd;6UK#mk50F6@%=E5=HM2c&thm!_3Qbc*5Yu__={(9 zi7rZ>IL9Y)$jan?{MNfEkMEq^pMs}X_mk}21du&W_MU2Pb}&6IVV4{&j6Y6A>R0nB zSX3VN4U4QySEaa{sEMDw8Yq7z5wEOkmVTV%UZfH8DXQbqBj^7+=Z)0dQ4T)*Eok36 zW~OygwCal?f#;$~`9b(5(AGjoeB|m;VwGXv;%2i6)%8zFWa3fJpzr7g74Rb!$zxk} z==Q$H^P(4L)-w4dB23=~tR%y@(5X~>^KL&55xBHEg>bfk@Obj$&v2=Gk_O3SLH`a1HNJ4eBGkS z?S}1zd-n~u+bT4RjfCm#oGIh^>`nAUWaYhn>vOqbJt@4!22bY$vWvcXzn#(8S>Q%k zu;ruE{YQRk%0<(lv}6)1qbyXQgs57Jaq0#Z-tv8?VT&mCEEckkIW&p)?$-pK`t|kO z8?DxMqT2+Ug8oH`MdG#|>l&S%_J_7r(Pn9c>642;rw)H)KiH&<9U}9t4|hL1=GrBX zoEPrOFx-|Sxu&;2zRF%Uu~fZy!RnN@7X0RVyJZ8dp`~YukoPiUjP;Fvdk}PG1b3jV1WSAMxQnLB7hqj~pXDC;a^q>g=$D zx;yY>Q+X)n<=D17r!^UDtecLO{;j`4BqJ)=9XHnnL{N%apIf(pSf#sds#y>!9$X*d zz3IKQ?cq*U_tSA${3qK}lAuBdHRgjFhDt*xvi|1pA)yK_k3Fq>Utz3K1+=9)2M_T; zB4=QG_iQm5VC_x~34!4~aVt4o*Xp1p*DI6JRDXpT zRPaR`TCY5{D<~+6pu)!I(j6_!Q!G4!8nmi|4&4>A^3d$CjZX*V3YD>NzYGY>-|m{d&r`>rKXy3m-QXo3234Xm zZlLh6?}`MSt=4n4^+ibxTt+i)4PeClzO38YIg?iHs55x|LF=+(PBUOiPDX*iQON>V zmAUjG3hK{M2RBz64!@g~M|sENWu!9DDA!*(`n}&AepDEC7m>l@h{I*#f}?z@s5?#GrU((I(FZTPHCfikc>qs|ip^_4eIqUVufRS|A@xe4f( zGLgQ?s?~^?ZLRs_m59D4(m#KnP9;Z8RGW&N_01gm{Xz~R^SVsf2U(yr4j3n9;)}Gh z#L(}`Vt6H!!lPKEPr<@hAsOodEopwY$?{5=%`gEcQI+*Q%`FGFg;nqH$SPQ`8^X(P zn7QeiD^cOKDIMbFhfuYVc9kMT6yqom%!4}Wvt=bcxLaze$a2pVWJV%gk}LRG&r^>E zrdZfRR(s0Wx9!0r?Jo(1HYfhC!EMTK7Ir{3amq%3SzWhfldSv0Xkb6;EJa>kg;GXfibg?fAu5%YL^F&x6b2}5K=jsC$GD^!?U@fR42#CFHSiX6n%eAf zBTl1&X*N|;PGr0ytI z@~z=`59zot6Lku7YPz_|0R3HpVNzTltq*J^e!`_ zGJB4L2anTe|G(LhJG;nx{M?%fIg3`frn{8kC`6pg{g9^?XK~ccD7HBZq93u}6DCDH z?KZultB(*f&nWDJK_O%bQcPwXfKb_VG2dd$Zo3)I5Ns3dBI5IeX1}TTU43^NYyP z&5pvGU6XFhMof{Vg}r_9j>ekzsdwk`d^DxBN~$E%+`WhRdt^y5$Qt#OJ@{@gW<|zT z-2mY921%H^8~mxRNE}Zx^~uWaInLsVTjLLDU%s?Y%Nft3Iz1NFSSd2&@}rQ3P%oAp zvbwpv7{tQ9#-OAae=B&hs5tIYk@&;D{V(__)){n-zE+|-iHlHlcB__Hnd8ByL0Lfg zx0K)cnhn4{YpkpFQ?Qs zVJJ~7=MZZV_A`Gc9%iLZjnb*5i8&sGvMbaWsZjVc%h)3mpO0v1KH}~TkHGze12sD< z+x}S>8>PY~WTA575zH**GIfAC-1fLdVL|VnZzB7_Yz;e2FK@$w$KVZ;?@+j~9>$UH z1}+gj3FD$*Tk}6?3Z=H=Qq?;5{i+6241Lk`5aEfC4oa) zo$u4?{UF;6@xh-N>pF*vWd?zBIAGf1HPu_3*3H{ zp95Qt|7CtJU&-_Ai~9Svd#VD%8Q64P-JMXI5PT+;h=#~|LY66r(Tpvfa&=^5Af2GL zfu?TyzhleQTe5kTvFmhc%rqq)rO+_Vf_{vP7f3bwhwBYHt**=lKQ^uYz%JdkgqoLIK}-{) z@tqQSXz{BgHhLdgf9Ro#Xm60?Rps}WZ2}*M5#+j}2wY-%sQrxG;i9UH;^!X23+4Op zcLlD*CuCjG3B)e8qT-=-9>O?O!7xr>*KW2HiFuO;9?)ci3TkJ>$?W%EnxTTG&C;MTDwFm6j*6t7o$JvCvDBd>xUB^hM4CcJd`kooz|O9Og*ltqbi+?q01l=I>m_ zsLIh_GM~VwdK5IZIohUA>2U#JK>|Bzf_irqweR6Qzdq?+?7uBBCR^SvJG)jz>*2PC z9`I}rU3&|Q0XZUjX0$)R~8G*@Av*MQK{ z&tYMDkwZ}_;I=72Y3NC%UMq#8B|%~u8*zB2J;gzSL1sUe!8b5En%E_;ub+u!0LR|S znLhe2z_z8UsNWh=nYcSc_S1w|D9f(ownnRi9G0~09>(f}8*hF_Sah`i;CWs}!$&I@ z?xG~>+}cej9UXyqF3b0NOahJt+Il5bh$kyToh~c?pa#AggkDbt;iI=x448 z4-!1oL>`U#J#XPyk4kKNat__oU|}ZF`ppRaNrgvpWeM3)&Xa|pr{z4~GJ#7PYu!$= z*v|heV%IL##=e1zi%SBG698dZcGX9IsOVXiP+l2ajdMq6?;xq0num8 z|5S8xyHqGZEF(ENS!U$e0_jmUf6QzwiGMGsYtK)h_>TBrz8!9CE(VaA-~3zUB^6-# z@Uv9@VRZ4gRmWL!2c9X(-J+_=6TZThT2fjkZmF7?|AFRMzPWRM+TZqb1ethhs;g6i zr>CY=zI-7M{>;alGatHasc(;s%q`8Cp;UIx^Y_%DYd1>tB0)PvhaYCEc=YcKo3=xd zSzbxbyI|<%u-MwJiDMv^NK*DfYXsPo9xk|{)M@Ke#_RQejm?x`H0b+JTTH^j*$wVEYbYB3j1L1QKZKli~EG4E@S$CA`w$I zLN@LwCRU<9YeK5sS|IXW+V_<(u~!(E?;<9s$)^;1TnqDZ`k9Q*bwl3R@?3K@ORUy)^Pd8pzDrCb$oo?~X^UPp>;udCGe-|FHs@j`huvC?8r zx?o#T@@pDDz$&>>P|by4dN+cOUY$5KlDD)>3Dv(K^uq6xJuQ{hJg&G`n_a!<{lboJ z-9$bITK{v4TD>6n%!Hy4*2;N|{l?dAv~k14v)pz(P{eKh6+V>>zGl7TO5RzbK{ixDIL;UU_0_>d~- zR#aEe?KWk(ZYQ?BFt)K7Q$U3maU;nUIrtLE1V$-uIXi^!C;Pt29AhPVGDp_fV--*@_qfZNk-e9{lSW{oMhv*>l z+d$XVP&T7il?#06#)`(5-xFVJe~*1DIKnh4rtHq3M6w!5L9-Oc?7%D9X+Y2`;UalVP-M)>kq2w6pAp9R;$n?P($j_e>zM1FUt!6Kw&(F*hICJmow6hP4=LpC$iNl zh`PGF5BowYbnnQ>#y4qu5{I3tcXoItG4#VEIU=gTFRi?*rQINnjp(tz4Tupn;BK#s zmQ|0396V z;OBN^Z6P@6KmKgPkr9J&&UbQ-S}x?<2+e$}vdrMEZly{mU7cMQ98L zo{{>etdf=JH~pT;ZJc=1*#1BOomrS|tgZb*B91FPVJO)^HuRozmMg+{adO#M>R|hT zmRRk(L^>*0V#E0&h6*<|tbe732hz`bTM6qXl=Nx%QAl_xW}?N{O;*oC^(dwx@%pLo zMYoU4^6wguZNC^<+1ZGSU2rPU5e8<|)4Fh~=hrr3J1%Ug=%j>X^}*CP^5nEHMLudM zTO=*zy!ZAg_4p1wfP>0LLxnKP1?yNo7;&LSP0q6rLDAZnQ_J`Lep}sSdndP~`W@Bg zB2$*e{fXlM9bcXxMpcY?bg+?^l?cZXoX z-GaMYa0^bL&#k(*s$ReT(QEJn#$fNYmwrB{iz7O5`21x3`VhyjJv`s8J!==oDyZ40 zXKi*q;v7R?sI*Ngd2K&(D(d##hp+qHTv|W|oVfN0r;wsshU%?#=%y*?sp~%Mg@g8x z2;{ougyJYIQxOofpuZXZ+pM>?%YgktcMo2qv^D|qrrjzTNGWCqRnBR8kTV!$M%ncU zmbBqBsx)+>&Ad~v>(S|4%nEvbEc>-j|EC}~Hz&a?$rHpUb)zCWA*Gu#`>@4aZs+Kw z@+4!lD`Hr9_tSOdgI&-smtWE+>{oZZ^!E?|armaM*Atg`zB5#k?}flLGwMS1C|yo4 z3s6OlZPG`Nw%*+diB+zQlxdbWp5>>GCyt&++CZ80@1QS`H&+YpKa(xvMv8UR67AVY z%WrvQLyFscSi16zTn?&sDICN1>G-4C6(ejmwD~w8Q3m&y zGW74C$yHoc(gYA-#a;gy0)P^eDh3xT1+Jq9MzDu5ul$-#jZ0;|9jd(m#8PS#@U3I6 zl3A~MZq0e6_pcM|Wlhl4T~+A}%D=k`LxPO*VV{M#QNd98&(tuN4Tx@0?#RdVY`K%2 zKPCap$fS_?z+(Q7G_}mTqkUNKKZxf4Cy4Xp;a_P9usZQFo<}~!Jqg7#AV1E3-;C(S z_3Xa{mePMft|M@>fdx}%QW~9lwJFzwetxOfPP)y6GRSs4GxtDP z@A)#NjK6@ge}DQ1k%H-e;keoKl`)}O2#MZaOI_{l9^{1b3x7u|Plk&`M_}cFyX)sh zI4Mks+C-m;rF(-Qw)bmWCcXO%?EZ5Z;#g{%E`5Gmf7$oy=z{UkQy)#y=!y~3Uix+8 z!%RKa%aoBSy<1zicHr*h@YcAG7xQ0u?>mnY5Y1DW4R|vFoc=3N7)d?Dif1frUY&6n~ask zgM`TdikHF{tFk&2!_gXXjcnCjfIO5)=AqH4oBqc zGg7K~`*o3w%P9Jp;qC?)1Qi3cP%dU&%Nvy4hZYvLQDyvPSisWS@t`-m^; zb#C?oy=68FHG z2gF71ct&?AQQ+Q04&5$crlPAG?P3<4bkH~sV-u$!9x_3dxBJOaXBIUhHI}A|tpD@b zUV>$uq^fFlE~a@o5#IkU0sur7+=P2~3v6Is4KDej!i*r44@BD5OC14sL{DZ1fAF?9{oX0*hXma2rCnT}ky<8Tk}h+>tQjShPGNU~_5 zq|a>SCLe*#MJt%Fq(bqtRFreICH?4EvVqcGOtXQsJ>HBcJ0t2L0p!TI499DF-bW&bWnVqn~a1P_@w19JMs*J#mVeA z0bHN0{vw}@`dk*AnG2Vhh#wQgXxM5ZyzKsq0#-6U?kQ=$nkJVS>V#3_ypA08r%8gs zNbya0J)U8Ez<5VOKLRmzKMBnnz?dfEgkS6?^}pv16k&85eW4$+82DO--LtY8(Z~)8 z>xh_Bi0@N3nYo0QV49g#*Fz#bnG!rrpHpmHp7&0wV|r+uTtv$Wc`C^a1u8NZQv3`L z%ub2U(YHJ(8QeE2H6t`=xv#li&uIL4vJhQ1kC=6 z=f2g5zte^xpMLa!E|3o?f|V(yY!@{eHNyGro#xUq>wHLefR@t*bw zGVP!qxU{bo6QX&tkj?oJzq)(w?ur?BwX(q0aihSQN1%&4xUmIvZ70MD5(*qpU&c&M zfrF8M4czkqr^2LsMy7c9*}d}ffX&RimFf}Sep+snFW`;4)qXXkww94*4@?3;Pt5xj zw$t+}y|%LxztV^Hsi2meF%YlTFo3YO+vm$d_BU?TvvA4IpK@qSbSwf8wK&)yFU#Qf zSnbSe84x})v!BcqG~{KyAc%&U`k$NKji=}fmVQpHaiBY4 z^RN#=`GbjfEhdGEcPQQ)6<#Ihlw!iAGc$ek96m6;(Jpwr;X55T-Q5O8r&-fa zy!>20i9eK;asgOqG1WkD9)yI^J?r`fOF6}aF4oxxq)geYwj>r)XW+8ru+uV>{iJHf z+>1cBM)`srSD;yA5iwNY4o=6>Mq;%txzW%JeUDbOU>`agyYr<^|+h{YN>=8UGJ2+ zUD@p~r?lT5e4o6Yp_`xkZQ~5Me_axLDV@df@|uGMhW z6cLb~e_E#lZXn4a|BkCrA8uB@J&T;cfWZMqy@c1a>i{s3^M}Rc(X_XI+}Xawp}mz~ z`AHDWg`S`Pm55DOfw{_ChIQOG6b?%#_F=6Ys?8qI2gLF@Asxb5RF5fZlf2pVrUbNl z8rzLR=5s*gN3j0HY8oJB?X6fEvzL!{s3_LNMP5a|=R!v!vu`vpkr7nP-VslKVXhRc zFF(mmqQUd{zT092)ODEPZDHv1DB|1{X4|YDjq$ze*21sna^-QbuqauYcl-+`3&P7) zsB39SvxYiv`RuPG=C$?pmYJ}P{H#a zBF)bU3{u4naMOGG?2g-TO6vYu)1vCJ^`^(^vfQ%6#_A?Gc1!kQLIlCoz#rFrEAs;i z^zdSqM3Zic64DnVSy0Fh*SqBUYukB=U8XI%E#iMS2svJMfu0H?cTzg}r~+wrOAx^~ zijo1Jpko7hx`~w9AWG-Bd`+%?BKrjc!epJ1xT}Uco;MryOC4P0;;1(jhglBc$&3tg%u*!fkT_2 zbv}PDuMBJ*G^R>Dh$klnzTv|`<^c+&>#P^0YkbBAIych18pO7{@{H-V81H(ZhBKFt2?BRJtJ93Y=55 zToMXuf74->{B!Li02qp`=Vn{9LgSc$J!hnrkGfC0N2zoPfu_^(EZ&U+3he~y&r+(sz^?hRrJo|>8} zFE5uyyvTEexix3cQTTy#AI?j_eNvp_0b_7rf(`QY4@43N0M5_t9Wpn_m3*$FwAC+i z-;y#pEzom^>(^3oPTT7GPaSGTYcj)tD~$FPZN^KvHlr-ivm5G>>FLPonp{BRNp*Qb zEkv)g2GdPW^Ym15{VNFhh35ExIrTmDr;S6)4)W6SqYC12<0o=Xr7FF96 zB{$_&3rX5TAt$$Bd~7~1y+}UeyJX4W*}?O#e0&PqjPH-x4=Qth>@xE)n|F$MM#QbY zhPN)aUaUanD~wQHqxheZXY*sPgI{mp4kh-Q247RXFCK;S6fb?LgZbNu^M*`S&T!{7 z3qa5~o#&c{2!EV%!5XBMV+v%o6jm!VJ0Uom(2|@{LA+LML(Mdfkdh8R=2B)%SxC_l zd&?xa7@XG})}El76co@Rgg!?Jv2dX;bx=eUL9Y;cXdl4g*>-~m5Qps2OuD9sc4qf8 zsi^0S*9$Y3AAOP6^PBBi4Q~a7WrARKuz*74tG5#5& z6F$uZb@Ng=B5(^}KTrD4Y95T$DQtbZ)b4<|y12C&07q-zQ}vbUra+5(!oUsUk>K<@ z-f@i`n-Zp=T$;@w@uGL1WSKrs8nDAMy-#lZ2#)}X`h3s*lwXu?Sc$_ zYkke~pN+G0aAXcG_~s@o?M1#O5o@M=_0Ly`i=Qa*?n(ezO2MQJKpz<$%>TERKn7&5 z=S#$nlg!HW$@IddNBei1HD2{k=&DdFvxNY3P@;#}3_^adZI68XD^B{ac3K+Xy)u-` zhuP;^$EiJADOk;SGF{_b2d`8w6w6$YuQA~$EVk6o&orGv;Lke zoHw!`ynZ3+?d@%9{RkR!_k2Py|5(>wWsg3r@FaydIe zzqzn$2m@8XZTNOTVU$Ge`)|M#h#Kzhr;h)6-iY$U&k3O1`a~%g_NTQ^qTvOvv zoiA4@V)i)KW*8Gg@OYdAePqMIULtwI;L{t9ZB^AS@+T@YL>-G1mI`_VlNy9PSxJOp z#jGgNvh0ZN+rMWU0ASxlK9ITU5GD!21SS9fdAav`-1NLTt*Wy*dzf{=D0V~EHE6pB#5btSXs4Mr+d^ATAZIjPjJr11R z+jiele9uTqDm1V>yYXt?owZh%GXjuW)|0j|V<;@%pVmm6)mXJ;njE+{{qwl^=3J5Q zfrh%ebud4OBMn4p)!fozBXD)V<}Dn)!S)xo{Myrcn^WY>@%*I=cDydj1;8v(s|}pE zwl27j;Hm~YZdjRhA69-4x~m(AjMapEn(#WpE`%rRH+>)7`|hA8=s z?D?O`0PVe}tbyI9xhCq4BCX)A>}))Sptg|#`qXI%Z)ov;med)3@Fw`|n>9W`<^0w)oz#U%YRg5`@)M(AeLswJIys zb#*&NYEC+eMnIRXpC-ydNwV-(>KC=<<*{J?K{CKvbp7=&sCo{k;fQffoGHm>&V@dn z6Pn4X+M$uN9Agg2pId0X%}`Q6n^lCBl}S*4iwVJ9Am*_e&oX_W!asd&$VgFTOoaFM z=MAa&d>&0Ho8|qc2r7Q}So@Wb1|w>m zxvT%ADY^;F76}_#T9!T}#?(sxtSu@M^X;}*Wl=1-dkA~(Xpd$ExwTMn-n&P2ZX!=Cz-y|_x6SZuw zL?Z=)DLpJ4wVcKYF8lKnuY-~7>=%*3d3j0?oXG#&Sjx-m!iEW#!qf=Ac!jasu3RXB z9wktf2DeAlOr`gjk`BI*BQ`K^TsT;J`l7;1VdS3+QN=)68b1CrkD-8sH~BG^;L z039t?JNp-m`fhh0yJgECLX*TsLDuZhDYHS=++p<(yh&+Dw?U~m{e{fHhLy{$!Zo9l zn+m~<6AB4Y+cjxK$rPE+%vS{H3sSlyz$D)fWR(kdKOSg~kDw7GBO2gQg=C`1nzQwp z1#@<@J8XqJz~&4izmp$PlIR6JzWn6xDFpb8er+OSy6k>5boivwHV9-kKkDN@RuAh( zo1}NP4n-l}oqK->1Kqq7=)tS@iipo4kfXpYX!`e=GFYrsv)|?D=GqF(;(ppUOKx5V z6;}06`|iRg;;}Q1gJwPcuoG2nJNs=JCU@B=*D`5@FvRT0@9uRwTqpq%Um{b@h7dk_ zr`;!Rp4{qo{!rSXj?#~;B-1nev|`PwKe>o>Iljv`zPt6j?w5;Encs+BB<>EQ&hxL4b|RiHm=HkLU>`=zYt2_S(%8GLbMxEIshpd5*jq=`r%hr>lY}&twJ5 zJ7n6sN_fY{U-AcN-1ip4?HhB5d!h0CEyTcR@ZxO0#s6CnL<-zmOUH-~F(P+nve~3R=er@BD#PW5{Mn9LUQ`yFEz!@s&?gf@(Jv3RC;x zRBR>H1u@|MjMyysSgq^!5>FgRO0T06hihdJ=S0s7?g5Er@%f(<;}aCjkGE#3BCen~ z$#-b?bjTDK8OPViFIDTTeF8d0g&ETmqO7NR_Mf5bB+Im~ z?cg7MwhiU*J}>wySgJKfSSa@r?)iQ zt6-8$+nXOJ_BM{_vky^GAXdxILhX_Irlf$+wz^ZVhZf^^1F3W3fIWX1YPGW8;uBmh zE9sqF+e*+vWXqc}RC!c!L>NQzIlj-d1$_6DUvQ#so=i=X#4CU0OyuA99I|zxvUCic zIw-d;;wy^p!EB-xbGC64-;OJ9%a+F)Wqm{D3xf9f-27A_)J@o|`5NIM26`@A_98Rf zo(%*LFi3%F9kjR`GG!{t{slk{`iphQimc8PW_ux4q4eMo$Cy)Zp{qzYh^aI>MTbES zJb|SM7rEt!Vk8okPT|2b>faN14-Vm-N>x0fM}`B^1u0QB_7y~}2E?@n()<-~hhhe| zndX-~nI=g7QJvwS|EreG{g1*dZWDyUxd>+e>C@4lzP0SgWW8UReW)Afp{=Wa&r8ajHddJX3l-hL}ke-9AtUx)G^=|Y3_AM-?9JQW(} zKQ;lGEClG8`)LxPb5Iq8jm>xX$bq$1J^J)PR5CI=MAvhqa8c%*DQ3LqS1Lj;;B2`j zN)j(%!z%~yfYJ){OW3vG;8B_aSTg$kyK1>s#7&MZq3^435{Y4eVV)++^Y11~5Lg4^5!waJ z98o570C*!?)Aj1D1wZy|J=L@S>A@Ee;+J-V?P2}omCv=~0U!xS$V0!ZkN+>T3JKIV z{8Ql83)7b0YtP!*E)@>qUZWgixPrs_9~7Zcqg?=~e@GVB#wHLkolq}1h{yemv-+4N z6PacXUjt9gsPn1nX_GiG!NZde0v3ck(F`-K^BYq=7B5_A(;sF=g1vgI{WuwcQ8a=M z;!)6fyWU|xCOncTLZU41$E!c%7`t-}k=l<|#$Vc;HB(K65HcDJr5znLBI@gKF1Q1Lb*t)3f)&gDp|2nOK_K z2=BFMTx$37^-ATKtQE%kDcNlX$|}FC<%8JkpwNVHl<(^nc&^Xf*dLkZw9-`NUiX`x zuebvK#ia`sOD(-pI_0se|Eh|P$6gB{A;U|IeMOxosS&Nt?cvIs9ZSQ4nbK`yU@v*X zqRZaeY41>yiK(0R^UX;Qdqr#9>>xg{kR~8Ln&KNiAOZpO5uXZa@mdi-V`Sr2@sDDxkw-mtR-h?p^4;FLnP^33F;T^kqHFG7p;0L3XUmUH z(+Q^!fa__3Nv3}8v*04fiy>p9Cf4Dss$9)(Ni|4JK$N@XkAjx_%u)sMEKx#(uM;uX zPp~qj8h}pxC_--;w3!zAMxbR10Q8%?Ro=Cv76E9jG!H6Vvm8_`M8L18s%Xn7addP; zp7p$J3xeq z3JcCpglb0YVHRr3BV|B$&BoubSrzr0DA?p;sPFlwJVLsv-CPnxlstxY?Ib|1(9;4|{Cnj5nM>JM3a*5F~MI6w-v81({I= zZk6YcM|GHm8U(_=ixu zRXrBvQIbs{b@)z;pCm3!TDi!!f3JK2j}A8)9t!)UkjZ@}ukSYu?vUBqRe+gt^ez5Q zksp>*i_?mQ1@G~HBFR+#ugz5 z_Q%~6oy+bnhH)@&WW}!Ts_em?@+jc8fsMr`RVQr*cD#%*ga?z{1Rh%bSuPa?*Qk4| z$d9>a9@V%*Ckgv;%eRg*s9aC|urDzS<}O!FgHj;m?;u2SAnAD?$RyXU(PVHRHfJ?i zkH1){P42qnfuo5X7?YY2UOeTxp2WX0*<4#(X>0j8KFkh)GSK8yQ*_FIDZ2ZL9Z(`FG=T zvU;(lVh(c3YV0AM)^At*s244HjXgFuY7npzetPYC6kKF}*uK?N|D+DgZem5zZtVs@ zU&H*ajB(ILim|sC7sl+pxdE2LNy_&GJlFS$X5nH3S!;HT`)qKw9!sHLMv5@p=8&?o zaREethlLaO#t`+ubYf!Jw%Q=f(W+IW6IXg zfNwl+dTj9KTF6HK7!6}xuSgS0KWrIq#v1irti*`P>35b(=*Q*PJq!l=>#C{TP)zI918mvci-{%M5Kwbim+DKu*p>25)QegX~sQRJ^ z{4D~r*rJ%A?k!wMU%^Z5YZ3NCuq>kh(~wH!lvMG%z}sDTTfNDhVzarz;7QpxfEbnH zP~RPLAH6$>fdj?VN<-k5iXehb!<)xz_^WxOp336RaJkONUaT3m=~A;yed{6+ca{5L zp~-nrB!$IC9Sm`cmtLm{30i|V;V7?R|PtMHtaegO?x#t$}B+u zys%R1da&v~)9r}>GKaI!?;)yuG}c({8@`&-2mDdwCTu!k?0h^33B_u95Ri$zUZrac zz)==FRMwbr8t6QG<31`@WAQvfoXl1RxSuWesq@3kyH(Yj>Q#+%(OdYFg3ZZbP?7QR z;mf5nX#6GFe3W<%xSfB7JmZ|)lBcJIR^H>!o+g+aR2R7{-AI`prGCND(2W;E)&qo6 zCy1t3K$JAa_j;`;vx=n6ER;9PfoilVmFtxtvCgn8c5Nc>fYs@Mj~Vow>7K z<#WBv612!(djIenx;0sSPh({mmr6J3f4b@1rcSx5fdu#q693Ec?2MGs=lxU;A!bjV z?&L7oJTN^dF)}%;n$80mYHOd%>hzg2@HefX6K($(LK(2W05xR<3+VXAw5!#eF!ykt zg?c+as)(v!&{4wjMxQ=c2Y|92KseD|Y3hCeo~k<_{RWU_pBzNx$V^gWN5)*e_c|k7 zl%B~dpnV~4IT#<4@=ija!~TH5kF(%DN?fHGofgrN0jn;>seTZRB~l4mW3c;qWH(aT zwmo=@l*Y_vtdMGmSUFi~{@X#qAd+|}tI1i~5W3PfeISJej7^_BiP&ZU%k4`%p9y27 zW>*YK>x=WRh7q!DbMX~yarPcmgoNyV1Pl!c;7CInL?-BW=W|Z-sEx( ziOos>ike@&0Z1$(WJu%NCE)qiXN0G_AhMll6n#U^+MwUE-0Fqk>>Q4;yCK7U0tiK0 zX~%J541mcGXvJFW1Yc>rwCH-c@qi4eoD@H;M^K#1V}`bfx1Y@6g%3_ABk(`i1*kLj z1qxO5=b9ymoBV({&ysq@fbjnMiMd=>117!e9`XHtyJR%erz?G0$O253%CgtA)od>p zDpNBXjvI-2^^@m3r+s;?xSIx{hkB>V*I)dxI6Be8gmycgal*y!)SQ>q{cGP^n2)VU zJCzw_r0L_WwOPsoS)Ls*?m5m>G*+Y2v4mom5E*byS=bjBP3IqE7Xj8G-Mz>;oahY&41H30G}xz+3|Rf(9#OgQXTe{D|VflPE$fqfumpGN+}|w+QQ3 zOL0Ufny+ijrnmf)g!wU| z!;P!l&)2J?n(ii@Zq?~j$IlHuQYn=vOe5pEeDMOi;_?hrAuLB)$1hkMorpT0W)sok zaa45qp~(^0SRDIBW2aqA4hEw}>BmEO)*=-09V8ZOZ5P-f7gkiYkSeHhkacJh;7a&+Z{JXM@sxGHU5x#cR3n7qc2}V+iJdQg$!CVgU*y(k7 z@2=~Lc}O~eD!Ot!95J)i*EGWqkjgWR_o$N~EFfpblV_H~t5*%sAml@7y8WZw(gok= z3`1YbZ{B%6I;Nh6?SvE1R!P=?E;f*E?$|Ds@S8pHD9DE?4hn9eVp#__t8&*-%1{y7 zbc?1RjC|6vinmXDSG5MLDYgn8&}SVoTde!J>uVB?gUn3M!{R-2{Al>*TyPxS+0Tui z5ql>?);im;PLcS#<-|G5eqmO5-gqcN_hg(>Ma(&|*UcRb?Q?M~FvPKMzbv~RUXB6M z1tNH=R1oqnQR+x)P9~~>Eu>Lm@qDJj!L#tb`K#t?Uo!U?)kNLKE?)_xU^9OaajVIU@MNQy>*}V-u^%4DGyX1XjJH z#vx_Use;_~Ud+evA0_^9Do;XF72?+F0OA?`*Uv;gFWyhO{i8Hf;R81F(^cr7GYUds z#euMRlQeUz9fImf#`&~4gf$}Ohaf>lKaZ|yQ7YnZIY;z)ztO^2KSHcq>#)Q2%VppJ z@rpS?LJGFx@F3KUxy?qrLCpm-wC>GA)8qas~7X zV+A{`_Ao_i!{Iw=Qvk=SUESRvPGB3E)H!oyH z!4GhH-bQ&j4n14t`&rj&duEeqw6gu*YD#@*X5+>P63xWS;UXOTc$|)rQiMBkH97SR zKjR(n1*Ouc@v*-JvP@?g0`Bwc)G-N)cr!=JNO==S2Tbg}$(=X6vG-%)L78N$fDQ${ zS#yFY3?%_#si_HZ3dkqF0Cf&Y=CeTzm+NBIt)M&_1sQ7woHfA1r=PRUXmJgi_O>>{ z?C9bpWtjI2_}62VRP@?jh>CpA>I7U)z--x;M2c(Umj0~$Fw$SaT;{`1xbw=ksd=Jf z2j*)*<5(!Alf1}flXR&NaUM=taU6oNRih#E=o%xabi)ey5yKaB_1>%SUq8o=#Nv|A zHoAqT%Z?ll5Iq2Y=*C!~BB75}d2=7sOMHI{iE-YFn%}8djk;K*&B!^=c2_v4Mv|CX?%L0rh=$vMsA zi)N`bDz3h$5&rglX=5(c zm0eS=dN)eQf%juAuF~sDCpzi@8_s3@;xJRgvhOqw$=V%eXSJD#A%Y;54Z7Y%kFJ#1 z7mbnU)qe7uxtM|-#&~IN+&nTNL>0?>L929cBq9D;(g{1T(NzGiNbhDW+BWu^`)90g zuDptZe&DRL%y_Dnp;nPx7R<>MN82{@k3tqNHW3Gr@JQ9txT|$Dpda;Mn z9t{~E6fS0Swl-nQ^WG(F#;LCK<2AYU-Hj11kS(sXvJ%B)c;YAgbq(dRq}2nZ_Q&?^ zF@@ts*qa76bP=vop~h{cZiy5!rc0BIG=bJENWwo4-eSSAA9c>sFqkjfoR;vZUo*&J4u89riaYg7 z0*hgRuPY<$%Y@3R>>}BdATbS5X>sWeCW*Dg&qYQEF1F_*;Nbc1{k6;UEc=1;@WP z2Syf#tdV4EZ!fGSmy;fH+RK=>2(X20X6FJHHlSU+7d-sv9?1W`A;luD5ne**s1XxY zu@p1=Sq&)#nVo|J*gh2}-TWxR4=khyNtM0}756t9a6-qg<r zWjGxlv4 z*Ofmx;wlkJk%=T!u5cEXkQWOky49gMw4B}a+YuLVRHhfjOAv7wkWjSs2VrSj+q#qE zA=%iRHGb^HDOL4e-mzacUgfi<`M2boJGz2P)7KzjjYqD-Te3Yiw~yU(?}< z>s6&<^CY}z+^7!p2Q;5rjAAfBB#+?dWY3n4>qgEH8)f1-a!S-Yj`2NR9j~J{Wg4ft zwRRG2)q7aUae z4=e7f&``B#l=wD)pPl^^Epf+)e9Qlk5)@x%eUcNCr9WC8ml00`t7)yc?OIA#dln){ zze}Obsic1fM{}>eDUwKQ(QG3Ybc!5bKeaC&PLQ=i;z$r4EJ(u*<*jROtGulmmv+m! zit!+u4d^doBqUKUkiIWO$Z;a)mT@Cxb|ZXZgFauzP7d z=t1=lN56f8t=TycK6w^@D{d@K(pK(UDM4?+x$$`7NjXL7Ie&#bM6RgIMghMR_5W7%b8vh)^DH zA)ee-{&`QID6r9ierIv+!C`$TZd|~%B_Rr0!&P9`TJv~hjpJ!q?PK^_vHO#;{GjHDWZu z9Tnw)lF+lbJ(7}&3jFi00Lv*$_wBxWTVX|ufvlrkY0-q z1H_I&zp)_c&bdF}V$9de&WZ=}sWV zy|v{uEvb04aR{Yx;QVgTs(plB3k)EFZS0D% zOsy(ZCV;rs!Ox^=wYjmTM~P~kfh8W45c97Xpa%+s_X1xi&L~FmSfty&Y^xr6{=1Ag z`x9{XSG~{-s(ZLQDzGrvA_-;lAm}ub7Klw@QPY0E- zF;G-h92Y4nl!&5CVh^K5TexHbw}_RA#Z%$Rr=KX-v124LAm;Sk;$UKkjbN$g5=!>CQABhM5A9j!K8)#ra4<|iC#r?FvFOt~qb5?FyxfYQIY4O)}+_Cwt z=5**~RM-QVVNc)g>+wDoLiox90u#F^4p)xvC?insg(3%ntE;PnvcKowlt3HOzzk^I7l$# z$al#R-(I6vSiz@^4VoEKBii=ZznmG(cGzN;8U_kfyE@7(-2hZi}f6bH=Y35(MFwtLl*d7<$`w0#Ai6yARMm=eegpq~;ZR zk$f!L%oKLBY&~sgId!0Xw4lv=yt6s*yIh!+kvN6P`A!KN&isP8>FD5Hx$tnv%ssc+ z84JkpH&9hg#t~icRZTBxAeEW66NiwoSSoC(IZoDEzUN}Y#9(n9Ikm31ooG&F| z^M%a!#IjT9SH=LAra9>j2%fS#r8YOpj43}Ir|1=D^bFT#WnpQ_7UnLAe7_sd#(9** z>SC=02UPqOTDD-Nn$G380hle4DzgX;or{FT@VMNF0wGZ&p5%$R>etlPF8K&$P%*NR z$y&`dsoyrIb{A@95Z4}b@mh?hHrJHN2&l#4almut#DVR6R?&#x>bVvr__N^#C~-km zvSP_;I2guP@wpvadrdZr$4wL_3dAaErs%O4R3GN5inixvsko0rnl&oQ==!el>U;gA zh~?rJ>&5+1$q5F9f~TwMwjPuOp6#r)PwrF6t5-*L-TMR$oyLL@1=CmwyEuf*t#$`N zn>Lj-w@g_hS8nlLLXGP3!dcD&PiSg|VH#bF5ktDT>Ty>0g;l6+XbyA*VeOhoBNfDR z4Jg7n5V{I4p9@9Ljf10;h$Agf2y=nVYtt-yV+7e+ZgQ&}GcAqs1OG@UIG^yfIo-$f zbsU=C=a28&S5_36M}t4<9_@}+2W+@f>0e|R!O|aZwT{xxYa*9+YA3c=1dL>E4I|`E z^G&ii>?T@&tB4;U#(<=O*&rW>`Pp_U%LlYA@ z=vVt&{%@*&$1OE0w=XEp_Xt%gAW}Q$-B2cK!HXzV!;XDNhCin_PXd@6g_3V4FK#X? zaAo_sZqt1>W%*%F8!zl#Q3-0^T!L{<8~)U`oJ_-ufgNx;du=cjcpm*=LfN((KVKEx z?Ki^`1Py|9JylCM*5Wnt149<|T0K>2qaq@WrP$H~ufa5z?gW#?7r5eLJ|g6PxX^K) z66S&HIlmtE^q1Z9ryvJHlVAmzOxb1%>cQWwO)*2ND^xWZf9r!4lOl}e)97rdGR|LR zuTN?V82-<-`S0|Ah{*XmFhO6!r&)~N9wKO25O%w=r?e7xJJZ&8o}o1eI>{OOh08Q* z!GNO}>UpX=_rbuI+3Hk5B$j|Hgn}yw2b19eizFI(6hm_X$m#)KZ#0-l4V%fZ&AC3~XK3SUSq)NAo zSI=B4=^J-$^sTuu*dPL&86hA1r9XFCUhP=ce|{5xzdH_;uruuv2%pv0ONige>yb=X z5X2pcrxTYtV_ax%CT-h;&E<8F-Ng(3+(oP+Giuwz{ND$Z>Eq1dIRGHI0)U3jtVIinVpgrSKwtxqW;e z;Bp~D^Vw9utsY0d61)X^xXvKrMQAhT6y_>&x0c$t8fDP;aEyWQx18hD>7VQjW4|Yb z`z#+OnU6`D&Fg;VS|9v~0z6CAt3y@C`*xAxSwUhSoYA7)-8-(JeI@XKJ7nfsL>!IO zr=SkAd%l~L?I+Me8?oGvK8ay3G1e}xXn>xy}g8NKw96qk;ULCqtk zzRs#kp?A6Yao!TcVLlwzn5J3XHmEbME8&=SaILKyD}wC#2rk0_^uWLqw5|qFP_Qz6 z_jIBsdR|fU%>T6t&<7vMd*%0X-pzf{ynk~SiEVdhTVoWd5J%+h$Xf1}kNacEVP)ex zLcZXOufFqI7Pr;x4fpNBl}U*>OgG*2tJ};#MOhvI#xM%T&5W?~`j|L3){XJ|r#dFP zrDTbYLh2@Mlf^3t8#>XkF#B^``}r-$k0(QYkM~*b7ksXrqHG*{ERGs^#$%}##XqaL z>s{V#(|lL_8(#Zyy2;UL8*Nt!fp6r~0+0IYnwnI@6nN5({NAsj+G|JRg|zsptgYP- zJY;5!{eJ>G;aWX4jc>{(nt!`05dLt#3;n*kk>qt!bKDn$Y{Lz|STn$9N42vQdD+({ z*}5~0twkwFN_Hyvk?q;sJYYML6{#q8k)tFM0G{GIt3$825cq&Y6nMjNp^16*b_C<~ zi?HI6V~=?G50W0QsrK7oi}u%}3hw>bs_Xo5SiFpl;Pvg;ZCR^ztB=7NCdW_x{|{ep z9n{v_Z+(~IZpGax9^9o+D8-Ar6?a#}Of;+)o-~7&fpYxpeJae9Z zn8^&u>?GITx%OJ$^;t>xSLpj&vs~j{O%zXODMzK>QrhpgA}=z}yk(xIv`#bKCq(Wx zM!6<>lUa3fOsD)K5U|L-uuhs@&>IcC3GCNbIE3%WbC#)#-b7*aTs}HJC2%~Vhe?}+ z1xtpNx`rChF^B12fx=#%MG02|!#W-~qSo7qlhMy0{-1a5mzthf!@MkBE^WLg2Xe(HuX+q4 z>8@&N$-m%Gg=jkNtM0F+bYi74<(Z$PXKfGKEtbU7JvUvNDci6?58Vrnm%(q5ns06I z({61^eV?_P4|b}z3W6?cOx01@o=zd|58;M+k4u;r9yVCHlg=lO<2_ds!tZ7>_%?Ir zsN7vEd(-tHM|$7=p+a}DE1BrhbfAaf6IGV?g<0?Hwth$;(WU+BEC>(te=PnW*;@z3dh<4quwx*u+u8#hF%5kQkF5MEXs0ySBGU!m9`xeMstbY+r zh1h-Y2#IRnO(bhjIwg)2#JN+2=T>T5PiY4yLIgZ!l$&e`&X8rLL_YKtldS3x>wB`` zXSv{9qM|R>C}i@FA@t@UL@_e;$sN1qS}h3LI>VhW*LnWp?F>x0jBN@ z-mZv!{&8)Wnx%^or0%(%W^AdCK67RuwL&K*zFoje=->w*psk8Mm=X1OW)RM+i7xNw zgH}10|(a1Fd0OS=}&jpkBdW@ zAZORdFmXLm{WT+{m!c&1?p97+lvU|z1w83t_yKuRL11fSrs^$62NkObfhIvgtVmw& z6I%*|gVD<|_?CX=q>do5B`Bc!|Ru1RWwfgr;@Ck*JscI{*N;WTl;W$&M&h%VeOrXTJ;AMzUP2VIfrR zCRkYgbY9n?FV^>(hIP$pfb4!q$v3a#wU6C5jxf?Pr%!UO|BL$_`-6D`vN>eP79eGU zKp0KWDr>BWrV*lL7gv%^IOj2fCA;I0w7HA-LkRokOAXAKs9$yRsmG26G>Le3eo2G5 zk*35~78LbaJ-de^IxEDK+2(v|AR~^;nXS`ACn!bCy36XSxGQVZ|7wQ8@j*ay+rhyu zxVvmGO$@U*+1tNqp`yR>K$hP;j|}e$6hgC--7jmQ7cn5_*kvBeZeYPp3@jJ*eHbyc z?rx`eJrBLVZ30EF*tf9)5YYJr0!lm+tU0YPKh#sc4+4Y@#-NAU`I5jltq0iNkRdW1 zV<#|&M49J!a+wJ6Q6G1UQJ)>UVK1t{>Y9^Br3o-*@)CQ*AxJHBpzh<|(KM@c z#11PdN*>$xiIbyaUMang$wF%WBOXGbwKn&I^J5Y?K_O79^m+rlM+aP9?~Digd`kYP z6tAE_@yZNVRXnv?Aj*&<^A^fQT)g(zwV*{xT~%d&0DDR%=aOMQ@0mZ}nyCW-`$ng= z#hW=1whhf49E2tuI?;|)VTh-X?`Xz5(EaX*3K?tefg9r7`2EYC9}%f+pKWPS>Nw{( zL=w;8^ZU@w$}}%#e?;FeRi>CE{uFK4F*0`&=)Bz)+o~Nn?YGlh4O1P!qY@HBJWd%= z{n1mh^pKWJO#3cZ6|dN_{|l+x@)G~cG{r_A$RJq#4jjaDG^(S_`M#2kLPyx&?U;@5 zFaDw``v}>)rd8+2hZ)My9{QJPSOw5f^u#8bODhf~@ThvUYs#1t>sN~(b4QiWV#v-F^IC&lAZ$J2;TAO?~<(OZi@ z03hL}|DR0ORQHoj_v?`CoWq(SMs~JKYw{H zH+=c}^z^j;W`KG=MHyEV{qx&zN}CGgBDWN(iq7qtwQ$D=Tib_azM4%7ko4|n)OQfC z7%FQZl?EpQaNjWGMy!=cs9H>OH6%tyj>c5`_Pwq|V{sh>tivYBIXfY)UZv+Flm!2afnILeJhX zU-yS?&b9SL+1i~%HQx4Qnzu66dnXL<<=aT_YE-Laz%qXQ@NZWN?H%CCLhPZtDCK|D zQCNgsmXatfcXCDYD}e8FhJ_Ka59j!wvo7{(QCy4HLlFN}lq%q_{i2Uz;tg@wdP{*t zRzddL^S(~3aNY|8KITrQD_mXU8}7crPh5Eh(tsY!^xVR$qNHsw342#{c4d#IqL5s9 z0uDOg-d`*J*BbLx_j&l{CM(iTx1$}X4955bpDohDf8;hLwd!Lvc(!GPx(w797WY zd>pxbnDzB&0dWR|4lU@?4)B68Vko;5B0*_NVxfn?qpO`5RLNgd^loNq=Ks4~I8Jbf ze_RC}UH|_5JG85`)bz(4^%{KwGRb^JcXKeR@$tcL81e2eU4=ysmhV<&m8MBQ>Ch{D zy3%zpZV-%=qJDa-;<)q=t2!k}`FhHJ2YeHvzF>o1MRyolhI<%(4rS9}f{b5rmkm7# zKOgy=+)4*V;2a2DuOjmwx3U}ZRyu^jz1yY2^O{)_Jh6FwdTg&QcwYleu4%F0CnhG+ zhWJv=>I7v*8}Q^I2j@%EjIdBuW2GP4U^S-X3=(}(a1q&H6pvYhOXvwnWe@u@8=Bs) z@c}y7tyc~&;lTXdFV8;}5R;0lEiJYzDb2%-sk0&+_DelWZG@4HBpR(8#!jdyUz9M| zW`{A#@r%PCq2Thd^1{YvMT62tdm`7!+iPP5mOzYH0&_2flV!p8For_uA}Sy7cDg=5 zhXp!dU}QvxBcLs1Pm@Qn)HC)WD+J;p%yM2Ovqrl4F?6Q=QB&`IrF^K&JbFUVQ#p*^ zS7@|oFt8D$mHa3a{A{+=;O|nCi=j?N^&yHeh&XXW#$}g{&{ms~b(q40z;RL;7YVK* zqg3e+zlzuI31zw)p3;4ROvMlQ{l{T({(^k!8r{mA#AZY%o?j39_OFbeZXr5LBq%Nq zumQqEu8-G;;couLxkU4;q!1uo>DIv&_g{xWe^$ak0WMq(Q^M0C-o?u+W0c1YOu|_Y z{#UNFCSw9?wU>rweoZpT=t0*dD3Bz8Bo(|TZ@RlSNHbj{l_ zD+6oM3$F+$XZEBab%mBTkyLJ%RE%W$Im-fTLJK--UM52~3#PrL#nxw$u>#U_u-n~R zYSa0uEfUrM$ALEKV3et49E)~>m2`sI{#oR)+F$VO<$YN|E3rQ!( zs_dpp2orRSVFU{=#IK%E@ur zjLY#dTF-G2)}pgQ>l<$SA?DLuqrf4Hyuc>o&R)9lC{xeD1&vWyi183(_kpQmUzBQ$ z%*7xntADD1Cw@_uccOJds+#YRmrdZiYf)U+8jdKQhe;y_TZE;kYcbr`w3Vx61zwi}o` zW0@xexL&t^h)u=%#eWw{^%EpW@N};}+Ol3RYtJoo{2u#45?OX zEyArDE^zGtFIT@Gg_k4GcuXOG}IGmNr>x2IQ5^_I)3^Wo^(ANz8>gx7BWYsKfTGp%H4Wh(iuXpPrI&AEC&>2|5-vp!h})f&BoSN%EpFS8d^A8 zz+RcesbXkYO=e@JA3mMAvk$FMgzD1PUs5_YKOGG!C@4U?GZxt7$T+M8oFnm&!BUTa zM{1ZaJ{^&}2tLNdHGKo)3Z)Fk5Ubjug{{ zxSswa3qv(X>+0&(H}|M4?ZtBOtS?z9lN7d78fSB!ND;FxM~ajRY)?K=ann_dBfo|k z)iuQ|_90@t(ajI>@)!B&mFKpSp82k$2}ey#OIh*{_*sm&Y-U=Mp+eZyY&-)HFYC{a4^LHOAvi~s8_~)f9po66c9KHe}uRtsY8Mm4#A7f6)s1Alfy zJu(Tw|s%;Q1fTS$<1wKWCA6T+hgx#P;fg!KU z{KwrRe*a(5wyzG-k?{RL(KqPgETyHYh7Y9m^4SA~!N2}9${BVWY03D@kt6l?W8OEn zKzASLozj20t184Bg}_;%r_Jf*h7OHRl4}V0_{tY4ZnYsm>VTo(?^-l0h@UOyWWbL2 z@Y!QyQM}zgG;i#P?o7!}iqcojLs103W&*Tc!AF6^kqoKgdu>HH6RSlw#boPUcx&bW zB!)4H$kGj4H`yqCiap&8>6Pk95(X$AQAy0D9+drKhsr03)H8*CBQIpZL3eWo#|dh2 zpf7`bj5#xmq4(cc|6yhJif4Uy%pQOREtGeV+kemCs;k=pXdPJEk$U zgS2dUE6Jy;h;h7Isi$74%%)10C8sysni?#{&T-K-xkc;U%cc{O`u6M2*EdeGMquK3?Rkr+z{gh^3*xa!&+Ke>0EciZS|v#vWH=LP~i`- zQZHxTCWlFQxiIbT{YBkB&;%s0nk4OShBMVrbhA32(iO(DJ2%Q|28ouRXgi0;EFqVk z#k#)aY>TkFUA$NU!pUaDmYH)5o|1b2Lg*u8Vz$Tflfrlp&fg2bpQ0f(Sr2CM>o-uu z2}GJ3tE&p?>}_xLg$)<(TK##eFH#y9L}mZgQ6S~zpuVpKjrtuBLKmvX;RXCg>|o7L z#uF8OR%w3Qd67m{1FqkEHPckT8P>fh34aZ2Pl4Su@Jrrgg9TK{{1EC_rzWS@1BBB$ zC6l(hI6(WT5JT5CGPdISiG7qb-yB$v8B492R9X zNK^&BUnGlBj3sjRg>oAZ7JM;whSp;+_}-Vl23M3V%uq%VNX{BbuiQue20Xy=tI>(C zYdi?8zV|2xmvs-n%^E#j(nC7*T7}Ft$jvkPad7cJSoQQuuD=lSkgPZk9_~ULLrcSR zy*!^~!uRbZeMZ~w&2ncifl-glH+ecr?jb}~*X^Ofzbp}`r4?fVJ#iP~wqqgt&lbH>kf_Gfflw zOMwj9L1i#_|Ig{YJP{zAKlN*P7()2=NaW~oJo{yNBUiyr$Mm(kMC>7(acBa(Hm1|) z!4H2)J9s-zlhLq%^R8ZC%(CLrQUZW{K=xzFeN_8{nDXIW)yQbmwva65>?Cmh(eZ9K z61d>m1v%6e9SDg%0vdB>uJ*9!?5!0fQ_+*@G(2Vb*0GVyHJ=uBo%$Ody}VPpUzcUf zAf5mX9fOzJ&Aiy!Z+?pedf+r9Y-FBbrZthbe^^_qcE+*!hUh4e8%-*}2}nc;N(9Z7 zYvwbu$D)tIs`(*Yem6+s;YsDN!ub;;67(wdBJ2BWvB8OESSIRV#!S~4jdV~vD=|Ez zi2i#yr$&79Xc%K=%bLCIN-LgOVd0DCP(k8ngv(C(TR8=NvZ9I9xW=0X9-DbfzpGiN z`RTqHIZW=$j-vqKCTmz$&=C{q(^h0yp>g$y8oqi+%JYHDpdOY3Y;vYMwe68tik%{z z%QzU}auJj;oydg5w4KpoARcq*IX&SKU!M?)8C)X@NTy}PB!0KUsiZKfo@Pom7Ywv_|!W$G^*B9|R@?7i;{!>?#N!MtkN z$R0IJ{xPkd0Gyy3ES|903^oN$Fpxif_SX({=ag6S#8NVJqw08z-)CK+UZI8Q;5$2h z{s@{5QVMjhv)2^+S=}g z(G@JJVq9E|@~|wKo_2EE!D5M%j=4!4io`qIjs;c8<4^*DhHPFHQGxso6Gzq2IS%Pu zJX3~O`3%Xdn-OurnS@2}W7uISG{MXt>bL#LO#w!idFZXG%pj!z6My z&v%Lp9naSu>Q#1gP!>t&DNfi7`{vwGBdIHx5CVilDW7k&tX3V`1=iV5n<~w-Kg6$r zBkq|l7IfMBG&?Wx{&>AoKOaZCQv!DE#UbN@Kfw>}*s*$7sO|R;1Rbz_Lb3W$HU>+9 ztkpi4nj#<+bqD>}D{}Xb7gkEY&bPA9W~W*G3^SmHF7bKj@p!*6be#ENKRdSik0}NInSlTZ6&cHwWo})Y&>|6W>qFz zxfez$<4ApI`1Jzv9ZAwk1X8Qr{Go3=L7iDiOFC*;d zxi9bkaq!$v^{3h=Y!lJ+n&^fh38{fz@!$(DW5&k%hf8y=FOMFYOyMR(t* z_1lhx-rvtDJRgRHc}gy$kGUVs;H!OT+D_{gsWq*IDm=uS6a|L8^VNo+CkdBN$6UedVh2WASTY?Y0$ z^_Mb`g_ghGbLQ3jwGZFS_gfEART9DA6FE=jt=>z=(^6f4sUON2_c3=T;WM(c!xQz` z;r-)xME%F7AE4zv?N;+GFNkd9ysdts`(rU_EU2?tB|~&xC1~By>;1Usn|FI>gM^&M z!wplK;HEY%gRo6EW7L?Hc%)F2{#<#D%LwN)Bz)ogZ-U=IojC>6(k9UJy}oEZAXzZ- za3RERBdXM0?@H3l464?9Q1u3f8mjU+fTOO)g)qhLyD=MRVcNgY211Pzbc<{sUMA+d zSF8_tubcg14t_`@K1+;^TEMRhjSI=J+iblecP}5t-88q?l#;Cu=axOauPpAiAFrf0 zcAK&!pAq1sdgMy%$?&VQqYPL57+x*ZgigI{uP9u@!fyMU9$8t{we9$?YOG59j%5dx zjGT$8mbS!SEc^!YCqQL9*z2t~I?oW+mQMvRv9BAVwx?lRkO5Hi3_)h#jM5Xn!3wtY zcKpi40AKP@MXlM8>3tvS@f?f|;;Z}168~<)jMGiNgLi4{;CQBx(-2+C1{B6NPi{@s zgxw5%v$d8})V51?bO3zx63cg+wTRuXes|rkkv5wc>>-;ieL5WD*VzNuZAax{FNaQq zJ_u6zfL?0jUNolc3U}<FvOc z1ELJ+?QW%QLWB-=TrZ zY=*2LIi;2l#U(yXKlFtfZ3;(;-C2%~B5$VYQhb_naod_Bpa?nZ zTi?{bnXB;Kb@fh!S}Yz%qETE93*V&1Lj)6ul9R{o_h0<_vmM^Jd_A^fYb!TUSSmP7 zSNiD|%?U#t^qrX$K?j_p5mkTJv-AQS#GdHw+qTeVS=Rk2mnSWmyC_aQNGca9kK!*d}`WmC?PQ6(T~Ylx}z{GP$sw%_oL3BSI!@ zTAM$^VXJ87-G4U?O=kKU+mjoqDCHY~P0|PtQx5}B=Oa_m3(;Iy$g4GHZTv2MzIW*f z$JZXX5K*TRqhmYLrZ&fA*cTnC`l-9QMeAG*CNv=@1? zH8Qagk(ar6sK_EJaTHHr;7&#Ev4gGmV~l4xwvP|&PNOKW`yq;ij}5vU8Lh5Jq6U@m zD)cOnD`eQk|HB3Efa{qdQNHWQm@?5ro2k$4F-iivm=o$~cK=*qwro3*=2md&xi8kl z;wxgUzdb@qB&oj;eeZaAF^oH1l{bOJDyYrq-#QBaYyg6 zU>9+FtUw19ZideBPrGy^BFsup<%nnT?B#P_Cx-?dHktTXiCLbP{*gNmM@1sIKpS zeqAZ1!Uvhr;%5QSZLE)sfF-rS(`_f`3C$ORqRMLFV5qm<%g!!Ff&}UH)6m$QGSrVo zWq*aqDqoLMpL1F4^g)M?8x|3_VO>GT@Z^GrM2t)Uy`vZ(Qq+xX`xxbgPH|RmXJ$5) zlk!q^>_;utB2|Y>J{>oXEpCXR;5rA?1v6~U&J=ZH4gM{NyNb(2IUkH7-MQN|pLSOL zj=a3~b4Ed@bwA7N{3`p6RP1SKqTx;|XowQ@t{fC!Kv4cU$qqY)$XNM|PIj9nop9*4 zBA*r25lsHjdsEstkh;KcFxMzVYL=$klg0PcfOYNZe60C;>uhURhN6or+g1&cD02RI zSPg(Tpt-Qoqr^*Nv7_hR*G|mtGy7|XKt7nY2jv(sc5Ax&S#0%gUW2gWh%u3mfFZ@l zze%IApSNd--!l+BAG7WKfM-^Bc(Hz1=sNFTTR9dni5Nq%=S|FujP++})IC|OGpJ)J z>ie{^PT!vc!@z*0?htRCq?XH4ONmy5^>>Ajy7hr|=j|19(DMh$dmi))L`C8;@f-YJ zS9|e!L%-1WV({mjR{Yy2Jwo-B{GY>&JD-WM^zX?3_<>01V%epQ{u0qR&VDrP&Z{5qU$V%Gq0SgRN3Fv!zhQ4HK{5+TS}as-&rKg&Jb%!EL#LNQ zzc5JR1g9)C?$f$6$Od|Tn~E1FpL(Ty&@Kxwl_9~lT`Gz&M;DF##o_yi#`>^~s;p1Y zJI-pCYD|HeBHR#end+1r-9I{!4CSg$PS%j-V~~vXBSFU|W3R_>@8D>y}dd!a0Y4)o6tGA5^qWA4`aq8M4iu$6KY{jjgz!sk2s z{6DM#e_=|!bT}>!XwL7B9i(OgWf@iG79MYjS=wLi+Y6HcLl5k$PkSk6J`COMB=*e` zs9;$#)z@JTV%l#l@ro$Z;SBTdW>&IkgzfOD6$z;Ee$+rB-a@0Bp7E0i*pzSB9)lwwK}X^A2ZRwwCK}-VmF&pv)Pi zEHFt z&E1^PNg|2z^&uJm-6iw+xHKqvcz3T>kVh$BP$C4kBRZZaN}4q(mZiH@=q&;>aK`br z*7(_T3jTf>)9+Uyk8x#jJYdRHnFK_^^l6$)X8>x*m-1GVw)kJ0zHH7Dk_nJv8GKZ-r$qNDBw9`bL7xvth6=&h~@6RnGx zecQsN&a)5eJ3kZyOZ7dV0@aM1sF-JB{%SLr_&hXeV1~oEz{Q=?fbGS{;>#Ixtlq$5PnIfOYf!#RA9G9Sy*AeUPy7dY@Cr3JO z-_B)kKJveWjXR7`->A0)M?PE12aVdoyOz1Wxh(v3pUK_;js-nM^%(te5^l$>2kag` z0j`4iIOb_m`unk>p{?U01gA929G6K9fbGK+j?O96`f{`YXNoAXH`b`EsRRB^#zfE? zt@-QrNBQ#Gu0N|z#$g=2J5^D`725UxA|`ih36eK5pZ!{(=%P#5>L{{Lt=~8My{4kB z9vl^g)~v?{q0cSd**LiK1Qzg}M3==GY6Ec-3`Ox9YjmRv&=FXc%EZfQ+{DqJoLP+D zz8%k`^AODygTkiUSzIW?t8;AYnVIEQ8e0sE>(4o%RQsk>AGg!Z^}4KUn`J zQ-9#^DOsQMPo<$);>C@^U^eN5LMX+oGgb#l1l}*cRbRmF+sJGlrMytd-n z6e9*qA0sj5$T>5{pvr#|g7Q`ZY{p57{>@El+K2LU-lo6lWT17ZOG*U?<4~_L0YvEG zuxK^{{MxiS^rz!PEXpw?qrFfw>Rm}I-^}vT-FW1q#4GJw|0uAhK=g_SB0l!DWs8A?u6~btWY&LJ8df@* zEZ~a_Ynf(6$clx;RAL$<+sNmqarKhr*^p_;J*t^g3CN|HrA;iA+m-|)SyHt|tJm&Y z-tc)m33Rt$9BOqYll6ZTK1I-atT_;qiOJKokm#SZm?Y0{h6Fj{2pxoDtfJvZ*k|UKdRNFW^_AoFwOnjfB<6Zj z&Y(&$&>Tk?*Ew4_Lnp*{sGJ;59=-AK3ZK)@r{jC3Vy7pHIjPX6Cl-%2GlR4T-pUk1 z)h(;$1Ps={En*p!9rNhYP$_*LN@`Xa6bHk|4X=wMUWPsD3PS%*Lyt5_4ytncymSpP zJtsB46dC5-Y|J>#e73l@QFXSX{+%)+4z|DSxE1-$fOg@9Zd1Km+Mr?w{zQJlkRmw< z3H#m&xT*YFJ3am*KH_Fb%w9Z%6 zODSq~!fzu%iH*5`%FTS*{74BMA3MOb%}LMK3$ux%M`3rr%sh7iSisNYD@KX&>T5PGdr%M z2jTPNS*UDMi>*4sVb^T7$mRFtUY-z6I zUOT0nQ+eZd^uQ=+Zi^uVr?498_i~qCYF5NtWQs^tG!?Ma$$(Ra4E|vYaFB+KUF<%Y z-cbZC-_f%+;~owi$Z=r#1LBmRFiIfk!^D|qtnkoTIp|J=^zv!FN8JEi{A2l*{ze@6 z9oxgHn~M9q_Hs>p4@QteCalm38&P%&6x9EZyMP@oHL2Eu5w~Z@`OV~Dl1|s0IV+-l z8sKFcYRd)dLA&myMRxCVWK<=)ouDNcH)2Hws{<&=trCOv_%yB%&B_WDi(w!u01?djYaN3lm1PI2h* z{1o^f9u(w2{Dx~H=Oze~<4|ZlKs_@S0a~X+_`Rb%%LgAaHP zN~;9rkp|fy!CmeE^^VDT3gjl}fQ_|bOh2bYT9<}-p}DZY^_SPFC8tmf(igJ9ghM(d zXuuGfG^@;7c>GjEaUh-*V-^?^^vdK_`W?zUcVUIv%rBXmA+Spfo|H;QhSu+h!5)Y= z4xQm)6Dge!hLvvPCrgCTdwq`bOO~Cip>K^sBZ%?UM1%R=JaF$ldV>G?u%OXh8K}=6 zHXS}IfxrwcY0yuo8x$ueW26P0bvE!$z4B{e9N#NG(`PK((VVXd?&+_e~=8rEw?#1Z3R=|SaovyDJp&Odkm9QELT zy;$C64%8I?KWygzNqGGqw9o%NaQtuD?LP@OHc z#!(<(9|7v^4(8PpDke4k!PWU;)D(KzU#En>+#$S7;jv5A*yy_0CAtW>rlWvdZgm`C z=y8dV;O9#Sx&NCs>>|zf(r!BBD%_9@>nfAX8zs^18*lmh36}hivi0BU*z}wZCHvw# zy59r;0Fm)y`jsKbfUqXa&}6|W{HVVq=1Bi}kcuX*BgcY9b*;0Qxp+%3Vsh9RaztrYAUo4mf7xU8X!$r22}EOtN@ zo8JRHDF6P4jc_T`^N{?5lRWl^QG##?_Gm<@pD)j)Bgmr7Hfzr0mmCNi>5BC^lrWZVRDwZ zH$M`ZliK^8T)@cN0(;*M4uzZ!o(4snL!(?!WhH%&^4Z#TQyl4-OL>)EKwz_JCJU0 ztZok{7x#!~iAyz9upTWFZ`U_hKA?6V4@uS@S2J?PL^;;00`Sp0X^sfh|9=ao^`52jC>Napzb z4c(!!j#f~-c}EACM!C9NX~ATt>UIw@URpSn^;8^I@)?p*@1VT8(RS^@^02vZO)D8s z=R16dL-91GQHT)n#iThqFJI&K5Rg1-#L38_gCv-S6FA~>rMu$zHmz}j6oMU|&LO(+ z-o;y-<)CkdVs_KV4enGN4v*L9V*kb+#1n{~R9O<83Q)(JmVxeWFqiWd=T-w!8Xo~o zs{zr+$LDurqV9s9w3bM_6IBEp8ydH_e`Di%`>v{!{TeDOa!Wr4yYlrXSx}W1qWitI zqp$c#csKM#*Wn1c+E(=$YIxSTLy1`&J?>_9TrApbA6ix}p3EvOW2C26$@>#c22N#k zLF!8Z@O`d}a{*@jZP2mlMPMmjz2d=Af=|gEc?Xmnx?N0R^7k2MrzC*_U1`K%Ekw-k zh9`AYIx0;+k?`x<#k{1A<5|+%XJ2iEuMEA}TZ)LuZESw9Z?9v;{F@nEIFf?JDO^f6 z?~cVPx_5$UaIy=k1NdE^j~e!CF2^!c-R7HnvGPv6P8$o|51!62jy)r1L;1X$%h!j$ zIO|sf$44H)Fn_;uY&ru!fm4b(7%6l$2C~q>CXME;jOnFz{5uZ(oKzA zio=g$`zUTO8JlusdhaLmVH-`3q#xhHBoWtLANa%V5nX5Hv6V)8GyM`tzO3@;Z7(^m zV?3xaisjie3wIZWef*C>*r!m~^^C1926PGU<3SWXZNlz)JA~)0FzWAT&fBIAAJW)R zeVs-b|0GdNX1y2sYuTOjBNEUz8>0=c&HtkS_RIlut6+$2wu#5|_WqkUP#l<8&vlU? ztHDwlx%J!v&%d-9BPl~*5)TNxxkVFpR|D*&ty&%9XY=PabuRh7XG88;(!eE{r(@VaEaL`;!@7Z-+Jlj8N=^*~`E(Dmx^p^R8*))JW%x8Dw+e zJ8itxCB;7*QJWAK3E^d&9;bXRj%94g!L#o51@5g*2+aL#0}f>*(T+8U{`q?vNwtS0 z(qK&q+^$L3;EcswEA#-u(yVpAijWJJG!}9i^|jipmXC0(R)gX^q(k3X_$$UPs_wXlg3sJ zR(ph7p5^?s$sxSS7-f#@T=-U<9{ib1zrYc3?(zp+t2v;C@M4rdrUrP5I3b3MJSbjApBESfU<_aN)7O zooT69M1AohcDYSox&}>5_JNdFKB8UOT8Ec!98!87J}Xfs?_5DF_4h^^qbBQau8u=H z?$k*_?wqg7!&6uqo|S{OMCutLAwhD~scRa+epNQ&HlsPqw<_HIdXD@oZ7DQqR6a5Mws+<&mqwK@Dw)3gk(R~aj&@?X|qmuKTb5r$z=Ia|>5ii?BvB4rT4@C0ZitD^+Z21t^T zN(=c1m#Vj5X_X|=r?zISw1m2W}dB}U5qmgjIJj-@dpGwUfo%x9XR6Wh;AA!>tS zY9A+;LC=UdAeF;b0fr{+Z+gC^hL_V@Q05r$4OYH})KqIqamJCZRTBcv3h4^Br%j-M zQ*SB@sn~ch&Rpjj*}ykH1@jWuX1FZ1l~v1M+Q7&aYvBXs=xsOX)$XSq9Eod4Z3|Tt z@&m7}{oU4QH?(b(vBhPq06x;}Y`qX`&J5twjO=u4H=(?aqe_()4`I|YM~ik!yQtS5 zlDrGw2E=;9>nZ}v(Mu(Nc|0Tile@bYQZ|pwCI<0_8nXqUtg*G>81I3msj4nx?pZBE zggCOxsL@16k#{fFnNrS9NsV=)qNskP@#M114zLBO^nGsQjewvV>S+l5hOVIoQ*LdJ z*2NGvx5lkEQJXF~A=p&DHY|pvo@O5)N$@s`lTIlSYiEh8D)hdd?0zJ)t)`AH!it7V zd85YCs=I-j)C6<$7D~{|QOBE<3K(G>?!m*gb@wqvC09jEv6LY16d4P~!X(HvE8D8$rpc!Y{0*>8A=@8g@(0dEBbI&QuMkGv#h?_L2w$33sAj|^NY=WT zUDiCk9uY&{sph%i%@wtoQ?@W36 z`9M07Vrp_|tt-Uz-**tAajy<|_;7Y}P=K+@FLir9Fc=)Q+$g;Y%p(rn4>h){ z7|2*zR?%OGX-mH7C@c9#!cU=qqu@5$@ z$Fl(oSUGY`1^CC654^q{g^XJWeiJR1dAQfp z6XQ|>Rzi@PnzqFZ{9R2c|=p>#3Ox$GMjQ8xRxf;b%@r2`7ZW`%t7FihZ$j zuS2yrs97+)EhHE|zN?aNhgEEKE}FNYOM5;tY-#*>fx!<=?in6UUG9ug*o-`$mntkb zJBOctTo|1WDUM;kzEOA$)@=lJOr^LZ+L7ngzr@LVnyg)o@c~^@4$Z_4uV0ed(RWp^ z?(RPuWOtTBrib<+mv9z9@T2#QRj{p}O{H7*6PHUTwaZdwWkMF>_iVbe@*T+3fb86o zC#~GLTUzQ5hknA1=ZpJY_2LRUvny%o*J$Mp|D04L z@|j5AJ;wII*`tlDb{V5H`}Wqt(wmcWFE?ubyog=jvJ-p%YD0s{J>aZQMq8)G1iJVJ z?9zCHS9L?KAu%rK%lYXloj?|g>&xvk8TiZXil+DO%lL3}$6NA$sh~DwMny1#8PV1$(ssxF3O*>qct7$a(mn5nH^--@0*72>zo=x_<`zGn zJc)PJbK+JG&NKlIspXY4 z86QSnPYop#Tf5b)>H08LTKO$zwEwC&GHZRRh8&xx9fKO1&y%@K@Vyegc(_x_!&U@A zj;-_JTsA8ks)~k8l^mtIGz<6wDDwf<6;o*a(aQO)E(;?!uR)v2Z2R+YB(X@LGQw4A z-jKog5ma|N=no3yd6}h@vFo+aFXmWVdZbmT+B~^QK9j8ilz81%Ve3I@ks31u*D2TK zxnAq-Gp0KF0(48O?rg0syo(^1W`^$*+k~dslDF#4)XV15Ya3yWtU+PX!tE6o>+>ob z#=w<#s5C=mZDI1!?Ldfd9FqhZ&yc_{o34Ydzucoo8HzGF_Ghr-UH#-imO;X__||3E?7f&=03HeaM#xM zFtVLk#=?)|jJi{|$-Ai{+1}iV{4``|NPWp9Myi0HBeqS9!`=lj2GdOeaYQ4)x zy%V+Tc@dji+LBdWN(OeMJ0_JTUr60q9^X^+Qjs3+09#ye zY7*KQz$&CFC5aa<#_I7%kDwf4OqZlQjhnzzTKtlOTZ=jp-B9Dv)_NzFCkaS~q@;sP z1HYC+-j(DE-ob}+qP)Ef)|DUrRk4NZC*4IBUYXN_$>y~c(a)+0@@bTLM}Z0NftX}L zv^1DQ+^7z`e%di$9pnZs)a7_}qyd;`fE~wiv#yC}3D=nw^*3b+o$tE8E_E!|YezHh zpoI0*@!<#}#yeO0N!QX*kOlr4v37?FxC3;xYmnB`8S2*|FB}hiO}kYV);hMN^lbB; zyFC=e3bTfG-3{9WF*YQM?JgNh^ACXjaRq$X<9YP z8syP)&JbXDQe09pHXPJTli1wn6D32&C<5n{m^F3!Y44XP(yE*&6Qzg>vr1a730rq& zYT=roQBt>!#5>Od5A&#-#s1La_st>T!ujWmp|N1Y*1UF&yhe11f93)J)yh;tON%CHHe<%>^hI9oQ{g)^}KBM!h53 zYe<{wXd56$P5Y;Z8GCVdVCZ+@$nPkd>n5*IT{PK4?6X;8b<5_*y4D%hq$nMyVx2VR z6V_DT_G`wKWzAs9Ob}B_l_trV5;Lk8gPCzt`sTLztB>TijCHsSSeOEBuHRVE_l!l6oenZV6n83Tf z(TBPvxpdcCZhYq2XkL4ww{4{eP3mQK{0h$A!wuY*e=aUlFNm|a&jh9HpH)JTl8S~me&tJ4)22WxO z!rdnoVHVJA$Ns{~?JV$BVa?(3zRvj;cTibKg(f|5+-p)6oOU4{XDFcS0DgVU+J(_& z&2)DXPS|@F;+;?jHa#&M)QMR5mEENHZY;%XN&q|JCcG{gz)$E-ZE0I&gRSFn#u%as zYu49>Lu_D07uQjYCxNfj$rtRNU|;@)lbb}+?GU2R76QJ)Pf0B-7>C%8{7QF$r@gyv zRTHhPgJZK7?`LQXl+!cXpuy%^!I8=InYG)*t6h&gK<@6=_}zqp|Kqa)_|sjhPa|+J zV14%1CS%4-(-^vrt9CKHDrM!xNH|*ho=E1ECd`&T6R@UM>RZ(rcb=YVQY8TJmVsm`CHsOv_EM%tilq+j;D# zwqz*XmhrHoB3?6wO7enzY7pYrr4-iqQh!{1k@AJtbEWm6n7;Br$`yKSDs6Kv6^MK~^EYRHA@|iKkX5 zZEt?7_vGD}bbHWjB>O>iU?!fhtox!}&M^IzW+m;h9i*vkDfwp9;tbf(&O93D0PVTB z`?e5N*T2kY5-WF9?*gW>THcE~zmE9mHzH+auOog_YDS6Z29;IQ*NOx~h|ugVn;akH zdi^y^G>&B&GW=JMac<9+mYC=IYojSi=Z143*1U~dO^K*{qhW#Y4`__);3{E zo66hzy>y55(Ghh~E!~d$U3tfAX0AXhRY@nZMaOif0$6Zzqa2zTWCZWkD=m8|>J@kw zz8f~SE=!{D`bvcovU_$6d_5ayuVj7XRJnD(r1kWBsm)EgNa{QYWGa7=n;3by3J%Y` zcL6?0sH`yyK54kePn50Dq!ZnRWOF7#IXbPUo3^|HtZr%BOVebHHaaG6LXF_$&tXa~ zo_1HLPSLJkO8gFdQ}wL8>SA7v@^&Aib1m@Hv?>HoX)50=Vr2Y&%qpQLxpybmtYyH>4CjoKFdW@&rs?>yv~mWnx$_>-J^zV2qqst_-kUeusARuEMpd z^^*;oH>BKBDp>%ROLAvx;G}MFXX}%@@!;QcD_^j<{f%65xX2bWVaat6+!o=|547%w2Ss zZEUD@8XNgf1{aqF7Ii>hwM?&FsE8P$N`hx@|FNgJNX-#2vR;jNmv&Pp+uqFyGNyh?Dn_T~ol|K~&s}Ge_Z7$m!6#C!aH$G4v``4C6?G^2 zfD`TO*DsG^xWtnh#X74q*D1vaI_gMwao=`xKVG-gE6_fPdvUtXC2XXRcNhaT)Y;FY z?A@< zf=u`8$B}Cb!#zJ6p;RJKSyT$y^|cj#Q-_vTA;TjeyV14iwR?(}Pa5e8m5S`TY{|h$ zZo-Pykf+i3ecAo=$#Dkt<4)5Y;p3IGag|?Z+c=BRInq*mSy|&odx9_HMrZEep2P9| z0`^PBcRgvzWA@*TE%nI09_|aY&Gsix%EBl1t$TQM8|KHpetX_ZB=dh|bpK!cktS5b zTp!9hy|<6vIgB+cFb>L(r<5Zw&k@S}=0KG} zovN(cI6LA}GdwJ--$T22JQe?=)k@X5bM5EBgw)dOImVuuVtP;1fLoO2Y-LM&K%VrE>|qP*chie zDC-{5Zl7DYP4Q*ep}tT6pBF3ABwwlDgq%9yr^(OL@~gZm_EoAuGmctqAn*?mFgy3R+$t9hzX@D@NdBkQ>kf8v#-k2+N6a{Y2>sZT01 zPsy+Haca^!f;x9b@bi2+t10=hIu*3}k;h_H8>W%}hjhi^IoS7-)k&Cy_J6R?WBV6z zqNCWVPo*OkCkz`q1oKG3VYK6ha;14;>fnE+%Fl`jKvOiVx=G;0eO>`7ztEvuqFv5MMgZv1p<~YVx%eGC6DL-q`bpl!gy_m zMuc)BY#ydAUebKx#pRxMaswnKC35=2s7R(Y+GI#>l||MmC(hgo3ko3m`}^OOiX#jD z=B4jdp~Dh4G$g*hzD~%=$$8iM_)9GrWd4q|LLt%D*Z&j2^)KFvsc+OmS9NuDs;a69 zc+By?7-*J?ko=)n-6lEzA6*oF*8^WR{>%5& zAw6+vAU#FCYXq3k)d@xnn*7bZqILna{DTus{rWu+aGWXx=_zKwN3KEmTqtq9r2>7O z6zqX~_%C-ycg^!N26T&(+$zbFT?Ad>FK?2PW+SPv)jbJ&dVPrhPn6sF%1Z#!yPAWr z0>W-i9{ldhVZOZ!bdNXmHD2G});Q)z*nZ!^`Yu?;w*ek{i~)br!~lN}a6MVnhz&2M z^PS(si<&JTQ(Crw136)e+aU>bg|*(!{jz_ zxp(2lv1KgCgenUT*Aok&?!ULt-upKYZwg`$_^0*qG7QIq;#~&*QPgWkX`Ev-tl9Ei z$SY75Ey(k~KUFj#KZg~oTdKN3BK!{?O)~u}#O?Qqg}|F(iYC8T50Bo&zDeKzk}!UL zh9xU`g`s4}i?%9pXSxw-9A4?3sfToG?D?Qtm}S1oSXQwfkGD>2WOdRSyHUg^pwQE)mgpY_#1_3U)=( z#K;XIwV*eR6OWZdO2?53`;<&`Z|GACuXe0w`k@@A~%s(laokOAT5N_7q8B*1vH z=Y8?E;b7b`Dmk#I`rR+N3)6t69l`&mK$;E??y?i)!B+lDYI&>68f|VHDOLar$+L~; zv^Qfd&fh3!FfZ?VYp6=kr@T1g4S?4_m80A?SRf8a9N3t=?L^rvDB*Fk!hF5GA^@0c zQzk1$-*q^z#AjU-oCXFJTWsoXi+|hc=zztbSi^xZkYAD zi?wCiA8_4!*?uvI*cXU0B=^W1t3Ra2f0fyW=rCfe9!e&c2t&r_uoz1Cj~`d6o2*MT z>T1t53$e@XPnZ5a$BsTOSx^MKQzly7RT@2}lbh|tG!-6ZlS{}Cs>!ge1fU@)%%8PO zS6c!o6?)VJr?5U&tthv}?u)i_qFHjx<8za)ZN4>2F$@A5r<2_zMm@!$@NSKZmmPMD zuiFVwny*sGtf8jUbbSoX9DTop-epvX1Y!nHTyzYT$g(-MSlz!*nSJUm(b$?Ic59m` z5o0M0B0uOZ$0V6uSiUMdgKcw9hiY{ye~_DCBI34sUTR?QDI1AvAO7g)Y>pw-3S+!x zE9pW*(ZJ<|*TES#!)a=hiuUTd{3Mq9zZzgtm4T~C;AD{2e?5G~mix7}mz!_$Q*0?Q zLj^R&rFHb?t?f%U)z|Q-hsm#kaZ89zEeVqIRbd#OOx3XL`|)I%!#yP*)M2o59e$gJ z3x`|!V;xb5!0Lw>sfEOiGdkh>_%j5)aU@C0>q@rD$GaKA;!3MO+}T5t*d@Qe@BsmO zl5Hn}`z`mpIgc2ItjDEld1L`;o=avGjKFstAg|fA$T!EC+UEpoQ;Pb9my!JhVMheD zcnTL-P%9q{g+pD^F85sB>j(-(`q{Ya$eDqu4+*nsG`jP<`kRBuI_z#F;J;7!KV}{c z#_#uhMg69~e+QxQ>IPzte4v3aT#gh%DMNhX`|4=!`Ew4@qStoys%TREi{E-~RR=2E>1=!yjHlV2343zih9Q1$YzWDP$a2834KflCAWkmgC&CrZNy+#i zMIpgO@3^VT`MNC&_5C-@sHZdDZRzCNRM^|40VnF>r*GbrO_-x5`U=FaFPv+9yQ(JC zDRAfvJlJZNL)}(BURf|l?w3NI*OIya=Irldj|rFN$&=V@)cnXuOk5V*C3X8@*PnW)&@3q{Tqs)KubxpMoxguKm&!(fRc z#6nt<>;-6DLC|Jn;4!WX@DWDyXNpxUh!7VJR|UlOOG1heqvThPMc|%b!9$xz?Db`n zz7&emq>J%s1_)O6`r}>pm@aJXxOO#qr=fGtZRd&n!6iMZ3RJF?8rM&BJ*SW>n2b%mNElpx0n z8Ze4)<4{?sAj=yUvn>l9D3TD~mk=wEVJ9ir|0!aHi4}^BC}}PX+{;$YRGiHO+-6n9 zmi|;k!Lnlf6qS8wC44F-tV!lYkUw4Czq>0y@@kIzKJ78#!GJ{Cf6H}kjF%;tp2#eH zgeshJ8cLv65EFgUkQ?w-o!& zT>JV4sbY2ot-WWFmeIE@S3N9O<30I zk<{)B8m*5-o${VE7X{t*G~S;pJgR0Q0TahUAO0FN8r=UJhlh3`?Zs~fY^-al^%Yo^ zO`#$AHje+dixbFq^02N4S^n!X__vuJpaTA<=lr!?4v>DBC#hU(bjaf)lNiv46wzC0 zLTTxIn2;^uc$iT>np%DX2fzTcpKbo#GVk{ahWZGzzE&yi3OybcZU@9v7JOn*qXRrB zz`uRGO0yX|$p6+L{#5#gIi1Or`*}99*LeM_xV)bX305($f7+~qG|akE3y6(w1XUu9 z6rpbPc}HUZN(9xSql4Yz^&h=!#dNBok{IYM=;#o8Hq07&THo;3CrWT+&5$zMU^uqR zDW>#qQ)R%GEGOkDhare9aRCXFbzmXs*6P3NT}$|U+lxmX?G+`1&QXRdoFWtaiC8mZ zboIDdQMS%zN-Y6-Lq(zz@nX+|6uu_ia(kXex*zEA!lm=fRsb(k*ti)+#igO1>j@c{Jhkk50Dw9HsD)?HJWK;uGO@ zcL#gF9nxBUV!(zCm!6tmMy_9?QV|z|&Ird$o~c=}|0YnrHwTNoIfv{11Y7Gqq1;W2 zPuTset9upof(OI5W=Q;bq;#Xwgdd;mX=Q1NMkVHrGSG8*LioHZcN!i40(#g-2*eUW zOahxdbbE_ty0LE9bN7!(iE)Qp-1i0;Q6c4AkU)NBNhIt%ov4`7w>L?i#0; zY@3m7f!*k*OYIW>+^)pDi!JO|S3LAd8d--EoeU>jk!56Oqx)~@?G~wu7tV<)Wa-_K zb*Dix6i26+jX=mjlLpJ8X`{(^pLn6ULCt?@@n+}O1zrU1w8y77G~lnzcrQbopU5IcZKg!{ zKFmkmf>V_HaE;w(3}svLkD8L44#=V6Fq)wW49zdYsH%CN95~U{*$nlsn)||?I)|T4 z{A?M{AX2?)2jmJUa_y7oi}l(Ekc#Eo3rG=*L9L_p?nI;db1N0;unLDrvCeyZ!hl6L zN5kSgWD=3IjcGs6QL5Y&d&5iz!j?;(Gp{!0C(O zS9#yGW8L~Cg9C!R1Poj(r=M@FQ{+!5?c53K+i z%a_WOo2Tm*==~+H#Hi2BRnrJ@OY_eOA5sf%e&hwk`zQ-E6tMg#f39~T;u#FV;JMQW zwFj|&ZW%sH9jp&(K=Be&)#^*Ke62gP&NLnz;F0njo#578(<{YOQ~?XD^TeT_6wmrK zf0;kHZQ*&Gc70Oa&ogUBGt-aHTF$EsIE@xM%6Tcx1C7c1!g6*KF21LL7B`$g=IXXoC(HK70PMt$ zm*RXJr8BMnp6};O(;-0yrz&gW^zCCZBRyZXo6Y$QPkd&vLoCPBzny=?n4SVR`O$5%uP&)>J@}{ zUA00m_&;U-kqy({oUk#SPo&hw`KX6XrT{BmT1=AQgROzyL}`n6>qQ=ihTK9&h-N}B zZEmYtU7vZ#O!K@wHE^^<&BVk+`EjDljJKDYBf>Jxk-(cAlU}6l3Nl9E%=Zjx1+xQc zFrLT(IgW}>Ho%NgL0q}~ltwLHT`j=jD~|Aw4bv%#8m{1uZhDVG{>AbyvfzC-Hm<Dw@}??^{@R)b;e9Unv1_XFf)eAa%%kLKOF z?Mro(N=O4n{9!XTQf*LH~oeLm|O2+PjPQ}FWeBbE$~9QK!9y72k?v z8)0SG`0FF2lFH_6Ag#Q)fB*8fwd6N_`s}_ancspxT5qr#ABj&I!$UaNt@M#puCb)u z_7gu9n5j>j9l#cIv`3a=B{y=>l{WEQFd_E{F|md&;}ZE@eR z$MXVjrdAxI9Ldz?RJ!db3&NAhhA5q8un*6A&T6sJ!dqQUF&^2}C-O8gb+>BvT+2g) zG@XVNmn?@fiDc4YU48504*L533fA%eIixxeI%%SR*Wu zpfYrs&&yN%3 z+_b;B4gDBi%6?%)P570%vqWsRF@WAdyiFyF0)JZpy(5(0V@7Y$h2JAs?GPE3YBl<@ z_*0GgY1e90n0Q2SDptHr!6*$Ir&#Ub13-&{>azu>D>hW$KL55}*CyE@If*2lk>!d` z5vCo%jmc2_H)XgiBZ!S{EZ8t0ZoNuDhFWh!%=2Cwtx`)*8x0}4OL8S?|7%-L55$6yNN~EHU|T4Vbc$-XzIF!-ehMT0|ap~Kn(#mp*{78A`eL) z#u6_Sm@BUA=7=r|j0{wOrHL9`@~3)HfVbebNd5%R(weZKFS;%NdwqrP@F9vX8~;jAb zEdj4S`kBmspir~K-Nqgj=|({|srt{)B)kK@@JIS3hZ1YbCrSI099*wIZA~GWFuXlQ z$*6Eg9Dgc@ifcr@_!VCTmEEd_D}q*3oT{fagvGy)`+cSUPz+Rj4IAic6?Ftdq8IZlF-QUuS?Gbg$IxBO?9dNMFIy9mx zlhTYOKyrsecWPzls28o}o|6JclzkL+*nm&Hf#-KwjM*i8!8>}s>or; z`-5R@Z6AY*har6XQIM1qwXJ~@F|GM^&M{I(o#IkD#vb~e+rpcI1Y4o_9GB5UyUsd? zts$>c@{dDw*iO0@9Jl6~FH;j7aj3cTBt!U9 zrGNf-%Vs9@CUm zK~sq*2Yo!4EEElF0UgCnO;4rM3C~9O!O<>Zw)@z&p_7nb?a0Uzy2T1Y)~k&`QFs z(c@_Q8vsIR#&nbecUz*r%Oc^hsB*l)u+N^`nAB55fDQgP4i;s}#H+Y19GI9RL z?w;FXVW%0ABFQyhFXr!$kgpgeIC@sM8FU7tKB>GHXb*Ss27K@f1`SktI-_izuH{+` z>h>ziEp~pYoU-2ZIhR?b0h7j9ugaV>q2J_We6bz|`}>^VOh|DeaTPG#*>@>~$e$)x z7Q$`(%3J*$Ao?^UajuqYvJfyF1F;Ad&3(pEF17(BCB3RAQ5hYMsGUB($WloopDgej zpA6_y&JZvq&JH4lO?wv}2!?U@+rO&P3?hv*~!lio8Ajk=liw z6!z9Q71#>{Oyz?Rl#)IigmTGkm;%^Kf)XYqJz|} zLvZ1~5t8VLSoz2yx6|7)@oa^^Gki1ZY!|)6sPzdU_bYV#-g9hy--NA2l-;&2NqwU? zJE#eyw#l`2CtH~9+kUTMKUp8W0KbBjkj%B zNEqzj!;s*81V!e7{NYf?vt@2YHKup&wDg#7tK==Zkg+XzD*v^ z()LnjFRLIrSgmPUuY)OXYXo|NU`Zx9F3bb^3`7;=&F#6*m+Gq%t7FL|1rimYzdcQJ$29*4I_JeA$h^L@u^Fpy%;^0&iCA2$qTRq@?y;==68(J#D=1N$tOE$*E8^W*5GHv!!xnZTWZ#2BGF}two3u&3(GJw&iUr}@AU0vWDFwG zL?*V*A0tRjpk)}QV#L{8jKn=DTpH=CI2Oq{vN1rgbjO6;Z)pwPJftFi4GKZc~`Mk(7e@u ztVf=-XXr#x9Ou$@o{8sv0gQZ(G*U_V0txm!mY(HirMXL@YIKacV#z%YD2-y40B$T@y)Np_*=0`vA` zCV3w{Y3^Bba6evuG}j%`3Qiq4D31hFKV&yuq;0^{a!4rd1`~qrS}q2(-c7d`ptgV! zMo&vOg29@Ufp^|3o-mMU*7~{c$t3C25{A`c$irPUYHy}Uq;1b>_r5BYLh^BN3NqCH z8``SaTScB3$kL!$i1D4uorrKC?TL;?CqJ7yAW-22ei|sx%}_n-eS__pve>7srB-p& zg{hJ)8vPa98dsCgpt^5t1lRFyn^_)@`*7VTe)JmN?`@f1F(&RusXugbt>FIs{kS6y*#V>~xe?y)U#LUpa>#xlGXvZWv(d^vhf#?Ip0Tv&q_RM^*h@=dqiyvF?6`H=qdYIEf+Q9oPc>Rf^N*J7;i1jG?AX{HYA z(QVcN7JHD75mwHwl)t_ZAg)GDelM^6;w?BE_|Yz2C~VMep7Qj2caSkkxfA}uIEuMb z8*Zb_+K}2u*QXw-)$htbD$B83nvk?7^7=z_<@#c|ZOW%jEgfMzD9-+I*h9m zi7P6~x%98e;=7(g8&U08lKgyk%S9-q&%}220(ICalL@`qv2>GDItt2pkE)|4R!wl# zInDBQXMsygAp#2M$?d$C%S#F_Okq~99-@BOxXO70{VOvOG?+s=`n8?EM8$ldVQZtp z9;>(u|5OsMtq7Qq^Q$zHN_u+{0Piplm8Cw4VMKaBug`t>uy@XC0- zScCmBBSO8L1bXbtqLG4mQw?%8E27d0>Te4g_QbMYqzRG8DjK*e5wy2#IPP%L{vEi+ zLcFYAlQu+e!ckQ!?aSjm`dO~|?w|4nZ>RhfqpCkXtsrV&Xtwzs;owM!dV6yQL0Nx` z4*EmRQ3NA_5IF;m#U8);FDjtU>K0-q49N!gHSl~Ie<;iy+4}WZtws-B#0^ew9?PA~1Kftv` z%+srC&ml*DCz6aOJeKA>wj-d!KMH;63ct)PB(A~d8j_@hF9q>|*Y8anlpt`egKQk^ z0|L|8EX;K-L)8`*W4K`KtYwWIZl@mf>?XH=Q|uEAo|KMnU!Nh++38K%k8kdWE;xn} zO?OT5QPkp5JW3ONnKdzG|G*4HSs`{E2#=Of16+?{@=cDpS%0uIb*I~#!kbzh=9oi} z84lOk`Fct%ST}bl$?jl7UQiS%87j@dtoJwrQG?>f zB`h68g|43L-uM*f#%hku55d3>$lhle58)&+o+XYq+pdaUGhF*;L!L61D;qien=xpK z_7L1CUu>wo;iL$Bt6y+f^Ui`*zJvun0%k>`z(<}SrBN|4o<;wa@L#^ttFK3zijMI7!1p(4fenl-(A@3N@plxsGngM1_CORpFEe+I_K83=vnoiCWHCqiYGTF*)k# z5D>~V;#QAtbTl=A&}f&CO{`MYQh43sxN?QClcBugj$nLAu9;0xJSl7fCzEG1oP0ZZ z{=zh>vN^m*s1rjlHKz&X@P_?-H_AQgWtLK7HMLla%fqaecDa4u>4|V4YxGC+U1~R$ z;+;S9@{$j>G|l9MEi`pSICida)#v&5Beq2qUcbXC%c)&o-|XQfE%6CNFCOyJ$?; zIcfUE5h^yHTka%5-hon17l2gc3jTF`VMONV0@t;EG^37yJyo1P%1~CNg*Iouf(}r@ z5lGtK+?`;&ypil;Y@5=w3Rtc}PWBPXGh4Mc`5q~9*A_nTQr87Sf-faeasgil9^_&1 z^KfB`QT38_D?*m#4?{#elCeEU3lpqUc1IzokE~*65R|+SO2?D^l<&=jDm4LU< zU++Mw_DSz_(hw8VfbqQcz~Um}m8>W%(#jvrx{-_rU(Fo@U5>7mnEDkDkH1myIYPaC zJ4UQBZjM=??KwO=mgK%|PEawQOYJK_>ma3dckeo)Gdpj9i+ibLOZFA?-v>}{7j@FZ zwdkYZwfW>e_bM3(JEJ4XF&^KN8vuMs7U+321Y}E`#Sphs+3@9Su}`q4a^hJ{opfQM zbzy>msO6E{Oo-==Lidol?eHr#fDIWywtwwtZvO%Lu^TpD?M@<*fP%n+uFmWORV zDhh&pG_bly&rIP=EZ~xJN2yz-|K7E^TRRG)YB=FhmSumfgSRY zn*CPhr|n(Zye^XIYOhMt1*;#2_Enh4EI%6U(|*Y9+UUzmP0g+%YfjTz*iMxewH4v$ zvfgt33X{N>YAC@*!4jE>gPyD_M^DU@i_%3|oU$6^coGdqproYyx%PxbQtV+ic&E(8 zKep>Ye>EJ!Ciz+kEa+#5y+1c3KKxoP&X(UbMN86Mg)_|gT&{D=xJkCcA)L_%L=%o| z$Flz86yw(lmrpd9;7EzCLGhiev*Dc$T7mn=NN~jW#=`z8#ywIZB9%_5%2f^u%3j_{tzu}NMgpT2o`V^*ZVMP{W2jht*|@j_fPqgTQV z$RdZ$(`3}4H*I$TOEIYHTFGN)0sfOdQo35wJ9!f(x4|?GM2vkkj?%#+?qqJWEn88`%zcE#W;xV6wlry-C z!i5P+tpHb4dmcp^R62N|Wjn*>On{UtJ?aeg5TYp)Y@SGnNI}f5FHQm6zv>D5yW0L7E*_+zL}x{L!ub0tV2~ z82ubVawLiO3Im0_PXKrU-*0~CA3|*xukb82pFlv1XKI8gtnO}5eu)LfXC6WgXw=wr!_!R zuyIB5+|Mf#IuGJIXBkwJ^{yr2-G0gQ6lwV)RRK#kg~=t5y zwwbWR(d|h__mG3SOQ-()Qycb4k2nI>@Ll{fpd~}%yEa5>Atn|3mPi6=TE)a)q{Cp8qEyI^M+;sRaCHBXkrjphAr*(xhAl9dxQ9 zvUwvMHGZNa0S7;3#ImBciex<&qcL4dpnKmAP`oX!eHgF|@~R-CK97cKE3(u+Pui4M zpD^9YXb`T&sMs1P0OQp;ZxuYTk?>Hm>;_)^!dLLQCz~+PHzj!7viBsu@YOHlac2l~ z{t!IF!${X1!q>k1F>I@%@!^$^xfBI7F|k@rK&;54aR@Ks)@%Vgn$1uej7SCp2oNn% zYKu2-q=?0_K@5-jh-YuXwA=?AG*?l;3$hOp8oN-~3tM|Dbkr|P>tWPpJowG8UdHX& zpt##Cc$Q_J1t@uop}}sX1T2q&$%$#2V@;ain@R2DEkV$NaUI@T=GPPA%yzi$AYkNhe9BRwxnBN{?%l>SLMY zNBo8-=CJ$ypTXBY_b4I*<8X&FFgiQ&flq%PUwL0QCR`q@OpL>?Zp9bB@+q+$Y&M9x zNwLW;N01SB%_Y0DY9hNsl9VeNVRiUG@ttIMN-~v;y3jM7p@7%MhaMhem$XiDl(AVX zlWmI!7Ll*nfhtWF8AGkuo^IBm=hQ2B^3?B4Isxy}BC-uO7)Z}})L8F> z6JFFF{{UXtX~Ni;ACGo^-GV9QL-B=X5e!N zVJteaYrg_xiy_232}&F-lKmo?D3UFoSV`fLk9-6Ns?!)93*yO7l5D-W7qi4yf1G5Z z#8>7K^OaY+#AiJ)?syVk`_d=ijPzsPvx2)5Sv>cd&*LLcbdYZ-5k*3zG}YqJi9N|GBq9Xe(I`9ync6e2wSQ$wEG+WT2u|^kVR>o<{uHkS zVY$r1>sx}Z?HE4#;y&0YfPCtspT*bzj?O3Fi_d)QIW!uno&@P>Xbv}) zRQTZMzKG90yA4YN*Wpj+5%E)BNUzyW@K!{Il065=)Czq!k=qiuG%TOCLu~=q?r_87z#i;KZMP z319xydvTLby1&=YU;_)rom%_w2@A zV;V~ovv3@lPrGsIr$5GDfB!Wk3{5!DphqgBM#J_R`1sWtGzRXeD7w1qNq{PhCwDKJ zK||LrSjcCMF2$iDTd$-tkz5*z#zt5aDNOZT#P@#q8}yV``fmj39{E&WU8ppe;j}u$ zmI}sDq_PDX^XkSnR4eB3^Pl||0~D{Sv?|1w$#+&+v8|~d*$~AAIet%C0=;K{hwpsn zdw8YCi(Lm>pd=q(sV_XqAn5(skMTEu|5KbHd&}?ODw2+7DIQEw@NR2pf<8w36dSJf zmSvIRWv!(R`|WYuEUm)hjlrv~ycGMZjBS)iIj}V9g{it8W}O?JKoTp#5Oh^7FsgX9 zrUF^=S!#6#wKX=sI^tv(kfT_4M>kY1UR6On;+2-18*!{k{Sx+p zwlu|eMSDGL>b!`N6&i|%DP~}&I7PVr_e_+ z4?oh(Pb<}QJqp9h0DkuCQy5!G5)Tzf#v;5}6CL~a!ss4BfN0Tb(-`kPi|>B>@A1=9 zJ&5F$2rc#D=imJvzWuY;M4vSG$OQS!ToP`IZR`!Z(NLel{36MYR)e@}0>Av>_wfB+ zT!-#(H=O)>mZAzyXEPG6c_iYLgOJ45)zy&hR>&$(%w;V&vb`Fkw`uX-sUuQX#HM zUdOLa_t039Tu_W0U!6h3x*tb&sW8d0B*{!Z5ypj=e~SO|H$OoS7CSrJ zP@K4mpS*kpu1JpRR72^X!>Ql=8bAE;FY%LKyow1wNokRMM8bl)8Xf5d?Nj%vi00f% zkYY|=J(rVK0h8WTuE=BXyYPIYJ@~vSvtOeSAP5>eEWMp$Au}< z3DRZ1r&nx0{+l1*?|=3RrUH42VWrjIX_BcWAK59h9R^JjW4F)X@4o##{Ot5Ck|iy& z{zd%mr$4~o{_rfaJ31(b;kkf^_K-4U{DDH6JLA_6@is8&MRiRLbizHcol7I2*NO#Z z*}MVvYCnRd97&;lgOX5kY{OT6PmcJf z7|u80@tw6u1>CrK`gdf=eu-OitH{NoaG7dIVfA9ma$rFLZ)#;8*Kbb(_F5PfIRsZ` zasA@&@$K)vgfR-D`F#s~$D%++SJ)iBYmkV;4bn6a>ntwsa6lBr;+;vn{>vZXd%wE^ zZ;pZxa&(ZQ62TWNPQ|3#D31v)h0G&FpP!iC7A2X(DF(K zqa6+-IY^PnacKo5&zosh(-?@VwuCe)BqJI_D9Q0toXr6c&;LnXrm>?SY5K-p zgo;`uSC%Qc^1|bb3YmEr@G7G`1v>e1zeG!%fQ51C<)7g@KYA63x&vZ6(nR{ifiDf3 z7&n$v>eKxkBfmp0MhPi}-!N;7FjP6AOH;5J4`HI`0{;GQe}LcL8AF^La(G3L_S!09 zhypbY4Wb(=a~+Nx>x6-1rQ8BPa_E_!fvTDM_=4t-7%a2aZ1q zOLCEdD59lw?Sq2pGFqxhZsM4nUxF`KgU(tF#N(}o8a(>M<9PH?7lM74ahF#fD1tcu ztDoRIKRJV3^C28+pa6#kxL8o5aYrqd=6vwXxX`etPHZWk5A%H&@OOXxeZ0<(`A}J< zT7&lO9nckWXxMfbdv%NW&2L`Eq>F77Njz<-kRQsnW|)XCMjHh%S|4I59U7eNs3yCl zCVAtawxF@%@cum%%t{m24CY_NHG_evB=+vx1_O=J)}!}UK>=aWfF11y%q_bxxtK?@ z!$AQ(*)giPVcUK@_w=J^)dX?vYCjTWi#?M!@V#$;7iVXRIJSQ~47@U~q7$iPig>9< ztyK#J1!%Q#1=2jpH9Lfte*8mx_vPzY3MUZttI$aHoP#>vs_N=RqFB^9aFFbdRkLn) zG|T{&RoV)qSHuR%h!B`3zWF&6?35&0^!JtLw*mCCk~@7H;pqrGh)o=Z=S|q|Lsq3%VWkP$6H9xB}2e|!P4A;4yO*$Xbg(D z6E!@>#1|7eBYsp)JZ3}m@U%vegqUt;j zrA#NwDECi#tg!$}fXRmQrYFBBSjY8Jd845P_0?oi)kbKn7DO{D?Amu2&DOFFVV)~t zZ|cB_Cr-d#BzrjP#@vz{9Veg0bB}IA*foij2qi*11`h%D)B1)koH%|2Cr%s{+ku_U z(38)B)rmUtyYpTjiq>|tG`2%A+Kb6-Bbv-AL5rw^Y*$P7cGT#Lh{Y06C7q};lbo0x zFcIrBlz@nvD;0d@vDG$opwp=*nb*PUpyWOhg1@d6#8xQDCNwxJY&w-^9vAtw48&L7 zisl;Z?4qQM5=Sxl%EjnkQ(ZHh?4q?6SZvh3sv7%`?jzq>sT-xSDF31pDxD2G4xA7Z z{Xy>>BI$>nsJa(Q8v8WQ_mcf8Qf$-N*$S(!fK_jj`05~ERfMIg9>$djlBC!6hGtNn z1g*)+ufrtSEXgp*mf7hap2fKSjkB;A0$4LeW&=T%*!0rqtMw&kA1k%?}H*0p`@{at~-oY zhZ4bHn#S}Y7^I|lD7c6_(^Gimhd;-e!9nzm2Ze31w{)PbT1QDS#c{S8wAR~EpyL(| z$s8T$Ew7?L*jhkFge%lO>6(UQse_VWmL-clOMXQOqe%((6hD4SeXlZ7@=o$Y>4m zjWyVJ^e7%BxoER%guby}#@+Kc|GQt}Z~p#w81+VxQ<+KcA{ZZ^z(OEPaf%AVd; zcGQ20ebdyL^~X=wQ790v4;+SawGY$YjM(_26h#Vl7Y2K9mGYNgzkCgob5n>>JJmW9 zTocn+4J6UjUJVLRsTQ8NRZ%XWqL@2R@@&D5UAtjSj3SUG8D1K}r5io?^)G<CNfH z(s&p78Y}V0wK%{}9OlHM#>_j8(T^Tz7u)pJK?DjM`-w|8fcYZg5B|YC5U;FZ z%SC@x792R*3GeMbtO)y4fZE=SXP$l>$9C0Y_S$(&gcV4-#&G#=KYsP&U*QVL*#a-0 zg9f$D+j0Dn<2baVmGXuH4E81*I({6F9NdXoQ)O%_f%PZLugAI7i`QTMHU8oBFv;K| zk`z1YDIPd{XfMfE0X39x>M1bbMHzL@D$>s&rults**etP_-66OdikcSt@9u{%}cmF zwn}oqvZ{tUokohvQtjwGxC6#a96^d}?`uW`e~6E{6hf5zmfvAnApLgk*pH{4I*Dzz zI8L7#Mn;jrRNn;pue^jGywr>7!7=!<3TU(jbniWcM~N@n%yBHbJVIA0A#S4D$R-{> zibqcFL7h!U$JS|5QXg`;1QG_Vw1V%xVBIPpt{@vkcFx|i9Zx*_I1V%xas7G^{Be>& z@>_dICr*;jJ$_^_>P$59>=ad$7ZTqkx!_4e(rJxG=;|9m_yqEs$BrMx$-}##S{Z^X zLAIW3_wK_-@W`=)=&mL|OL3FQLa{DwM@}Ba@q@cjZIpOBcJ?>;Pk;9ttmqrDe|Ig# zbxPE>?7#_@rR^;u2UU^pIB@6yY~;60v~S(?ZZ8=!-YwvGHXd3P8!rH8ZmJu`bU&@Z5~BHhhZgC$Gwu^oHk(__^AR#_##(ohBuS~k}H_? z*Q2$y7Wow)DE~lebpalQ6V56F1@E)CeP@^wP5YA9$hJ~k(U zV+xxDJ%xf5PkiK4`05uwfu|3*i;aULemp5Mvxo!*V8t-$8IsT&`LSB6P;`K~#P2BM zfKEetrbD=}f(Rvq3BMOPiw?o5F`}axfBu!v;nA)ta=;Wk)Mv092$9X8MA7XQyyQ_9 z$uC#SV8u)YF|(RLTWc${JXx%=;+cF zWykdSi^z1hgFmIhb&3@$l-xGAb)u!JfN-2w(K_(-pL_;i`@+ZZ#DP}gg48BNblcHhWf7avVn^ftr|`wEeF@+C+MnZOtC8e{@49lrPE?bQbsc*OFC1^iLeBsq z{9+&)8=a#Xsi_6TNEhRw5Rw@uj1;IyL0n0mgrKra@;>*1*hhvu;+aGL&?@#meG<+5 zSmir_LM{h=^EQ|#?qVR4MopbVBqSWHC6km$RyAUKdo3mLQ6xwX8n&IppMUj>_|%J! zppoQbEuf}9+*dsXo@pxU4iZnJL3k}H=uo$mLRMQ`#$6%zS(zt?^Pyt!uOPuVG!JtPhmPCRs$oO2C3Wo(J+hF8L`aqb*CQR+up}oBx*+c@7L{{ScLxB6GveZyrt!rCTEq^#E zPrNsw#Tlo>&I>aIDt0>sE3pAgtB8KBctC#*f~`cC-e^Ep?}0B|AW;Y)PPW~kC%#6L zlpKoJ1%YKDxC-7h5O-{TEj*=bPq>0vY zFPO(%tcdv16g*L?BNal}pQZMd)VF(Ok;|^FD$FGj&uh@o+KtWzGvd*(SndDN5S^h8 z(#G$cN(JX}XVeczO$*st$)@Bf(RVo2m|0i_jUXbc9wh2*Fy^xeE==l7qoUr>`CULN&g?+c&Amp^OTq{aK;_!?2c z13{(CVs_GpedO1__02Efn_vGkGzKQHO!O-FIp31PvWezBj`?_EoNcnO%lwC>^E91apC)(F1^yzw~nqo}ydma4x3j=v$vi~Y&9Q_w((E8Yi z@s-a$i&`4Kf~6MS#i)20yt3^W_BT*mtT1EW<-pO2HBbJ4h&Sq532$?Dd2qq{MOp596FbwqD6NwJfaY;y-{DNhKKznWbr;*;O{ zGQRnZFXQvi9YSP=7Y)Ed2;9j>G!M zr|?(b_yYdwTOWZFA@~9*sPtyB0`%GaO_&>>1i5@+I_EzXgCWRW( zRu)x0z&Evb9XN#a*j-FgP6n+5+Z)s9>y@4)scUOS9pyP3{%?jPt7@oqD%~ zi7I|Fiq0u02NUs-qZXZAP0&()8u3iRUv~t5K|J~9x4wX9_Np*D9fCruMQw9CwvnvX z8#4$-BO*`YiDZtgRiqGXQ~4D#E$yA??rwsO9~l)5N%lJ%a^Y_O9IShqp`!q)Or`*v z8zsMMPtvWx!Q^R-vf%bQIlWB zlwXD2U5)SzU&gB!Zeup4B?Hw6Q*<6zF7-fJ&nxc8_)_5H)Fg59$~m07K8l#J9_{9| zc;82ReKjQlIRq$>RoGhKH0#9s)#mSB#%mV`p=daONA@%!>77K(Ku*fRU)6Ep+HGGmU#D_fxj-jj8xE5q>hW8EMA4GK~1DK2%vBwy|%dcF- zyw{7N+qZCi+=J?E2eHc#z~u{rHxb^Jb$hzl1k zO~BSdyyaDSN}+@e6=h;95nvWvY)Tgj;#rDRel4<*CwnBDGG)U@v;T2v%MMcn20EcPy=<=AoT zXs$y|!H09NzK%QY0**X=47;~=Vb8w3*t@p{>Z~0{AM1v8i=^*O-;qZsDz$J{ncyAk z#hDA&&_A&Zdutce!4>3eb>vK?i59+=FE^0$ReDBn>f9yV84sZO5Xn@tLnJPOVd)5N zU%P@ExBAiBI{-uXA++iOc>T54(eEna*h%{BphU302UjVfvsYQ5ceZ0kM->+OF5~pI zalm3nm9-HqI->jP0-SC2&{2TLcZ8$9B`mqM*tx$MDh|-tE>M8!NfgmefxOv5@)BOe zg^Rag+I|!}_?=kyk}dfEhF`6v;3m9C!M~*noh>T#FQ;&L-*)JeD_ALzeCJ*G{qKH{ zi#LZ5w{+w211*TVT_{x7lP!<}kV>dES|okbSj<=B(9S0DMLLVaf#kvv&c1#D{qsQz zIJ%&spgU&jK#RkG=<*1D{i|1Tdp?2f#}1>xkb)@84a z4qd{9=~)GK9cqJyGn4z^&EJuyKswCto>HNs%L(_K9}U}fpvjoRXaLw(7`W8Vo+F3R zNeM85OE`D>5*AbBODO4U*;|L$B-`nFu^c|Q>LNL&#Hb0larzW`rh~9l)uM^Ur`k%% z7$vD}VyB0%pl3yi23~J(w2H*GwvOz0HbG+?NBw>WymwX*%uM0p)e$&JzYeu((0lzV z5~e0NO=@NW!gGCi<(0Fzd}|EF+BO_MybU&01Xo`>hs$^8;oL#CtDPTh+AL2J-rUCp zF& z#A~md$8=DEDoRFc>RVye&^VG2A+5*oh0|Ek)M0WZ1}o{Hnrw>GuBW6tgymHQ+FLY~ z3!mzYg0=>tSt1CZx3Pj;p1ql;Tt^Ems|#`UKdRDJ1K5ZK^dB-8004W zS{rIrHni?&hH~x}E)FcCw!Q|jZ~^VRJ5ifj#+ld8;_hM^drv%x29*cbE{($6EWKZm zMS&*=dBy2$&pDjFIga}6M{ux%Y&!92WRCjZ*@{~7*EcU*A=}i5{ks~W_zv(VM;K*2MCq4_Yf5g$Bp73v$D(pM)* zZdRAPFtxVA%&Vvs8LW{1weM;n-3m~gbrp+oGn#6ZuoDk`6N7L^QV0^?GdijxGLDyC zdKGuw3OsUr50d<`f|wo+H5T#<8O$%b5YOaLu(Y7n$uh(@IpSDaF2F>8HFXpN*~}=A zZ(WWUC~i$6s;a^6S}i;)9<=Q_0z<-wa9)S{DmoTOqM@-4N%EnJY6q&T%&^y(F*io> zZ|iRI_w_I+{J3-RGA>-bgNc>RPcK*>3;-fhH?JNHS~^5U?ri&f#WAo z-`s+BhYDVw7kP@woyjTu`q!`GGL65Ie8-N)0v6)c*w<-8KBs`uoX6By91e>0u91BA z+!@5En`G)q@<-M@MlN5%rGb9j?i)wiO#OWvV!JLG+QV(pg7o& zbYm&0L`O#r7Re^o9yx?Is|JNk9PVHo)#R5tYAp!P68+TY8@*%5SUS*YO=AId*xPIa zukf-`Ofcw5ppER1Vhy1zBcMZ9>doz;p~-O%!epmc?$2_e4+ zA(De_H71JX^jH}lhla+tig@^&-=4y?yA#kfAHvbv1V-W(>}{(dVOGFw$YIZm*S>+G!cKqDo8~NbClQB?d^h%C(+4% z=RJ#vDo6wKSy-!x-*r|5#)pxx*FohDL)YGf7HbT5y?Q)(s2yql62iJhG-<<_Ntm&( zK@Hag#U6VbsBaXL7JV39$zboEZn8;EBq$cUc<~CZ^$a7ZbYRzR;;Th3$tuNiN@Ov4 z=Mpa59Kg`%9C`;PkhON;$s^lnJaR%;9o=>;P??usWgbSc(I zq!0*3>8}rG&tApd-aag5oH%-TAI!NGT)%XYWMPP6>lM^>HNZD^3+FHQqWAV~M09m% zvZQhI(gj?9qXuuqeRTaeyc0I3#Ov2|0qN=?eO;uIG-@nd%r5w|_<2a6V zlJ6v>LjmzBgL<-g8j2;fC0$X`Uqvd6Ta+hUr98BEa1NI46FA&ugL~u#<&$@Co5tTA zHluT!8KdXVBa`yr66s%0?>MrSMmV)mxN{D&KL+GD)~47j8(qPTa~E)fbh&4gY&qq& z{8ePFtqBbz53%_P_*GSCq}Y11i!8^x@;mZm{BeSE+-wj-y&;6dYRV_cF3}++$bVeA zj)0*ByP7oUyL=AkZZD$o=n3qtQ{e9T>y+O%QH*NC;_WLqb$Jl_j-xofy+*oePy)Xq zAh0sS^8k|O{M&!~FY%sdo)E$LTLIg3@$4@-B5Ap}l<*fQcx2@A3Snr=p&6IwBwHl! zg}n5YI=;g}zj>uyj_Ts&)a6-weh&ga=g%uX_%T`jGROVEi5$P9DVHlkrRC+tn*v7q z&0jqgUob5lDhG|?E4Z9ck)h?g6%8L0cvNAB5(&0+v7i+9=Ob^H;u@=e)9vznJxA)eHVme{uzOd=h{77|URR6GN)+ zev`bL!91LrnuX0~MNLiBeRWDaF2e7C;elkH(sj(&t-(C!FXH9FD}PvCH%vYd_^vd+ zpqQZ|xlk)hyeGZlXYl!qkaw0Fa_TH6+=pU;j?s1O=!Nc3y<%J{WRwci|D0r0=oalT zU-|91onLC7;HjM`SCVhHOul_VKb;+{!(UveyjO0o6=!nXUWI0 z9BkyvI+&h8;p29d+4bOHITY8HD!6AHHe;Qy>v05;#5(q-e5JZc7IXZ}B$p%JRmz2s zWAX)DFXNs^;K-&I_R?9%E#{*UVw1w@R<p@aus z5M2W8^SCm<%HUmb{r$TrfeP~2OOHX**ihSRu_(u;*$4(mM*X~uit4mBZo{GNP84{8 zk?I!lYiZfuMt@iKlN^VVZJ{Dk8>KSR0Z}L0D!#VtH^quck{5o2kHNCV=1PnEW{~nB@_npd#2_u_O-bfCi+IP9O1{y0kfk8d-u0OOESUWE(p2cScG(Y zEq?8U?i_1PUSjE=NU@AQ87J*kvT7NRHss{#g2nVQD@-%n@Un0 z!fq2SEK_A&mR1Wg-I8u@)X~jMld#4gs*}H>Tp9`j%LB`ZICT%$=JUB~2gzHIizUOuiELTPxvokZAvt~N&f6PJ z;xVLU%^dtn69`goDnQpWT^swu%w@w)Mpq;OlCgT*ptjgJ@f{fMI|upfjMz{!je;JI zSSrB%D4%;P6Iz1b+;2__*$8hYSkSw1a)Nmz1^-OzJsf&4(Dgh%QlB-@tMVAU{10OL z#g$d;KH5r&5%W_TTM-Bf=eLdrrTMKuBrqfgTqh@h^g|l=w@|&{56i6x9wq+pG43PF z>03|w-#S?4s0AUn%%A)C$P$>BJULz-!;MaxA!M1)3!YZ+o>(CTVI_HIxhd1gaxa2r z;uDvVD!NBTnU_>xW1DnH{N}nu{nQ@wyHxi(g3Wc&V3u`@_3EuPwW$zYM3ze8`zAe+ zP->%sPZFf|_&O1|F@v|ny>iFN0Us-m&sLLo4-M|rCPwgNfM|zhh4tbsLdeLPonYHS zG&9esE|w|L3?D1;h&M3~d@+@~$Ih}|ZLm9JAJ=$8|7@12cLLnM4V7|ZQoCi|KbStV zE|u(6g}*E7mk9RXfC}a#+ZHiVx2auG7waFNdqY&}uB7`+&jvAK{#j`>>FlY3=&E3D}k zxBUS6bw7x)EXgOoJCf_%L=tyavRh0ub#P6FnFhYLbluiqP7-Z&Ewe*1U0k1Jm)7ZB z=PQqiWaGBxiQqZMauqVkWw{*h^ZBxjO6ML9qTPEc*xZ|k1oc~OYd~#u1b_GK@8GY0 zau#ZP2e#E{N{RdZ!Q@Nw$CKrNv)zf6-q-P;{-3|YFJGTP?ZG{;Q!*_j>ypi3S*v_m zKkscxNu~2(@U@$car?P@#5(a}2X0s6%lMx0jPa;UN!exZK z5HIfacV$1xH+-c2aBXXl4hWQepQJBR8TN^MtlW>a`nVhiEfrB8Z|48zV|>AVXy1$t<3an}ZlxS5D84tA$KGs!j^u(RTg1h*&ztmk>BjcT z;%@`7C~yWp}-dka3<&CB4$oc$W3bsOOt&QvKyN zgj|$tcDavygGQ2x`$IZkk_(QlnC8;CGFazT8XZi6SIjd5^^HoE+bP>^zL1D2(^Hh+H$dDmJhK&D85R0vf33x@ZJOxPj*Z=BY z;Q8mDUb{oE85@>83-C;%bf=DI5P9~H&+^Qpcp)|I@HKpwPTZy8zf^#iH<$0OmG3f& zLt?qJ^qV0bl@xbZ%7>+y&9y$1>n=6QMWnlp28NOr?rS&O@iyp`pI+ zzC7d(3O-c~ri0F5OY%OQ>y8p3X5(N@XhbM9?b+ zOGV`*I=Sjnch*sAV`JAOKJy`Q*MQ6LU+LrqaJh6kgNex*9N52GJO;8Qh&bs^vLvg* z4s2*!`YVl#)E0O3e&bQ*>)Lh18{(csv#3`pvr&H}K8q_w1AOheOz=**Kdh@|-Q=eD zTK-R}c^!PNJU-=iw*vR2uYVZ(_U@!+xUXA)F6Qf{_NmMkHm{O~a(^mmtc2i^R2h|G zy=D?i^@?*WqYAQPl3kV>A|6&8+p1>4S5cnzswA_b9qv`>{C)aV2J6%4*d*%foUq%i z>pa|qwYthWOy$aSi7Uik9z$vTOB@m1xfhkZEbVWigICuG-KAq)9lCD>4faTs{%)0eB{^B+$GrW#UYG0y;+N(ghzx*LFd=O{iIWCwy>gI zF30th>yv(N2`Ip|D`_AU(q%bKz~K8T&!fn*UHfu zc7uyU7tx#EgHJx*f{bej-@m$ur=NHVEmnolSy9(oJ9JfPOt>O3W~7lCoeJ*W9*l%7 zcU-DF_KEjnn~CbF)W1^S%P7+$wNUCG{l`5omnBw9@=z|z$G977G;X4e zE)YJHD-~r+eHFz;ZQ@$qS0jt5;XX|A7i^hFraBxuvJ-Y4KMpMEW;uT4>dNFZ%KhW> zqATTNj8ebEQEFT2>bfp+H>3}2No6bh$k%W=VGo6k<=;|2qONh=99|aX@=6`rckRQD z77L15sefGYmiE6?=NeCGE7MeYuB>N#J^d28#{K64YqW8B`d5_T<6KMW)S385hesAzK1nIa`hf1Tw+>M)9H82l_UGD5Cwq32du1QQbMIEkPsqnfB?LGT%k@5+g;qa-DpLe~WfXka%2K zPP$%_6Q;3T@4aBT4TU4{toX2N=QjEAS{Z+&sMLuPc%Su!HsKdo?^)%9f=TDZdD>?y jF5>A;di3-&AHe?y-&K;RUQB+&3 literal 0 HcmV?d00001 diff --git a/docs/Screenshots/mixerprofile_mc_mixer.png b/docs/Screenshots/mixerprofile_mc_mixer.png new file mode 100644 index 0000000000000000000000000000000000000000..fe1766665aeef9953310e92f8afd26e37eb7d4e4 GIT binary patch literal 403235 zcmZs?1yozz)-GH@ibH|m&_Z#C;_kG#Q{3I%Dc+)`NPr;4-QArO*Wex?5ZoOu=bZcB z`=0OqV`L}UbF8(qv)7bo&iSmL%8D`=sKltRUcJKjA}gu->J`Gk%OUU%=|y7pItT6L z_up9t*-5+ z=3wolVD4sYX6$DCB7619m(tYE+DX~b+QH40l3&-C(uiP2*NilUVgM)VD?|NGPSC8_Jt(*c&_coALrllG? zxfWer=rBnZ9>I*Xfo|Fum#ZbtB^75AXi(%PG^C{E_h=f)DRt z_>|Eo|98ZTfcpOt6vSpeeV(crP5I}wP6ohc93QdY{mGj^uKi*1&r9^&it}ek2LyCH z*}?Y?!EMI?y)BN+d+g>{@FtZ8GPGlU#(HQ6Knom88?Hk^;-We_;BrJqd z8=wv8S>S*X#IXO*D|Ajshp=_OI@ZmX4pR-aDn&uIV2Ul3qlK`O_WhR>JH@tgVlUfr z3>2J!|1;<1%b2Yl_tI`5?gmG{BqjUZ;X#*B&#r3m%x*lopanN5UYq~B(D;6y0vZG9gJwH0L;GP z6cmhhq6SSq@&Lw4|I!&eEY1XHV&Z8t@ zX!^mAQGO3k^&621<>o0bCYjB|8rH#D#B4G^n+f1wk-hOpSScvF_2GD>R)#><(vr5N zwY8oibANYN8O(p-+0)tH-tKkOYM#9C6n4Db54lDjW^&47|haiK=qxfZ*kIbrkc4j8@>WaJkS=kgdLSnww zl4m42`gB&EU9F1vCr$j<{0)x$dO8p1pSXycxakZ`nNeW12~d>zwwxgkM~;XLr3xu; zm7zZtyzitb8yzV`3>`WA((veJJhb+^l_mipdHC@5)S9<`V4z4#OG}l}JyT+^-Q0Fzq0SBMRScV$&=3?&=(sWK^U}0pJ z*SjAqp6;<#aK;1>{6kSvFlyXmP93;UeA(ut|5 z;D!e7&>rK1#d_R&clV;Qvb5jzDM98>LKOGno@}vC%A`Ws2sVBm2svL6p!9b8=+Iqd zbovBD#z#OION03ZyT)I<%)7h0I%2|~lD~k*QbxSrH#be}i8S@}a;SEX;L_i``Fwm@ zR5Ucg#$qvV9>ZimZQl8$HR8~;@lW z;24N+o%Er$KbQ>8sj#Qbi&xhsOhHUcTxAQ!>@#8C&S^QZ`nGfGRrd<0>5TNIm)B|i z)n+v>5)yLtBSedxcRnuojR-LbNqud}$qGD8%U~foJOqQkBPWMae|Kd?pZ_2@IJj2l z^dDOB4r$U#oz*&TW710|H?tOzE8FUGjypN3=}bgX#DvO{wGDqb-{oa)$2d86tG+F# zUcJ}Wi7}H-9pUyi7^ta;2&x5L@ejv z`_jY|YSSLTS)9Z_Tok53hc~5Z#za>NDNr~ZVjQ|W`w~##Wv-sA@&ohU**xC(GnoLA zqk-_O57GzA*nDfJ<}ntJxZO>((g-$lL664-LB|Mbf3d@zkMr~;wXqScJ1Y+2{+~^!#o6P z+DS2xHZGM*i5_JS+(br3)+46=^Do*t@0kNlp%5)-NhvqECrRZ1zLr6;dt552lvyc^&f;M#G-iiM1=ZInUBU-Jap*|N!fVXevzWnGsAGDS&BV}!S2 z_OC5OyCa7=bkji2TYqsr^YB<3k7_A@-$@3LYJdq@phkYhDr!O!+EDg@Iq-}ni~rV> z5m>#ut~mIk9&8b^kR5k7oNR51dT3MFEtV$A{@9RWKEJmIzb zi^ZxS#MTkpSOW5ws|4}1-~@(RHJ|YR!z|mRK(9}z*aNnIFi>{UK|>(U~WdO7nMfi z&TLF8FDfdVn6;4z30Z7mW))G&AFW^>-<>bI=&-=9h{cqrcWCM@ldqGmnSCv z7&H#Kxg4|a0QYeI;X8RL{&Yx$&^cuFGndxrfAbETRUe~?rWIjTs>J(@o^Qw9I{U{e zTFSJbn2^Icj(xiRdGeP7QRE()>d-ePnu%SeY++9HOML4nvSWRCkFVxd5NpxrKX1SY zC#;o)xx5ynFv};dzgJ2%<3uOv##how3C3rw&dmLc0oZIs!Pg%7*YebvLDA20r&iY0Wc@6|yA2kV_9+%=M~7>TN~}R; z#l?^UcPN_t{{<@uV!R@gJ=#i+foVDO#j<%;D%^M5?m;M;wiXHgy*+aO9Etq{Fu>n( zZ=mG@{D+kVe@JJ+8z|^d==?8XTM(PO+jUg`f8jAFgN+)HvCaMgj`4rrL*)stJ===Q zQu+VHb+7&2noFbJ?*%>)$nSHP5&X}2UR$1>5!Ss)T0hwS3%8|fJsdS+4eQb){?`-4 z{cp?_dj5X;j*eqjaLfB~AyvBM~Wcn|77JB~w&ix-3o1?bAWCgkDkg1H__%TQl z;{HSPunl$(q__b^I{JV51;UA!V#{-3XupYDy|5c-kW)&^XYx}s=qHgFYmkB zTgiL21wX@oE}fUYioQlnz8uix1=8IKAXcMk>VI!(;b#t5IP@Up^Fb)LFaLYJLj{Pk z7Goy(AB&KdI2fAeg0j77!D+%r8h0-EIQeWR&RAu{RwNQ3{_$X`6H8%KLAG$}j#S@M zi3h-}7aE2J$SJQ^&`nkdwO$FotVvY;_uUv1pAdi($^EDc>x%bDh?2v|?Oc@o(#*Sq z4sH!HgHNP`rp?Yj;ZE*#`G@8?Vy{~5!U`AOBrIH{S+C)>(7D`hq9pd^XbX~dm1KWR zl*&DE5@AhJyhADSZSCFb8+$`Re0DZz+h{s(5hj&UC;+Mw(XO|_-xg;j441NW&D z59Y2Y=HrA~ue*+~p}*x=!~z0@rKP2v*1KLa$5tPwls)7AZ>up*bHXM;jqN&g?%i|B zto?apizwub5rGpMx^d=Z@!2~@no^cp?WAa*Ru}F>W8ChXYfu0Tv65g)!yu$ZK0Ngz z70zgnm3%&mP3-63aXx~AmvPWz(EM>el{e|P7$4BPBD+}oSP!eaMvrcLm@CS^4adO@+fcUlXkDpYH9**~>*XGM;>E)( zX73-#%(4tFf@3|xz1?hOXe$ok;`J?#rf@I4=Hd&0e7!y&$VKMt>_pp}?@3!T9H&$Y z&CK#`EWT!$b`YQI&Mpk~o;UU*Dk|#5^-EO9ZEf}a>fip(^gp0*`g@3G8musZUT6?6 zmQ(OELhUFjNFO7nkgo+D6S+>bZ?1G4K&tNgVU#~#n|(>V|Ky~KyiF}HRe_MFKT`C= zA0TLCM{=Yo@b3OzMMsB!e-p19oma(Vxt6-iVtR5i=mjhDl43Fwj{=yk$Ho-><5Y~& zMw`Cv;EC&#U)Sw}<_0JyzY)YC8gp+v4*G@yOt~X6Y!-G?7lQ6Xm^H^kuqgN<`x(eo z+?nF}5EJ06Wy8SUL?GA@ART9sU7=8F`ORdUJWpdykuFx{(~_q4kHGRuFuVJ)>+SY} z(c|4E9V6qk=EH$uG>rGT;|^ZR>v1rjc<1x~Ijn-$$W;UHhXlEl(-qja>(Ph9#L)t| zJ$N&w83^vkP!KFve13*lp?;PZ2sF+dZ81y78?a*cU@2>$i*}wiK{c&Kfff*2y)%6f z1}R%*LjdRgETQa?YIx$7!#2a;w?~>5#xkbcM8*-y96d8F7kdb4Tf^D7m#hJy3&Gd4 z_ohdj+$%8HUYB;0*1UrLir4dGu2WG*D!>Fu(6RHz1n=R%QvQ=?6D$OG9ZMU&kpCVv zVJ^x{1{vwN8F_Gab|frUnG~();i1#}ysEeeoBM7&ou8^|`NgSTT3*41lbNTtn|!Yw z?D+;LI?zi`)WnSKJOT^;g9NJFEGb zn;WihT{wNMZL@FF$#&Vv^6dCF z0Drw77;W%iVcOPS(=!oT;eb8H|DYYX({aXaPGn%bGA!|fT#vx?o(gtoT35|f?SZG; zytED$u_xYL0mcmtxa&0cTGtorrV();vX5%@atNzuXL~w~->UZZ(%nqP8I@N^U+fjC z+?@0}t@<$LC<(p>L$s*Q)}G6O>ah`W9OVoTToMvif5#=F;Ll@QB#aA%Rm<~Q%GkMt z0~}kYdlx*{Yo2QtVeFdZ6jn+2_)X7G_owk#fe6R`F2P22u)U?t;02HxE_)%;tnjCW3mMz@6?irpDV ztj-@6oGPX2*tmOx+CN5*a+Br~K?fE>or!zqqtET@Labv+h_0L84-htfjLtxFj=Ubb zrHf{-gncD6T`r`Grq&2#6cLvXW+12?#c1p;yPr&4s1Vk@aE-hs&L~0DxFS0C^UD8? z@@Yy_eP%p@YB6SmEv!De(=E-_j?=`ZL$ULxBnMS6_4J9xn3%scj^DOal~fNQW|+ne z-XO>2h?9Fd4KQtAi;9RyoDFYI4#D!-!Pme0$*Uohoh54vMEeZy5}Q|Vt2;<53Mg~k z>2f}-|M36|gf{>J_o(|kk7tw3P%eSKQG5=q81Y%pf`x3-^S?>q1_s3M;M7SUA;=jq z#kXkWk&}uE-OgOz+0-)yHgYYuAiWCl0;3>O=u&g!)k-l?*U3NcaKn4 z-x!1cW;_W9gql+LVqd!Mn7qXJyBjxSs9x^WSrC@rt5%OAai>qb+rbv#(Ynrkvg1Bv z$mI${3{#;V7G<)Gf&zx{B`|9W;3^YKN+iU|sa^1*8a%53&u^_9tS8O+RQUc~Ut;s; z=+X93HI4@JIjjqt)k*Uw#Gb0Evu}Ep%Mw zJUyha%jW^mWNa^aO%VCj)%1lUHKoOL2DDj~La#}Ngo}J#_scC9&s`Ql$kAOsw z!yGu@^it84rN%YaZ^QMpA&n#*zg5+f0Uw0li_#_U6}oJ1_<4qoD6y86iv*?Xk zY5AWRe&){MCY(t&NmxmmZQjFdLvA+L9?1fpcd2d`=Q<*3 zGyUGPww=7;wqFcYVD0#UHghX*)bw^-@IE@=#LV-1TR`s}#to?R$@T%J^o;g=R_?fQ zOOOd(ZTCH$l4IS-2O17g1IxOZdDhA*0zF3B{005~uoyOw9tW=7SGg~7fByVA+WkyW z#`xgz*jHq>Qn#>t?&@G6w>MSMa>R+H^TDN@{OPnBJh3zRzDVwg>iWxR-fu%!@O?e2<_n@`ihp7J~GnPog zS)4uEJGU8Vm^S-x8;G_!eF+1jO7_4T%c)75ERu%n%j|lB30XpoA zQ4}#2USk-qH4T8?I#vjh;#fckFr6N2JOkCtPt%W1p#v$nA!jghK%isE4PD979WgZ-G9ssr>xxIq;muQi_J0H`+ZP5yX3U_es9zR-xWY&0fcs^V_9$R9@_U7Gj&OKgJJvcsx2dz z7?gn4D5eJ~O-v`x0ef;@Pq(o8B7D_UOWJ-h?6tAJjAv^h4=4stPFNYgUFm|Njutj-d1CdR?+!{G&7!>8^%HQ)TEd=2Z79P-0fHN za*hkS26F+%ovXYqAzHm9{KryJ0ONDU%H76nd6^HJ6260*)H-_imz9A+<@n>wJs_)^0m~aHf(lLC@PKw$e^=Lca+!4cxuv;6M4o|_LSZG( z8t;Z5#i!%e%=vDa;&hYd85*kz+X73+2v6D$;cNpG?1h-U8qn2zAl1%QH`ja;pJ0rS z(egsiyc=77!n@>gsU>Qjk2=bc4_Cca;kVKg^r++v4v{8qYJfuNrCX=N_jPtnxca3P z;?Kco^}M_A<52qI0&TUwogINQgrHd$HNX$)eV05t%$_Hgd1<72D^38#_WJ0K&@DSQst_BwEKiAl`hR%ow zK*QLJzwhi`l86Qyh;yS0^?~giJU`hQpZuCi?()K_vw59tghvffWI2x3FSY1%SU*Kc z7p>5&wbN^~y6jyd;l9y`B~m89P~)=AuzWq+nB5Ujab(B$>S0eQutbWwLuc*;9Kl-N zwi^+QAt3EB;<__3>6Cc<#*$WW!fK!Ppc=QuRYRvJL*{Hb$uG=FAo-&t}1vd zK+6JZ+DWsWSe%M9d^iK1+&^mj4(epUPBZx9s_p10UH&M1RD6Cfq~KOqbmp~?4}>2p z3E$=g{P=gD&S_`E)ss@@#t-K4QiT|`(u4+a!qar?ih5vzU~JmHN}7^WZ9Els;Z**B z^m}mM#c7jp1tuj?+{etn@+Y@S#{#`4DI(#yG{UAEijx_b%{?TpHt669+&Vq>X;rzH zBy}IxTQyGW3<{m*PkTJTP8G{v`^%Dw`24~BkX?fg%oWBts+}RNJt8eEHMi*)(5)$v za$@B6Jq`;KSo9H9pQa_+MV~VWq`1uB#QesiyzPB~7hV!5AnKvuaaX?$5ESW?^t?Q$ zu!ZiDL2^v!S!IWr#=RVtJiHd#-Lh>XZa%i91xpQdH3SV4ZSnK0IvVFSlyF03g7VDfLuy z_dlp>MmcShrW|_M3vsKe|I8Z|*1_WIA#vvnORz8)_lp9}I~%gKPDifpNK3YH(Vf2u z*`RCd;834U>~?H4`h*vL7UT5cM_VL+;;o#D!TNXRab&eWX!dURvI3zTzNOf`ItO3ZLZU!t)Y?c^9tcYSoa#ZE33FuotNIBy=EK#2JLYXH4wJ)o+tu5NdzknU=4~$*{o?r7)3c=^jv3em%a(^X<6P-lClIoWAE?UB;m_ID!^vG?pPipxa>I zj|MX6@<_^Ba%k6JEgiuZ8IDQz@V!3ly}R767fHT$GrHAOS6^>=aqq?&A_@u$wNJK* z|E~UlH&VjKH)}U|Gpm;D|BjCf2sg-}CC8!@acRpcT0H%G;q$i`oP(qHdQ~1m zv-))i!iB`?1tWBz);Cf6f^Z-A3}TNh0!>rJpJ|_{p$zFJBUxI=$d%)v0kdCJ){Xr5 z^uESyv}oFiLhUKKs!NZgp4-rHM$daCaqMQW5ZM%G-{PN7I8S2m<~?xhyJPhrn!_LZ zj1%<0uKXIxD6MGzQFB%*HhFF2{!uJr@6;0d*yBN(%R|*UDV^CZ`S7n?3w85#vVhYh zxNCDo>R$y$2S|8uK9>)rTEli6o!xx!nY~gMWGQ@O$a@;FQ$WnK@0OQ`G^*8sm_5ZG z8pSZtabgkpP#b}QTprY7K(Xh53absvrwM%>of5LZiI=45DP`1NuIa8f zWm$3O#fSuwa{CGTd7m=A>OoiNp&G_C_Ly#!%im{*9VCiOFj0MDjh_k(a~+mUPc9pb z#u~uv$HiHc$0sZoOwD+Qz?ImP%9}*{W4FKfnJ+2;SmmW@MuGiODRuzfhno9cDAk&$VVx_mJ-Fw$lzbJ@d$(pKwmY6f z?iL-fZ+GiYGhtGemnV4~G+X3whvmN>;uH8ejXsk(MRUh-WgEEf^3simU4-oS6By25 zO+>M@(G{-uzdl-De?=a6hN7;e1x+ihOl@ErxUsUA4!E6Q#X-$#>ID5;qb)Io&u^o% z{wnm3?={!0Iv(Vpv8qEEfp?jbl*!VML&Mc2%b`{6#3Zw0kREYT%^AZMoO40ryoX_@ z+Z=v8JeEH5xwX*x;Rl_AFVrS%_odFacW6cm{p(qs#6V_xQN0)$UgNQhaNHGnuw7yB z@J_f5AlLHNXa3H2=Fe*A?66~RwJo{mi<1A+gwi>PQZN)t@3-)5%-3I=7Wup;)h~aS zJe%X&kA#mj?LjkT*|VN*PMFg8HBe6HaM!R7DSHz>a@J8RYZ1uW2-u`UaL%G_krgWz zF0gF3R2kT^c-9-R#zLG~hve|AHH6FjQU*5@Ko-6?6P;?o&Hed1OUk9uzD{_bx|fhA z=lVi4tX92P`Da(7y)u>bop#{ga|pq6=?P9CK)}wFIX|j8sikX$SWvVaB7JN|x$pOL zn%=L8&I+EHPG3_T#$+84Xt=lI3|V@gNoIznbqzoQc41P%%8S%NgHAr2)Zj^yfW)uvW|EwtDjz zcsVn+gljxIK=g8nkjDeL_vwfyYXRf#mjxiK)ChErYo#Tmh{5oWeb9 zgMeENQftBBCv8IgaW>Ob;Jx|a1K@5F(JG?OV@YMhVR`!tP znKA)CR3ksalkAhg&WGoXp6ceC>Rul$cQr!KOoT z3%_sk6W%s=-b8gy+$Z_Nr?UncJI@cRBL*K3&%1dTIQ;H1=$Bc83&sqe&VcpQb6|2m zY%U1b-C>;NTj4xyZY{f}Hz0%M(DwT)8`~;a)^h?2*3nOHm4Gr$5^l%UGM?2|w?iGT z<)i8|Ui`Myo30M1g6F!n8m@uQDK$?2zj{C$7?JG4>zP8!9o^e5rPZSE2kR*616YZ9 z><7*T;=1%cN4V;1A1KZMXsUegv#R{ZJ+?HoK1^P6WO{p`1^VJH2B*%%4Z~LhZ}}uw`D6e7CT6PMMb(P^o_)8+E0$(F=KW*I&z-x8=4?q# z&62-G3ic`B5QUkQmGVwkJ;&&6`gG^B@#8iu@63DPHtM+3r@7N&-bj;W?yy+sgI<8* zHce!f`PZO&%Ugaf`s!?x=cuB^D+E&gQQ4w%dak${H`3{Q|I>V|LtDo%U5HqJsS@RH ztshr%4$?Eayo)S~m{|@5MWq^5YPNH*+}wHdhWVGiWPSF}!JVMFguQdp%r}X6w;OdO zR~$OwZT>4Al!*ZRF6&0y5Ijd?6x4RVE7df0)27R;Y1mEAd{^T$gGm>I)#5 zcC0C@tORRyo@pGcwj&$9)K50{EHlaPFGB!Yj_oi5vbnuBm3S<4og(%Xy__3RL|_ym z8eqLb;8^mjJF)zIYIw|D31j6{C#lfcZmulNZ~g!l`{lYlsWQFh_l(Jv6If%X%3fPf zc7b=(u1&i+QOX7e?AwMRO$&!`NU4gNT8RJs6u&Ho~7{d#4y&?vWML* z5{XvvSAuN8d!JyFTHP5sC5$GBHf1&qKMI$0wf13EF-qdMQ9Jpe$++ZxuX5t|I=N)? z)9?F+Vi;A-4#g$bPU>jZ3&UCjwNe&SU&@@^LB7kOa-~Kw(Oq+O1YG0K#E3Bh6O9)f zb#`q8$yV>Ulpaa@eR;b1=0g%!!n6ZE+EGd5y2lG(lKIC%Y59EQX_U|42}J=r1XUPU z@cdBsxJQ8pn_Ve^# zmZj$~Q`Qa?uzk1`EY*B`& zk-3LNP$s=}CxA`AHMOw3G5G@gWn_lg_#^d6m(C-6Vh@`We~Yx7XR=8$#5Oj=2sik2 z+?~_281?u=^k6Q01LL=^dUw8(4vc#7Ij*1Xy^~Jp2dQrJ>a{B;>GPrLV*Yu^U&}Qc zrZ6Tun!9iQn4ucTysKZ0Nd{caSvyy*fqAFg^WzlhhXzRzP-*iSu9Y_TWU-foY+jBO zHVx{#9B|(Ib+~g^2rnrc=%TdRBsg=ilATvBV#cs@*y{`NsCN!rfzRMH>0L~sw|By&d;+WpOa#5*x-Q#b?k3^@Dpo!`X%g0sc zfiEQ;A+sh15I_NAbbd=KyVLc`yMW75S>%vhnV<>Jj@&r#3u{G)gNrcm%jd`;C&|M7 z`e44+>9mn*DsocdKF`j3eZ6*PDsr#&fF^aYogJ_D?!-sGoysRv4~X-c9~8su%8K>9 z<1MMG7abXhnYNw|YV=pLZ%Rd&6UbcEDT^$W5tIpfvar zO7VQ3^8K?g^P+h;t)M`+cM&r9ln4FszVlhYz~`2_?aN0k7jG)Z?XDtbDLVa;l#GyT zoK|L0XKyRn9Sjk5MSIix5OcfLMC%F@5~C+AAw~5R!g@X;NEA4&q<=5@nbox3byoQ{&bw{*n-9G>HP`yt*q&2K%NXK* ztQ?(OqfihW{HzA?#0$FHZh1=0WH+=i5&rCnkJS8}CM+D%lp?|WKRGVz`o8c>0v6l{4C3Hf8agidD$9~b2lbbEE>B+Q0Dl<;EL78Y849TrIYaT6 zY#GNI!W!OjErjlWmheOH?A`nO>$tmg;M-8zhns`7CyaordDp7dvk&Vm-}i2_dN1a$zuUjymQLdC zsN+77hjsAH+4FT^_0DG0B?;AW>#^{|Em$PT(GN;eR9f1<=D!!UyL&K0_Pl3g_8W^C zlQ{6Dd$W(c=(~D(L}c$ILc|W4h*r4H3fLjCcd^gQI#r_+@F+vk(s#!{J3Dt3?%R#a z(UCBH>(Fv4-OjpDJoVSf#@6Pd!%V>Qu%|!)2&g&B8w3I&vGtFWBJCW?ZaA!Et0qf|buW znjPr*qJ{5NNbWHPN{&KBg6K)bmcj*aSSqBOs@^=xv4#|0Vhd(~FGK~knvj~u6n2e< z773`&zflZtd%piyMEEjh7H;|nEs6CJ6EZFoYQsY7ugC|jYrbh}O8Vu-&N?=16ej*y0B+6?12)nwli>u$1QK6N*?SXc`JB_{Mu4bj@?oMkM?c zm~-ZjExncC0-xaJ@^bU+;NazWWt~Pi#n$fu=S~c^EMphESE~w$D7aV5oMA4}AnR;V za5G|<6MulEUO4`@3fo$;Y13clZ9@{vz5YFAK3GESOuyd%8C;Jn=Q^G+>m0pm1Kyg8 z&8Z}|-JxS+e%xe~{$o)M_yc9pV8zvrCaXN%>)lTca4z(yd#Je|s`fGnGZ-s!P|+s4 z{d-;NQ>ydh?mg}M62)9+*5nGE@b^H(e)lN$!uj}A*MgBM7ocAu7MCkQPRm3{TaV62 zIfJyy7cv{Kc1TFe9Ut9^SM}y*(n<3RMbPjEM;5_l6d-rPTIJN+NYgs|<>uWY1s19^ zvJ?ngsJ?vTJoo0;2C~X@V+Fi=p%kpob%Y1`9`{dxMPlpVjO~VZ@AVvgmx{)VyKm?x z7SweGTbnb<|JA=d{Vnr+g6wxQE*#9P+h}yO?4#!nNqS+8=JLck^7|mfAVz6)uxN(T^-qgcS#HHDGzAS&NdZ>Hc#U%~8N>@a>V%wIga5xks)r`xD;*ALbl?hZ`-3d6s04_551nO_h&s$uS?{e}8RcE5RE1aC_(VX*n)-jJwX`+9s&|uuIc!bq%4l^%bTX zsk6JG3!k}Qvic!a*hU5S!CEzeeTG=mO#9x~dei+o#>qE!=_5sQnQuR*g;{z=InkSGGZhDu#eV_<>>1%~zp$fm#(a||^6uFBx z5Wby6rs#upo_M>zJ<{ZfMNV!p7X^PzS;Q_xKq1H@dgG|?L>mS1Ggq+>a0Hl&Ch~TnBEf&#{E05C>$W1i1qYya7{JUaHj?^>%0&W3DQ*>y-rPpzQNuz3STPyAOU#! z1#nHC2Ita8jiS(AlW>0fWvCn~ZfIa3VaCPI@r@H!Q)%g?=qY>vn4Yhh*lT*B^jYgQ zXxI7TGG)IChM*}oohzNxasPQ7YMt~LeIzW_4Lu_W2x$UGWh0i>)9oDCLvSBbbI%ep zSOW^6^GtJ=A*XBO2n=nZD?#x!{GZavFS+u0re;|YPJkbarE)k)X;n@+)LF6xjBhF9 zN^7*Bv)ApK^q~!}+b#GalPFVeyILUS5E#$H}rM5Cy-HG0Rc-7a8vy?Z8J zQ^Hr`hCXsAhAWk_T~Vd0d9@oH-qbK3c}j!%Ucu1P-%dQ=P)rx5Bi*URvdYV)mCK@E zzl~Qe7}IEPfe5L)xDm+Pu&B9sA?qDRK=_gqTsE-Z>-iKvs1%L%@%4KZ2B{Qm(s&lT zsn%!V>6Q3zZMPb0G@7dl;g@+}>FFU2`Zu_HmprZQNgHR{s0m}Kp33`j7yFJMxpeI* zpI;?@5t2hyQSYKoasD)A!CMBHXL8tT&@MihrPPc%I_^fL$R z86NSo<@L?**r{EtCTHNK^NwpMlBA6KmlGf`+MA=&Qv2ZM_R+4pitoq63qZ;ZnD^U+ zW_3N>o-6tMk|)@?uNh{6bS^$TU3ZSBB9lWwwpT|BA?Cx$#X*PS%tbK~PnZS)u}Ea1czJQn%IQ!EodzeZ>%(ZcMEBs1%X)mr-=cVop=- zr{7Uw(o6eM>zLhw4Bjid^4@(lpSh@K+g%*Y$c?v7suaOg`V^pcdurRM%PZX-SZ{(frD z2ReX4GuV07N&8b^PRnEF!wrO=vK6N2Apk?trD@_3><(VT zy~9Jun-m0UP{>-_3dk+qj#z%k(X!^6x^aA6HYW|;hF!vYHt+p`&mp+s5_62w3F z1ydg0!Qj0EOt}X+W^XM-T#%cU*=EMJo?$bUPY&xIeoT_~ugpllo)#-q*_K%@&KOJ- zzpgfY$5&cq+)G`=;Pinwl5+5#fk=WWQ!@Ba{#JpuJjHi%yQzvH>`}qLrA%#zf@fMu z`i+&%v1oVBaJ7TVYn`;Xocu!MiW0Oc4=Lu&pzo{NS*%bf*J)D=&zlS@xbx<33=-wT zccvc-cA8Z^)jSG)v(ix`g?mdVhRYeYJ_rag_%B-po^&HyH=x2ms|X2j$C_)>>7oF! zR<*7=Wke#Cz0_(#cR_UkX_vInFeyEw*FHhPh;mZ;poFm!wJwUE1h0nEi_m6w8pDqnA zL+slOh5z1EK|>B3mK-Gl4MhwV&W2E|IgQ9~lH+)ar9HR)s=RQ_SqnvkZ;pKTmo7-? zDSUQ69xSxNKFM+Yo47wl>X+#n-39xcHHwR2aogr-Ydh^&AnbQD(lXE+aXE`d%G#DJ z`w2IdLZN(`V$E5;7l@^RK)cND_;Ina1-W4(0MF4|4~+}O5alcPGY+D!fn<|kYy;qo zd@;7o)R(<(>-~I$&-(8E`YWf;dC)2rBG!HOIbJy>xOy7h%nLh;8L6+Wf7j5T>rT^g z=8eMCo^(-;0iwk$$%(ENS2uSL0YcIKE#-GTTtrj7znyAitttpnu5tDKwih6JeIfh1 z7?AwhNt?zA_aS7M-nAbXGa0@Rz#E={w;cg0^|be@ecBLsK4C!s7>33VdH;ajZyZ?% zQS(N3Q`=sW@YAdAFznkAvi4IuSOs!ee>jyKuz zE=4mLsA3^FwvX|87~39QWQ1V&^BfjLdb#;*6k7L?v)+HzRfQ2K2!0BsBzjgw=al3# zEv9}v(;0I{XRJN7U;K+Z%}35`<$Z=zrt?E|<-JCS`3d<-Zd@svQDms`@$q;1l1;AC zeT_!2Z|>uOXO1BRzr6oq$wxD|&11uM*l4`v(g#MeB{7&lS*o*LP?+*d+P69`{ORBPhsk2 z*b!F;eVG!>Kk_tmBhfdyDh{o9{qXGDA4@W%CKnbFd6{;P9l%CxvGEns2lMR|;1;^Y z0i)c(G&bt_Su%LX_$?Fv+mmMXqNBAaYO;C@c9I#o)#Z2yWwQ({pu5?fM7G*{X9);JA5&SjIfSoBnyxvnLZC@ zci#1QJ+7B$x?P>XNsf77ciXkz)#YZ^`UEn_MLpR;j$gfD$yrEirdc-MN0~>Pj$bNQSZ$})P+pn)W5GF#&QvjCHt7?stJ+TxKrj2uNAmpfuRse)_id?qn{E8b4V!8!p+A8hB22W< zV0DN(PJUdS36nNfS0QavWge*&o27Ub)GpAPcA-m0)vs|1J;8?1-{OQo^}ELaA*^*v0|~K_D)L;B za2{dIkW=s_QIeL@^y?;#W?C|byaOA>c=bnl)zQ)U@FW7AuQr{6V|*mT{Wf!lYb$H7 zJ%_v5J88krf=_!cs@gBGtHhuG%#V(R>HCUJ_{!n;Z)7~WGwo)ay_*sPp1^| z*TqVErWMHKqTSaW$gma9-VTcx;bi5xPcO9iZB>P@f$f;cY3VH5mLHGR%%uUQ;Xmq( zp5EvMENnO3Y(~|guwLg7l4EuWE{C|OU?}GxAyB)ELd3gtOH4R>>jH7Bj=iqIbGfT2Ay6oC))T($kG3sq9tmLxN?lN~n+XW5Ji-*zxQ@XUGI^XMGEL_fM~8Q%v5cJhFh!tRxJRocBbC=&d_@NaYVFodKi}W|$Bylf9XpO~uei?Zd_Ep$hR_=le{!Zvaoc4G z^($mxWYI1}G4Wlmoc@4%h65NmcZ%QbRDaS?gLRuHv^{b$eh`&r)bEAqv}3m z6A3mhIo(jE#E0GJ^nTDong#HF)3YdfSI;Dz;nCjVhiW{id*+)N?@83fNNY}xNqC%BJ#+?J{l{&iwz)0+zR5x)MVIdj+PIqHoS6tNpVBM97xjlD>6x| z?4BlAA(64-BG@(Q9n8fxW*CM})?FEw>~x1pJ%T3${UE#+m--bX)6Hr;V+9h85;5uz zRxY{zo2v)_=-62;ZGUsVA?~n$uEMB#$Y> zQ2T02A%4Bye-?DpX>uB(4Z%J_78=k-$E9%r?iY%zald^&07=V9KlgC;#n z0zlSg6>HP78?pY<;`tS?>aK(7m2(QCN&ZHK+MCN;V%5F4WNvC~3#!?w{^!U0xjoHT z8$at&l>k^Uy4RZTDo&FRruw^1oiO(izB$(ZP9~9#AlI2e?R&f|eE5&sCkF5qH6aDT zdb)G#S21b^FIcZ~HE2hjQM&ljflde`QejLdX!akV^dS3Gzrc zud)1azS+-LOivmct9;!r6;oom@*3?hIoD+=!R5+5D7`EKLS}ArXDMG=lg}skqhJZg z{v+DZKSK72NMZiazuh?TTD$GBA}WOPxPnO*ZPc5YDOL%jLE$WDEf<7r%s~(H#=kqx zsBUjMaeYlcnLr6!{C>{zGj$CMFPW>p0W7HYpi7m^E%h~3BNFETWS_*tyd zODmQ&$QZJZfz^)bn?=CywD{;~6Fc@XEkeDsKc2W@Gc+h(O{#VLGcE85V%>cl)}T)G z!2ZpdcvBA{(7&7r9{PxG1{$rlqa=_K;8dU~Es>L-`4c#Y1yM`Y!)P>9Li{KB@( zh%4Fhv0QgHtgKF9=Bau$veWAi<+B_Q)ulD`HsvO&ho!qZg+Hzr4+t8SZ-PZw%EfS0 z`oVbQ?*U1=JHh??p7g+IZY2gs2fA?Ww3^oNxV3$+xcz*Sj_H`Zl=u@v7%xcSvSM%r zFrQx$BAE!sg!mB5a>==zV7E&r2XCKs$Beh1=)i9zIZ&1~uzouSqImln%cl8`DXX2b zyQZ%c4LJ(CjEP2v5*L0=!Lk)=&vG)tw5GeJ+o2GZD8}~XN^Vu1!^bn*_``=921qyn zQ|p>kJVRdb`dCr-0o}nEi2JH|2b+I>*=RAXJ51V%HrHOpyuKhYmuFNYTASx4%HkFtU-@B&{)Z=zKGF& zz8IkEqC4o*eTE%ImUa8y!XnPErc@7`G{qnPtl1)M1&)_HBfZ&(E2h;ZA!mK@-!_1v zFn}Y#!$#?GLr5P4^nNc;G-3&``rGwyB3}*;-72DT)*>KgGhV2b$+keIiLa5>jk`(= z;J#&h$DsNgQs#0s4D(ZwpCyezqbwyrxEeo2n=|Vun1xMzru!=I@v|^(K71SS6u6BaM54*1h0~+q-;iC^M!t7aBL{S zLWs6M$KQ;XmA?;9!qVyz<_)bOKHy1|uCGQBJ6tW;V4bA@DMS$w*zbBqvzWBt$>KX) z*bQJZuO_&DtD_a?vOrCvIJq zD<(^^V&}KFRkqor+_jqnVH4p4(w0u9M>0||qH-o8?D5=rGH>j1AeEY%>beFD7wOjw z+|MY@wktDkpB}Q=@u>SJm6<0?>^b6z^iV?vdjLToYViwQjCmt+1BYG?28ysXG& zs8gI=XJ=pYh{C7d_)fJUqE;7?Le#7E=b!fKD+)7*SELpPCT`Q_N`$Nb&Q@Jojd*Tj@KD6T|W$J=aMIEZ4p>a(01zIj4Z{^me$0|=UV#X zj>8vBDw8$SjBlL_JSAdV@4Z_u5$g}DRmm79D^1Sj`OXdwJqT0`muG{uqOg*1cExIk zd7&&UGteC@WLs|vz;4)#dB|x}eBnmkA4fB_%S7DgMKc8B%|_I7hG48BUIbiZOLTG3 z`CxY5ZgVlYOFZ0-xd{sxH^hsHBRk!eG&{Eu=olRAa{|a*w-4&t${)|ewlm#4-;)-M zWFsGz4tRxgDbI4*6#f5@f`za#yC=W6Y#Tsd%@5MyQP=)$4PJ_QS9aUN`Cq8|bg4F< z3qI`BuTvWP0e;yvOpX4 zvG9onyn}rc)zAoQo~v35wxK$h83K$K1a?Z{mO1HK$)gNvU55B<;RdjkXX^R3#3pVfouiPtx}xCViJ3 z_Es{{wc%6ZTr*AFs0E}A>O!{?^4Ld1p4#-K^Ig5mA#pYOtDmC)kFjvG@6@94y?U<_ z0)WBoO{iT$irii>+4q+?Kfmv??S?Uo6Aa0JdJuV;1b|ZO&b|VHx5aarlhK#Z0!6JK z)L&4v)@D@B9@zK* z^5s!ifqvI?{5Ly=?c7h)tW8z--n@D;8tnT;Ms|JQNpfM847PSna@2p#z=sadNxs8P z(y)7GZDF_1H|&Y>We{GSQ%Sb3-_E9)=OrlHE!TyklR-Mz=Mvb{>yZIg6F>E}h-;jd z*JoSS9|aca?)n3z&)7^p>x=cPx<~LvJga|=%0v&)E1sjt&@N&G)kqmMI#8@4{-WOY zN%#}TM&R#bP>Re)M`JI0uKD{^RdzmXkh%9i<`M*8rVEIH^&ZSp{>0I@JlL`u)S{gR z-26FzqVqE`0Qql0={`F<6QDq$_ae61VME-uQSfEgG5T`h?xP?kvs-J){}%T2t6d=& z=S2c5xxLlaS^lyTw>G8jz2SI5VStXjq#?OeWVoq)`T|M*Pi}X;?9(!IRg5w2{%T?Z z-pvlAMPuy@}NMEhm94OA3M5S?j4KaK3D&Kr&_IE$< z&9oS)>wBledYm*1=ySQ5XUE<|-peu3I>th#V&4rt=s$3@ZrQ@DlSu>H@Rrs!&Rxe? z#WW?NKr<=nRNZvT;g3>FFtK`uguZx~x&)JX{X5~L6&7_%2R%>=_&7wtXsntc5gz$4 zq*i^|f+hWj*vt?~-|%FAbkeS@Z>}S7duJ#_#&D_IO^W|_Vs1balf9K3=uCty@cc3> z2^B)CLOT@KZ-b=yHMi5xTWx`4*bu)_sQiee^cQ>6Q^yFYmSuMUKz5ad8Gx5yRuCH? zBmnD4%-+WZMoV0)Hu?dmvaBvp@+-z`=y*mc5Gr9v%$3JU*u66a1+}_? zZpN|s>-)DOMfh?}{eJ3KLV&qKR+% zTpTu!mb zi#Om|J&>h)+x05THXO5W1R*sOgIvTIT7he*y=e&gYeKyx64fM`+50YV;J*}3>}7EP zj-TfO(C#8U_nzASwg;&S@d`kDxO<6{l-^~~ATK0FPS?Lq(vT8Y zYL2N<&LlibM*~g&LW@~t;hSGL=e8lPIX>yQ2&B6C>~T4*U5*e4^RW8MbF;O(&y#@< znuS!t#Ja^jAeJ1MRb;o5pT&7uc&5~B4m@Xu&BnZyt;xh)kH}viWDRz-Gf6(E-}u3} z0$%PKtOlix(#zh$gzR()x+SE+Ltm2%al1!X#5r9<%)!MqMWCS%sIkbi zoSmT(I55FL3Q7JGcNo;?r9_MNP)aq^#5`JE7v4ev;Yy2JS`eZ5pqW$^( z`H5CFdvoZo?Xw+`)pCpvn;0^F>wTM8nIDS6EPK8eGs|Z`KMk40;SK&zE0AIYQn6CL#F|iO&7= z(|VEjJfX6cBHg?i)l@unklJsb)&lZCX3lU`|Ew=`#-#}MUwyWN*p1Jr0+o%NNf2Md&(+R0aL}7Uzmi;r zap=4@17)^u6giFa1KqukYWlz53%wbZs2I=kxwmcCoev{3E`d@I^nO0!=&RkJ`gF&y z$l2v*d1>{Lk0#xt?SGDw4Dn*#bCJv_bAH_ZYCR!MGb=SSKpQV*k&CRF`-lMG;*{Lh z9b~bmZr@smo~$sL%J7b3{QNkZI!xn71|Cnh(g!@v^g%3VlKD&gQ-K;S~)!YbQ zy9pEyZt4_mScLc1hZ~YRol5;E&yLGX;gy9DWqw0!bAgrr_AB&j_It^!zcuvwO=R4M zDX03Gc$Z!6$RN_Th zkdogQKKMJ$$+Q3MUpo6;QrU?52^Q~3f38r`-oTq%`%#?jFKb{-fkHGkVSc=m?)2Hf zmn|#ce!u3U5_-|4DfF`zBxvW2u3>JcD^l@7ux%aQX*EK*9Juy$yFV5XuFU0>rgOW% z-IkSQ-0o1P!_T0vrzn+qq`SOWI{5yG5*>@Pik%ormcGR;oAD#FA1T5=fM8^kxIXU1gi>q(VZd4RuG@B5t`zZrb^c5 z2zqBN;?yY9*q%B)vu_^RH2h$T(=rw6U1*V+9n-wviL{?!Em7&_A)hIVjg-65KYJbj zWpe7V>y5cHmY%*e1q$Lewd$(!&rrzR0asiJ$`zC8ua{jT#UGABg9X;6L`v>kPfKeC z0(G?MZJTU!j~cK|xP>Z+FlAWvH60gP-yn^#TpL`7#{{2FHvD0Jhxs2>0o!Hw^HR^3 zY{%AZCA|@+Qk_1S22G`howtmBj}~pJvn#E+0e_77?=N;^tfggxxk`YeQi*S>=N-JnN=SH>DI0LZ=v$;yWIV}ikT?TB0ufeMT#T`%J9j!?V=>uf&YFq*v&t%p z8=coGD_TH7x$(44abuhHUxpInG`sNlhK7dV9mYt7MDQpb)C_9mdAGesNB$RCS;+a1 zQFjF8ji1h)yU^9-%Yoyz8L9dV^!1|?*>pE%bWM7HLwj-leX$r>aQ?}fhz?yWPcPAxWMZDh9=fdCEk%%`j zN{8Q%ZTp+VZJ{=0LcX)#78MIe(mwuzYWOzvoMtWV-?^=dmNJ8*2_AL3clENKSuO<7lD?Q{TvS>0rtNO?%a-{1N1-V6t9*IJB>J^m1p6 z*}1%`tLt;YYloYI4!Q~|*l^cf$H$SV7J;{$NUczJumwiH$@`d?81=8}QKOYANMq9lMIr6# ztODDN7c-FMlY#=);FqDR0Hbi`o`|bbO7y9}5w@J2eL~@UGhJ4kAh$TW5()xfpZ|vx zJD=FA45yC&j*rhN6x6Qd-FnxzA!8R&>q2piv*j&%s?phg7cAvQzEP|8$S!e(&)9@! ztnck(@mu~tgkO6h$_+{WW>z@~d2_+9U~(u=oTsN}_V>1*Dm`W_>=B29P2Ktpg!|uc z&+~l=1MWN5+iqp&lPl!Tbf14rs}a13m?--W^~;Lm=AUSe?p8DN=Cd1otWKH4yl#To zXbQZxqpuoL?oEsWTc$)M_xDfch*KeIVSs3K!{9W{_v(lWP6^1+@}7;O%zN9Ho-^jn zvhp8P9yR+s6G&|Z2R_Oh7?zZ?%U1tE?V1M?MFQ(+)N{;Mc37)^4+L+dp))JE=jFP; zP4N3e#RrGWyYuI{Gy4vd59aGcf@=SLBAO@|bnrVH<~oepH+^LKsnVsc6^lMoSPj`p zz$D1sp9kQ|O>qPKjt2-`;`%)w{~(0#pS}t1Yzy@{gGyE36RTkJ|DKu7tz}lFQ83S` z!{VSZ)8aIYGzZ&RL~$>s$K}{F<2x(h9hAkGDMU;F%N1yF054P5Yfbf2O;&w{4h?6j z6_r(1Jhb^)@oLU6^K7+cYnV5prs@t%mq7`~$7sMohcG4yI?i;8D0xh1SM}gS6gQh} zOI-ZrdQWw``t7<&_hTW4iq`CiRH?4OBBWDF`L`>0j- zxwHs+p$z@17WY~e_xKpH0`VB|t8>oj-2aOxYbqwgFP1VG(8%G_&vCI*cWUt5}tQ5`E`DgW>8fN71YawJ%TtFnpyIpfhabu)~ta<+R0sU<0s z;Xw$_kGsg9Ci+0C1$7{$r4z(UV!qclhY#MDJ7#Mg{`#ityW!!lGWqpKT+3c{i1}%l zv8VoM$-zA_5RY_wANfy_z|{)J{`mDUp*;(P@;Dl0M4p6B>zT2qA z^aIq(eTWnH!wNIU#oJuj)1q%m%6rooF?cF}v>C;seh@+z9NuY zAJjY-9>K)NH+`Q7#^Fo@k3RX1^M2pxa3hiXK-xDcU(z;g(1_0#<8!`s>C63EwM)|w zJXEO{b&{ObJz809haujqMVrq6#SFFJ{+f9PiAvN~cK$U$LeC%-`JN|FhJW}}x?4{; z@kbMaei-^$w6hrFjUs2Sxe1|&CtVoJ8rZM+O^w=%AT_Nw?NSCdEk^j#At8}zhRkQJ z@zEetWGuuvl z8FHwxiaSS;Teflc)sxP0%4D`vah(djQdI{Gv&_iOH1PjH<$MF~@YEu=g-!}ShIrM>pe@n{1)Fb zc={5lkd49&($X5V=>ppT_Y53L*VhM^y^OsF@$a?+`AzRUN_Y7J|DBQDs~#kbp*y@J zx=tS4?%g>1u9R~kp~#Gz;Nwxa5FtzxS%L`EgKskoew}$z#;Ms~*{;H427QIt7d74m zaL%`!hr>QuO$N=OWt_nO@64&g>gUYJ=oLI4HP6GM+a;^t({FUxPkDh9MMgzOe;0c> zFm#zyR_5!FCrTvR|0F9URFKnm%)}fA;KhD>o>Y@A2*x{*B*k?n63GXv$5-sQU(Yz0ep87LeF->PD9YP zmO`854m?yAGU}xFvcYD}5K=RlFw|os|9@qM;k}IbUXWdL6@{0tC*J<@PSn#I!U`wW zo?*nqzk2se@O;E8T%ITQlZD3Itk1;aGC^m5_-dC~%CU@Is~whMX?2Hq#v;Olts2XEdpXL;PW8G%zAECP({Y@mDC~>$a4}ET0=7ZZF=|faw36m4u)9n z`)IaYY+zYhPf13K$oShOw{ z*0||}EOFceTx`^E;0wNfb&t^8pQM2+oHtn8V}(QY_`~e(Svd|~#zsW%C%Gf zt_rnjRs2wte#GzaeqCY3Vuub426`c}>auOLn08kzOdPeWC|4=|)4M!2QEUh=Ub zue6?d3;H-;x~pD{Bzw=ln8VssVmB2Ew^5=4$!T%;76 zFO4{MKvDl;zeFp&6l$i6J%5_Z2h(L^h$ceqpsOTK4eDjTmHJf zPs9|vFe*Ut=Uyca13yAFrN`84bEd$`uGy~}Xn6{0#=N#ZUCBreWYn1{~ zadzW|S3^6AIj7@*=CUE8V@k>MHalDzVO&=kzC1aT-dQRClsY#Sln3L#jUh&7zi0CP zk$!$&9~e5+OBT9m)qq=ZmO#5FKgRL(tBF(*h8!EYXmLt^-QY&lZ@;|{?`Aftf9>7w zdvZN!uiNQn^}tEw_niX;|i;7lgmoU$#X@B zvbep;R#yc{P;n^Tu~vTzp!qV$rhej?cdUl`ia{YX9AkV*0Jpf4WON#nz7b_BVyXHr zvE5~sQx3StY`joIfC>|3*V~daapiiwDb0$k0|u_e#htnb@>h&rbdJS!RT}F(ZR>U1 zo3oc+nd&9V1ZcnE<^i=`v@mt-kM!9aM7s0Ed0r{WETA)zV`i3`31AsQ0}}B zU7M$$`jnG725W@ELs&%=Pr1J z9)t~1OX;l$Oz2S${I=`2%S+Q(n__L3Iu^s6YE{zih__DSTk`Q(W`L;o(pc(sIEY`2 zsN=pOW@bCjuP_twII$129u?i{wP1#D$^^Qi#x+Uhg!H^0+&q zWDbzysYSpX-y-9Tn1g5cY4zKp6Siv=p(kZ1(D|w$+I8Sp?-?0Mj_=ji?Bj@SI;|VH zy#o1AxF^R0Z_Is9@vAw^iz=Dzkp5y%-A?}hUnFlv>GEkP_IrN((NiW*e?PQ~BQR)p zsfh-^ql|^2N3D6|*N15R(4=q6KcBUHWA~e9Ui|6oG>Nf5xBEGACN#lcK2by;Z96T! zsMCa-w81LvDTY%r&?Ynn{uYSQJ%%7DUFC;h3~pY9w-qyjwppbTC}g&^Bk>x|kb_a6 z50pQ31qh0=r1l!MavGOWn{3fyN1%2WCr~v-f(;$A!LlL3{gY2<__tqTU`la0o~CF% zmnZDFHS5yxp}w8^YGPIRqoHZze@5hmVqkIZ^fp`}T(dE&C21K34$S53y1awNXo-Pk z(6GTY{jDXWsok59g7%YYAX=CuIwstjy|4E2Uo)N=I~facGFReT@oA8rF<$%97uufR%bl@LctxZC7=(DAGZ zzH2|*E!5Rug2=<-Zi7-ffuG&DmQb7z#?HzmS>8lUMBIy9DPw3bS3-grcz$%*=qK9J zeqmkSvpKkMIHRnc_t6%)XnPL3MT%Yb)>TLF$lg zKD|Bu#4{fg-u^&%G1_&(O3?bpH+~CYmrAJGP1yH6F}9aR?lMct=I}@olw=VwBTmoK ztZm}})=8(~kHLx4dhxQ%E|5QgHT|vZYp1Q2AXDiE#>9xI!A$oonx@{oN`mX$d=X6N z7P=xY?AiKg#YFIkneMKCb&uT7>w=${Wgc>6v@_RA1I*>dozW(R11CEDwvVL;OZgu* ziEyY7ygWuI9W$SL&g&T`)_^1r`0n{0y{uck+7jz77Sf5{A1!6fWGIwigcs3@+Fty( zekwD|zJy9b)9t!F-I77PrGtM=;B@GpatNSU2?xp8>o+~)Gj9YP%|J=DN1N0T_Q_Im zbC}Qab&WIZWJy&1t6h!Fwpg=E>>FPbZ}cw0Fe+^XYZ}^3SPauoB_<;94(yjmN9Z4} zD)ft|Pp57Y(xOe@>fg&rppzc*)(Bi-}+q*7n+uBElO`&C_S zA-s1ZWMIu%Nsetv^$kzVcQg~Oc@IZ{QezkvK4ClWf$QM9jc z`0zTvxk=CeiTWuu0rx&1j+!j}{rji|Nt0mCt}*AMIECmK5G`5xf>AbOPwm^L?89=K z=a;+`$p~T`Xoo4DgDaO>AXm8mzNLI4on-AMCa<&!#n{x31YMk}?RgtY5E&(&joFJb zg3Db}25QjXeKsj=ccS29$324g08hAvG?-TA;S-4^JTdad!{RNqPQulf>DwvtXkj(o zZ8;NboN)RK%-C0=UmEpH|0<*~R*~Qg9?f^$$$X@Clr$L+@^)1mpCginFMki6+4^9q zzOS-tVH`^k6qLit!H3@<5|7_#Hnu8zb%haM?ZRUHE|}G*%ck)*DQbyO;Y#lUZ8{WN z=XYWvgZO;uq;cd7o8SDOC+3X8H!h(l)uo*~tFIg+rXy;F_#zuokDw zqT-#~4gNa^9ZU7%11lFaM4FIGtXqkKi@fq*RVCETZz7gd)O1a<-e9@>>fK~>l|m{8 z2COYI?VP-i1gJFrXTQB%Y^Lhwm&6N(mdsqcOg2K&XIW&zT;6N@+-p5;{S(==YHPcx zJ@muX#=Ay&Q?yV~!E|iW1nafOXg<*)#_RE&n&|4=om?4tUkQu%}L`f;lvn{J0 zK>2b8(d;?z1roN(qyrli_S!{EZOdl${2(C;~~+t zlm(7pDGFCEwtVGs$7NJ@*%cwAi#oXKOME`(7_>R;>w9*fiu04ezFc-`xrDF!znrOR zX4}nUrumy=x8!Q?zvtladGPpi!5<=Ds9mb!jJaARnAiQv=lSW4_z7KeHQW9Z+)G zD5!4RYdZh4k!F9WO!N7o<(`8$sBOp@y1V8n##wQeQ#Tgd^n7OkoEss_dvqcDm3VlD z@MM=dMWF7ftvKbllFuBHGCWS}XrIolcM)`A36#V0H%o*iN-h-Mjp~LPNL+C)>!wF| zDKgLowh%#eqTO1CJXqr-@;LOH33Z*@^lzGuZXh!$IZah$PyYVwX2)O<2!w56Cu&Mf zYz6+W2Z(J^+(>?nWtMrJLyzoawd$8%^)qJ8~o~>v-usT1Lz1oh9mT zoUIum8J=II8T*5P4zXyfYgP^2ai`X!AW&M7pEmITQ7e64kr=_NTRSjkF2CBmyr1?g z*6CPLX`*!dHrZoOK|oa$uVUPPdzVb}0=l(^+|}M$`3J56LgID01<5~{i7vn>EahOF zxs!Zf4ga?*(&n+wo1TECFGvxhOPenL^P*&ca|~m8E3Ok0`DIG-Z9^q@M_(jx2~gAyMPpg7BLMMZmZ>IV$XyFM|VNwv_{iIKjY zM*ky)NxcJ`gGk>lvHIEwl3x!)I%b0BD50?MkUbqsC$7v8?>FLTi|OOUQS`LRrBN4{ zvh;QVgnP28JOr+GND-F1#aIV_iUSFeO6a*VD+sVApYx|q4zDCe-N-l?C7Y_NlHZLW z3~u#2;Dw^YhmouNd*MjZ(vjnfA~q}SJ5i*q4{Pk+N zIoomEPQgMi5ny1R!o^t)@dg>u9G=MiQlwAi0e zS%;X9$ zXfh2w#l$40+mAThXK_NX{2pSmL)?#bUB))@Zx@>af(|7v zE%i+9gsutLwOyMcCOX%R%gF^J;~u-n-;gREw4Oh zLeHJoZUf0%4g!`>_q)ajm}-1VUOqp0q(oi}gnhNBS9b8v zqK5gR-Po~X3_l5l(D`=`<+S(o?qZrgC{&hE9W_G~EO&QVhT)Eu_$INHVJBU~rbDm1 zJ64+EKAf$pM6Lg>tkma~p5tJkp8H@}Y8P$to014?1>4et$Y1)Q8}|S1h9GmhQ?}o3 zuZHISUA!aHCSWd#q9=cr-2{k5a&U6aX0lG~>&{(}t!cbztjP%KPxUC$W@08g5TxRu zb5QbBH_JWvNYA=DT$Kq*Fnb+sp_C0+&wHz*QT{3i+qpw`7i@PC3jCk!=xp(`SQUH; zFxRg8gIUNzjYo zWea7aWR;$YrIo0Hg(&$z-fKF+(9s}F2U?6^8o3&i!V0#ZpRy=bJQ`^Gf!9^jE zsR_X_BTjV*b6m1OduY)KH-wb^Q)?9#YbvX1eo$Puppb`E+oK=7RZoO4aQzc%9IZ(7 zPMooJ2fp4EQ9bn{n4!XmoDz%SbsWR%BdKQ>r4gcOG>sYG`YJpO0{)zKYc!80&4z-6 z%U(ge^Q*09Jf-TdTFAgxZf-7-Tw2hNEB9xY?@ICPg3}SJU2oY{2?vPsv;pNKC-ZUEelWv+GTzRr{)Kk}wfeY{pc z8=5nV<^4gHy&QgVvkI>54~%6paR_rBfR|i4$yUK%|MvFCS!$$4 zfjzCAXdV_w8$DPtfBmSqM-^Qr$Z}6=0X53*x<}`@?VCdoLwrgv_iO#0numGRg(;)Y zzM5SLg)?-SzTgBKG!fHBBwCM37DTcHw@Gn?sj>N)DfkTHx zC+Ds6i%x&YOJGNiv}M{@iry%nsTU0R!}cGF48v1gsG?fzSsCLb}1ek9dG?U6@EW{rbwkx=x5M$I@tT)0(u zLSe4-721JpUh~wYmO`i89a`?5r80DbCL9Km)$}mO{#DW~yI`f}tIdg5g2i#>vHH zQXC6YFWB^?9m^Pk{$2m{fz#b}{KB!e`F~Lgucz)V+J4I7@4OTw2fzr*1efKWFyv%TLnOy6BG8AGCL^jv9Br${GZVPWr?;B<=Hvh=vit4(k^yGOHNye=`h|M0h2oo^%-4wZgSAr)ZO z6zsW^^8-3*f2TiR%CIU$I}s;io2*#ymE%dt5hQooM<+mid90D3j*%X|klP1h6-}gN zTQjxMewlWB_9ijs-(k3jYHY}#bQg#5Ao$#Jq zSS~)B)OC=H{U4Xs`CWUfg9D_R!-FZK)o;dq@N0%QvkrV~%(E2B@`R_Dmt5lWmSlT1vV_G{Cr>;Fa@0`y*P|3lA+U?as|1cyA?ys$n2A+DQ zNgv*Ycv)~P?q5Z5gFm%-ei6W`eq&O!QWkoMcV=6BE$PY*nMofY@i)#JL5<% za*~?&Maxp5Q0kA8mr+D^k1P1;)tJQ7$5vmt=^lw#ueWixrmxSF1V!C@xgRP@Qcip2 zJq-(`jC%aa_zNzp5Z%*ZHq~#yh$VruhCl>v$KB1^>`<*TYoAv=xo+Dwj$V@=mpDAC zQ^R%W2kBm1@n*wmGmq^IMBD2upI~E??m-YaH6SqVrtJZlK*;Y>*g)${&?X*YTjC1T z+81wqBk|PBa0_?7w&>y@Ge3`5i^dR0+GxtYV|v{AmqTiH^#^-;S(s9HuH-Q9+({ZW z^Y-p0AX4>d>KR&$=zRX{`xXmrhL=6*uVR0ksSU!t86p_0dqex#5bg>ByZR#-5J<@vXc^t~$M40wo3NKP&LlozC1Cw>gn50IYE$o;8KTsleh-+O{o(Al>3cg= z<&SFec%4nC;DX2+(AC&g^`#p++!stbf4svv`)^=c_U$cG{lhqhL_w^#3g@#Dx{?Oo zR49rMWen#%GvY}CL1A*cY<&(tMNoB|(yq20b8 z%R3_&>W6f0w3Y7E*Q8)2jW)`R8~RHygln!EIj{rxF;$3k!YmBl;s2fj9A}iyvP5DY zuXO82Tsfd0dQUI$i{ahYeW^Kr>bN;5QHqU~GqC{k8}9sV*~_^z0s_1^ZEA2Tht87= zZ#p~cRH|;o6v@I#^&u#^1V3Amprzm!UJ$7+yC}Al;neVFqp!B9jU+L>7Q)8jDYlNi zU9{+h%o1g8;}SkHIc&{4|9+@LPodT0BEl zv0-D@_b0;aV6HxHhl>n1B<{nGU$5|`4el2T-S?z3odFu|O-s{wgC-(c`WKh&i>*q# z>WM@q62puneGUJw%!OU*a}{cBVpzOYWOmAAGgh>~gql0Fe&bRek+BL+01ltZo3LHe z2nLs=QpF#_40aw%0>3||O`r;`&nIryIIyMRrrOs5I_L;I57u0}n(^!#q8|5Lc(UUj zC_LFWZ5YXd%*yaq6kBS`)}|Jf~x6M#U=$z9A?HamL@<+ z-ziuu!Od3l?ZPLzF+Xy60*6fm4 zHMevvBxcQ9V%Dewd;9p$+0?06%r8YJxfWkGA5nWXpCfIzF@u<2QqN&z;FoFb|RYCW4&5CF;2bT-AMIQto?$Up|MFB{^F-l|K*L| z823NEN9X+$Ud`$&s7ZjpZ|?>3njXxAsHz_s>`sP-#16SE06TxtlO6uX>T>;U^DYBk zW+pRqJanEJ@l${rAzN65I~UL382y;fQXdPixiRGrPqWKYNXc? z=`|GTaN_fP?|0rg|ISP%b5AC@=g!)Duf5i__PQ?YqKty=+4BaEhKFrI=vy4CDEMHpxKij(e;N@S}6qY>s z9^y4gIV78)LY23kuH%HdV$?FB8iD6b`^W`Glk15S3*F@hbshy;HV<>f%%JtnR}2kj zsV^#PkYOxM=PrHodz}H!jU?2=FWRqLObvW7#@N^49EZSBAcM*g#nu z!{mE|Nb5aI4@%Prf2Wqm4wH)!bY*6Ew$6019^SDPB%a&ZE_Mz47ex^NVAg^tK=(+}Xsl*Jfp9 zeQRf&3N*9%#?!Cao+DPvqk5Xb=w+UAPudr>tJs~;X9R}O=z_4)(o%7?aouroDZMn^ zz0p@&!UY+`pNYRXJ2Ojhs(Y0|p6C|~dU$!qMHzESjsrNVD)G>sg}A)Om!@m|mvg6u zxFMsY;!5I%#gxg9!6QCo)Pbt>osJLcI&YakP8Es>=hW)NbgntbW)&Udzq;JGn zmlh8xV}sV4rFpsDals#Ucsw8?UZb*O4Uy3VFH13qdi^F%z5M82XE}EszG&x>>YH^} zmmT&ztytQwG(pVoF*FVXiIOXPTsR~MO#=nW#)F0T=<2A4Zm*x>T{$8KvC@Zu#Udk_ z!~mJlIPI$^!|sLt<}u-xt3O&T8-2mPt|T^Z`>?-#bsBxLrW#l%R7rMSld*-B{uXih zpXDEDnNBbY>DMq%$b@_wyxa7giAo6&`ITo3V;`h|LtUNpEHJ+AkGN&qcY}U2s^mBpL zJHbLA7xt2wPb!`t_*)>(1z4C=jwbcQ(z0D z`T3D|#f2S3$G2h)CC0gT*Xj~^nlpEq_8giXjxO*qJFy+86+bpDmg*kIdeD=FzZ2<5 zc}Mrqr-kPmIoVP8uj<)!-y}dvgAzzEvf|zAuR|L3Wrj%}4ihD#cQAi&s71i%0N!=C z-Mz_K-7^9L9kHy)wcFfnAI9}>xTReOoFJR-ZSohI1krn!0@A>}N3HXE;c>j%?I2Un z2K(1c*XTAg#h;U(z+21^^!&hnbPJMLPlH zEMN` zq0Vr7OY`X?4FA;UIa zTLAu7qF~npQ3d{1swB(J+MNjuovr{R$`L9f!)xw+a2fb}o$M;r&1or1s|hF~bj9y@ z?p|DRnlZo*BMIy2md~}sNq?-X;d9j3l%)e0M7X!X2?VxRI zfFdk&#)d1yEi0`NC$6>YD1jq^1#c_PGIKK>rA@K9+Dh))HynyNec76u_R@|yQJvGD zjztezW3C)^lpCeoIrKOgsz(xDnu`SdRS#iRQCV`<&W z?pv}f{M}tw51!{K6QBGLOG^!#wR%8IY{x>JXplIhYSOp#sB@Go1TTOy-Hhls^q0w3 zo8D71nOLFWfW|EUYmKQU=kl^}%nDd^CEDqZz;Ox(wb4%KV}7E0<8!_icU!t1%9E=b zY`?zy$@Pfz?uf`^*`QC(ZZR){o*otX{;}Zul!<=umWuowUulF|xrk3UErPSHn6cBI z@Evbz@ao`AbWniRBQM~Vc*1pi`_s$iWL~t(#e;LXxkrmpKFR^=@Ob4k3;pXm@ezTb zcT+YWXo#(Lxwzd!TP|mx(~Df`d^(1 zqi6g|HA%S-z#dUV(IUB{9GkbliK_=)=0h!kBvFbr(iqn;U7140#Kgp6OVTZKFF5UI zaU~guu2?7^T!TH+rlhUmn*b)x9&8krc+=m{nc-B7p3_Gv1GRfR_G2Ewzw}2g3F*va zkRYahIKg<0K2(~d@I=4!frbZiT;uL)Zy9?L&Hr8!VV-V7lmEA^x4Ctx;gd1TK0Z&U z>)oK!pa)tsB1xOxm|yah4~x5W%tg!@)0z@+gYE(M6B?2= z9V0E}!t{6l@(ALOWwh)Wj25Rhzl zodjJ9GzRmC?i9z4b0mm6jeDxZaUw?>jtvVG)_Jhn-$$v}RdZh7iRetuosKBlo)tuC4C!Fc5jMuD?L9p&O zOlCyCmbFP+nFc^lzcENpjdAEw**|+r=2LvxU;dho8)hF+DDW8?dhDL%uLj;76wIaI z+~G1dE@(;7X(Bkvv0VFcy2lhqn02-KB0_O{-`BL5$IeuF%hc0(T9+vGn6f}+ z!c4$^1DIFx%zlcQ__ZpWWqF zn+|v1VxFL!CA9QCl-}6f?k}0kwRo29>am#J-_o3GVr)jY669x{^w!K{hk8FhPJDlV z&pYpYIj!P>1a^ftfNW0CulVlhMvW_nZ9Zl03>rofq5g&u01G!`mre%4eZoiZ*Y! z!+W{Wa8fybilYand03Lv_x!I$}Hh~AOfB(z6bl$wI=4AbEly}m}cozP%4SRpH; zUD0?zxN0%F?AEZY_YGrNBe*RO(x*79J>(x|R188!Hu{cNuzak8&reNKz%N%`@Zn0J zl`q-MW?YF9-KjyZ5=r~w8Mo)ENb5Gmijeq!gakX#Wr$B-o*5}3i+FCu3eqbyWpe9jKFBK~m&GRy5@uTwat8IH)#rZFUTJIR)neY8^lJytN; zr+_RD3t3H{Po1`vj#urluI#k0XC}i*fG&-_iLT?)!58pvnzl17>U>?~FgQ2BLrgc! zMjr8etU?>A()}o!&GVEh%$fiDX|D3OF+O7;wkJ>PnHrVouiCYKR&3;V0+0^>!xvDM zM`yRz249J^b^&7(B8M{6YNsRQ3O$dKpLE3oDZRZ?a5&zNYcKkw+0)Z?6;s$Dy=BU@ zjj%4%ye)$4zNy!|O}IlkW^udu_Y7ooA1FNt_f%}a$k-;!pv5o{VMW@QiWrA=5ecZt zoB?-g(0r+L80Lr4sVmH8OBE_w^MW3DK5*+uNG#GjmVf z#K2jWD|hX{GMl~KO+_uOr;ye=-QU&WR_oiFvaep3mI& zgPk5W?$bm^>lDO;>FctlS# z$}6xWR#4hpV$uf5t}Rtdt{ev|q@6o{B{r9DuL8sN{dH{;1L@cf;gT~tkhyNY;(qV! zHuJWfgn~+VWB#blvReE2z@3F6uk`_ip3LdF#8o6V402 z2_Kz)!E05^qeOH1TiUDM;x(LJ_T z@odgIpEoyl#_1H2D5xEpQBW`{%K7|T(-j!VSXcqyqxiIb@atGr z<8QZjEbc07$z3%+GM7=I2}RkX%uYXcMx!&NOxi=g%)9?X6ltfmvU=?637Kp7OhHYx zA*i*V+omJ%9i`6xNXy5{fJ+2-uttG1Y`~3kpZba5Q?l*s=4y?N^( zA22a9QH&ywMtIP&o49FfL^%_MTM7!*XP39_g-8)kfeoA}q|$Wf_l;H)?5*8%Z^6B^ zzKwN=gJ2Z_>CuC(|L{=!JzaPAl@A6RTiTnIjnFQ0KaUuiOX%D$ume-vxYW|aXqC~ZUwg7z)=$ea*JTy&t+ zF@*V}`D2tyQF3^{rp-TDQ9FIgO>un!aBX zQ8<=0&*+o+KD^UH%Mw1u)x^!eL!rVkQMnMa|L-pI@B0u1juehUi5=_`nH%&=JbDx5 z^Azy`!BMsT{L3b-*^jH@8+J!cAGClhfpkZFHkFK>uZ`X{yOS#nH^wtjNh%Ll;*zu} zMg^$k7`dNm@!>N3nh#w*cB9=sG}PR&{R0E&is@R)$F8F3;#V~~5(#$*yK+aAM(vtk zit5R7s!=4nbsVXuGgeb|rsF~#5!n~wvSfW*gGwEC3mlm-;n-@3q4d4LHnX?=r*@-= z1d1krNSs!~z*h}cuBiC19;VO+tbtBL%~ywa@5UzVo5SpXU%OB9InFcc(58??xl7_W zSseD(H8(z#0ncfe=#nj}r2a0r|Gd)expZ|C6L|8!t&ff_WEu+7#5ruS?1Ct1X~eXq zw6Zv+43JbcwY8fo9!JSp$#FQc1nzY90zUfPL7~S)n^Jk~fmov`=9;@0@3g_J-M2y+$Fdm@pl*Yx_wav4g#J&YXYhS!)T|utrxs98pc_Mr7(Rh_n&5(`N8QN z_Ns(BXJ<5Ik)0|1_yZvWiZE}U;NNbqqabqw(Ib9QfiS1c=$>5h#b#mie3-wNLZ>A+ z#Py72AR&u`Xw&0GP*{7nfO>bs>Ie`U5L&IhK#TR~J3gSU9xu0L7 zmWfUY_XI%tN5#*4h47B^{Le{yeW+Zf9?c0?=1fgbzTD)uRg(5<@ccB2VLM`Y049ZW z!dn0~GGRy2!`>@YFAQ?A(7YI?x^ot3)8Y49Y{Hp~Hdt-N+0I8f`DyZ7#XPdBO|K|t zByiy6zbo&bceIBOVs?=~H2-S>(#*nxLV(>-i)b0VZSqA)>zQ#8-{lyY+yk^ZfjEWg zm&k7mDo9bK+mW3#H=90+aoUggjRgjHHrP8yv_1=r$!djuqEmQ&oN9K{(qiQ}gW?fm+5m0!95Ci}RDJxYWkqWDK~EkMEYb1v!0EJ2YwMYj(QHh>M8 ztP5!N;kxDcIEWsD?3oV-eHy%zb#d%fkMg!39QG4m!Ms6Pd`b8yNj}l+ORM%~zBADy7y-q_{$)RVH>apwYJjnfsVgQMExS=q&F!fPdkBpG~f+E$cAXa7|!B{({5%nv#PSSiOmWa~Pnv zMq3hNyPCF9SkWUYuuQXf>-$h8kq6C>%OArgcl$6zan6x~{hw@7uxT9L=avBnw0LHlw(ReJC zEar-CvHFTGix>*RT#;cKuwrx=(LQOBg`0Q z(sjF!lhfnhLyNW@V%qM*J>{9!PDT&mV%)dDOmxSf^elEsJQkBow5|Ag9dnyr;IvNVzaBXRwbF;k60PN9 zMKXp>$$wmrQLal-th!gLjaB5O`>!v8sR=;20?lFB%14S+fzV4Dr{Y|IZ(efD|Mg%G zs^jbjXH-~g0OZ;N|Mksxw3XL8SllyyYV7VOQ%)GM(@1=e=;J z>3Pq9l+@I54?)whfS~`{v2o(JwIn?iOxOG2I4ZtP6N)Y(+`%j(Bfn2QxKrMFEL717 z5`L=B9)l3;!&ALbgHpY#$^EVhA7sSH>43xOB)EE`tvM6nv+y7p5yJ;yY@EJZ#&@b z38c#u8M96wkOo86es0$Q>{rFatwQ3jG6Ex9W3+g?mE*JurdOo2t58neV#a*C9&c8X zU5#{_(yZpr8=uX#af(d5irrcdw{iX*vlw&!T+->Q5LzsWEhi{%uDU#Ju!`(|_v8>q zQQnp2M0e96jWZZRw0?yj)5M=V_(y{57nM)uHTVwBD3?q44aXD48js)rk+t!34LZv$ z4=n)j@td{7GfjPc{HFQX*jSR9`uZ)<@$vEbWhDsl=)qkaAI?3`(uH5!z40vKX!lj* zN7ROVP>@V&YN~p_JdVUj{V!3irvZ+@U!0x=YA0A6M^0s>pm6Upu5|7Ak@Q1Nm0=wJ&Y+1k#{&bKAw-V|Mqd@roFx0pa;i833P60 zX*rivkV*=j++vVWTrX^FG%Ad9Ws-&fDh*V#Ua+&jG&F=sCvihm?+<*j6oANi7*$x@ z4hs+WY_aZw@Go3mLQHv}!M+xT4JJIMW<Fu+G*2-cx6HenqptfM_s3>t#3z&u zNs!dT)!h5E1u^eGO=1nq&9lnrlIE9|mJBkG6sv{J%_fBjXEO8q1))*1Z*^`b%ty*o zZ+S(z{@5z9@l-~Dlu10QmJ~JU!)^K{vC>NcoqqZ`Z#4{C zAwMU$iM}M#hs_ZW!&#nAheQ6OMTO$2H1w@#gx(b%47b`Vf>JEc0gy zG*x9oD1Fwa5gQ3=Uigxgb#ss9R%Qc^)f*m?70uJAOvt2f=KFkgIIFyeT78J)fvM-X zu8SzWL8Vn_<~E8y7#BJ7B^)We3MVu5+sJRg!s%+4D&Nlvn`%1y4j6k#Qb35b5bQ*7 z?~9%KEk46`Xtb+mei`5jYjiCtVPIW`|Qq>7?t*?^TpRlHQ{yAe}Vz z&Y*h6zRgDzrOzd*2M~D&Li6)d?66n8pKBnaHgWkVt@!aXy5b8i0d(D|o!q>vp7UvW z`i*~RfVYj_7^gN$UYe2_NskJ`-3h%M%?rBAp%;fjG%|#`y+A z(vmg*y%zmsjxCGh&2b|OYq0~sEFng4Gh+i|%Th`)0j=;&ccn#4T|hOso%Z73zDb}2(uw!W4l$ph0F`MNh!%#Qgv#(<_`Vgj zld>|7LgmTc=4sxS{mXA^Q2UNDiOVpzr+jEgJwR$}f5$nfskJ_d$Fz8sA#{lRfJ;4H z)b)SFT>oAS=H}_iz5jS`g332y-_xP9DoKwAU8G0^ockZWAG}?Ca zA^b9Fh8*2IDXJ*Pz9~VMy1w~OT!%is%cg|eJvz5v;XNWS6N0 zWIA}6Qa{nPhf&|(Rfs`>%P2?-fazx|)6CNa=wD(lt8502HrdM*zui}ekD7GZc+TBd zq^1SP8&9tEq^zf3E*2noXY#Q3aE>v0Qj06k2GI2_l*aP1h9qylXP7AA2j+D0Ly|Sl z3Gp3Wa0**v ze>1uny-ZynAn<2WxGW#o{X(3;SQ74XnmoXI1~aD6`ik-HT6d5<(iq??K)Dd1o>XVQ z{g1K#?(3p#)`a4hmwv7xpT1V&i)K94#4);cvzxg7Wa0Mzc_JLj$>aQ+5j)2Q_5Vs^ zNi*rH!Ecm4Dh|C!)aqSkJUSX~X?WNp0E+Y3<%hdeql9!-aX7yp$8+?3dy`3y|71k_ zexG=M;P|L~q-1|^e&Hr*Va$G{AQhRm<=)49_zE43u*yTV4z+ z(}B*sv;O17Cp^Y=bKKq_qg%lo4?{F%A3p#1>~5e7=hJ)2x9{Z0t@nJOE34wB?%Qlh zPOP)@Z)v$a9BQc+_YbIl-SlIA{G=D*zsrH!`e88OqJJw47j~rBYhJjDXA~6`y~OQu zRJ}a5Qg)yDR$WBL9R3Xrf#GX`ZjYGEFQi&77jg6;_5TKdCT5zq+<%&|^YSWjQ3cQL zOe_Ozy_!vWDqnRPFvlyG{~Pro>4k5OT>OaHvl6n*$p0}=10;K2;VCrNfDa(=;P66R zLIOV$l+03x3qzhcXO_8N`XBu6JK}jtcabF)%mg_X3%ST+XFtSTBX-sHa1Y!d%6PNN zD0!Kf;TNz17jM3ZraNwYqRQ5KwWa~uLmm5F=`tBb&n{NKDK~#}x_iBf$b55iNBVGy zPU~$#+O_9d#ZC@p>U%m2;Em!k}FEIH@0`1Z;lM@XfdQjB9a=WAibO`aCM zOe1o!)nu}sH!3Q%>=WbTLU#VHuKdjL5ew>t-@l7q(YBlzkIR-FAAZf;VZ4(R~y$K(q$ zc$4B3t@#@Xm#+)`$FzW;l3ar)j{uK)9^5Oi6O6(|fddonj-L?#d~=CF$o3~9It@ny zGGS4f(_@LFbLI58`A_9R>yaPf!lXq(m2y&iIxoyqdS5papBsIruDS7*^OGy@ zONb`ko{GdG%uIr`+<_tO*(^Wx9n`YS;<56%{wCorBFIPMJo(9kWIPH)){S9t)1*f! zoJP#alY6LX97W4*3*tEJl6;XegIw{zOh zc#EhBV;b68ua*2hn+x|UF^^EHmp@E+NPG(j05(-V{N&=gJ?pVb$@omLx$Q=O_*;-E zAns}}Q~%eMB7}yRg5l_Qn-vmb03F_cvBL0<&%D>B&hEPEx)o(ER-TjKj8@ zrHOcKm6i=U9-akwMz9~yb#kX^H|;zr zdV>f4v75N?PffvO$Oge-dwl6yOMY44{HLRtl^!t_nxYhmON4^ougZXKH|%%ww(BbT zIJLhI4rT^zJQbzA{hpQIiKRHE$AJrFyglJv`Z)}@5;}>x&quBI3J#C2?Q$ykdz((j z*ShE;mD=hYKC>&v?rmW@@IcyheVPZUy0 zz}OAd?oIBE0r$emf7W!K570K$0|645Kme}EiNXTsd&0Fm1+&2#2qupYi$SI1k4smckXA% z$H4}4&uI>)2lQ5LYY2 zmoJZ{Ms7S(r`<+MzW(dG%Lu!~4--6-Smai>qb~(y7CHg=VnR?GMJ`%L(jc2cv%=d+ zr4rAHOLM?h%c7!-ms8ps=3R1f@nOl7TdJCJ`Goi(t5YJ~;?-1`z@rtgRFR^@4aQh3Sgn4vyNA!jFq_}; z;LAgIj6`zVvSEq`SpS845X9@~4XynLr>)~s;HCht^VN=PK!8IE;exCc$Xh(i08LjCpw4I32y?a#$G#c*8taAUdHjM)z4pN0twinyb`{k zJ>M#`M0DN9eE^B=;kPx>MSM_3qFeKUD=Tb=m_$_OS4*n+ka)E)M!_-(^p$2`IK>C|q<)a~?w_R*>(l15bgWr}9f9`;mG^1cyfaj8Xr)#c&XTJ? zjcHm)mQLEp{aGR`=TdfLAJY^*NrR~q1tUfPRl+l+)+!e{fOk)@*og3_hp+=f$d#N1 z(WW$fzciB+6l(SL_{<3P!Sc`u%GPt277u2CUjhaoy{DIcl3sbgF=2%<($e3}$fZGr zVS80Y9847Z>!Qd; z@akBBeNi50nvmqgB!&O=RvZ(J`vT1{Bt5cr=-U&4^jmgi4%ewZ*wzx}*hq4jPlj2> z!m0+V5NQc%QimDrw6%ZSTMGtG(}tn6OhLqEYS^Y{V&xKrwrYR=O&*d-DV(FCqH4nR{>7AP z_C0pz#H6C1HR-C?v4bt<1p4aUa{_le0iiquX7{(U`vf1I%8D2$)WB}p;s$aS5?OCm zmlhf}(=+B)tR!-+nl}L<9&8pyrNbvQM?UkLhd<0>BG!~<@*Cnec`@PNFvXjcE}I$i zYqTBCL-%PyG54n}&jdtiihT$yKV)Pk;1YYhaFjfC;-i@xszR z_YnIhd}uAW5_y!)Z6+rr!YDzT5;*Z^*k#{P^E3Y>8!O4g5vwG)$Y-D7{ZOS0jCLrrTp@r>TSzR^rgicaSE2g_K|PBfpNzke-X(!=3_Isnpd)hl?~ z$rQ{P-1yc_%yU!6Z!)w?@g5!PeN@0lUVqfOtsG05|Fw@xjwwee76f{3?9C*sR{}rR zoX1!6Pfr~6kg0@^z5$;Io83@nEeecOfaExrzca}c+M&l1ECIfxXf#{1v~w?#Uxx*)^XDdg;|FzBT7Nta7evv8`o zon+Scr`4)vs`XvSHLFeOEq4pQm|w(cC$F7Zt)!%ZSvEh6e`XBnz&!1O;}1UAi}1DJ+NZPX+iX{|Nne&k zZ%{g@E#@3l)pA=^;9#(9{j^%br(K2Ypk6BcPOqemYezuYoDs$fY{3vU`n7VDUarI@ z-u^iJ#;5DWa*_{W|9bm%VYl!JB`%1qCU2vEv`+7M$HI*X$?vn3L#%Ouia&F^W zfdkBK^X1ha^!y9AXSvLsrz0NmFbY4J1`G*;r}q6&g=OkDZvr9*|4=5yy!`P>6~tD} z-@oXXLRT{ED#;gPgF00)bso=#0}nsjvx6C(Lr>H!u@os^72R(+;%#v^8g_t28U#j583c}}7}=^W7$Yl;m+TLxR*jvEq2@Ix5wx?0yM zdBM0Q{J7^OX0iR$*3Z+%3fGZr>RY{%oKq1c)m&bgF0r8M)tVk59tB#ZNs03{1J}zh zke1sVj4G?jOV?FxVNn~kI;pY3q$#3U`dC8vma(OjYR)KMYO|w-5pYK}MOCgKO~^?j z@S@ou)wh{a8ihOxTvei8BzBdwyy#5TpjmYEB;3m~>nn(*$E_c$t6Lq|i>i(qx;F-y z>kzTWs=V$21xj^Q14qmLit@MwDP#bj;3Y){`x{pXKab)QS^`G7r==w&s^!|JoLpSL zWT}TS&Lp2Tu+g$qlN?E|OrZj?HhN}eWe8GCB~dtH)Zsm=z^*9=u^u`a@4=zNfikbZ z<@SgHZGVJK*Wf#-dvluV5Tm0;c|OsyDhOfmKIKp>){`EFZdmJb2p8&}Zm9Emm7^sv zhjkP*yGiO$Jniuqf z_>>6SH_#mA^0-KWx>FO_ZW#Km*8^1_D?OBS!+T6>sj>3eFVfBE7!u-n5wdm>{OY(WSI7XlSK>DAWRaOMMG3pL zZ_9$dj~dM=&e(DJlT-*6%+jUF)bUt)S6lk@mjzv15odjC3pMnXegJyMKuIZFIt!CB z$^vy=^4y3NPG=Wkpm_$3SsOH@i*Ba=KM&X5gu*(L7z&0Cc< zebDzAdnS!Q`2F7d3jOiBhsckI_A)abhVB>JM@CV|HBXL8g5o?fwzU#YmGbZBmPGH# zU#N=UNv*?~Dbz#HJ$F;1j*N4Qo{y<2EL0-Yhoc5O5}!%NW?E8I z8W|hcCewH_@*If+LGf4-sV-$(+qHISzt658g3N+J$uM^sl28ExTMASIF1NE}1U*Z; z1y?NgiB@Bzw_A9$iyNe&g!e9IITga!0YBFW7kfUNud0+26XRD1S5%4{jrP1tH*C@~ zWltcBiw{9oS{zIA5pTyQjUu7_*y@sn#}luj?4Ln<9^~`MvUoN4K=D~3^%8C$Mhne{ zrD8oqSvO(oR1}dV_7)lGJ^i61snYX+y}#D`dW?CPHSZI#fV13*QDd#)y%Ov1P;W>Ty+t<02u=Ga>`9sYVjOzEJ zZn~J4!lP$yf)x-$DF-n#+_@k6nEIc8LDR#Wb(_1Ker{R~RwA$cKErsvP&DCyd_t&f zGM1#;s+;GFZ#vnu0AeNg3EaWGZ}q$IJd7`n|I76JhvxIVtucpA>jbs09A)CpztgoZ z!rw_6As*&x0;6IDnS;l zK38m$g+au`P5!PELL_|1j!GQIy|QEhiyj(v4pAJCmqPXZCWuD&?|y-Kk`TWnw{4Z- z`6Jiw6J4SWi!957t2AWwLXel%$2$E-MYOyEp=H>0McaVDOnO_t_tre)5@1mQRIn*U zwUqvr)ehVzr=qojKm{q1PPA#hcwl_BfWEM0FL-m+kDVwP{>t?HEVKD0Hp_wEiOb9d zH@!NMT@T)FvraE8lu^eLEAsMgikYnOAKjvRy@(EEwC(XoK+dT*%tzQ!EGZHMiSs{! zVhd6tFfpFU2Lf*=Wh~ut+HG1@4+%MJ!}>#r`|xi-O6U6To@{Tl8xTcD{(jp75;P-{ zdlf%0Q~EpsxvL+-3|BVQVE1!@^U}VgCU1kahtA!|OQZU%zP&oFm$JiB4fq6^JRrAh z7!qV{icRf>q)#(ARY@;HC-?7AcN)l#^etPVFjkURqSExXYIT7rHklazaNzvgCj+cJ zYKiBGOj)8>JbzPz#cIWpyk4b`s<@!Ap*csiCv^Tr3^jF2BQ#rRCXy1^Q|cor{RCo& zc3n+15kU-6+n#eKcPRzQsR`#qKk{HD zjLm@U_>$DRfG46qGCA)CZJTj_wuy3dT&sv)amm!z&Iw#WCS+Z1I2?10Pn_Ia%qbCR zJHJMZ8RI~fkbzJ~Mk9)LcB|2Z0j?uf48WRNKv`NrxbyZUFoz{^qd*LmGQtlJ`A$j~ z2CMGUx|{d3FD!YyI^5h`41;5B;|Egl)LaZLIdM?mCLBAtFF(>m0*5@N?-MYiJ82KX?MW8%K_9w)(Ib6XaaJ7zz6 zt!ZM=nzb>Ow%qAEd14$#iP4@7b7txh!kK5LoOv^r1Qq+kmFV)Q_!C}WDB>|Taa9qbXVPawM( zACQMvE+72kA%|7s*RMnem&@laW@d9Z@U&XH%7GQZ3+$vV*D^6F=~}A=(=tO%S6%*y zpo$7kNZM4vfu<|T+PfFkdvgJ=<%za#UFE^92HN>iL=zvs@P7UNIBwKR=rjEBV!Y3G z(6C51huNI>O)VZ=Ftprp-u3lW>!GU!_0K*k170D)nV7ZbKOeF9BkU^>aZqfenPS#-WH7MwU8;1WRt4|y&OL#xZ<_R&k$#nBrHL)R71QFuqFrf9_eX>l=U zOT|F`(==r`&zJQ4FJ_iDHa2)b^8=G8H*kT<*3aqAzxgjq=afyXr(aO)RTpo9qoh&O z1IT6giQRCf%5!V3mO9p!Br8F4WnU;(of&3n@<97JW1h`IYKJ1)2Vw};e+}XrS+}e= zqNSgJwXfTxly0T!Qlt`qOk>z6s1#`-{uf=rQb6jGa@F#f%t)VtWP+_Hmq;MRMk!+` z^_HvEU;@zzE{TynpG4X)Zx(HaDs0qJz(Acgoo*JCGgbUrXH(+q*PVpy=J&U@Bc`)O z?I?9O^`IJ)&JG#veo0p6$_BPxHW`w-lC=@K?bEg}j-$6$0Vf8BQZSz5ALBUKi1F|G zfjv}UjnbmXXa5x1WjSy9<&J^7do@)@i7D&Ph57lIq$H{xDLBSgdU(Z`RWcKSt`Sh+ zal$FNO=TfaDo`}mh#rOXle{PB9#EYz`5QZdDG+Cdsy$|*8PvY*cMdIhDm^`-GI*|# zIe!{s=_ z8M7rJot!iRyv_aISJ-*wI9}#a221L(rxFRRd$Ce@iA^lKfL7HMSaV}(RZ@^QT=*+$<=R*VVw z-p?A;Vb|zbI83->u!S$6b^If-0A#vRONbC>wOIY<k=AlD28emPo4%d(X(wB=cvrBAdZS)jH-L2a!`x+Q6w5q!e0tOIKUR+aEk z4jcthn&2zh!TZ9tj=8RmNy9fCcr%)-ogdBYU&eXMxeCsm?^5E@61+6LHSpn^W#Qdw zKel=7LJsk>tz>=Lp^3H53nT>r8z&=q&#|-E;`{FIWS|^4_+%hJ@Im#Uk3t+Bh-l0w zn>r^^Kgh!r7owCR`AWtE z_)BxOCRFu&O6V89XwvJ2NzD_<$4C~gHYCgRkZtDT zCF*dP$5EN;)`qFL}NaqMKYKtX@=QGdmgHJM4^Pr#tVrmWHZhNF5e~bZ~-}n+P!3YW{ zz@ase$e$Wk2j89o8DVFc!MALI_ko9!_>#hzS}^-T!92@O*Z9+W>1!}im#o)aSWdzT zKg*(1I=B&)VV&H^^_S^tflH3A6CW!dB5eFms6`5bh`}`{f{eqzqK*UmlsAC%u;V@# z&u20H<^h%t=lW6Tv2bWU39BH^NjoxpzwU+Oa1v|g%{R1LFyHClA`U*yBrUIF@RtlQ zuX&y^p)jM}XxW4EV=+x+<-&^~|M38u0=m6K@-b__X&U%}BQb>>`#0NyT6>vC4u;QJ zdV-B-5ZM@`1=vzOn=KURCX$pV4rWdDYXt`!#|D&Wi-S}ws~C8jJJ zE5NTEUtnuYr;~?xSYW9=B<)I-jh0E!Iwe_^K4owBY~QFw+SI~tluu}Zj8(>(wqCU! zEuS^&RypkP4DxgLXr@~>?h8_Ub#szixjcrH%YX0efLq)=hN|Gjz-c~LJ$0A-FRi_c zz1jN*^-qD41^l*Y3_G{>F}QFeFjaIv5YAa-?RMd>NAgA{3A7dP*v$4B|E6qqAqz?z zmG))BVyv40m40W~2LWofXa=+)4{Teqkp9enON_On31ZTj$FviW?n}6>h>rIkY?=9n z>3eR80xobXlk)0R0_&b@<*G~=0`jls_vupa@NnB=ab3VRhzS*hhz{#wz^h)}R|xD1 zpk4^It7$&^k%wn$G12BH{eQT6>#(T0et%d&LK;DuK|n%jK{`ZILAo183F#hMxakl2_+zHYxEbxw~ z8F;zUZ&sC!?CQvqDR96&GrIeYOSrM@tgBi+9O77{7kC)CR8kKOND^MpwmonqlL6~ov3vsrM!jG zwiF@pEHAxU2FM2ncke9xyoqsQr6fNqKpY*fPO&o^YrFRQWnEVMA@s@jUB$Cs2JkOh z>|EU#o3}51pIv0o3l_RXPyV(gHizdwJDd#NEpxl(r?zdezgoTThwyC>YIEQIeEv#h z&srKes?shwfhM+-6ytTJi_M$9y-X4{<&E_+o$@hsb59a%(2olPbDq2LAp{aT;znN0 z7TzE5X;zz~^>#kG#BLuJj?vmWFSRw?E%uT0?ND+MgmzJRNcbDTlWfF{=ftvZAU?~vtO(86op(+ zftIy{y~8hdyo8qyFQ?fGB^e3AZH7fd(Hl-)uRy?<o$;N<*zt?h(zmW|&NTKFD9l|PglZ$6Nw3gBLsNRGwd zK4Zs)PRO)q;05s-1I5~Wuttlq|%l;9DJTj9fzOQFTVC7-k}IF^6%ee&so=J zjJn-*Gj@0n_B6bX*WYAF`g!;L{o^qPtVSRwdEwoAZ5b*Vno9xboA_;1;vjT+!6DPZ zcLUa9BL+_Y=ce7ZeoNS-D$Gh{<@P_&GLwgLl>m~m;!=%nAS5ppj+C~sd4>^qucf8M zGNe)O=_6@d+udq>YBeZi97tsRomw1iQxu1@yxeRP&j|SO0}P8EZV8-a3>*EOKkmoZ zP2CU8nw)<6{s#kQZoP)Oc;XxbC3SyN#y&MaAAN9e0=gWhUt&J=1g3`FTs-h0i;>9@ zzL?dx4U*@IL62fhXAg4>Hi#a>HR3|qs^tAh{ zRmYugvqL-gKa<8gp0g?A$cy({p6|dwUd0)oAQ6^YP=yFUsWk-)rvvVd?+< zG}O&v6&kwz5{SgNL$@1*_4CN#v>ZTHHy~4`h@!WNinz2S3grYAB}~zwGu*Q^{XV5ua*O?ID3cMh>t)}9O z-WD)20ASm`=rYq@0Dvp9R-W$AX!v(4{nwNE@kIkKeI)^(Qbx)=30QF!>H&9=O6Hi@ z-wpK7Pa*!v7DDwez)hK_2W;mS(+mD*4*y01Ks0_jwfFm|w6qi(=#k~(AHNe?4B5)^ zAp-Q0q(6LMSvqTIG#@W~7Xe2$-JH#%=9h0Nl#)56otBFyQX&r*{vTZpI-xvir1VJRY;y zCo*}fX^SmzDb0R#drwuB@P_U7N?yfGq}QZ#S{mK3Rc_DbWk9%hA7QyK(IU2%K70%To#OCaa_mgH3}y z(eh0c<#KHm_XCHd6qa@+gGL$@NJTpE1&i?GqMDD4@32oLjpD!ROGur>}&llX7My_R*2oI{6| zl);`h7g^G7an7#;5sIM5FzDArM#mJXmaXr>VKF1n}Nc zoj4%KD=Eq>A**3J<6#qDlpH;!uzh!MrViAIj6}8LKRaX!Ei|W7b^$xS?QX5*Icq=`~CkAaU-2pkF3 zQ|5OHySTa@3f>W9rj)`xiOoys zMspxg>Xi{GOz4D%L*8g@r1>;Q+6O(UYm1o%A7>XNMM7`H!!ce-O9xWu>r@(*gg&RK z75L`mN)R39^X5$?QLsFJC>J}Y_VoUW3 zMNyI8e@3!D->6EvEwtbiEC@}bh~eoa0BRs+q7`~IuW64}0nti;`GRg2zdq_V(E1_y zVAmp+Z9H!KEhCV3+m4S|Ej)X1l%~eMYAVU>kWbZr`dtm?Rw&&2=e;mN@I3q4{z9{+ z6k8UeNy99MU79o; zV3!oA$iNcU9-d%~N2AvH-}@s)DPcB$&i1b^3&}8tTM87hy#XIeyvPpjrp@wChowF% zCQev+L+}J^+fRpcQlG3QhZNl!ndY1xEO8u$SPfM;C2KJ*jp8bJ(KE4mFj7B+ww_Uh zcuEE9A^GS#4!=#8xH<+6r3d$+GM%&sr`A&Q>vR|xB(Gn5jtEwTi*rCb+dT2!k;g&~ z$^9+{Q;RP4o;^^1WpVpK^vL9rF57F9+IUJ22H zPLeiCj+3|zI~xbty(PyO>-8n*H^4|KmwST;DYSb*fTu{Fb#eXdmjtSZtc5@w@}Y^m zjQ#U59bQU|)WE%7r6pQq-!AoP8p@J}cZobspNLuzIVAo|*eUZe`n+5C#qeOZ??F$< zkP94~%9DmY$WIXM6>*ue5oI$N>P~T(0F^+(ZTW7Eto$t(yiCcj^==`OCtUI760)Ns z;;R4NH6coYqZlEp)b^sIQ{R~>?B4--hNg|sm`Z`iYoC<)63kIh-Lqhi91fPdoj~}6 zD4_~8n3}!ORZ4>IA_bdUf)B#U3`Z(ciD!igO;@Deh$nA3WrB2KaJyNiT$_e%Q>&@i zkf;lYS*hCG=1dvn&PMHp}aACgMU{19hfb}y0-)mw$RGg5!>Ov>=zKB z@=XunM)7~%Exc<}z(;od`OuQSo9@&Ue{MbHC2_m)dNp`{`2r^Nu{)bsij7Ud5o`n@ zxO-s~hFE6hY93^)zm04Xw0qw69~@=KEi$Fbh^_(4b-P?kY@Y}(&iQl*(YXPT2b zAVn7b69)q^hf_(8u}qI3H7HT#eN$Z?eCF;Nac8~tyz)d()M&&j%HxU8)M!b>S$=~m zU@?y4ULX)in?K%S|Gc~D7`uWxO2|tDY6U+iCx^|ThjH)o<7+-qUK+f9*TiMGG_)X@ z?D~I%O7rXL9V+NZsvA>x!Q7tbrlJ05bK9A z`@Ep}j&v0dUMS2*;s4^Vkdkm*a6b4|pT@R;mVvWWZ}r{H^4;X(vshkv2$B0E<|tBn z6X4LJfJJCOVU{sgOub4S{3oCPPmBef=#3Dt=q4r}@3*G^&o}WuN%vOvDg*w1)*HvX zZjR^AX~w`Ydei^+-GMk3B@I?e#T+?j@_yo zpsf?ZHq24_U*TK~F;h$|i0ggqXBG19j=P&fB)Tf#=66WV*w~mfG*w@yFSuD*J&k#L zKxt^I*hR4faldu_zn)B`D@#Qyk^dOhalOHV92PsIQ>RjT`l!0Xw9~{WFhuv!!>+Sr z#J%XMKnaSj?yB@?Ce@FeqW|t*AYKgFR`K){vg6RLBsW)vuq2R(A6|$FCmZ7!3dDq) z2vPQ$D0mnBSNI7%4TGj;a$EoC`(popq);Gx>{nbC{;$9LVD-oQK>$}Pid=dBU*iRG zzD(*wUU}*A>S_{zvjuPfG5OgD!l3$es3wC6)QeAP|MjpS-pADSyz=UH!xS)a zo*u2onY;vMiF}a3&Rzm7*RNGGHo-{i`v<7~Zv>ng74xIKqUJWK7*7jHxFS|+q% z)%N}l)qvOkGXSR=I$)9RF+_ zK{TQQdiDo@(yO2k-BPFcznk%&d7&J5Ic+7KYD9P?d)Z(c!^qDl6kv& zz)t0JxIX&yc9FtM9p7;!i%z2-|2zFaDRPrHZ>)Krz447l0ReU}z|HIi zqPY4-DmlKN*sc6=h57SG3zgnqdD>_^m%U%&?GsIKn_zqH`r9pCW5fXxWo^T;UyAX5iE9|GuaES9WZ`+FqsB zq00aL67ZQXH*8e#OcVD!pv&^VvJnUFOvrXY%E}3JINIIA!(t$r3->H)0L5>OyT*IXpXAZM_yf;5OW30&2pn~{azxs%w74hsnA6++M45GL$#54EFTl@ zt8ejUTT94@nGB$%hMhpN;CN^F-{;X1V^;gWM}%f_QTAdGJPV>TYyD6n^4m00PTC*j z;_8x+n2y3WO2$;{fAIS5@JL2PJ&h?%i-rC$nVj9 zMa5BzxOaT__NRfQACqp=zrO$2oLEDk@(K&-Y^N(V&deTL-=ERw0+NM6#UI0O`<=V< zM!zcUuXcx{U;SZ@w0LG$EoO8Ckud0U5g8N_)JC;v&M$5|L+w18Ciy^(l^<7~npY>c zgjd|=w9$L7q@C}-rmw)Amv9=0iAaq8zv9Vw#@BC2+1b$zXF7HD4NN6${Lv-Gbhey@ zl4J%1UlJ5f|Az`b>69MeSnm zH;!+d{aYE)J}U}4jko5(ixkkMt!(&qhZ{>pBmQ_iu7|{_t@w`{yDLvt^*!HXIK*w5 z`i6trzPobSQAYRm-M?(hRVHV4ABVGY19EZ->vRs9NX8L{SEi0qL4mw$d{G}B3eyP! z*6ol*hr0T@wciP3xM568Q4fQ7^QkpZdDB!_HC?qTDy)J{Z6?Jn`l(Y7YR)OskNUu> zIV{mLkN3BK@^@Z?8m6+fsw~hG^diM3TKHAsp8s=mQQ>HCW7pTeEKb*sUT8CFT5zbJ z3=8@A$+h7Zpdo7gG*VHoB0R{uFI_xsX@}eOkxnhsPnO`aN5w;h~ogdz!lrWG)xp{xA8`obK5mLdO0b3m`(IrlmnpC8bc` zP9ISs4+-E6I#{}Qb=CcwIAnBmHlLn+EtfZrp=$aMaK>6be_{QVx9e$w)0X*UIi6d_ zVz8RGZ4@`%97XR=0SoT=ae9)d=vXj)d|QNn{gO9?!~gt3GVar7)`$vKsjx-D5;Z2{ zB2??4KXt%mr0Uvo=cQrBe$>wXD-4CKg&;C3;x*m76EENOJ3o*r=M9nAILJ9%LpXPvOkhG4PfxT@*Y_n4{tc*cJuJ)-gQPQ`$^Eyq`Of8 z$1*=DDJ?N7#gBei{2b#O0`&9n{CpKQZ4zpPCX#CQk;+gq4fUza zh+kMRny6?c+#N6y_ODK|VzQJ9{DS4Va#irSZvfTJ6+HPr$90NGbF&CtBtxJYNrvgr zZcX=oU02E6iXGSde#V2LLi@mj4*v|>{ZI27u;xNRfqJ*!yzi?4p$AKvGiw1n{rCMw zOdsE{!W}>MK?dVmY^QTJE>lL}%llTNJ@)l-)of!27WzkDt9mQSu27de*BB?2Eo8MW zzt^eY+nZ!FngMjGQfTt5wc}GwVXtGVZ>^d&;xb8yB%H}Ngg9kv%&D(-h4P!t9=jNvuj!dd z3UYGDOh;A-gSflrSX|Acv7B8FskJH$2?9hzDq;IG0p<9vDOKGW$8`IF9xi|Kg_kyh zIHtlu=)8mNgV#)rcxBU7(sCWNR-XH^76*8P+(+MK{*7Yq3yOUk&XiGgj6Wl*wISy7 z?^Ag~t;&?FSd12)z%%j?19)Z$fMM?BV)&0A8srq~g_r;hJ(XG*pxz$F!;zomlBJcN z62O1OR;NtH#`Ah0Uwnl~RG)hyFIELl8|hw8qCIn1;bFsxJjfmrsNU~EqU)W4r%PvN zv^75C(MLRbVHP~61LBUCwy1_yA+w=xFF)#+C4VUHD^adnI-luPz*vT5u_8D-zNXYB?2R&P!`Nd85_V*W$w$^iii^b!t8#rK7 z8D}m-Us34);6h@VmRoWL=__sJ-5i}CLB`*fb1Sv0&3@od5SB8KevxnhrMB)p%wCAv z5HbocEtP9Rev}fFy5RI)=_&1v9=Ym^KRPbantl^yzL>d)E2pvbA_hgr`Va5$?;(Ye zk?^CuPV4;9s-A^MIwnyOCMcT{)Jf?P{w`h$hJwvx9qbb`QA9!yo%3pHsQ2k#%(nu^ z1b)I*=tEfC!Vll3$!P7nU+J+)+PbSPhMPYN8t-ujFyguRm7wtKJTCBER&~m(i0l<| zHoeQUvk?;PhWvz7#NQSQLfX(cq0ZJm~3}s{Z0JW#^ zc-+4sL~wCAr-HwK2So>alnA}Y(>3)Tu)4%WNB3&T(B>=lM{=H?JfdQvD<`5OOH+}x zg!Y&W?LhuziP4~4rW0Fg!e2`sSHzaU8yXq1;{RtETC*oQlV>h|+S1If!_(a#BEoI! zKwHNg2@&s#DKTzg@%*1+KJ>`xM+IA!7X=OxT@e5FD^8Gtswo3TS2f5ghM}>Ui$dwA zd1G!~9&T;v!07DbSK9k@3oXu=QPD2pHr4n*X`eyftt9sej9N+9ryrcZ|0HyWArP^(oqO#;cxhw<<&zaNQ zHMg#m=JKQI$Dij9#6{$axp_1aXqfiYrHS({_EkV4A&$yn+o0xory_vE1R`ZV& z+jJ2=Pul(x3)`>abZeu`a z>*%PUsv3WWfo%BktmD)_Yp;QG{hFPsuo^o}?T6yHmt8J)EuYoFcd zCi3fefxX-yqSu|JkE^8XIP_(;LigPGAS4kbdL2bNzGU@Gl|PIOOeuQ18MrgIVCkA< zv9ZI_=jwFi4oYt+M9C@DLHcLe?-Ca}21OKw~Cs%O7) zJ&uMJoYk1h^OC%(23${X+J6bUA&tOf2Hy`3?c@#FKNY18}d-9YSJ9dPHr z@6c*J%Jd*uT0lS`2Z+o8&xSd%ff%vm2sZWBz2}3TnO*sa{ntJUY{T^)Pso)%I#%n~ zTIJ`Jlk_`DUFCaBOlUF9Onr)5V$bWkx5DvCU!8kTMe426F)9A(6Y@sJ&hNM)OBNG@ z&!x+yLKcqoi_0orb%+IKy#fS;s(QF~x4P_cUO%UU@%^0Dv~&16^ewn$#|2_fdWsHT z?H`iKic$isHGf6BlBg&7JS8GhXVHsB;F|d1)-SCyz7w4u&AJ_p! z+$JryO12R4snFT3ob@py?E=*+gVC{ zLt#Ifm8u~s)L%$*s`K7@wx8;9b-C;EgmY~61eI07>p8Z%z?vz}-s*av%T(OVhfC3V zddZl86Gt2(`1{q?k(L=+TWKYhRjuAmVv3tx({sCftgN#8nu!6gloGi~JI%bDAlsGk zxap&QYzL*eg*oOe(za8mdgN!OH6U7%B|R;GPx!U}=K?atqeGJi;CLn7aw!wC8(0o7 zOnqqbeJh;==XEqy+4K4V!Ya+`JkGkjYJ5qr0HqV6wt=|}+tz?mhn4Gn1vSUq+j7*d zuMtGZ{X3`j$}OqeZl6=Z!cp0dtqZ!H^G3op)Bkjpk@09_(Xl_{>%`p3;dbxKe6XaO z+_ZGGn0TsQRm`rqw5+%^C*5oY2`v_U5d`f^q|ApZJ`Drho+08f{rx*VX7k8ed6BPApx#1ccAZk#z# z86Uh@Wv9qAG9FY|=uzj1{&|21o*r<9YizNQl~l%ggwy*CvDJ8Ex}eyb@gZLfl+=DGl%JnZ*v^OZ_S&N^Q!KopaD2vRh28tAyQS>=P+Gi5eW-Aa zJ%2;z^&^kWy{Lzn6FDXOP?uA-dgsk;jERS2c`Mspp8xXD%qx0>g5lz1Wu$3`peOKKEh-3Pp zeeyso=~UleZ==-pj2^TmdStxwEO2WzK7uS9H7z=o+7tO;fU@x)_Kb|rN8fhb!^3kK zWjN^V=eHt>gN^0>J)us9~urkC~NGUGu#KU%Bg#%qa@PF5J&9F_1S7C;_+yW2>W z(qzv40lP_L?C$l<^*T|=Z`Sg|*CVp8ojPwESM@yT?M8V)-it=$K9}OaH7yW$rxE5d zAmovM5gV<3@eONRf>LGv{5*H7WW4xxu>Odf{jK9roJhm9Us;0B{v|i-)~&19m8Sr4 z2&w2)BrE`O|FUsVew(2}k>RB%&Fz_2kC;sHpW}*ct}PK%W%%dX%14hGnwi=^?2MsX z!M`syR&~EmYFRYZfru~K#9i^#Pnvhf3=4_LG6lozE_=SyR;h+X$=txRLh}2>)||V| ze;u?PE+sB~@tc<&JBQ9XSB!^j4_Tiq>n$1QcYQ7DFRoHvxRgY;6D6I$yWyR19^cMn z$EEx=RNt(pzxM9#n`B#?t5AdEa-^bgUaJPof>f4SeX;!oIUX~e_B^^X1mws$y#?PB zamR(P9eE!+&vOaoG!!a__LvCsyZ(L*#7BZMc;G#gK0ess&p)SsdG)Zrl|LbB37E&; z3||wi1ykJn1I`7P6VZ^JbL333e-qt9xAP|F{Y>4Jy=c{ya`1fz1MQeClbNtfj_G{l zPl^x@9dn&y&Nz=vWZ~`>`0j*XZC^Pl27@n1QqgUKEvIkfz45myJVj9I-s^et(Kfob^9=MGLz9ov3#_ht;%+fK8d* zErv5FfzWjo%yJFAFB5`cPMi zzDr%IR<5HzpyIoW-B^4{!&=+%qeCg}JiLW_JZQq$@FeQ|7P8#=L|OZzi!nPj*vIR+ z+VaRJE1}Ma;W!mxdZL~@^^jo35U9C?KD7iiuZDdO@T!jQD!A3w(aOmYW{{9jH){8n zm@;jqBMR5k{CggRk;8st!M44(Us_@tuR9XK9NXZ46w$f<8(97;mB%_fY4}wGVS3e= z3UQ#oe79#5ljJ#_tz_*Ii`M(UU;BHpytaR*c=79VxQSb+Jv%42f(;<)UP%&HYFme% zSLd%Hs!1NV-j44=@^l5UoFv%pDgX%kAo~jIowyv!QJ0Ag1?N2o$91SfhL|(9bPzjVoo{5_`+79M)A$-tE(!0w_g;UX1 zWdfX5{eKjt0t$Gy^tx-Hl~3u$S!nlKKEV8IJY4%19H1QsL(w>~;}&uJPDU&qoy>bL z&W?0F0DLDwe$mU~)^vU9Z6gmt0X*DISBor69Z2OGVPpKYrnO&h~Mn`Ug`IXhh4@mCcC8|JjDf$ zG9uqp;lE3_LzOH~hk4%azQcrDN}lKbihR>J9pKWwl+CsH?xKydkd4o4GDJ*E)S$|0 z$aD6Xly5b)t|mEvUuBxm(fEZ^<;!@>LO?j;9c*!~V$e*&vJR2#j*sBqaBRB%mWGhm z#3AVIonlDa{&>JrTb}M~{%ahv(Veiu&&htiTlZs0!EzQ<8CQSMXc0T0b{W5#G_l#v zbokBfSKHR$3-K}jL0=wfWf0x7r5?Uz44#euSGoXvC5R>{a+uB-e4lxBHN2)1|MGIBnOG+XZQv$nIF2tFM5iGfl{ z^tQCNnleU_rgvi*=1?1&&V&?Y`QxRVF2!ekrl&9R0FP^`g5g;=!p?=HU20T>Y;pPg zB+{w_HWQ6*`JIhqRw{e&DK5myww0;8?WbS~nDg0ha{-(+@8_$EIgiCmA=v3z%aQrv z@%g!}roGICH1&o@>znk#)6PU}aT)S6+ab)PJvI9XWItOrtP;6p=Gr_uuMv+V+*h2- zPz*D0y6DpRU}*5wxTmYg<@ z|Ia+y6wGPWO*O*G-3B7GsLhP^b115jlK~W{kipp0@oa544nnYdgalx%Z>|u;0?aRs z_njpd4>fsMpnP9cy4AKHtG|F`swJyms)>MgYKM&Z+AHNY2v;HTA=iBB3xODjqYmgg zo_?lrJ4SNZDE<6H`?igRi-`3XyzqsiZxQ4bCQ^^PYq~VT&FK%eAgi5`}(eZP5b0@Sy@k> zns~{Ob)mrmS$l$xDoUrMDL_} z^>tRoGgszbF_SCE3%MdTb^Mh3HEQ@D=REaPRd!_ziaKPn4ZNa++ zQ9(nA-mRWG-gC=ih7(*qIN`ZT|I_(DpYpPvEzg>H9|=Qk(@*-W*X(=6`E99~Yj&oz zy!g?9UDtve&&VWomjD>3X6#q2^%E~O6K$gSD)*bZ$)htT~{VU&&}g<;H}?&p zx4S_4U7{jK`G9xRxMFx_I&!i$U)a5%0(yLrkb;~(=;V&a7tAVt?$TJ=b^2bO0QahDqSFwJ-q= zmQb0re10~Hf9WwLMyxFjy8vzljO;MY+|`s-z&Gp#ffq4rdkniYGFbje0GTUyI|lcI zC~AQH-A2PaOQncyKcXM<*3~}hLs%qan0)=kc;q?aboJyHtD+I^sRi{z?<}>a)v(a> zk7J=WaN)FLGc%ea@hrzs8%Mw4kjroaHXW)T1%%VJ#?eOxtcUL{u>XKQO688cE_db+ zI#dgqD|o_xL#h3PnH#Zaaij(G zpQZ5vSQzhaGSdXpP)xHs&m`HF$PVoVw#6RFv=hgqTK^i-qq1#Fy9GafPYps0T$@3C zR_nuMfC^sf+}D((CknF~bqT`vIvb{~SxWAN*`=`fzo-dP*b6(vKNlNCx-(M5uFi~l zyLp^#gMo@#A#FDvI0S=2qFYo{v~DYPTStVcbnLyS@@{x=;4Fv2>+EzBg#6S^$!`0X z+y?x_hqU9@Oz*&<)d>zge9T7GWd^KvpG@}%Jg$RO_~P(s4`YHSov1h{Ka$h?H0$4G z)ib0fx1{H#fYsiv zNNAFqw+~-UJr|6%lBDCB%_=DIRF<&o8yxSR)GRz0CP2QX+VL}68{)nMufAUM%QeYJ zV^9ve()-dM+7S+vJ?VZ$MXMX=#5|=Zn{aG|6ILyk$^C$c2X=IjVB9cr1&u~?rYXC3 zDYM$KSFy|5`Y_XcqtOifo7?cqlfww)pOA$_2gds2y%#XDmepUKc3?J33ynRD4h7K_ zmf@z@g_#P@?89hM1~1|syYkQlShoDE%S*6r_oTVVe_8y)3pZxV)j?{$?Cyn>@y8gm zZ>F2$0kzWIM;1uYxog`Ts*JRySy@2A82a1#0e+d)ur*e_Qmj9>{_&0;RlJp$NvaE9 znw~`b4~aumUpQsAwVZ5Rq9V7v8y)@>v5;jm2`m57e+Fz3`bUn6ETn`G{-v_AG;A5} z-GiNSHDs?6jt`0_24D)$RQV3H1#=g-|2A!OJ%tub*!CKz;uxf2hb#L7aDX8japt)_ zOnHFR2KPLG9`NhjAK;{X5jWEdt?{s~(?{}Y2qlcVJd2r%?xJcw#pBJopO1FyXQcpE z1Bm#(dmB|hz~V-V(%c`$YgPZCbU4Vj8x{!j12Aa4}+Blz(ZYZQuiu1G^N!!8Dg zcR;N7P#MMyIFErJ#|@&$-ff1{*2dIF=bOJ+v%fKeURet;C|wL&T~>FT0Ew#i`qsua zUqNK|_QYBJmz&eaf)_>Os}sYVlH1ao_J**0 z#OwvrZ&~rJK;BxTc>?UrirpRAp91Ehgwy-OZfyLf&}CnOK!V2BH~ zL%1|mR_cW9mfD3Z4IT_pLLnY#*2Kq-!Ix&x$VZBs!uDyYS732C!Q%(!*Uxyk8ETtTY%{uMf=RBpKjnxyDwvM+hdSVTmnnGJyF zV%426AH^+z)C8QC{A<1FKXgNeKahQwAAossPX~0K_gkHs24C8vm-vix`LQDKy&Cwj zBsr$+$w$*v2TueL@5PT-^>WR?$7IN^ix}8$0=hG@vwp!ja~{I8N$<>;y8FI^7*`@0 z{w1IE{x22iDt0OVFn4!AL*kqeT)D*}GAl-_(R_l1=H5qU00fy6D_>p$6k2|kF%COI5~TyO?ztA_P9hG!fsa3l$-e5OgsRL2{)={@C^ zw~|Ut3>vT+ydDCxTTsES?5r>fi5l<%3KyIO-@4RXI+a&*RxhMp_q26g+0>!$#}AYj zH4XbvAuf(Z(+)AYPg`iCN$gY0A+*ZvyatXMus}rbSNhtcTPqi8(vWR=Z8}OZD zeEBf#hdKnSUytCR%#_e)(su^Q_fIG0Omxf#F7N2bgAw>?kVtgs61v!_FqwyOJsLnD zSUn8--E()-t5fcW=3GGKe%P+iWFTUiU(Tk958r+N{6_M^h|K?bn-X;v(1{m4J-xG! zq?V-KKCiml_^{`DM6h%+nXdLi=;da_6Xg#bccUpI(;yg507TO}+NoqkSk}Lj!OM$M zXf>veF=Sg7=rs+WkEbaLL~+eGNE;FE7mvzKGNxWYE>(t8}#w z{DBa0ysBxS|MpQruX7v;MNb>Yw#=2f6$59QChfdCv4EnIOy66h_Irtu!tLLAfRFhWfvVxllt$RPugIFnG$cBYA4#Sch>GmWh+?sGYuTMecO|_4NIz6SmcPEOjtfXY_ ze3r|mU2o3=(90#Kt!2+5xZJC{N_Dk!cZBv8zV+U_cX#?mR$5DHWFF4%`(o@6AtgfW zRbb)^LEjhXxE%6M2Zru{JKb8(dj`Mr(f&K~9A0^L@~_DzGgLlyGJwMEZ+8F!u>IFc zVfbX6G`U)<1dE74ED)&>4=rhcY5&QrRfSnNKL|EIJwxY9jl^3E6#gm@)w|)zQZ9D2 z2Sg1N)XlRfYNyNfgVDN`p#vMrSkHm9Ewsk?CNY0(j3jL1b!ZJBDtvY2ec_v*E}@#* za(#p}9CiCn>-eV;U94}Ay7Vn?)r`{rG%}@TGs|G%wyOYm*V#dT4#RDw-}Xg=#0u|J z3YO8WVk;(f_cl&W%pJuG8sn`l-Zw3`&J7$zlSMmil}awG%*Hw-nFR4pnj25fQ$TV2 zoxpzwoEs?ab7uE}u64{%9!ElBCXAPV{UOvXCnv}3=dQQt_|jx3y_iRCQM)E_9fP|4 zm7+jiFRypXc?nB`BGke46AeV1RN=)N9(9JOsAG~?SwO-f(zdFTCTXL0TMg(r7IFi+ z^2{!|P(5Kf7@+Cy#w^`&s^WONKdGAIVlKIaD$w;dSEKraVr#T9-)kV|eB+o2Qln#* zKTUhvnSC+GICu%`H0zH|inxJGZU3`~cO9iu?TEw|L&ER;*3$^y-N>59fWQG)H?(6u zAxaP1VJ%+++kx(0)8fJD)F^4Btkd;{vyBYycog7=M$H%_x5j6;*o;3^M7!!NOd2T% zXiJ|eI5r$Iui~!tH&MU=iN3s#Z=OeY9iHbsStib&2K=c4lgf0>hJF<|wQ}1DQvfKv z{?{RV=Ca)KRN(yN*atQfe>X+9k@^fuHS4*K8%HmS-TK_0GuUo= zJTY;NYQRbW*7;2Jhh7jkc6P;SX4QROT}$ngnsC_IkGBhu?w9NwWL1CFmIcpFml^rq zC0H|+P@=P+#L#+#D+whpI#6cpd?>A%MMt|&6eEqf8?*S}F|oYv)m_^z+o;EMfcfl! z(%*i22xIm3L7GYty1kUZbrM8ntqOpnyR^P0?e_COA}_QjZ>RGPds{S+J9p@@xal#Y zoxWH(*U0JP5%(fl_9>m5sw$6oso(PKXkZvDS?ez#Ml;pikfVi`?C=z7kU_c0|)Pu?Ssr}Sw?4_9*8yA_bM4StmHH>4J;0i+!CoqY-%4febXM>w_0~ffYCH$x zj8f-+0MGnnX#d!AWM3C1P`JS9KNUlSv40~v?5YV9eEPNIKqIVqobgabx`_l2|2Uy4 zIphcKB@a3<1%o<8i!5W_NTtYR!9&c5ynjz6q?=D-TSu52iXtl-olW}|0nC|s=~}Vh zxWW%2kc|2ARvi+PLrE=j3tCiJ{?p#Q`FHfwn!<_bTfIm7xm0@;kAw1N+J4Zrfz3gA zevAV0+65&T$0?g@n9;{t8&q;&MeTBnI#rH~Isj{`xD{UWlMe@wWe=wkPRY{Z6F-y6 z?mcgGdxDsX9a8Q51VKMq7nF)Vyg4RGcGL?tVr&0(@kP5v%_|Z~IYWQi@uPc~vYJ26 zkJz6U5bq+dyk;8w_7dL<6uzWjqZ^Q;;poun9XUTC*gEV}lG2jN<0zOq$tOr(*bFn% zfEQp>PTnsC)FH^&ZkAuoY;|k#xwnio{2}$-_>=zml#&TfCT-dm8Wm;XUTOStN)xb~ zBhc|l+{P_BNHbkz&m-(HmV4rEv~!F0M;jK!6De__Kz4p>&UHRz>S>3Yu?3a+`QO2% z@wF%rBsOp#SSUff9n~BxaF*xXI)@VIVQPFk88GfP0WHm=tV*A_mM;-Nr!=_m3{n-hh*}8|2o}ccaHaI7{ zdaZ=2+H}u@HC8M{V&E2{@vMmtB`T@R{Wm@`4Lf`_`eHzUG#%%5FKuvgRON|MidI+G z$wT~Q7)KF2iwV_YInSMBxyb(@*HptwX~MR=^fO9>r?O(WYwQs*NPINiyK7hC+2N1L zmzNjONpcbASVwk-1kN+gTVE`E?K&934X#F3oRG%af^_?Fx%@;;S~85Js!VyqR+`LE z_s4Np`RyiDtgTKihF=KDT=~q$%)Y3G@LD#)ot*}1oyz^hZg*~~0#9a;kR7K-N&{;% ze#H#Cj(RvgIapRZyUvyT_dFf$`<_vKBa)2H_O-&_(`M<56hx*-`Oqx^mtwkuar~nI zjIH5}*M6E}EB$hnh)BI^%Jz2Y2Q3C8V`MsB+;ISSPt*{R*UbDNdpUF%HZD9*@kxq@ zVG1R^{T%e$8rnZ@HTpQFJG<X~w=WR@xz>JkIRN%!gatT+?l8xvvel5IOj zxrxy_)}{v;S01<9I*uPdC zjPymv?TL6&upzQ!7LuaHv+-AN9nh8Wd7Tya?HR*G<=YvweOOACdhHjbLng)0%3v|N zTi=Vx)=u5_&fo+RgY<7C9v2B!dES+`4~FZ`pqcqg=iFjztDp=CKfHHb5})RAIuWsY z0pTApGvrmZjG1{TYbx_EHl{(ZWX1}XcAJmNJR;jtirDzyP%&SBo*$hIHRJtC0o9=9 zSGlh|Yxyg8$M~X7nOzklzF(>$v12k?YB# z!2|GQeLG78=Dzu$`uxS@uB`3@gbo9hHXMaiXvnQW z37af=QHA2`K>g0BeJ^hh*X+Ji-Z=B@p;gyTq=)NmRkQMg%)&Uk+9gpjk4UcL)TF5OjMJf-S5a_p40Ev5{FNPc{a0XfcnC+zl~ zSkPW1VvI#;^bE>#G>&urWbHV|L+8F=z+pNrPc!DpS~#lR@do41u;AKJ<-T=PlDWG6 zgXOFE&K`WWz=LryRL`O5>w`QF-m;MbTE2fyWE17@yqmvu5BD>N^wbPKnTe~m8~V+h zrqlQF9OrSUM-bYU9;H{^;MRC?kSyIO`R=B9lxJpZ9sazNhMZ{^?|D&6U2G%@yPiGu zI1~^2QLsxgdx`10Igfao~C$N_W>7-8DL%`TIZbdBx5--}v13 zbrn-7>ab}Y1aYhdQj3SHIbj%Dx?@sbu?0NLI)2C!`_^52!{wyTYkY&$IXS-Iu~9#W z{2ah$`?dA>7}O3rkf(Gpg;Do>-CMO=h(Eg9SFa1TXVivImU`5%z2(^0`J+VGw@6Le z;_Ev)HIW}s=yPA-BSbejQeYdiCr*)~7mcdVXrhvigwBi$L3^U2l1Vz+IR#B`+^coJ zqE293znQ7d=Uc$gh?(ILdCrv1uJ~8Rj(Db;(lpdUb0Od7O;V4b5!%VNs@!Fg$_eEx zL=vqFF~3AeH%WZdsJ5kDS$UlUy}jv|n;R$&he;OetDjsBGWWqqOBA#-YXkI{mbXR1 z4mb|GMHLlYbSeoI2hL8S3SG_*1D?t+NZ*u&Y8CQ4Pu4TUw78UB=~?kRTyf!kv~Am& z+Jh^}AY*tF-14mEfL=@KE8&fc?G$k%M-qwoWP92iutnKM#C_nyd;6wSTh^Z)Wc=-i zR877C&++dZF|^y^Ay<Y;vogRA=D*A@Abtw1l_`1WdS2j;+qDe(xNNGg2s$W>_TNow{L-NSl&>-WGz%e&29 zPUG7y)zvDoD?9-ZB(m5uGh~TM_Fcydrz-?#)xrrv!H~5QZ@OV?*ilI`z}Jp`xm+jX zIpExqxh>F+?K_gPs`|L;>a~D7P-A+Hn`Tmu^THR*^1|#A&ts&z^!%m3{p?kdCnCY(Yw=5mXV1HWq9&G>}%3=6K84L3(h9(uD$)&XPyYB%i|MIDQAc6^jX-5 zxsV~7>C;RSG3NJ~eniq4%^tTju0>y+T?GbSvI$JL5mXuf3}Fbk_m#0SifC*{ifM(L z^q_G7bdHRW4@&EZ>Dy&c3XAMA9jTBYNQ;TNk6vn z{_m}`g(Ydg{hmWw>xpq2vYtQRas{;)I`MG(kS+Jy>*d3$!zH{3WyJBi{vxuV7CnP< zN17q-1OhH5T^aSOUz}N2^g)gS`5g^RLO#=pIU7kfB~{b^N=+|br~-R+Za70rNmP6` zE}Yj`Qf-IJv}re4O*IZZ3>EQ9O~0d>SId_*I%We^?Gd7Ed{^ddv%Up@$D{OY ziNlm5_)0)_$cP_&h;h%ZC-8A#1`fH0TqPDdT&>@CK+7I?Cz=Z9!;1s2My}kCh_8-$ z`TQP>8IBKC17Gn9egXs>2OdNGT~C@jS}~OI1Myb^@ve?n+9!|+xSE{7hj%~TF}aByZ+Z2*(>$yQPn+F>9&kbRRnXgIPMXKdOqwp8Rf9W2eI4h3a=Sbu~_;_?Yo(dJ4)u2W4*=M+b8W0pNWnh*R%5$ry|fg9t8vH zkvMn8!tt3R;d_r)PA;B@?01)!Dr+F|TdqMDK$ni#E&ZVXqd4u+bzqP51OFN}>iu1U zWp`~o+!9QA1yW|+PBm7q#bx(qvg}{&m^`vIa6C%;Jq)p+l2j8Ta{msR?9>#0jf{+R zt4+JoAT}t-eLR(L3Ix~8Gq(sVaxaa#nk*=;!f(AekhfN(6j3R@cpW2a5eW|4ND7?u z=YIW?_7$eh2$v(M*W5>YAa6~|&GYh2mh)O=t0Qcj-c|GIzvS@S-#)SGn1W-3lBxpn zErtw^m4Ca4H^f+3&rKbE;)gj3`{7aIxy!wfsd+l7T5Q_^u*J=H^q@ZMS6Y52=+ZNZ%{S|TlkUO47S7*+f8;f#zy7BDveng<0INQyrWC)%OA6wZ zzv~2u3f9v#Anwefx^<~Ue!$DXGrc~wJf7Ejz?OH{G5HaDCQCi>%$YkuznGtPCLe9> z73|ZW-o<2Mfd)Gal?J!mic<2ZU$SXiVo{mC!#Sk^;wlj$x;52Uk>Lc|xM+B7=~&|6 zZq=UrNU*?<(D~ux`)2gx_3KwJ=ccrxB z#|t4;s%=k>`hAbbE+H?^T&W^u2%T^JnT_Vh7RTei-%#neMD^{bHQJCryY)b*SzyN> zEn%o$b59ca0KH1x=uWn;uTaC5|9}w5ivaOEL1Vf}@p!f($`UX{5uUzm{sCQ35WUyQ z=SSg-WmWG4^*8x5X_^%gQvM}QHZpH|5(|RKXcF(O~FTz!zF2=8d&6U}YA@5bm&Kwpe5OcKF&(UC4<9x+Gy1Mst?@_R-4| z2aWXgd*Y%SnOH8XTKdtY`DdO}8mtv;!P>=>3%v6yVaqn`+9v+=;Qa%y-Kecs?0Vk> zd#BPG{YVrBSm3rx(el}X@nCvvcmBn^Ic(0>^5@toL(+(8*h#CkXa2>nnKdLoyX5aG zw57KkBo&5FvT38#RE2Mhh;^IGv1$%I&grqMKhGHobZ6S^T$)|admn3%DbA}mJHO0` zL!oQrv!QbV;wi>8)O#c(rUMooJrlmI&P#SH;gl&U??%UhBdaK4NGG4<;t|JF4$QEI zx4>JvzQC=mYj#xc#f#MU0mcK*HuIsE1qIkE=6t>LcBJ|Si378t8OzO%#v4^&xy}4NYiWmr-Sq4puDjAD z2Cpn3xiEx#-|_8{AA!MQBRnzCi}#&84QwTF$GdH(HZY1s(P)?YVBRAB@}mmagOQ?5GtGG(7@ueBy_BcZ71Xi@WS0exFpIA{@vg<4V;Nv zC;>2_y9I}mptQW4=)q8&f^x(R89mi>(Sr0beJuS(aB{_ww?=~*{z~hTa{EaBW5q-k z+@D|>n}IaP^yu;yes;Zz^oE~!!KWQuS{(;s)ZSxGfXY!>r;f_X!LE634t+G2=gH_s z>*{??^D}@*bCoR0r@rgKABD8S;B}=~JOwx& z92uX0-r$yAcqHn9IrGkltUXnlpAu97j$M@YGvK9nqj41fwIUUWAf!(HePc4m{`!4T z6j2{L|CQ8%SStqpq%mInjML0fruD7B>R9}@N-=M-*RvD8g-=)Rr=Fq~-bZ6l? zLVDg5iq?eR{QVM{1@mVwiAi8+@x2y4!lbRXdt2-4xpj5VH;664)SB=TUt$zzy@*{8 zMn=nec>X;9y~;^UURotdb7e#A!Y}QSFmn9t(<=~{2YJ46+8x*`#U3}{UqdbJa1=8m zjjQk5-QC@PPc-&IX(@Zc`Bk2LS|Zv$3tCX%4wvQDciLSVNU5%eCStls<{g$LQx#Z? zzvm;-Hhy@$sn&P#8VmHIP;gT`nlA_XGk+AkNm5m{5o{t<-$=RlK4Ky_tSor(*(7kr zTxE$h3G6d~aNo;SV0^Y~rgX0M-oB%_hc_K7Tgr@%Xj;0&Iah6VX(?v9fiFYM6{~nS zL&j5w|EudMYOJdYQ+oA2LP?kh_};h~$Bl{FtR~#d@_l5xv=7R+8Z>7p(uex7P>@6H zHLmxVJWo?PlE!>jSIz1g>Y#fH?gWz%YI80bL0VtdN{sEJogLKkD8orc@#?#7I8$u% zBD;W**mG%hLw{uQY;^#xA#?c&lx+XQso)EJy4MQ5^qq4EO+*$t+EZfw_=J>iAqc!y zfDoRss7jgvNKwi2yMQ%hOBZSzwdWFJF@F{({m?UMZk1EK-G~2VU)#1Nbo_H*WJud$#qrl%e3Xy8ScyAIT}>8z58loeDeqMUo_2cmbyL3eiK zmm)XQ+k*P*f7Hg7bv#Qy@_g77n7$i2*aXxnVW8eOxpni<8bSsYlv>>;$MnA)i?erU zAEzj6Ya}~R5=tgsi8~cu0tPFffODLBsF7?Ax?QxT7_dmM?~6pOVj&+i*=1=(^(}Lb zEM1BPyBq*Pr{|cBExL4H0xs_oyY^wT`EI z>}kd%3YJraVO(VpWA5Sm`jflJ8Z)au=40xp5iRX*)@xhgTeUH}Sm|tM14c5rKofB( z_;zc%3h`xqMjFVV+;$cdjI3ZZN^jT%`Jefh7rX(eWV zmnG=>VrputrACCr#)j{|1{b>>rFpp&Y6T`$WhClbhWL)n&x2!4EuWNeJI3xOc`9hd z$nG0|Bw!-L%oTq%x<-c1lCpt9omqZpCBT&Xhu&L@X3=Is(@WnjjrrU~hTQKb1DdJ3 zDaJXGNaTorCgzKF2?CzYG!I2urcx|~n`C}k$$NwIo;>Clmk#0H|Av(%kXRZU$zyshnSvMI<= zw@B}a8)xYr4~79c5BHl`7aE?9VDC(q(HSMDiM8f=YGqI5O>dDbBaWRb^2ldS&(AekEJTU4e3oC}y^T zlO*m-eoBgWzgL5u6U$Ozjd%|F`xHxxRe+m#X*_oLkEVkLgBq)Y@u!GieLN#(jnxu4 zCL?a2(t{NR2E)*niu>f(nk*ebl#UTByqgKsOxZ75qS0`DEWc~MijgIZq)(DmnUc`E zR%unnw#pFY=Ec+R=Xp3R+(~S(p$PR9690&|Xbt|=TTM+j za`%_*V7fS|d#!C!O?Lia=-1%VRxc+dLV~}cxn|_10R^M7V~rghs-AJ51ucv}FI%_I z5WWFFreS!qGNg@aynck0%jIfQ$rD7s(@{&#TwV?+$mr0x9?eb+$%Beq0k3nt3TsL` zmX5zwz+tV#;y$w9^6m1pHvJ=pDO z)!tb6q8h(aF;ULnY~^6uZvkAD=IrQksIoQQ^LSE0LKJ>KlW}L+az4 zDdw-AdcuRW9-E%dg+Lb_8T`bm*w2XmyaTh=3R^OgslV`iZ4C5)IFf!na~-W}0BTQ} z-vjr)XCKX&jT0(+Cg3>7RtEq{3)(*0tWJE}5|A_20UOZmYdx{~Ud(#>bc7h0y7%Gu zI`xH*635O{*c7ybsE@IT%icpWMh@D-V&fDjVWR2z61Y{+^Te3e@{eoA`-9}oi@drz z0LsnA$iyTeY3vC0O=}4x6`f(6Mokt!Ml-(uoO4!U%t#_TmVX*xEuWgzlULO!za_tE zmO?w6(QmJ^BER`wlsZd)d!s~Z)PP*&T@e(k@Ws*=Yq|5 zcdxm-KiiwKFmGdDWAGkVwrl2*emqdFOW!weC#@D!J*U=Am6HUQ@~nB;YQh|qsQhWs zl(8t4DoOl4Fx^vV0n;keoV*_Guvmi6X<6j{!P9hF)$22;6DC*I$`c{kR0Hb`;^!f+qv6cal#;M z=Y@5Ei1X?bkHh(xtV6MLH~0LqR!utz?`!Y=SC>q*i-qVsKAns#0F_zzrMH@)Mx>2M z6rQ`v(!L%zt3<2MPk`4djrno^M)oAi;%Bp9dLhZrSzxRMMWM`-3f?isVu_sHmmUWi z+I4&dQ)crvTYS@R34Hud$k_XBwgf%{2;-JnTYU8eLTv=VAqA1ES~Hs-2TMOldcC;P zhjI}~si_gc!FT7YYsTw0qJMyLZ8~gX?kfR-@s*d1tA#ke?9dGrg=%Holo4`G-&-Hx z+|D%h4?st}aU>I$(gvw}`GxoA2d=pYpOhOKS(Z&@A9aoA6H=8}Jf;2N6Nlk5Tj3KG zr(g#9cRct-{peMhE$w(pD4djk>DN>Wj@asQvXkf-!R&=P-SW|AY4b&4!Y^O~Wr#Jf z;fXF%I%1@WJ6@l2E1(Z}Fk_y9CF~x;1QLwiVQt;mAVzUx*{p`ZR87k=<_7h)KxWzJ zT?%y1FBcw3;w@*COE~+2xirU;gZ`Zz42zUx&GxIR9toiL>TO#Cji%Siwc`e1*c+tT zfiFiM_c?b{Qr8gTZ440i&;OJfY8@T8Spd=p@3RHepY6P8B|k)gFWGLB;RBW0eCOvE zd9`JVzHMqxP(sR(3HaE7IhG1hLmRcQLVxs>6TiN`eqEE6x-nj=FnxevCcBZfmq=+) zGmt(9o%P^pUrlFT(u?5*f;K#K&Vvo8=+421dBIBZxKjxk@`W!a5;5jq2)@CcR|BH) zJt8#i&~Z4BpgcXp1J}-O^2Q0D1+wYzn-; z#`nUOci5?febfb8xztsaRWwUWqWVM@jfR_cn=V$a@j9^h7{2;AC&*_FhxO~7JAlqL zH-#pgaiOhBoOfFc-Ke#@s6Poq@Bwfo(ykTYD)b88WUQ`&WfoekrS_8e#Y$Oe+sI+( zV0!7{kHyLXf`JVESR1Q`+QGEDp;Izd7zmoo4zi_0C^>QYZ`~|5k=&<|yk}*3NeYC`7-~S)k2jw3-3t zduS(TQGv`;NTA~mHaE6~IA0zV$fxz`5F;NJ@8oqQH%``2;4PRto!q3&@auYSX6JM~wNNr=~K>}42xgDJ$Rl812lz(EJZ33Fvy7a9Z`s@6~gvVsU zKgKfH9Dsn{fgiT-U4Ya~HYfZL!6`G_O!Fyk$yh$2GoFE(L*q|y#om5<1oX7;;AVao zupB{>HnsAd*^V{PaK>FiWFt!Mi0`2EFQQrU9`uYmRqZ<=&S)Y}_=DOLxY{e%tx0&L z@X@HHO&*G`{b%?&wgqd_;>zM;`AqX5omYp}I13Al`~Tn$sg!*}Sqc?rgIw!!H8^m(^oEw>kz+>tWXQtrq9XpHh0lQvD64o(fp#`&PY@kh8O| z-x0{SlQccS*R`l!#MgC3T5y5m<58kwWp| z{ClrFc(BoTeiBYlTb^(B53s1YC!)bWYWWt;W!M_^{w>@sL$$_}l8DMWuAR%gM!Sd1 z8s8ShBE9I!E0rz8copAN{S{JyF_i9;rAvdD@_K^U+Z z-a|m7Eo$r&ehpWH)#8+nPQLsishCV?#ib%3nV>;-Rcd|xtGzyl(AWC5){)k)CC@pH}J(r_;TXKrb+ZjXrfMaAE#NwloY`*+>~F@ z^XA57DKjY%N5JEI5pdBo-BH&m3aAaj=85tS9dhh>>fhfs`*6e^VEu`Lm__l+TeEO|V7-OIq(|Py&i;GPqBMbWZW6k`a>qjD@YaTeDrfv8H zuSy16eB-G_n~?@Jr-Ye&RQOj+;Zi`Z*(l-!C8USA^ z$-wJflP`Lu7cxw&tfNMwjD4tISb8K&R|a2y`02#~Gahv+npl-0?B{5An4BmEl@6EI zEkwWim}#L8akl63r^hYp=XP5O$);rHqt-G)%B;AmQO8$NJ+g4Smt2#{{L9g&dbYpi zWe3WC@FgIV& zif@JZCk3z*^9eJy=9h+Y{hnoW-g5#WN`z9AMwmJej`RczuBMkqBTyzORjQTP6wM_c zO4vePr`wd>mbK`J4+PfHjG-FfnH_Jfdl5`1&^;eOC0`Q z6y1C}DQRrQu%;YdGgM?j1*7UD6jW>@7>386u}bq zLNipo(&}7JG$;dNE*VaC{dK>#PKOg<6rLL>A?i|IP zva|uV#V!X#eVcsqatrJX=zp{2WnNnOlidS!zWJ`>4Ze3+vyVNeNA3RME{f}-!Bw|I z&KnbhrCz?4oVcYq)3A5)YmproQTpLyln>Ef#?IV>VT;&WlL`^md79Gvt$f<2W6_>d z33vp;x4zNy&Fl&)Hd}J4W2^hdM^e3M%|5Oa`b=QL!kWN8c0QYXiHrojWU>dJC?%~U zlX>K88)x(&lT-I3-K!{pk$g{b*yUHSUCmv!mP@OUx-a{0UyFW1)`T1kvXx}O3TQcL zf1Yf{D48jm3xC4m$3_I~1ke}5Cqx<&)f)7S^hgj8_on1fm^!YjFy0d!hPD}@Wz_lg z&oN^>*OC`r_d1dsG+ACrO^gRqz}{}^`9ZY1pC%qCR@r>RJgE&VsuJ)PU}k1MRIS2) z>12;$TD7=9<*-l@5|>#1Y#qpRe)}dYMG_9^ezeHBdtI(7Fw{pbjCK13Xg<~dXjJW+ z=7`ImCQQ<&Km?G|jH4_>*>bIsgDH4Kut6a!?3+o#Hdn96=diF?v=_fS&t#>bLmX>o zk4K4DyN!XdG(>ct27nXLQIqqjQ)hkOo9kXSQ+L&$UG=EkYtEP=vMq zyra%5&`bbH=Hgf9t~Mg$QHxSlS!@ZRXiPz|(ASMa20HO`EdA#V5f63|)Xx`l=jA(YpxWo2 zVe0u%oKjaGeYDwIEzz%7qG&Km#%O;;x9aNX8SV`rS^<3{0HVSbxy3bjy~jLmUBEdL z6OQoO54_xVmm=7$6gSGB`P=w-_k~ScuiL6APF}d?_GBUrm1mYs-l;m4c6N3R5d)bK zMr)!xK0XG>ym$ZHLr&t=*Q~?)PBZUjH?yh7FMBM$YEf|GdJRc)d{_&=P1#1^`es+o zY;jdod3WcXPbZoF*MDzHx8sftVP4czR6OT1TQk+;$)c~j+@=~In=6ddY1nI>I=U&c z0tkC!F~n2J?=_Q%Qh$#?8(|4~IN#BnZMGx5I24YxU>MG+;?Fs#4{#T2{peC&QzDdQ z{-jl}Py}i}KM^fQWxZBbSt_R|+suxpf35-ht*qqo<`veiqpc`J6!XP1%=61a5nU-F z*bnf1zwft;(>!ZZbRN9j%v7Do{!@j?p;BpMb@m(Dw{>;(aKk;psfWYq1NV4uZ3BZS zJzFLg7AZ$|j44lAeg;y(>+^4Cc1N5`mgC)(KfGHU2S!-Falr6Xg;J0|4)vLecIqN5 zgDB7ko}KBY_j90dCw&RD@@j#bu?=Te0oWyXA0;E9+8O3aztfR}rMn!kXZhCVB3YwL zk+(NKNT??zLy4)ewj9;se!$*^O?pB@&4i^Y2sN6_BOiE5rSgoK`p$+3=j+RNfS0zp zah5zp8XKWYe8{~YmI51WrL78JHpAlD*MaGWiFGh<_M=2XBNQ-v8u?BCDt$S(jbtJS z=0ZtY%*?aD{PQ$cF>VUx(j%}cj{T%pz$d^qn=d+OH{xabg@bNyGF10_UcFG!Z!ix3 ziW{wC+XcnJ+tikrzibNmhYH@8OP+hs$MrghVvU70G{1vXl-aB~X2F~1PC-IP0{$+I4pj5|H}}#u{a>$sDq-ilw`~WlptU3M z2NPY5HFcC%0>9-G-u(sXtdj}KF5xqWPMRbQy5kXBsU}$Q9hur;vxp#mOL<-1hT}%d ze<>xm!BuqH#4{dc@^~y>1EI$+1e@tKAF3?s&BRz=X7?f+Aq4bUTFsw;U%{-;wX#5H zz08jbXx1n9M|WfgS?E_G{EK0Ny<$}M@2HjeUuCqkow&8EYp5wkIk@E(#;|8IVY~+t z6RT>$z%;uLQjC?Xxwe@%!MVe$HAUQtFP)ij0=m=~PK8vA#DLNYygvVKa)OR3ch)p z8S}&4$?va;1_REHIPAtE{nlGO@%L$`_kOybDc%b-?=5yh(ypwqZ&6Ck;CRgjU-D?U z$bMuqb*{igk*blXGoZK6DPW%o@&LxK=tZsFg)@KEc5GkVHX4ug_%o^s!J%fYDho#7 zSQo=eQ_dWSnSicWj!8wChqs9;M=)49n<7Un7e}wYa@eeulirJgU=?FIE1<5?GgrDk zVosEq#QIkAKxYg6Mr)y7CyWqhhtuZpYmt1!z{{!;)FsIHLNww#n=U6l3LGa#2au6h zj3J>G*rUdEpjbBCX4=$nP^}V*kQ0M6Y?tQgmoZkAsPWmc-Uge zR@Ng~ea)M4?gs_nROZQ=jX!^frh=chN^#=>46_jeV~T9NB#GSHKjr!z3!mhO_Ov-R zO_>z8h&NPd8u0=t_3ER(^j&4-npM7!Q_dN~G-bDFw&n!$6GPPiWg?eU&+NkL1)2{^5m?`Ez7qOZ?b!A-HqY zE)MZ@bA7|?`m|7Yz%j9il$^GBA-$l&LS~*MjxL8r!wA8COweT=ZLuxi z?j~E;?i4Bt+Y@uKX_ezloig-S`nFl+O$Sa{$_NmDFv9Mz4YzD-=Isc%+^Bjq3x7H6 zx2!8%@d6bFP7A<+u z^6Tki5x#*DD+f66q6H^dzdi=v{VB#3Qj>%B7eA$I|Du5VDmp;G4JX}XF=8Hp|Yd3U`f%kLw1lA%<^Y7XT#|AiE(Jn}j(xDYUS{DqEoJG=2C3%IV@?l+8~l$cJ@b6b62xGO80ZBicN2>9iTlWGUC;)9Mz-t^ z7;1|XWF6?Hwlc702bMplpp`C6?b_wKh~HZ-oe`J)N7-T-Hr^3&Bm z=KWb88JaTc22@TCdh73RN;2C!te3?&D^=>U=HVO^kn~?AG?tbU98fu+QL|*^f@qRO zzkt{p4eDzg@D9f0s`UsDHr`I16v&JS$uc?o9AXzmmzEAPDVp#d~n-| zO?~A+LGY1w-_MTb?bFhI4@7+t2x#Ui!s(H{&eet|Di7R;Yav6}5w>Rb7Pi8oyLBbX zxk|}q9+?Fn8=bpE7Jr|}l^fO=deTsRfJ(VS=Sy zWgM6Nc(>)Xa=RQ+oaKWRcoh*CiE>u6>btcIcc!Ur{Iwb4OZA!iZSz}2lNVHF&t-f$ z?YRbC^spCS{ML_NR_%C?Y(gH|xg5;9r***J8+PQq_NBR{|HV?(yrlxnsQuwySNjc#{c-?S>%~-ALxWI9-7{Hw%Rd~9&#aRRzIE!c?2sp> zr9%>K&ktk#O-bSnd<~? zf?ic0`?=&eEg&#T(ACPWI39&mPmZv2r#`Z=lh0|?;qZru>VM8xPEAbDhuLtjv#WbE zGSG)|@z~w+EnzceU2xXcroRoV*ZOJ3A?VRv0FVp$zO3s*qTp_C>sOsbN($Rk9J)(8 z{fK~Ccm)o2B>8BV>)Ph{8>7TF(BEr z&xZ0pGUY#qTJked-|cY~mspcWrFUO+CFy1l6fED3T%Sb!_{5yIYZgZ6^FF*un`6YVR0VHuy@_E%!mUOrhyXJWWYNZOL=vWUea-O@^XHn|fgfZY;>ubVR-{ zsI&FhcF}o5stI9MKlYm6%qNkxD`UR3y1M0cKowb zz)vjt?pn9nnS4__)dD%6yp4&>zdq;skU1L#qrSrBJ6Ztc$N4kI6?FX@@F~$SzE60( z9kjZi>8yZ5oE zeeO=i<&R%Y13a8I=$_>hFrd#HG98gp3ctJ&h$#Z6}^>8ozuqZ66CSn~@rRfjAu zA`%flHgex|JP~tW(jxtUs++fGsHAaAN)|OX(!|BZp`1rF4GzBK2953Ir~LsR_<3n( zX})E3X^EP!$*K+abPM%ZD>U7`?Qpl~q@* zT71YFn|u=;h$!UK^20eW{eJ!%j4< zG*6&efnb)YeK4z~_||JHQZQ2_;IP^}*c`2JqNm%Rkf z1&a9mI3Aj1Mu+^E10%4oQfhv<{%%rINv;SrNy0Z^jZK?ZX>9wv^={4{r!w!_A z1tjWX2QPBfo%^m{l=Z1&0k6MMvZrvM4GK%~x)dgU!TT@M3 z3e@(r(Nj7r)qj{tO7pwLiS@Oa9(Q4arD0e$`%!J`ptM0Z6F?m|DOxsWRZ?82MOaUs zc6kOZ9qW&oYkrB*Pon`iwV zwb)W7WS(;H0GY!v3VM)0k*P>+!OS&Y@Mo;XZLf%d8!gI!T=`$N@)zgK`TF%-)@jQd43T;F8XH*;;4VjedFMQ|3%j#s*JQ4`YVu z;oY8JyV|U5Ha$Nwc%1nhx}zW*;0vcGuA3uL-rndU0E@vr&68niW0kCnwEWaxanHWd zqULHOX3VbbN+^(Pou|j@_KC%8gN1N|{aiG}7jIR`KZK;&epdiA@svNCB z#oOc#smLCIV}G?dt*6P>zGGu!(H9M_Hg*njIuXAm3Dt>6Zq(I{gHh#ztFLX&Oz8vg zj~fZ0zm4igiTBZZ%{>V5UI3Sm@NFbx%~N;Q$ne7IBMU?!lQri;6Dl(OR)tGNu_iKF zdh7l_{r((epfDatbD04@E_*n4xge=Adn245MvuAIB4X}AFr}|>`jhNRLC?0my*vW zf~8xFS(6sa!b1Io(Uy;TF3jSdzG-86!5N|4hrT*)8X_fonHjXzUEf*gG? zACG@_bgeiFMfpB{=CyS_b-5`P@2ibCb4KNOyA<&Qu*L5#8jnL@4YV0*Vd>z2`C1n` zvGZJf_)qIBb&je1rMGhEVQi`Ryso6C9uDY+U@eW&eBX-hOl;q3DuYIQc~2-tqpi$( zD)H+6vh{H~1K!&_W)o@*gSXntx)G^?NF%>XVQ~rnav~Pe9&(Zd5!mack5$Dn4}y~TTkrx3oX+xg^ECXk8?h%9;bi@TEF`)QC;3Z zJlm8i$*@)$4hNrSBaU<74V|XB{|QBkgaDXXh|ex_n=*|c z68`PNWd3^CEVWc5QWRrnD-_-7s;ulBqBe*)YhLW-q75CxEF$QyR0EKrHntW5s7&Yu zmaxaZfJ&xN$V74TWPWL>9wk`CQi7D2B(Iv$5H)*TeD3SX|(l+L!jSmeShVkb2JWhBX&RsK05k!%fL@t2x{FX zyh%9F$vnM>>%M^azg=>>q%<2rcg*_ z`QFwiK;puZijvOqe$>Wdz55F&uNLyMVv7QU~!R`+>V5;j(y=+csn zfbR>`Hos4iqy1avLL*{3f!4;+R_nUnBsql6kQpSzM14X~=BFqeeVqzdBU+QnWgvDm z6h3vH{&UwRqQ&T|stPEcHp0XBQA3v}^f*DQG*<>TENG$oy|4C0!BO!84lmt+Xp-1r5ihP@73;l1E*V3yehP@aHwKPpY} zuN|;FvUlny8dBa8en z!_O)0pDe6?40lmMr57EjY@F=6eiF*NoEmcM@8-T}9nQ@yCC;R(5O6tvrNZZ48j&9_ z?uxagFRWFVAu*T1?FJC|mXB-gq5(YL^3f{#6h5jONa8@1X(Q zXkPLDffh%^#f3*5-wa~?r#8w5Td2^A$=I)Sx_bMfwc|CVwqxi14=K?mYh$FLVIWe3 zh}1{D#hFXH94zhPO{L9h6uy|JQ64yy?t(bgU!SUgLa&J#Gay(__xY{r>4?sqgAS>Y zejP*>i_Yri%pC#WFpGrB#%sg+5|ZRvyK1*yTUOQ~*}vuPO_%t~kuB!pBo%tmQ!)Js zd*t4xEAZzz>bUJA3f+g2-j-Afr)}WU@8EMlyA;rSP|D?tpsnoyvI#{%GYYY+9Y`?I z2%Be)4^fL;1M9O^vWKbm@^<)9?<(9Mlg^ke5$og`E(Hep1SHEgJA<3Q&hI%xJtIyu3rEzMht4WOrk!F_JFJ|kcxic{y>^OB%0Pknl_4X!8icXfy z#?DS%%C^~N2?5scT}vhh+hv!A{5 zo;TJl-nNAShOtOme{3RO6a6suczRSQD+Z5Or!0I~(-0{HlBVV~9 zR$=@pODR@HYKE_|v7S6x+OVNRUskjk;e@qt#)qr-)4@?jACuDy5lQ#BeZ$HnW{p*9 z`s%dAbnjEmaJ$JDFc0RDxQYAejeBJlgYA?W2WR2k@H7$q#phHv+XVNOwpEo z&P*z7QDPlxLCoQcGQxQNZSc`Q@HE&`v1HweER75eycfRx>VFXY|eP4j<)ld5kic}IWOGB@3{T!X3v>X zyF8*|l&C_uTB{g^5_MS;W)mnWR?}w2>ez9JG&?tU?qms_L=#Dc_uMoWqAJBg5=lNIABT(LKw_d(Qe)*`;C zQ%%bdsh3%M>N3bvH7AEU46&)rih90EKQeOb!_EvZxr)|=!JF&;@TU82eusd3Zlc(S8o~IeMN9zgZ(Xje!*mIoX2C7TJa#~w!Nw>!?0?MO^N4+{2G0o zRy1a-eUp{Yje%|Y$~se@^yR{rawP55oTzV6Iwk{8Ol?}}R;`+mj*7aqzcY5D)OUo% zNq_uz)F+H}bolj_9droB{as~A`@mkyJG-d&m?KvB%GOn(@k-8$I$s)F8iqg6lOA$- zW782lZm0oeLDwb8z>7QhF}1o1nW2x{?ytukrW3BVuh$fCc`91=Bq>$RmNc;IdQX0ni7@I?B zdW{%zNDC3Ow1&ZM4l#SOZ4b5is7~v3EGwIvn+sbj4VJvh|Ct?;kU@XfMmxub8YJaL zMK*kxozwZXUC&I@iA&LoyUS~--&AN#AUb$MDHMAud}}%~{}yYviG@KX6jHt7X*yFv zczHmhYC6L`v2FiP@Xqz0y0%eF#W0GNj`L< zBU@?8o)r_`hy|C@vr(t--Hr(I9{zT4x zLHk4|r&W3Dyo3ZC*6&mQqI|%9sukbXweaQ{bPgTkDpu79G-W?0>-wg@2|ALbzrJ{H zH`z^mPUYrBrG@FR;S~#%BOuRswUghyo;)KrS?qi4hrJx@VDJx)x0B{~{=fysBNP&S zWQw9uAc?bX+Vc^8^jXUB;Z7Mm{@g?f%(;w#jGf@Tp^<)McQ04baTcxJ&YW6H$O5DnrcffvP4GvdN0dy9`(M zPSq#%8dL|QqN@(XA2DCrqsSD*Q~t#cxajJZ|MMYJnuvYA1l^Btr2WQzTvB2$;){V2 z|EhCh;8AH$+2dKKDmi)ZdZ6f}0h~Dp(MVlsZlL~z$iLCui9~u;q|wHGUD~hIBnaNW z&#$#31v-YNa$<*_R3v`z!Cen3GgJsY?lh7ZRWEvdy`S?6<)NzTYJKnTkRmOl1`4#y z`@K=6PyK9xef1mS&we-$z9WAgQw`!c!>k6sU(b=afp1(KX|iEM{cApM@%^3&m*y}% z{HP_Jdd*UIXzWobJQcIO&L14`WUEiNF|sjq>skQ0P^@*}NhTI3V}IJRZl=M_dYb8c ztvh?(5nHjC(`t@*n5%LyYj%B3{k~v@uknfc8=l4|@u}HP(Zx30v={Ib{l%W1g|w1c3;gz+Q?hk(X|&aZ<->N;)aYU9;NnkJygt zBO_56xw&(rXga2e87&j{13tPMgt{rs31BbUW>#!Xd9Tuz^TmSdm9W{Fg=!@sOQ9d- zEiJX?s^4V^fBvhdl8(4-6Zfp%kJA4g(C|fl>kBeDWM`bq#@t&gAe>MT(Bj z33u%P?PE`u<3dJB={}FJXl?Q?{z@UA2%j!pvbwH(DZGwBD_VL%)+NZiJ3w^ULQ|n= znI(I!y1K&OM^Cen&?9gsL{4syhgWphQV{FQuBxi4ou}t`(nUwYP?JV^5#uGTvZ~SS zK!i&*3+rPbp%guWcVDx^m$HR5YMRUF4?|gzH!lwl8O1gr3UAq2Ewl6Rh`;bW*Yt}xY z@JjhE_UkUbUWqOuKNB*M?QUujNB(Db>?n!ysi&=}46*Z*$HgRdz~KmZmayke&tV0M z$@`Pct6Od7V5)FIYelE9MtSOWYUo?*7{XIGD_v1*p{-s-?Q?7a|5|N0E6K*wFa@kh zsjcP*Q5}mTLa|e@2&+^qC|r=OWw+wdSdGUjF&bfNh^iIYyLtGKxmkVI zQi&oVaJFbMylAi7|KH-L{&sEEkM#6*HrYeakRL?fPZC)QSDFuY!2G%VP>5whc-{PZ z7`)KG1ef&pql^Ue>SLa3zUMvO=kV*Ug#!MON?E6yr{qDlqm3u8IB*N(Lo5N0ouvz= z+R4J}OK8VEZmsC-{^@WiU;(hI59?_V?N<(MlSiwyqu%nx-axetwqUH>2!c8F?ra!L z*hn9*Ctq7l)Ou1*#+p20S*nj88D4U!dGqENs`eY#HB(yTzFX96e&$1|9Ng#JO(yE3 zXpPFd-QCpU59~tQ@}!+xpQ^E^JG~77tmA7R6;&?pjpBK*DA=#MgyWz%&YU^$)H9U} zeuBPK>!bE@8RjW{yFncwDo(2`e&RlRhj-><(A*wpK&!ybW>xO~t6Hbd>v4w$zhl1%WMt(ANYThKO=qjgdQIMhm(9@-FP``PA3!k*)6O&UOsUqh>#J3FFunt`aS@|{Fk3m*rs(b zw%7EJ=s!!0>~N_*$hoYdXqOCk5hP@+(x z1ABX7EhW11fdQFAx-wm#8)Ku`>y@v+5JroDJeURIS#>*SX&31~FJJ+0CL(|Luo)P<2E8RO%j& zN1$HV*-FJ(zR7k_b5~6fzu)+6fEQXtn=Q&9-5t_h;;};e0HMpcC%Mmd`41;uiloC& z-reQgHU>U!K&iFM;_iomjgEyGBh}`7xChZ z&s>_#+uO3e9pYX|zUE@!8{$uFtJu3k%K7%oNwuc<#C~wub-g_&T#p4ClR(SJnvr z2NI8=IwJ&L-tX*u8fHsjb_7ae1>os#g;y`#!Fj_o7#K|0c{pezYNo8=^sA0D3u1jw z$Wky^ibz8~JwG~fS3^N>s(b{Hge>QO{T_MnD9PIW{@%34 zS|l0`(=Ur->l?OetsxU=aMlvX@tFc5%Gvd&ijq93*&l=nH$jM%&4(NWz;#YP;n7ph z%&Ir00%wiCBZ^r-W?H?8cRey-6^V z4vsPrW`gI$(P~r6)u^g!v-R2DA4^y`$fzCz9`ySITbXWuu;A7et;T#xY?W(^oOy&o z_NUZ=t;TM}W?M~jbKLR9s%A>U)AbsP3EaSzeb?onO$f!qY^nS2e9{vNaZq#DPyOwK zVNMvG`3Ukxrbwv1AB4YXsq0k;p4ae1&_g6yfwOcW4*ROGe^@83wKTcT1Fx-@-owahCRt#ARzeCh%;Xfh?m} z_kHL%mE3+?1e%}{(`KBkp20Y% zXKlLrDiPxCd_3mFP%*^R#QS2u?qWyqupqNcC|&XwXIbOh2@{x6@DKI42>{OW+JfQy zO{ZGCZYcsTQ85o|gk!(#*EkGY3A{rS)6B(8HNHxeibh9{KPh0>)zxW^)?OTL=wySV zFx5ufOl}H9sHvD6iG)^(pNLBoe-AChR>cJ|Cm`ju9rh8JN7u`2`p@U05TxE<-dmmA zzmKDn4n`z8ivy;~0cT@eBy*}=CL6T+*`lS1-;vLh6>cEfc++oPk@GGMb~haDYJ{Z? z@dNO~6m^c##W@oneo&hKXkZAvUM-{m1S&J<5`m*R4U^Ycmj~@l>fc}J((lBqZ3~M4 zLEFOjTLJREQtJrFs3tpoX%=0wqI7Ak?8Le$f~A#;?Kf3%qEL2^zHbe!UXu^yCFblD zGbf|8q!gq=ZBD(8z0aNl_EpIhwCETZUtV9Hhb66N-!en~$H!pXMHRC?Hf_ zH~t%6rA%0gDrX+wMgIqj{}+=iuy-%TNi3jp$Qd%Pq6NL2uT~@XK0w=wKuOQ4;1|r7 zXQ!uLaSx-;f8Vaxr=Om>#&blE9ZeW27#tb4P9o}S;5ei|#|)@-XbxLwV7xSixX>%t zs6WJen-R4C3cCtSe+PAlbg4dyw62S4xsI09KEQ2S7_@Pnt|) z9AMZ41pNG#j9!x$p|rX-pfPW(lI^}rM7z`ss%%Y;>HHWxX|r)PT=6d{bTLIYRhx+* zS`xdKS%UP;WfXNybWNd@OUUD>YK(Hm(IIr?uzxXWZ;wz^=H1iT+1V^m^FaJ^a}YKI z4*X=$>MTL{4^)zy|I&kd)~CFKv4kKoVCFg$Tu0mb@#gn6Uv&eZ${RRB*Do4k z&+SP<8krZEA#y1KP|bW1gJAaI5DX!7$$J8&L;L=L{1J^s{I6I5dCN*Uq&l^I%upbs z9X>1%u*07G0TKw!RVO(Aq1yd62z9jEBwL*ePFnc@Rp0^Kj#;`pmfH}aM1Gfyf5(Vk zpFdhr=%Ql5*SRvQz3^6(RT74od5d{+mV^);bB-=QIT;q!Pou5!z*CJ5w#KOUz?URD z)Ld!`ly?^2@*!!XE}JUX&PRyKQ3XPNccAd;6!2LQx01z9t*xCR2O0`^NzN&#%RBa{ zx30Qs4Y8c9qKl)qs#P;sJ^hNDVU@0~zBU>@%BT|>G!Nc2Fv#+TOerrYSII=&6M&+o z_t7(touAza)pNxG;=$e3m{nlFby=s2()&I>Tr`N(1D%ZrFS)6e25l29O%5 z{35BIgIfy)>PyHc#igQsF+gbQH_ME<&;|gC+WHXuF$RmtD&o}d1QTW4Hrfu_@K;o* zfQQ!zho)9Ka$S<-Wz6=6^iNFL&~MDU5O|0L7kR7dwk*$I1&%(VuAj7HMty+UKTf!q zXsas#1Ur2LqlN3yrV=aqXBnkcmI%__dC?M+(iuIk2}5K3x%+>FJgrT6b5eSC%(8ao zqseB5zaBa|ujjz`vd>%W0iVg2idy%we~O(WcUKf3Yf=Tlr(AWzh*$mC-}`LKXaLge z*^UEt^S+Io*^M9(!9jo=thxe+?y~=)q5@5%sx>s+3LOJh_FUzIKEwe^AVe77GrIb> z)V&@pPpEXqtkz!GYzkZQUxFpYcPBBU>o}p0e>lIcFFlN>u-c{=R)q$==PH6j>3^Rej66XgWAR-VWvlM(qpGwUk z$rZzzHK^Y3k;!q0`H1Dm}Pa+GWaYZN~lWzb^3LO88@CqKCh`tzRWtLeKJifKR9IPsS@gXnw^GJ(0WZVUVcgIZlZ zhUqaWNH@ReFA7ncV>{{xg@U!4zcRj>CTj%<4y(EHO7$2lt!fYNKg8mkKvK~0@nlH@ zYDC~FBrOm@-(c@xW=i=IIHOsm5bLZIWGZ#O;&u21UBG(yf!1pQFm*!}xDI?`${#r@>&v$D!KDDWnbyTFjI_-C;3 zb8_uVWFV{(tPVb(+lB?if6bbdZ+aiV=p2Wr1O)IH6UV_rhIf9l`yoppVE=ulB76;! z2(CeN-ttW~a&-BU%W7BDH~igN1Y?>e7s286<+i8RZGXJeLnkOG_j`-u)aGVhhfrsd z68+o14L+)@O>c#y9N<>+Z=&i*Si~?>^vSJR;QQpEt-3O%29~}wE$FkYdh;u(2nz}G zS+dn7Ng?SePEs1Am_jHdh3nQ)AOKRSrytws+?5jVE`UaEj&!Hs<8nS`L@ zbNz?*NAXg=taD6}0kGawjJ47hUzlh;(Z2|$|5db9$Jrq)kI20nU_N;;;^upG zyifM7^Xj95L<77R=3)MZK-IcK`&j2&clUrJ5_a3GV$244ETYRZskw$;_T~Nry=Q5n z!qaA{1Z0pQaQh5$Aq)^9284P`l~f_uC&AefRY}$TF|8c~QJ-sZZKLp;;6dOw)7Lzk zCxOVCS3un(-lS`Q+9n)YnU+Eh1#NHrdkGn3VrV4uUn-EvUpXpQmR_}K^`!TkF|?mi z@}NI6(n84~#0-}J{#k%x<|c$!j3zPxEYkeG3^C8-S5lC-gi<*{nq(+BR(&tK9eU=2 zbUtYEdNi62%5H1ss^Er-I$T>Tm|Hg~=w&KXI)UC<3982H4^*&rF^FNd@>uNji|e`K z22Yk!bf|{H2Vi_vYaQ9`n%GGZdpocv&%zK8=if&rHhGrM^^@1%b*}$b3y?euv^)J- zJZs57KxP6EK*-%Bz4zVdV9}@Wx4(+_|BL#p2zDc#M5IE&LbRh7o5&F>P6hi*RzkrI zEynea?>(AY?ecoThe~wsNSrY1Bc%d2KjzVw8?Xgn!Qe}%L=oO)&G00^4KKdHw z{6Qw(l|Tg0R1L?QLb14h(>q*xg0jn8<6qkYQ`p2ZmOjvJe_Iz(EA#MySQ{Tnvv)qu{CU#Zi0zUN2DM} zD-D~s=hkdQ3IPE&w0X%_p=N07JR*?5*+F@YC8hZ*CD6vA=+P(IXt-m>I}<0+vp`#D z%T+B*#4Lyg^}06z7WLlN!@)>Z4A!8MP02}N|Had42s$R1*o#={r$6@P*RrnWFw~VT zy@gLECTJ9$RLJ)_K5%>CH4=m3;}gIkUo5BI$p6A7YjuZH#G&}z%LF)cqN^wVIrrA2 zhCe*)6OIj-R@Kht&R!JeCs(VyR8YAQAo{H)iP|W89a(qyzhuYT&*5)H2HZDPO`!4V z97*(M(Of9t;krbFqK!Sjzn~?5U-FNeV!8Z~lf4XCQk|~hPh<|affiuAHa{&f6_smp%cYlDWU7TQDt3iUDX4YqCpg_x?L_5&bxp5=(D!&=AgU0?bMUdX z^{&+t2{g)_5 zp?$}icc$|yeEi_<2L=CHKpu6Dm`iTF(c3o&t50~nnDq}1foaowpVHqyTw0U*MW>F! zlWBEgA(FF{CTRCkI+KzH4gG$9%J=O~fu(=l6`gWN)MkFN(r>3*S`Hxg(deXv0|PAL zBu-g2%I3N2inGCc&mIqW@9Z}nwdP8@ACJvQYd?s4kWPa-|-S}Y(;)R{CsMoUBZ`;@$~qvgHN z&CcgD#i;crWeogH7b06HsUrP z|Hn_`O@}3_Dg9?kjKdLqI54L$X97mYi!qE|4GQq9+8hnWLs$wI><;Vmv88x~J*?5~YF-^Fic z8%Xh%9ui9`C2*;O7I0qGU%5)$;r0I}r12J0U`6Ae08A6g0sS5J_&dW+YSvzt4XRGH zHh)3CnwM1!sgX&@KKpiD6H8oYB5`O0u5-YLJ2~v*}d1+eaHd=0V zOKo0iGqY6VL;Dp{Zu-QE_s=nHT70oK)3HOcl}xY-{_(cFv{Mr#g6QycSF3@V0mki()8Ea`m<1%k+SR`9TsuHa{pYs}4eA$NPAj z>;o`KLYhrCzmq1Rdt+bY3#ggw?$RUaC+Norwdm!RR!677i_Jy^8Z~yPL`T~!i2*;l zEoF@WE_S82 zsQPWW+WP3<-;CV@H}^IxwM)M^e1xx}`p0MGlDLCZKMa8Kk+emBn0QY*L7I_k;7m>g zN$esPH_9eA4g^@x^KeY=Q&HE?16l!tbwuzig)9KJxO3|+ham(2lgn?SM8-tKs=-Y{ z|6d;IVuxpEuEf;JP^i;#PiJyb7#MX26(WQD~%!a{0 z-HWfh$8lS-rDmUvN2_e7sZiJfSJBwTtJ9t#*(M$%!AtLD9F*aF z|9YMkA_DiI{?B_K56=9p@BXJ;|JQdPIN#CIB0!}c7^Z0AL`vQaXqNc5NYl+66*z$H zYXwj|T|AE@Z!c2r0H?z7h=6{>Uk)QJ8zt9Vj?SGGIuW10Mj2?z_K}hzIbera6?S0f zmhaF{v`aY+bI)6VLewdAgcxqH*nXT5SS#=Zce#N3agYYuErH*QF-$&1o*y<%XQo&? zqFWu7_jaBS0OsMasOu_F*Z>Ixi^vxU2S|`Tw&Y9*A|X=^ZEr}3kl8>;=C0l0GQL^T zC6&iT5a6fy%Z$_E>yvJ8ZA_&5mviIdM(9jT1qtkXu`LOExGuh%82$(^zQg!Wk_ypG z-Zjfij1Bif$BxVR7BqAcr*)w(w{!2DzenApF6gLO8iK(KS62;kgHT?vz^Q+4jwGHY zTz|yN#QV_Z4PCY^`O^*Ul>I4_5#hJb%AL$zSC2 zKEEr&MlWaKy`)i-)n%`3p?E`d|S z4c4dRM`wp`lU<+(uK3tA4Qw+7CE&DC%=Fp)zRn$x*Z(r2F9;aH zM+Ss?yZ?dfqj(D82fc+qW^mjWgKgM1E$X$LQx#QgMcu4qj=%B3Zc38CMzgB}dLH`g zD@eY{6%)+FGN*PYbgv{9n-90~v(` z1nyQcH)K5p`Tv~A^*YWm>);V?U3+nt5p(`Y-WNj$Ov#>_s&9DHszm5uqPb#4?wWYB z08~~P&u$|M zc0W$`2ci;~k?UEB@ol{^5#%3jCOkTtRlK}feNP(S9F(NtpO-rxeL+zX9&9$p*mJ_#*>~Ky1g?hur%5AoY1~PLs&M8gh={S-^*R%93-)?BBEb zoDsp^zt30G4RUhw?t80(%F3$3@euhjV>y#9wEM&CDopx6mQstXen$8&vju4#@zRb|-^(JCwnzp|3kp8(hc_&p0gnd3s zq1pZ%sZVeA&JylO0^Q>y8@?q1L8!=%#u_3FacsgwW!{=7P6$q> zf?zdBj&^v9Si;_~p8uhojJod~uwIwvM+h&7X?yGtE-gm({%(B{;w~1*f(cPyx6G!p zGRQMP;v6h{^bK5-V|pJ3&(XnAEiyy+F05Q9l!g6P9;aFCTo_h zT|vtpSFd8v=^YvM(LB6o+g+(o?nr}$fQ+Zq5s-^*M`NjVg0h;q!a}(h$!j-JF$4=S zc=>@$)rDVqIYewklsR=jrI*Za#>79vG>gl`RGE;l+}&xkB-6iMTh_>5L;l#pG!vw@ z)_Jbx_@$N)=d=Sh{^WuI6;X=j&+mq-%CUH*8vBpK-y^F(B9SAjhA z)W-m-0=b85M^>u_?tEV^z-#SVeCN3CWBv6$ppN1GQHK&v9La(dGcl2}+flbLob@BZ z@{`N*(>z`btvz)Udkf=F!wj&`x^_eTuV1ru_16@<)c^S|9cF~{iZs3LfC^>aPVNH8 z{r(n@D2P42PjZl8OVTq7su#zAeAAf>Sk32S4OW^5_ECidG*TjAy{pM6t`CsT_EuBA zw$ZIxBN@FZcYJS^8~uh<<{RGqCSgfe<4ab{=({gb^JC%iqquF8$s{ms+XtHHEjc2# zy#I24_#-m~e8LV`C%fRv76WwGAvCrIK2<+-D(uS-!q{JHgQ~ep<(q=e14X@G$xGmy z9=qT!fM0Uo60<*<^kym*k(K3(USx>c3C`A+IIi_T9rspeFBE+6rJfMQNa zMS0tF?!hm>Qua+c=SU_27CJC{^pzkxw^oE__)QHg(la)Oak+%THyt0Isj;Ot_wX6@ z@wq~{$N11R4{p)t>XCQ^>qeEF-mSXUGr@fVLf-e~6^J(8vgny8dl z&h>Nt!1>7mxD83DuUt?+GWY5;+XV!SZO^!%FqHalm3VDVO2V#hyeSUkf?og}5t+`$ zZ%e$4oQ$g{uk-cO(_hmufLF7z9pNOFv>qe>;#E%uQcC?_Jc)0 z5XB6d90{kYj6;urU!anzxR)V!V^oRm&&F_}P64g_g@=0OM8d%&Fe_8)5K|_%;F#s? z40jPmt9$ep=R8I5%N3!=^&ba5#4c`{j9eaHgD6g-^#=<#*Xsjy{B}+Ih_zwH^{e}Gcdmqn?+5+d*KaaJguPbA}^7O*%4UqGbSe9vrb*YGY>eQbGDEtd#ju}ILA#qsgn&7!ye&G;v zWI6aIKT#Plk*AU3X>KVKbTtTG@Cv$UQUNpBuH4RMl|VHSy}R)myPT`EkWZ6`wyCmpB0G%x|>W zqHY>fHK%mBH#sAUQTw&S)}u$R?XUk4TEy1`r`Z`SG-Dk~Mb*cPDY(C^`n;WRrsrr~ z2iUU>elDpx9#gg}?#mb`TD;AN&>XkuvZX{|YkO>>QN=8pe}ffVwOAW5iu1Z+Rye)zXxi5e7 zy=CoDqXxA;+jKMsWKeAK<0T9~OM#aR1t?4};Y>{gT8Mrv&!r7ZDRLA{b$=X_T?`B?l}y{otM?hbG33E8?mDH9DEjpH*exGecegkwwnuLj z9UJ?={RerH&NP3r`q7>pR~+5JO@-X z@bjKv?=QpqWA=^qi4ve47XtvvcrB@SChDp!&0pd~ZztViJ(5G%u_pRR81uDWrTTnw zjo)bsdi6C&^d{>8bG@);uR|_u!q&CC%FwzMCnjND!E$%Ml&4W&(@>V*h@3KgQm#RI z7(CrRMJ%g9K3r13v|_=-B~oxN^*hv3hh4PRT28kq=oOt$aLK|xQH8p<=>Cw=D2si$ zgsFJx$4p0?A^%I$<1Zt3gW!TaG(|Sm~6y6%)QYSFUBCoGLeN z>+h>QG)`e@zs6p}+6I1HyeJ#SHn4Y)#!{+~o!^GkW1NbpZNMG7<8qpOWu2vE1 z5Wo{88>y9?Fb~USKH-{wG>H{Zx1&)yt;Rru*0Is1OLwd4{F?PFf^o50@kgjvvd9(V zT66109Mkzhw4Lczh(k+Bb6Z^jxFGS{dEtrcEbH*| zc1g_3c`{h8m8BujmSh14u4@A_NZ$go{z~yjEOsR|1?Vl*V_O<`<=y#yo{LQ)(7#EG<3Sgul>=1ydSjzD5JaWg!?Re(_&rMC>vw_{3=KK&R}ES&YiUJiDy zeH^vi_Ox>BD2BaHM<^!HMuI;x74VL4%GV#Aa{9ubQK|5s(#D?9z8Ktif7yw_kng!b z%yDV>U;`v``I(gozUVGL)`XH8vaczO94Vl2n?;yD_Y40^;Y*tcP1H1iImBS@3|G%p zt+NKa<+?;S0g|d{vP?c3)@n`P{GsawXn`~ze&V#m$r}Sl;f&|jGH{MRyHCfU1CIK- ziLu__?-1YrUeFP3J14N3=f8*#yyc--nGlc{UlxbT{F-kbS6T79g%Jl;1@h@k88xN@ znxIk`y5?7GMB=F_DOL6WXp^sRrxAvq-}{s|=^fA7(gT7s`iS@uMb-{+znZ}kLIr@K zzQj&b38r9Tx||>=A#XO1&0J&VfRII#Lv__JaCUk)m9y5_Y+XC_(id+m$XQ{|-fjOu zd;Z3u`-t+7&3+Bg!)w2)rbK*~d4Br)79IEJ$o(BhiY39X^ z#ygMG*YSv?0TPPh_d}{3_ml`*cTfK&I_s!Ea!^Xrup$U$t@uiuDh^(kVv3g!Knd0Y z9{I-5;zq7tl;N^CS{yJS^PNyjbcc=dGR6W+MZfzVbvx&;*J9ItXwg%pkg6x!7Q2O- zu}-It7SSSYXnI)_L>w>X2I%giVxym( zOkU(>sqGJ9e1S!XFL)WZ<=qdN#u!)FoyT-uPcOXw=y7YQ`E@NQ>fx#d@8_r%1od9; zS1u_aqzKS6aBNrZ^ySi#Hn`A*y4S20hn)#lR6na{KmRRw=oo)fhre+o#*7RI@O*C2zWVk`ft7;G>4xaeQ|$Z# z?CMX|4aI8VlKhKS&{e-+^?oUAD{+Fc=Q!Nc9cu3rUhWVe6LcpZWa^)-%juXo74u&7 z>B2lCD|_ltmyXx@0!drd-{|#0m_8|@@~NEljGTvs4Q-z?P3zp36bc_J(7l`%eE0io zzca*a@<7?r@zj&^E{b}w?8;l)M-#15V}GUWPRE&n{nx^t+pVuwbmIqRjMdMg=+8sF zuew6q26MkIP<>t7N`8mkG7PC&|99b`OFeIw6k1-+sBDyRwf*oWGki|nml;hu+R5zv zbmjOale<R>eC+>#R*4U(TVGf43LZB7YZ=L}1BMv1A;X0WPA30q zPFOU_atyab)iDVkq1}W(Gmd5rWRbD<(?;x6@u;7lz05cgR@zMw1KFN#^y;p(I&kL{ zixBJ1F87)~Fq}nz7}7J2ASyNMv-5M27$wV=dA!qKaw#jOndZSg;8_}H-yW6fQ29fBmia*7w&XG7)(_xOG4-jPrQb}D%`$WvxSBrU9U0~)96mz8m0IDmE z2?j?$#WOw$`}+B=WqUY}RTRkHgik%eQOgaT{)x803qUhHlE5jkKo% zCXvtRVeWUEY#vTag~DfT%AKv(%o+xo3+uujw+{TreP=*?Lc%8f4!+99_;p%eN=SWr zIx%v|B1bPi=jVEAYc3yt3y4S?(GJy6^>mX}z`?|ERT;2Pe9$VtH4wSXzmG*c@dA*jtri*#BfeG27?Y=xx zBohqIin)iTK#et?zUNM{2OX8Mi9R?Ojh-!7Q+63CvIj`tkDm(NTqTL!&Vd)`&w4(? zcb`@$&AQ(yf+w>d6NLWV$vOyU%!0)POLHHN7Oo@woMuO(Hs;M1)Me>%)vo`5r)vEV zjq%xYG^zP4+#t$TEuZ)a!(ev@6|rQ36|rr~k1a%S(V{`7l144%!q3;{`is6%jw54- z5#Pj~$9f+c6~=qZtaUIB_^1+0KS4zrg3zCh?Y%nNLEE)Q`GxSlXJPbn+>^!J<})47|G+bZVjgOV8$#u=!Wb3wj!zgeV*h1Yx$4E> zB4c8sZ7qEU7R;;Q7ik)L;0=qF4}BUZ5xOY<519Y@#u=k(=srT4WD}=tIqXpU9UryE z1oSce%ARY@%KR6;_3DgLxy*d$8!NvsQwYS{4HiR3zi~1S#rTeXbDMFsTAkCwhUqyj zOy2JK20RfGU05>fu28D7R!O3{^c{bA3Yu6&-c+WTu*OA?$q6*$tDN=`mh+4yP#;@}#U^F$(qRh0X`U8k{<-f+o#?U>!^q@mNemLo) zYP|reHLC6@Z2e8Z1R&9iZmmPRP&kk#L&22K0PmeM=Nk;iW`FCW?Sk4n1O)j0uihA6 zzV#r!n{Rp+*)Sk5LC}?Vatb!Pb_0k2p{DBiZSUcB#wXa90|c=$$6ACB5Ww%w#toxI z*sH4q)1-6y)!>!#4JDeS>dTUowf(H59M9`Z*-|R>jo!n-%mw8*{I-&Sd39ERlXwcM zC|I!TCh94sx7v;B(J1Hxxd<9d4-wb{Ij_zFm8B7IRp!;7JHsa-xOJyK0q8qB_nEe7%ScQX2+CfZf6-?O38 z4?_$`ef^RCO*^-?Zvo~rLM}Ftof}CDh6HF-RJ-~`bgLga*g3Z(^p;Fjk1kV)E5C8E3wyDMCv{ys^7@mCdO+LMyr)o7`A504_B9cjKsAnkDrg(G{_1XIK?~fQe z_G(pMheezbQtaHk6>oiektqLaS^rT<_}Gb1t5xy)@@=6;vl#EgJX?Lo`R5)_O-!s- z@5TZLehZ$Pt>_y_lLEoMa_OXp1i!Xw|RD(^J!9@50L6)!Tr8Xh?I^exb6>&%?j7 z)DQRULZ}I>$#Z$^Bkd4cTj}-LDyzAmGNRshYVbKz_J+|s>EiD|+SenIviLco6v1EdAGLxPKKQYflUl%D za*+nmV*uS?i$kiVMCr>YUAXkSbtxKL*B0Y+gpyPQ@kjbBT(zsA?j#x z1{b=Nw$K2dRJKs+TwzBs_xnnorR`hH_F<(pIa{o-c25~nmyhCUbJXuL*F-kkNxdR6 zhbiRZsdLB{(NHX2xjfC(p}tfF|B1ibh6^2Z=wN15v9;$bB)uu*@%NX4%Q~sK`6||z z+nk90njK*XEZMx;*Nk>raNs|kEc~gRyy}_J==HuUTP*+YvjcMlA=u+Z(%~@5?rF&h znvp;`(^AjC%cngX*R)>ww4|NfapCE)km_#g|J5*5m?y|r2`KLQg+$Z+W+(XpT{yWZ z%nm^}K2j#)dFcQCa4J-Aibsrvm_o08zcY>Qps<4>0!bP~_&P?rrUvoNt*;f{55JSs9rpA-BEQ z&btAQBjcx-piS}D_3OJk0;eyd)lbpSr|a-GA?FPc@RWjrB5(z|HS7Zq-G)A7tL%We zo};y7Ck~#@hc#z9vls5p(cqhhKJc_5TM9Aik1kv3M+0KVcNg0ahuP0IaE_O;mpoFZ z_NiN!)d&>>|A^{>F6Ye%Jlap`-Gvk=8J%{^xuLT98k@Tb}%QYMn91BJ=vlN*Bf$s zRk&wYHBn40g@?zbxvR3^41(UWqh(a&3`Bb3HxEVnYL2!?l%v0VN*DG>L4}OTC3Lak zR4g~yDrSFeyQ24^hg#j}NIv}xf1I0Hfab`~n5PWQTEbh3t$po9irEYe(-oF)npyI# z*`f2?e}n&i1@TK(um}DO3`R9bzMasL{-7$pXE#U(nvm((EdHiWF(1l?Rhzm( zPeiCTi>B+wLCTWkdmi=_c{aDQQtqgaa+lko%4lojqlpz0!<@z(EfweFS@@A8A&uYZ ziW#6DG4hc;a+uK-3yB`7X4C9_vy>UqV6&|NZq!(8Az^Kojw2u6t7)gJu<>_2{%W@_ z-3k0ULO+3LZ_W}L&&kgC7y;|ZpyN48zj-)0yEl3Q6G8XTnlpvqL|l#UXUdHojWk+? z{nkQ#)K*jh??Epp4U&J620hEvcS6EcUS82+3#f*2Za*DY3SFRf#(3~xSD_|b_2RNt znILhB{J#CF)$EwR={DuNNl;Q$yvy-sTe7sU z(Azer6+(u6>|P;AHIjuuPh;<{W7!rVVWTE21KJI*(mCVhnj8xk_NO?U;e)kTSRaaJlQ zkOVxZbrq>lEFHRF{gS#5JN)Rt{za0IR7?(N9HlT-lnHD+n5|9oaIw_0QpuVh%r!i! zaSt1frB9V#UR$Yx%}iLkTB>t&w3nQ~J6JO%#U$Uwao(S34{iKHz>lTslZrmPHohDu zh5cgj#F!}E8nAjM7$TF=4uTF|IdY;**}*S zcJ<>#u&NUwb@Hhz23cNVPj&M&*JaV<%Yi{3vmLCafLn^v6n7U_#g-0!W(SyqCRnY! z?CikmI{Ss_<#*>pVOw(TVMHr_JK@#VX|RJlVs_@H!R@;wh0%jZ_QvMoL~crRCNcpi}Zz z_-Wg0oVI#l)#gvr?KvCrF3!B@%5PZ_uwaLJo~NzI#`UY2hu!SJFDQ-K){%E~3atXQ z6?G1gI>Z_+fpmU@u&0Zdbb$Z^yT(_ZO~r;{OL!Nll%!7U|J@}Tsr-%lOLPxw587Y2 zoC9kn#Eh)UNI0J6f2ge7q&rX5AH9upX4^C&YyTwgkumdo$EazxzF2zXv&*-jo-p;h zmWhCWw~awBXDrC&4_N{h3Z|Ni_9nG|AZ&h}3 zORBHC%#l&GhyKLTc;iC-ewmapiYv1B)PC2Ma94g8tm!!wCEOtB(doqjetPy?1$|W@ zO;Lqz`)LEIz7V@otAcV1f48EZFKrQ;#97 zE512{i&o)%D^dR{XnKf&bUxkt6N;wD&(t3 z@AYfd-7pLHeg|U0Iu=YD&XB5y#AhO8z+>hL*{y27_zs>qrHui73w&etMxmr`&O=6H zW~SBqB5_YqmNA(bq0y`NyLwOARWK4WgR`Z^e=|h(s%J6R-o23O_>BcR*V5fjOH=Ad zZFCjn4VD@+bHiSmI3LX4#cR#fPD^zI`;NO@;kDmSlEPKx}IU+Pm;83HS+ zXGgVeLPD*Qqhcz7%PK{ctgIvN1HXKl$tomZ^7ys_2eDV&)DTNW*zwu&#d9w=d8IwX zsWf}W$15GQ>}SuIC%i~Zko&1=6bbXb|DGgQZtL53{Wm1M_7i#LZ0}Yb6gv|_z6|zD zyE$7gCg)2t*^Cea+xi=DXlYiZ$6G&W&mA?lH<&>eTsqE=uhKht3ezum%svt$?Ogsc z#Zag(`Z?vMXQZp@SEYf10{8q~HJhd;6eDdkKR>2?rh%i?ZTs45+;YxctBs!Cl2^E^ z0te~^T0{)kKi-M;B3%w`e8+pg6-TX#h@*jZk?gR!YL5mR9+jya_TS5;*!RRNn-N8M zKqsG##^Yj3e;q7Leg2$IL9S6?C2@EZT|~6-F3PgO?*)e~A#=`loIVt6lPSVm@eg5A zUC4A&V)|3jqq0ICI|phWyAwwl>w!|c&u!N;*)4KQ-pXKD8f{9gLto; zEYGai_%Ew!uY1yE&{_C;m2p^*LNeRlX8OwoJ)E2!KKUauHYnzQ!pVIPr<@K)2qyw*wI&VoByU5vApMW5N=8#{T9@U4l%VTo0g2lJov8IH@yYHC$p z5&`5)8P*G65pXWN=`=~HuajzqXxvvW%u+_*At}mWS&5e!O*0X`yp*OAUNSd*7+R&T%K~h8RL6?)ot!d5-3r zlpM(4e_bUUEpYhu*veg&W>5Xse(E2EKBI%$@at2x+XtI%sCjz)>!aL9Ck=;(U!C`m z{S?6mrhtc3hns(8@0U)Nmy>2>Dhu=qJ_|QmD$ySu)nmIGyy!!gDS6AUxVIaiqQP~5VVls8L zjKb%x+4tr|tIa|E!E?1FRDZ=|_2K$A#^HAMBhv}5i!lek{okce=_Tbg>ikP9WfefP z|2h?YQ+~PW7Vj%!gzC&--G@-7ey$)xj?Hh*VYF~C>SaEL*@^nJYZICW(@C1BUB9mr zuQhs(QP8YhNN)||%*6qvjSsPzCB%Fjd=3$@9?Jb3(Ov~IN5HRQ&pg!RUmlEKpbt;` z;z4sAf9Hm0Kd|v^`L<4%el5s-RJY66SOkhMsH5clYgau~g)9dMm_C-tAC`FdlAG=LUgUm*mG$jD&@+;^kQY^}psG)4VQDug%2Gum=%m`Unuf;QUxG z*g@DFX;zA!gO$6jp|ae)iSncqOZTe{V_B!a6{nnic?kCaWC0Qf(EAQHxx&6m4i|7iU{5Y8?^)Ws0bw%sq;;zdwG)ibW9$Lz z*`-+mx)E*01z_DI3D`Yb9-B?#f<|EI8O2J2cnxr)bY*`x{OsKC1|CJe%dBQmdZ?>t zAz@8n;NkTc$=ZcjaAjc+}{J&)Erbn#=jV(_-YhS;6U})eWeoM8*)lU>9Ye0GwFZ+sM~Z{Kcs-w zyvvewCbq;(Vgz%>H2VnqP%Li?$LKk z8|hnIR4wmF7ioV{sO!?|{r79FZv?oO#jJP*v5Vg*66#(pn}yqyvKdW=D|rv|6PS!K zm#|sJjDi|w#3@LV|35BxIJZ_Vt zmyz*Jm?TYxi{_GMf~W|0!#mPy+G|{CRIO0PJ}7Ks@jERU1fyxq-qG&kl9~j%)T1p1 z@fE%H%f1y^P-;yCW_&L^OgXWsf6nbH(a&Ehn!`#s5@sN}))2pnIjXa?U;GrQK3S$P zvpiS#I^Teg_SDQ49)?w{U+Y5>tRNLr(&iC&RcITd5W|2_+17>pk*X9u$A6Yysd-;8 zp4tUtfaBR^%uvE-s_iD6o{Aiym4_GNcb~_dI#k3TOEcbj9}pz;vQKc_N&gG2SZ*8s z0jYUFb5PZvbo_>P4;rfesq&c7&|^7v7p?d{A!BfRLH^T!1pA5O;f?#|nPOfye^~II z#(1%Mn%Q${X9MAyKZl9jT=pxwafy< zG{+CtcbX37`&$DA`HNe}Tf~{944)HVmFX1>Fk^RRTm6PD=++AUlTW!Q!4qck{ei`g z3){n)MlJZ`RO0i}Nc-~{za>oj*6M4gSwNUKE*g1@&q~0u3SL~i5l;(m$Do$h+kIlF zcy>{2KF_0#TO&^XObzAvSz{CRq9};F13+0jyh$RCc_pSzl`ko%jsNQQLntOwu2 zZQycM>q8+i97TGy^c>$&I1&iCG5M=qS=&t}Z*0CR%gP0a=7Wleze3uW`9^j>IFRU0 z@i=zlk3>ayT>g6>kpIypB*T0}AN-`=cpDSBadYeyb&L81Q|Im9nBmw%WG&ojS`JXT z2n(V74eM#Kf)=whhwzVDsy*^`8=yx%8^}cGGa3NzG*nWA)tyO#>n2l2*;EktguA%o z8#fo$I7Kg!Gjf43J~5#$WFRuL++r6|iLI|#{AmaP!jj=XEZ9#Dj12oWl z@>ohRZ$?G~lBT~`lfA<(kue;`WchfxllS~ItkKxMi6+!LD3hTzFQ5J={f3fs5!$D6 z$$)$FNLJL%u>0l*r9^;9iFQkTGFY@qZ{U)P{B?C(JPr=c7p4^S4+%?tYAm=hXCd>$mC8!iz9aOn zG|m-QdBt6{iYMZ&O+5@X%xSZ3o(>A;N9ms!Z>T$hP>-G|^kcbnxw&eYENZx@8v;qb znbA~Xu(v5Pi(t`LQf4yZ(s1w{k}9gzvna~_+I+teVez}41t3*58zGeUD2*4yJxUBa4kH}+p; z{S-~xM!!XDMQnwJNtTNy4|Jqz`Y6b?BY-d<#e}pr-j<)!MAI=x4&_S*k4g0jO20z> z;rcMx3c_T|mq}SNKKVJoLf4%yGuB_VN-Pxu1^VXQhN-7-x&#QSo;^B9;fK{Y}$dt<64r@fsc?kNqp#%50#%Y zjq&XiW+87NtyQBV$wC!BVthrrh0;KDw-%i3fax_hTNf9ttE*-|z4iCi ziG$k)jfRlMR2b~mSLE|54N_zDE_R3WaV)!%@w6|3e#HVET#Zbu?YCV0lo3-S1MQY> z>$|j_84~l12t3{I%yY$O>C5vK5^_Jxo3ru%>b2%kAHV88neG{&qU>}eFJ~3v+I2a~ zf)ipYrbMM~u)cPw%}r3i|B>zvtqSanzJAh(L1tNmbRmk@yP-1O`JnvejJpH3n;1Td z3Q!#|+1IuRB;O;bsd(p1$seBj^dumqYwy0)Z7j@4IPIat3KCRyS}kpM00d6^lHngO zx=P%Nox6zMbq5IfnzSWOu>flR>lVfRVbH@V?d;$&ejA4K_1Bx7t`95W*&fMvY)*|u zb&f%J-Nat1@3a1tAFlc;WiO>Sh$`l^w`VPes*2yVA3HI{#N2?F@026e=QFqhidW0| z^h3omjK2OoHB?|1KNZ{8gUXY0O$up_*_QsC9FJ;GTxgbQymJG`{1R*PI=ks03^IzkRr9O8_{5P?e>RENHCU5lC_BYbB;g7L zqF&{7Iso<@+Kza(ej&^P;R4)f#p!p@Q`PYY`xXOLlIjQ<$Q~~89*_#>GWMxyPqCXI z3u*LxiH5ZjUBqueCS{HIk4Kw;^Sm_!gD7s(;dEw{~hY3A?5) zy6s7M^XXsnoo4U2;tBb)Ba)?}?HM{F`u&bw68=KUCHepI+7Nzc9bt@aaTk|f{s*$< zo+3)D;OEXj?AJK$hwsN9;F8ViuE2$xAfLvPAdlPwEx9fqMkxD}wmy6WMH&Myfigr5 zQ~xo^OTHfn&)-!R)jOJ;@T`K){7$i}8_bKF-5jF6;a@=h0Jgn~gE@*OP8^N3Sirx^ zKFhk^7AQWXPQFE5D|+JJCT*E940>GR?Wob2dvW%Q5aUYr56xhiUB*hhg*8}xMv~3a zyZk(NUjQ+v6g`>S;VXa!>(voY-3{0L`y*JYj*q1$!2$R%6C`i3>H7sS;hlbob^7+Z zVReW(@*=*CasxM26TscyU4|Dre+m5JfS;qM;0Xx1TSEqUr=9(c*ojie*NnA~Tg!1AH$v?p%6Z9sV z4Z{lQdd-x;Wa-hn%$m*NEtJ(myH^sAqYNpK|3j?jvN5Vc0saUGx}&Dg9C@$eTyNkW zO65J4E+L#d?;RdV2`m|DYsh$($)!%tX^w16nkiy@MrvJ%W7`3Gq z`045+2aemoL-u+Hp^B9>IYj?~`6?#k16OaEX7_xg*#)1S7X;$wb+T5P>+pHBK>g@w zxU^if{7?2INs|olk|05rhu?Ub@@2$Jb6sbq;}%jy>e$@l%>>{0$>4F>uRF$l1oS;# z>VQ0&dsLdVE7(})7;|%%w+i@-Tq-kX#vcA_JDr?(UY+n32!m!KglY(YrScg8=R6Jl z?|C#ZeNdHGlHPs9|1kt*Dh2>*Y%Iw02dOmYT2SFbu~#OqqnF?ppA27M+;&xW@KE6u z$fwd9`niselsA~#%!Ui{Bi8+)qc8Ic(%>PQhsP$%20DVNUCvaePv;obua_SYb4~g? zc%#G0n&$)>5}6Sz-}QQ@j{Eb|t?YE`)SX5L<`Q1lOFbMoHGPryp<`1S-j8kU_AP%mNvWU*;0m%# z>3{b_kP`2;b8Kree~{D$PoUR*g9tIo-{PmMmY!#P+DfBJ!SnA8=Gf?}(j6t@Zfq82 zJ~AY1Iq@3w7>n8CW^6Lfa6kb{`*sI{i*_G1K*1givIMz;k|kL=_gs{#SDl}cM34n~ zAG_au1hCp*O)zC!0d!aQ35ewH6yRTQgF;*=+;Yk+;)p#G@b85aSzIscl& zG+jeS)zwr)o)eWbMT?)G{~!PcIbcex25D$@L3rae$(i|kk`C)DAL*5*o1+-xhdc`J z4axlln6i@(v&9!mQ(sC0rs@yb5+`Pt8@}~%j{j$Te*h|^Ty3^FjbFtbcqhT?cAQkAZ^d2 zU@-nUCJ6OB_Ez7G${cO!^KD2T-$V;mj;Pfd`W=Ru9=JupyaQ8}s9%s48~DYgjNVPP zPz%-t0sotJwiSlaijUG5(SY=8zg|C)6)*!S#An$|{cXSmVya>rsdUbET%G3F(nghF zR4z@K@oh0bm<&~erMJhpKcVZPk)+RDV7u8FTVX< zQHvTRc-f1I=Um-YJ+Z!Tqz&Zia>emYRiN_-yF;}ZJ^NlBQOyoC#>&KOMAY- zQb?sm&&9c7YhxHaRG;joKMW1;kR%JoOy|}dX~3%@0zgmf32@Z;HqP$I2}q8qIyVL*{L&- zx)}t%O5O!ZY^SQGbjvU3<){}PAJ!IanFQlx6eG2H4@n9D;YMJJ{CE)mY-m?0hxjW1 znW-*9#8#D+g_A&nu7~&~X`OBkvj$y3Evt%-5<5J<*HA%Hr&NwwPK;#AT6E_lx~io1 zGq*@E5&!3ko?(uxNFOo|oN*csEtHVmZ3;a$Ud-)oQc1LLU+Yi=G@LsBVfw` z;s8IA4cJg)4PRkoue8|aj-Yg&M2dK?BQ#q36x~l}XY%@uCN@hajF-cFPHcZ)8(h;| zGzZS(d#{s;M#OM>g#oahYrL#bJX-)ApzNS8$hY&lBpLGkCZouj9Mv;=bXv{-BC<6f zf>jUoJsdC{AD;krn~0Pa&2>0($k<;FVS8Iz&M&9m2(hzMhmyW0KAwut6iykxwl;O_ z@iv-?<3CwolXa@+eSQ#&tCObYB%GdOLZE8?@} zUfp-x8f%m0^_tk#a~?4l#WQa|AYZ=-d}~c*vYy7m;)N$A`CwNsz!q>VVfDf@Mc*Ch zeX$0kFUG~-;c#$IW#xvnbc(I+_;5Ii9hsv<1^<5SZhSd&A)kFOZ8*sW32ZM( ztl&838Q;l|vrC4DlXHWxRkG$e{E{zX;Ye~-;7E#c|4JH2P|9JU!C}Opg1l}{{l$Ri z0mIqD#b%BT=G*26RLaw%~Em3#O~zD1qR*_sZ+e!=rZ6k zB4V*^;BC0w$N{e`XUW^0t!0i9U8d{nOz+IbDrb^REnN}u3i0iNR*#?BwX{-WgBlyz zSX(_dpHci8yk6KnJg=>7xT;4KG;Ghl96bY1r?4X&F-N_kLh=_lq$9$^12Zs0+IykA z+W!yaSscAK`z|M#YwhnKO=~_!)znk?vujxe!5A-Ol4M3g=z&&W1}#TL$~<-dto@f4 ze-99y;Gs>{?MS|zTQ!Q$AFo>{W_cSQQS4^EmgW{$kT++Z4$FY)>PhUEUta#b>c)$y z5&zA2NJ%zf*RnjjF7Rv0cqLmCa^%J46W*=!MLY`i6><)jh)9K1cECULSn6U5g3)JF zQ#8f_j5yG@SO)-MMOer!#-I}|)$$&DRR2D*NKbl1my7mzcK)xi;jo01LpbN(q%agsCu?C?bdqq40@suy`6W+)p zzt{bJL41L+(tw`xwfsHqww9M&C@)WvoM9Ei3Hn=e`<5_Wedj!S7!~C*_8lR&C@;l6 zCo+hiwV9EEh0TCSp=_RcKJfBmpiZVB^+y4R#25`GVX|3Qeg%DfMqEtqb$11h2gtqR ztqU8O|)-bavB(m4<$(9PoY*x-foTj%P5%b0+ma`Z6y#>mO3iNb$_J>W1V zdu~ls81jZA!?EeMw#K2%-iA3YvTU9x?o};$Wr)_T6sxJ`768RAe+2lIk<{3BK7KJA zW~I05uk<;AFXZ+{^;5+{p*xUMV^}FHEbN6|jyt?x_CpLi|#(IdUiu=Z22uN|v znso4*Nb2Q*C3O`?|YJ z5wROg_CAF;JLES-WuQ@oj8Se7x@ln5*aY)~*n(q>-sESQOfCh%mctWBk?T?3BYoUV zB#DtqY4ET8YOBx>(Tj3NJ#e~X`W5_6gFORA_0YeA9BZb0e00R48|%x;Bu1hD5Y)jm zB?%9Em-7}@_@;RSDI94BZ=u4d+%~`g!j>@1Vd-N|C)0)u!sLw7z(=V8+VOwOZfqRQ zV;3<$GW!A`vryNy176Hlye<#gP$mIs{|S7Bw_xqan54Ag-y78g(3D(d-||9|GBuSJ z;pt{QLe&AcwiZ=%^!d%w3NRKOOHfwjHK!zs(HLm41Qx2x?YjORzenqo79AEl!`F!Q z*4L@+5nskOk$F_NVSThm;8{w<&!&we*gF#vRDL}RL*Z&wsIcxg30{I+1m|zPq}Sqx zqWr@D*?-h1Kb%wodK?S}tW|lln%AX#1slwajlq}# z=(?ZjWh7p%^yQ3l&VK80w~K+iRoek(`~MWpv&g_i5ZACf!EU)yfLq=11}+!a@hlFy z_WV8mx*yC&&_Pzy6*k~~dLy1}49Zs+z$Q1YI#gj`ey>|y&M;MEyq4toBd!7T=`48- zhuBWWeAI|cyFYpHX$^iuqLXDH$LJ-F!-;!X>{=BLTT)s(#SIbZYP_1UB)7Qq*X4uR`f(FG0hPzOqW`&5 z0F`3t_DGcD$Vn;PpfzS?wEfU0XVNF{+(W6GdAqDs}BMcKRJuX372>wblNfV9|yjGa?e)3}$aB)5vAlpPA_0{p8vM@Gz| zgKBnWOu1##(I<;IC-=)*og|Xp7SA>=Jyd#PC^Z11t>}JMj&? zVz)t2!_u$Lc(3r-Y$iVb{-f_wSyk0GN0>vB^Fe|-)q;1%*oIrATeRNt1i6BylNe^G zt9xTLi?~^25!fl>SHM07W+wr8lMhtlsX=NUUS9go7#^@|L@q_9d?88=Cq>h9eIvt)*(q`cm2&zB z29;&5-on#mE4%Wzjk}pT(GUZ#uxN2h7#dquB`IaJR#RlEww5N?=RP(6adv&B5NqEO zj;e_K^ByB_5Q{lNfo1A1fQnmJx#n1-kN&t0HkIli+PXQ3oYT9(KpO&%4AgV;0h6KNWkDT&GjE~U*wl~Rtdfm21%*qQp=VFk0Q#f2|Bso#Oi zUAf$wRVv~~;qS#dNI2(X2aPxR^gMWv3&~=b@6H8@qeM15~ z{VR+%Cc+{ObV|6ev|``Wa>=}te~;fx39v7np8a0f=ZixIz3FTY4Aj=Uy~zk6jcIqt zfiGzM$7Cz{Mgseym!6)U$NxEGZ-3vg%0;O^E+G&d@j^u|22`X2MiEX-#ZALkc(FcZ zbOc#WxjAo4wCZ!`z#gV?B>lhiJS2c)Oci~rIe#$=+r2*){wmyrJfI_;5gb`NY10tS z$*@I2HLK7FZ391kqd8^w2guCE)b=yLc9R}dRgO@8^&tWNlIk!c)gVP9%@!V?&CO{x zbF?FQhe7_e5UVaF?HJ7JHye)ptj z%;CM(Ebr+_Jdr5*n&%->q!eXiVONBW(t8T|<0iSyfr3!RjnoRV0@pnC5h|`v1P>_g z9B8Dc#LLZXepz2KFkr#P`d8m?r9AlG{7G7I&qt$HS&_mcSf4XvCF`+wZG(N?2>oqkJWDV^xsU}he7GBOoKZc~ zGECQ-?@JKbgtDZD+Lc33_tM8m&PX+3xYuRXO|oElNab{E+q97H*!XhWBS=Puo`*{) zFG1I+>jr8J1_v;h!EPr4(U`rQBp6{?H1C)SUI>tgPVAC>e4=_%a^t2n^KmN$VK{ndaf9Xhe( z6%yEa2zB<7*s3rQMM_7_B|0C4MN36l<(uQ+sI9g2FcQ_^`|h{*1dCZ-EkoQD8P*Ea z+1ekIE+~-!9VJe(RuL$=yEHDH&bW%rXrwtt{d+PM8{R|`4A^*Y zZXY6Iqdm35xTg20p-wMACbI-L2-x#dNjNXYx=!|myR%PWw3w`-i;tE3UW%5?7Oz>y z%rqj#VRV|7vcBFeotV;1p^;6$@eWspocx4c-?3KunCB9JT7TJ|{lsmJ6#!)j*Ar5) zgJDf0r!R?)p`5?f)@0a**K=e|Q9j?(3b||*q{k(qqr1{`lZakDF^!KavN-yrRjjiz zG`+1qt~C0*MuaM_Z=_T2hX^-=Dy2H ztZw3dsR6aVP5S@R`Vif?nBMo0fl|Zf`F0K8>R_%&?WN3|1II;2Viu;5!?Yu%Cd~Y= ztLRJ5Ca?x>Qn&Kb<_?fqb5tgLv7h1))~(Z*Tpv6{F;yl0(AsJwSUFhqJf&6NG1n82 ze%E3=dA%QaRJTivxz>geE9p$Q=4^U_M#bkKqF2eM**KUMr=k;I7$?qUzIS@_Ysl`i zWHGupj?ovt|4gE8Ly0;5GW5R|4m$laI5afC^rK%NIVTE5pr2pmZ9@a7Cl;GV%SVJ^ zD|U%W(g;bKd6y865b*7Eet!eEm<}DF*Qu)7X)x`ZTT*)=$Hr#L7EWrZTMh+DSmYuA ztDZI{)~YBS5Zj42Ls;H83Jp{O{z4>857Oj3rB1V&Rfq&RP;jSM6XEvTFRPo@l-e{| zu2{uVG)14N&r%ft0yFpd!GK`u|YbR?gX($$YrxRUIbiGc# z^CR2@V5YMT?cU%#1hcLcGJua4FPO$N%ayswGtw zQg4ifg^vL>=WS|NaEhjh9GcGeHk$VRUd%Xm5iGOHfs~OS91Q+u0jU_>t#41W4Fk(| z62TGI?L<0Ja|l^;dnb~>yMx|=JXk_Xlj%eh?Vgr%DsJ7z#_x_5tAOtJXn>J6ow})8 zkbOTt?SWVhb+w^f=-ByF@G_pVX1PT`S-LTi4wbPyGfZ}{b zmjn93ldl{{wm@-lHsZU>RefKE-PXZEcf|TLMOp>UmlfykroNrf&cmbQ$-*d~O7?2& zg;O@ii!{#r$Lr$Lh3e-c<64+y#4aQ~M#FG5G$@w9h_>%c1(NynrXkCZ0FfMs5XKkG=fO`UIu?SAzpW&NIV zc!9iVwA3mrQz=fqo3+$0yEI9Nhi?ZJ^~Pt~au1}4KD1%S8p{2%xa$LoT&i4$5+=m* zYaO=@kS_lRWYnSkU6D&!fXnr0I(ZP0Ny;s1aj9U>AW?*!KrUm?@Ia9BipzeSUkBN= z14Uw>o{H0-b0PN@6+rAVoQET1G9YEo*koPTQa)c1<85U1&v^23G@WL=BvfzLc6^MU z_^}KEjAYKBNL8i-7j_xzBTlc~Vp-2Jw$Z4>ciHt4xwMXkZ{5n7l|`=wOfn5|CL8u$ z^$ZLyHRyh-ts-fZeup>>HLY%EN>>JA+o>S7v8g(LYx{GN--a54#B^kl?&t`Z*x1=x zU<5g2l5o4Z*6F3#P*tRl6i=LqUkcqvys-}I2aXcTH~(HYEKmc+BI{GZd_W-Dj!+#1 z6ze?dVtobzbxeTT*{uN^usTstC7Y?=e9Qi2+TMrDb#7(hqpL8ckSaSG%={3ts1HbK zN1=4a53}m%2r!~|Kwr%3Xvh>&j|f+K3j3sXazc)ih-8F}da3B3ban*;w`aR!P#sbg zj2j0Zqt1H|WB8c4pr6Y&6>|5>qi|w%3v{>rnw#MO)aYc;c&cf4%Pda{2?Voj-O}KE zzmR*r8J}6CyvZJ+T3-oicEmG8Fb|A4{s>fd-JP2IUWBE6)zJqx@+B(`%$5)~`0W!y z{QJg*JofU~mBvfzu~=G)9J^qa@M(_c3IvP59)`WO0KSBC{wI7`n_bHNW5^ilbnA;& z#!r^@fO2;y8S&FcYWS~fcEn5Zf8k+g-w}(x+jJ2~FW|a===x#TNuKMN`)5-?obMYFxDvIeC96 zGNRF$TKS|4VEv)*GJwL8-yOnM^N$ALhk&Y9u$@xruUMY@3{rv!zUzxfWkhBoy5%i5 zjvRt^eM9}3>Cxzm-aE6WT~NrU(w(ZTe)Yb;@xD@g_Kr=DiYxt++uYs6im>bMGm^*n zHgl6rwCK>3w<3deaUV;us5JTPPQXIQ=NG4|tL+Q;RCs|iMBeOEvVedBHf{MVFCpy3 zg&+FpdRZ9Ig*e~78H*L9spVsMnf{zwlQj=O6bf!dF_p+8oYt-cY_+`126m6P;HdLa^F|M^NZg3znwVFf+Q!{o#sGK~ zyN+^!II)6&L0n;@9K(L~&tCgtCL~wZcI?=DC5a>RGZPdGSVPJ-?%)0n_Uppjhdd?> zo2(rQi-xkjb?>*z9GhLL#b6`AV_#K$#pe+J<_fan`F)s@6J{*euMp)|=o1X$_i|@7 z3|Zd2<80KYUBSm4ahCnx%M9h9!!jMV$ks_C!ga-t8t*@7)BBV11#^*f`G5bN8M z%;+{G*Irs*ZpodP8~&;kuIcw6-u;4)?pYwys$iMQ1e?>yN8B zaP&2yK3Vc)N!rRgvY%+Rqaw8b9EyTN#a7A6;^fgSnwazsjA%h2mA?TT)}#GidH zkzXM%_NZf*bF((HFFoyc>(Uf{s@*Bp-pbOc(3&Mo_-(7J#h2pZTx@nCza?+uW8yQH zHC9$$KLdRQcqQ@warIVVZG~O8_6h-lODV2}0>z;e_ZBT)+}#`8HAsO1Ews416?b=s zQrz9$-T%D*e!uV9*FMQ<4l=Wz^^7s*J-FD}H>qY97b9X*)6eTMs}`#yry1Ck zbo>c_bW}Ik418`k{@J=SDeGrz*5zmV=2folK{TChgJ!AGcPRs%Hf_D%g*j8Xeg4wL z_l?EH&ioq$-!Iwd9cz1dO1g`UVL_9Dx5lR;Q3g8bhZI)jL{)6k+4$d=;W(J&I^FA4 zV#khRlFW+a3Vk_My2f0ljJuA19QF}cH=(GLlxM12pXFNj>@R@C?W4ikEi5nytDV$ULoEr9l z`?7|#F}49m~kA9!C+^2?ma zmy-%S>*jwx=hl-SQt5=M3jR6eS9@*@e?DF=DRqrmojE`7q>V9+89Ml`q$+~({?3T1 z7sO9FEw?k0K2u@R=lp!Ag+F~htth7Cu7DCz1J#Cc@u-%lkrl|`G%@`gGGdQQumPk( z(?eoa-~W^#I{xMYVOorx-JzLa;Y>*hO*UIP??VVB(sY=z>2QK!GdI-}@_1Nj3)fG$ zEa=8pJ5~^VJO=3k4k&4qHsSALLmOnx=;A9qI0#b?H46{MC#xk{Bdi^)=JqvR@4|J2 z$E4+;oj&D^y0m(%B`x(ZV><*Y2y7D0JUlM7o!JA00j|7URhCY#N><9z(cc-vYG7|* z#KqY_vGl~u3ZbUKoZI%-!5}v>G~kqzchqjnFc%)-uX&R^);z^yeFT2Zh?D$x+e?%T z;c4T#p|Wz{J5&;n;x_HRPDc;gTkRd%gil5XP_FU7FnzjLQuX5gjk7T`Bd*4ueTW^b zPm3&~ccEb+FgwlsdWDqpQ6G?L5@?dgx8?T(gj-UtvD9sWV4whSC(Wa2I-CTr#uAzR z)d3ubn1)y>W6(p~M(LQt_2*M0}4ygM$9y%eZ(H(m*B3%o%Pd>iEe8#yjbakZr!$Anz(Kf^~6e6y12 zml7=Z?rJos1$c%^SyUd*biSGY}%Tz^er>eMb&9o3%a(N&3HwI$*omh!KgBS^I?= z)f*>Ib^8Lo^KP|J%k0tQuPxNIZ9i=JZB4fcryR~{r%qa>5|_MYF(BBbPH6rWQNFK@ zTLJg>`<=_e3I6L&IL=3|K(n6-Uy-*y$jc-fw_D`r`g2HUXq@!QTte4pG#^6Z%l1nw z)9xo>#QKl+?h3EpnyZ0ff0wT&5RS-2Ng|(22}g*3_xHqlayBxoR8V!2R|ti35wwTO zQOYCb<0CxQn?>yntNsXw9cor&u4t3vB}Q;l%MY`$?XTxDxLIv>&ss)M-RHIGq+y-U ziOhpwfm`?kk~8@3=G<8nCy#8f6`IHLuT^C zn@A$J{|2JwL$>iUxNs)P1R(KBV%4$>J*5tIvV$ z0-iWmO_uWr*wgW`waM ze$&Fh9*mkTrNpbww!x$AzNzUe z&UDSrX^C~Q9AoQN`ElEUIdrZ<(QU;+oFn!epWCQ>zZQnGavSJg;OBxf<>@(WE%F4%dmlTpj; z{xj;!s5RTDf=Ow9&mJwe>*0;g4Fl_&=iplnmMaK6`N}BwEMTX-hQb>mCt7(!X z5ch~(#Y;Vua1Q1_2sfV<9%<4v4KXK43INGXP*hh_{Tzpe1EmdJs|tnK(b1lnA!Ibi z+@y63MU=aEx<8p$O=d_0SU#+*7PixLNJ&9G{Vh!^#7$5dRBxc4ls1-IsD*zn;Z-)w zQW9#1#A%2}g+pMd&IJiCpa)%6l!7t#54l^|QeEwf4KLWul)0hZQD#0uC$`@;zbhkq z;Iv`$Hx16&l-yn;kLekm^t01Isppkh2e7#0&5y9v;&T$pr6+L z3)a(H>fH!ZYa1R)PfmAX&RW8YtX=s@wyp(9+dTc8oFY+WjE)Vhn2&?o!Z{!r2o=6&0JMDT3* z_mhweIBL()=!k~R>vjLPD-aZYv%@sHwL;igmYa#RNKBOTyvL9p=-u_(P7>8W@>3^o zlA?qz-+W~5TSeQ`-omp9z9-aBG*IW-6&9xve0bB zmABdHNc|%(Z_Q1a;K(nr;BwGXXSLQ~x4%ZO$k2LGaBUH;ZF?{?J()uBJl#by>~=7n z%zt$rJyH~NG%?8JS7<@EQ0;fa%`!4v;I^X76_P&M)n`%N!dAMYPd2vtujCK2oE3wC z@=Wa$Nhq_WJ8NEYB>ZPF@ypy{Wllnj|KPC}qmZUI_S}SJwbg^i=Aq5qr0Tgw}IXs7g7A`)gKFoEWs{v{L4;iP;>Fc-eyYs+grr8Se1n)29A zp`Dehmq9GoufL&axx{|97>4gri`|d-=#MG-YU|~_^VPi8{g0)!fLr-b5avQOEkOib zeeZD}tD>Eh?lwdL;CQ|T^!JZT)p?eB_3)QGnL`t+L6+uL8x_2_zXFM2YW;5rS2f=I zt0{K*zcN+_ov-do$2%z#>SGyeZ1@s)XCRoKSAu4l?U;sH+Nd=Hw7#^bTGteRsVM$; z-7bKBBUrrP`4y|%5NQ;BMiC;;?B@om8St+ilU!tp{+>{|m*TjG1?g6gpj4Uo59^sz zsC5&jU?G)1R1o-Ka%P#P-K$0)yEra_640IGjJMISGicjufnuHF+%QLPiA!z#YUxu| zsS>m%BQk_uM3bm6?BJ`bRHqAfY6ctLu`nCKmEK#jtMjGQ(dBdl&C`tMdYo4#=y0B?@y?L*P9gUzPx=<0%${OAQ<#7Th=fv@=FbrpBS6-rdexFzI{pJUD zB)haVth<9JZ{Qt)R;N#0A=m;yFVJcBYLfhofct4iANhtr{!R+N%OC{JN4c!e<+eky z$nT0)==_|P2ULxlCEcueBjOy+DtJ$>$IQ)TzY*A&Z6T9CEl^X$SCVf)tWkXuD(w3q zlhXU7-gW84szy;H(;`3GbG23H!&#?^_CdW2_OgTYuffK=kjR6cv8-e7RRxxo^J3P& zrB;1<=`-@bIPZ_YbNifUvUsi~D_XH6PS=8^T-+7gl4`hJuBI*nMch?eDE*YiI2Ctu z3x6ZuEae40A^rI4wr{u+K;d^EU_H#bbi;{VaC*rZ2Im~y?W9dL)Ku0|c!)xhcCL2M zi1D^5$=^1z?&_hnjO7z2fxg+`N($r^R21irfQ^=}sC< z0i5n@Gi}zSjTGsZ6c$x|@^U>H7d41)6sYPDxJGEFG$a+p2jan!y@c}$0uHE$2S-!6 z0}LYV0FRh)$e8bZLdAV;odtP9&?#^BQ-t10w0solBe2{7UevMJ*@p9_@~dOHIE9Yl zOnq8})azJFN=rP`k$ZW;y&}f$ECT(KD;YXpcvu(ZJIDbtj#*GMVi&Lq{=2`o@3O2+ zzsT(~RsI5si~Fo*Q+6dL6@Tytli7|%B#(R_14UZ6n=cT%+W&-{oK9rA4vShcX?h#W z(IpMs59%D-0jxNpQL%V|*-ar`+JlM-uZOH zBzzZ;M#`}FZ^T#YX-IKTfKBSEaOCUMh2MR>dSl%|c=}VqKi`|ktHF7g@Ai)EM4_Fx zL2CMK$~>GcNB^(Pdgyt<<pnrra=B3R&RGhHNKFTGLa+fLea z;Z~OG;yo(4Wy;u%K^mri1zi33H83Fa^7C)d|11(vl3PDf)%rYKyI~LnwQItyVR(3~ zjDGudukd}(=^eVQd|>X6zNG7VHE5WWiS>Ma`_T{gY1n5#30{FK0(r}*VXdvDH@&`| zWzDVsYA?buu{ikN3r_JYQBZ(%dkzkQqo_{2eTScW$=|Q7qOU3#`d6=kj=rlQTLv^E zcss0Y*w*OomVd5%1U{qnxX9|bc$~Sb#u19m&rG8otD}J4D+_OAsInI9(~C*gpuJPy zc-tFez4d3hSV%&lvRHM=C$ip{loZ!(rW-8+kA+w)rlmH`ZKh9-u@wB^rsMSx>$Hls zZ2!?DxsiXt$ChOQsU0k>QZ`lXGNewc5+oBgdr=uE41}CgnRr~1tXOioAQFL1ZO%p( z3=d?BmjyW^6y8oUu1P?U=%VX%|~G_ajGH?3NlP=GU{^b;O6A(V(<6R=3FR*k4_c zfpkxx(C}13@pxruz^|;I*$@AFEJSedTg;T| zO?UXPx+hf9Y&x?C8FDgk@Qo?sSeltZ6*zk$Y@4ps;kau>frl#XG}4)FIsFCOR+YNN zYJ-YgbkFDRgsfDb&oeVzP0gj!m9i}j!O#GL*u5hSQy=Y%9_}mGIvc33`me=|>t*La z+vc?>TmEV(C=*^IdtD|t#BSz?7euX6CaY37TUJ)S$m!z+p@o|Hmk5{rJe{A`c6M@i zj$_9L;~%*)N$uM70>=X4(B*SC)Z}%El;14pFTf$o549Ft=j#_FdIf*n3Us#Sv`SR> zKkN9Y)X>Va#YTuwI==BD)MfaES=>W(`agpCxK#LTceYY_hF}i9vex`G)xNunT85S81{uUNT@Y*X}3c@ta%It3Z)4dK&H;@@nD6pC;7&n!qE3L#!MB7Dm8=l}pM>1W>*s zaTwxdkeHq7FU=>{)>be0+&j8(@eWtCwe{U0iiCy)=Mrv#=Ru-o?~kzZeqlEw^=G#N z>M$eNKFo=!$mY0qmntVVgqEE3r_}~hY1ZZl5)2a6iv&_I!sHef{`VH@ZF}=Rs%$<_ zg3wT#ksNlT8P~x%XbW;J_WOZZJka>KJa`^vzGI%sHc2e|k-6KFP2JSCaN4rb#+*Oe zAu1*T+OK9qW(eYeuU64cRBX@*1L66~@Ny&Xy?potu+CO!GJ!Ni^Q6v}I&N%XSw=A`+G6yC)(v)1cPX ziT2{q-wZsjM`qg*r)ruR)tGva`POl>S-HQ*4XV|=`RY3Hr%3#L-VYKhXeTEKQ;v$} z4`Jc!zCFjv;3)%++!AKQ7x;UBKo1e#%;{;lA~MGI|7B4g(tdxa@_X^sKv+ioMqrZJ zL-Za`JHp2ql@Hmw-Da=z4jrDLaDlzGa>V7N0J}mz1Q4l0E9!ao*m33m=rS~I;WX-? z?}9E-j76aJ$Mwz4`)Ac~(&gm%cvvs}c8%FkMlIHrKxmIwcLudN!980$I0MZI3l_3t z0T=I9F>h{3*Q4)H8=%CHQ`R`uoUZx7iwI*Dg6_@Uq=-hb=8`i8`IyQx*T7X~wheY~_-x*q{A3E%`ZnP>$D>UewWEnZ4~ z&VR4ZdX-If-ZlK2k{Cg@wjHT*E`qm>fiU$o5UpvxnOgIJ6wSa40__-|6+mVn-Ut)z zU(koxZX=m&S>qk_FNDpM)3;)2Wf$yM(S41CLhwnBwEG%I&ex^TH$jFYiugbJ#F+&m zZOm_+j`*<8DZ|G{#?Q4^--p!@K@g}Waf%``?${0ZNlvM5l|2kT^q=P>dPTJrr}zPP39*kR zjxa9<@eG}grVRb6stCL1jTpG`gU;M}=re>Kt?Xxe!ZG0cmMYDy!#DyJ!e@oK z`hO22p7P`EuUMg3fj8GUnLV189Kp{HLb#uwLd57q-hFfhy|zyzB`0?{D92-KD{h$M zgM1FSH8@ZBLZlAp16YPG-wvpp5Hg5AAuEN~Yh6M_C;tBx_#!Ors~b$qjJB0QH0B2Q zmSX9(9FPVDcyUe&UujbD&02ZXQ#2$JiZ|fgXtxs^;#ujy2v6LLS!6?mgKYnL0UWz? z-aEoBS;qjh1U+6*lucB4KlFgyELw`a7d)d(7o^LLa!vu*R;NXClz7j$1bT|gOW9T> z&63YVE4%RBy-yv|P9{xCH5gr|J`TgreI*w4Oi+)cOtT1wv#Blp_Wi)0P_o?mqi_D!Lc^hCtlj6aAIQQRCX>9%8VvG{eA~Y6^L*zyChVu>k^%&LS zbNOV))Zu2K#^s{Z2)w&`g0ZyBoyyy}H9`JOuYMifduRuUvN?)(3a1rpDggv#L9uKz z<*7aqxf&)0HBqs;lV77!fy+Veze9V$*x8>G!`_*jfvOF2{2w_+09}swGb~9`&5Mkc zQ=U~+LtL}F!U)uT@x_AnSkCBS-U2C#O)36!#C}or+hlL5`LQhNoWjbfBJGOz@)iMu zTS;~CT?m4;iL{FOa`DzQ1Ztm2r;?gB;knf&mtQoFREEi;v9&1Oz|u#iG3DJ5oOSQao6@44eD}A$Tqn4_{oM>#um0Wa%>{6G7uy<*m$I z^c;!^dpS5F^d7|}H)37rLa?0O>gN5GF=3S6e{P)=66A8rC$+C!4SyhGR~+u|?OorM zuANPWQWD+>mw7##v9Pi7!CqhD>RaJMS}n1Uf>vTb%Y6H?T+#;LZxP4f!&2DY-*-*h zDKQY>uf&p8mK=0e-w$Et&;V;XDF3`kK0}A$wo(sO6B5cVuazTgLJTpBsu~9vp=)-c z@AoC_fS*Q*lBp_%IWv^(xT82!`0ebLpT>s@v&$BoO#RF~B~46d{)ve4-x7}tWY;0} zYInCkt@p%lc8p4k{ z0tg3?6IG-xq6}euMs{B%o)*K&h}7YkqrW@n5yfgpT>XsxdX3mG8rx-+!pb4r#wY)$ zpoKzrXQ*?`+$+LkC(s{I0?x%y$+9jzYQTkw*rs3sq+$e~#oCZE(8cd8e_|u%eye(o2HQi?rkg5H8b-+ovEZ+ zb3_8;P3)-HVbdQoW;<^H`c-^j;e0UcMp45eeySlSoKEUAv#f5UL#!3z^GfrcEBR8Q z{6E+F`dsp96HUBVZkQB=;g_GLmRR{}ULWu%oV*n#^^p@wv>3ovdJQm|xxCE~F(f_P zE1&F2!fIWwOs@R!&u!5Ux`d#K7<1J{R(u5b_v3qCqGSN?>ek4D!P#nHla%N_!06)N{Jo|(?;=r65R>=kF>@64kyIS$ydw^7U& zEfOuWxf%NA1H4$)6Pw27sfWb>mAz@Uo5<1mgPTod8%=+wIHET$`9~wwVW^8BEN4sR zZ*z|PZfpB&lY(6FIR5-2MY}0P$u#TI8Ce z78#T%m^VDGjJFLo^)oUWSUNrZ+@bf|!9N!F=_9|eM@Y5zj?l4*PuB{IQpAUnp(`9O zNpe7n$~YEI=7wa1{}7PvqPHp_U15sjX~*_c!6FdWjQvGdz-~Ne#I0a2$GU+s%`v=4|Ojt)-CQpK0?psTUpXPmZ;7*&|;M`_f(JHr? zJmobS+a6OqWs!hw23e4(7NEyK3L&<6kQ9pY*~gUDt#*^4c?cY7%)aovvzfHnhp7o(f32yFNKs@!5DtvU0U~NqfUW z;iszD#+x;v=qJm@)?EX49wcZUwW)?vJayY%y!;9%Q;0PBriJF`wPrZ|&RyiIk4BIE zBYM+)HARSQ-!(kOJfDd?tz7QP5~`lGDF+Tk9+37)emFZc*pH<2k(p!RvDB$8IPrZD zv1F;z5O`Q{ejIrgw;0mef`8%5W%{#$=lx+Zzw4n|t-YAvBc!d&&gX@pr1zo5O|~r1 z{l9nXOCvh&b@-WmEl&E;@bCvb{zJ+7kyZH=Bpw{XwtHuhK9x9;FV|qeqvy|Sq{*2m z$n(8T&0ds&q{{^(p1oIaTBX~xvxlR+_T2l3QnY8iGi&++QF_Gs;Tme&5SWka(<#`E zg!V}Y;36xixGBK%s2S%dvoCXTq(+<#sKLz$q`mmi9O;cPOI5T8PFW*A23vY)VFlOl zm3R06^;D9s)Cpb1LQ~pmX3SZPYBh- zbdCqi2w5GWh>{F-o%bbu*N5?FR^$HlWl66SWHw+5YbY6+hJAX#=1tGbw;*rUWhciK z{qFgDTJqGOpMEi zAQ?T7szX)Jw`ezzI{LRPu;+kyaPPy)rL3P{I@(=8T=B3seHw{(*N@oBU7mX$vpbxS zAK|=Kucn>Mh6XkZiO-sMDgroLYwLF8(l(Au!`?`0xZRl5=|dVL2B;o?5> zqQUiyQ(1vtEb(9Nf4hNR-1FP)q_4D9;`8$4xcSO6R*(B9;_1lAY)*DB9aFSr#d+0Q zg5mh_;Me01G998jl`nS|-R7fCY`zBhdFa-g^jA`CH$Gh0zMn;$EJ9k(+FsD*ub0Zw z{S1pJ9^76OXzoH4d`@mIZ~t;XO|9I9si!|U`P_8V;+wPXt~{o%sP6agTn#K-GtL(; zWSK+{?MB1j6JGpnZx_pU(Rrj_wqI_+@|!~>Lf4;C(@}r+>(!rDripOm!;kSL#G6dE zrxan|at$Vvk^Kd~$9m-BCq5r@MftXurWXZ5jUoQ0b8M~(T{Y&h$sQBMz1yCo>tiCN zsvS5nL)Kty%s;sG!pkqCVp7@XO2b!y=V&);Dt;&Xf37+I*&x5S|5D!8=knFpRvnJb zt!}*<%N*JQy4>@n_(wr!PfD;&Y3J&V3p-c+dWaS5M z1j8uEDxSDLz=tTC|FxX};8ggIxC(w;GyMpA2VfYdI1rJ=X#%!a{H#GKo1_&l2&-S= zMa0YBdEc4V1uf`GS>y*JhX|@Wb=(dZfmx^vgxYa3rgQfg@X9W`43>;vxrv<4q z-yu}%qaNDtw~DXEj2E95U}rZJEU@=t0JE zz_$1SRIn=a^b6kV%=N|_`SE1$cnqE`+oD9Mg{~Y^;RO?U$@?u>KLVy;RYbuc#d;ff zK+mnc8qvh zIERrI8?zvY2tsd?W6jTG(OGQ#VNvhxWA#AXUOiAzNujDfWaloy?D^n)u++G7Dt6^+3jJI@&`prmQ*ojFZz)Fyi*mfAZaH^y zpNZeM0tapyaHYtzpRFQJs7}*yC4YDbt}PTH)yQVa^lz!#%low8a+wB+nJA|tfQl*R zJrc4m_s~X*hHE9`sO({3+LC@@ohZ~fZd2>gc>eOTwzi`dn|qdS`oEk6_|Wfl$zUN) z?fZtUUa$$4o%o$J@jLC~t1+3a*leszxxa=10FLgzayUN}1|$Je0087KszE2TAsIoU zPk=?ryLz}f1(A_PpZ&H)xEcf2h{Ja2&_<{7_p+TcGegi+=I-V!B``#u1(g$Oh9l)G zA-8KqQQm=n+bb)cBcgPDjIh9Q$rIf9CY0Z*DY3>~UtPcHP$I3!7b8Vh1f%RI{9R2N z&RDz&SlbVPL*Ez}tE{QlH&-62Tfk#;)jMSE8(AzcoBEh*XSaf;=ptDkAEEtwe^n{r^`yOb6n?klrtukv?(aboG{yxe8sT0V;DWL3LR zNtHWVr9x?(iC)3V$ak!yl2_o|AD3Q`id|2iCe0$_dNR$MrJ^d9PC*DhJ7i*W>4Dn{bLzjx=Fh@*(2T`ha z5e3YYC}F}dZe4cp%!teIFbn@~!_@t2H`QX~3JSymCM{w`k+UF*yP*&+A&)UrYw#~l zG?#Iv!eL@E{k5yca08QsZV_qYg4%_Q-q6;cch&Omx)Es1i5!|jXQrm(rdItIuJ%T} zmHjqO9>Gud7PhKR*?<03%a7I;lgNhwXNm`Q|d@(Nmv>F!-t)+b@GY z-CdQCUh*sDijo&=wjA0)A?C^m-U?%YY}!$H#bKv08h~<&9?l4hA^>{!f)Mv0uW2ON zkBu~EMRTwNV()xSOrY}5Gr52eziBrjGOZvs_oL=jP@zzcd)C(X|r8(qgq(v|Ai*x&!(z z-)%sV17ViQj(ag*dN&^L8@CC!pFRxLax0{Fce3!F{&cI-T0}ZXN=!yyZ}(UL*-P{L7BoR#*;B$$e7i*M(O2_ZX!48o@NL{muv_v+wrFYRb7(^BoDYhecK+Fz zn(9W!?ZDIZIzK=}9oV<%D?8ge)wQkWM?ilJf0ICQiP(zy0_XnWUb)v1oer$Xg-IY+ zuL+(VzlO3BZfceBlqiNym|YFKgms~n|DpCf?^MHY?ZHz%2?;v0g<{qXszGXBeUF*3 z@%3FUmG}{9;B1c_ud->`aSX1+#K7R6N@tR4ed*8WQ?)_`q!U%1=W~2Z_j`~@Wg_^3r~Ll)$VyS# zc0k%=IAQhChQTCDpmM6mS@pKYHnf7-+VX`J8qt;$pFeRw`^3XkYIv4i{MD@v&17V6 z&!lYkTfDxy<4NCT55!L0+2td)$bAg!u!7a$-yCj7$kl3~SB>|%%+u+e5to45pQ6i3 z3O*0zsaQUt>nEw0>%o(;V=gA#aAdxcNs? zpMVBL!WMD?SANmdh+X0^M&{SO8@{U9V^ z-LCF)rPn1*+M7uvC3JL(^S$HV*k6|tLtWR`da0i+e%nrUt%%)eF*U8*`U9rB>Lreg zK*wO-&olAAZQy>Ko3KhU-6}_5=rO~euH$fKiU7U1)4rkG?AMJY8$TB43AFMKFDjxL zm@I%Cb*MQwI4EOofC#KL1&k62!ljnBA}5F(LULM4?m}MxsWRm-XZI6vDdYU7;>h<61Aj`~t!F0W}y@HAO{IOL|MTNYaVlO&5k1rTbnZjKLE){1ajH_8mjw zC8l9_XJ>P|KCgg4k+;!O$IohpGm7ER_RYM4Dr^Ww`#nk#d+ly0BUQK$XD$Vd3dPy( zOX=stXf#=@diG_I&%^!wA_+@6TO$_89ykS1f`*Kk@(48!5XFq&gN*IpC}QPkb#x1D z@U^3gh6HletU61>kRYP&1U=R)L>B#TMUkn9t)yjrH3^MSB_Bd{zFocE0yT@q1lHj6 zA^_SsR}alLX7=ga#%4Wk;}Zm;=!fzN;{ zLpu2_%%!;~>^A334!a;_BsdpqS-_4YoFKJz_rbXnf83q56r_xFpZVH#B(_2EzkT4U1pDy zlH&#>_V9}9f^|#P)iubJy1(GM{fm1>f8mvg=2v-f=Fj};nl|>rwc#}YG8;VoKqoTi zJbi~$-e|OeVE9whv0s?L1zmQ?dY)?Ia`dOJLf{ivpQl}K{z&wzAk-|LyD#Xft}NNV zc|u{6-pu46PRDMlBQRv~$4$1ve+o1H%U@9&`s{t=w(MkxLCr3lFS*W&%E4eCF(Aol zjK^33;{JNN!P9z|Ixt62PAB{vmp9zn_to_V7RLQ%z11B~X@6zLAyWl-{RRDzSpI5S zzrzzsIf^o_y_}Gi_O$&X`?Ao`b)WunV4yUAZqM((G|P1_AQ~jQ;4n0;fpNH<|=sU zr1r@Zpz3gA9mFbbEx$!G4tAiXqDN9M`760pjlvXOy@_3~{0L0mC4Emmfr zpfjxF7;pMrq5L-pogIYjvd(n(-@q8fO4u=qFNS;KIx@24RH8ya9OeOd-7NDa3Rypj z(Es$|0S;RO8CnRPxNO-Y6;J-z`h#|WwC0J%4lyfv>Q>Hf5pX-MYy{MYJw1)XKos}h zhDXxf8|wO_knWLA+Hz|_1RJDw#A3$eua4Fx-0@C06MCX0-mp)`bGWh*_mb2ce#p|| z7@Vym!z0>F0xcB7lHDe5MyLrxNFiucOqxH%yz^Jezhp06UK}1a2m0!SAd`(E%sPgP zFvWiY?-~gIlHK;6$L;S94(ydUXu`CCgeV#ggs2f35`@U%lvDbe&pS=891Zd&m^~T3 zhs6>fAvsH$14Kn?omfZ}5AV{?OtQA#|72F?_J6EeA>m$i zd?$bZ9d6#ulzBpU$*`zIsiQ;*M|lb#zIk5hyZJn*2{nySG~d2j2?Z9sT0j3q-X2&WTlXv&rmM%ChO`WW>iV{p)*?%kY-`(hv&75vCK| zPCL@@4!+zww?)K;HK9wOw;^U|ILk)7sn$-z@8^;juru$d;DKF}EE~vu*6{TF%O&{L z=XaSwuLhlT+-LjVpnYPXG}s0E2#Lfvo(>s&8408(GvvJqP2vw*sI|N{W2+k>9TBE8 zdbd@@#+x~Ul-wM3%UL<6lNmKrs6y{@oA!y{_b{O82dhu`+FGWS zC;>D>Qol{)9BM7$uhg1yK{lPPS>%tulA}IN=clFl9_S2pjRlCb;{7HDpfNH_K?fa( z*+pASNSwIlvoEel*rZ1|;Tp@aD<=p@(0P5>&YSahc*pib7G zp#b477J^Z_UKcfUl;H=_o&r(1uh}m0cJjk=& z+SEY9vYkU^1?iO6fUc3A!0a@Bx(0r22R{)X7;NAL(@!*P&QngM_{D4&oSclstV|R? z3Wn~*o8}m*^7Ci@)j3q3Z3xVN(;J=M+hed$#Kex&ZVEUPi=3q}oa-Nrs{Qf9YU)x` zlWD$jz6CdL)}FMd&(wR2e#?aZ(3+2(eb*JI9BXc@a$&?sP)ahG3*+n;#QQToqE84J{c3$d5NV7Dt9#z8h5O^?q-|3~nB!TBg(Upow~$<5|&knna} z6pHF!VPTLK-cEGgO&PXBNZ@=s`i8u5$5uWi^;GYQdYc3|2awwxt)>G|&@^Q>{Ses2 zD8*RIlLEiMc%b&EO^~;M_gd518Xzhf3Htz$z}^75Vz+OK(+kEEBjzOk9&8Kx?s#Dh zvUsKy!dNEe5?$DXUF}aHC;xQWHQZMy*xC^R@P0Mh(lvtN4|4QC^7n!4N}85paQ;>G z0h0Th5cOmu2~9F0I1mBB5Jjo`wb@0PI#}u5(ToZtgU}FHW(MyJu>WLOihIu|Aha=X zelSfpnDGOq0Apj1Z)fjc!v8KoE*IdB6pd*gbPZsE3fk*+^oDf|sIf3Ogo|pQfpbvC zYEx#q>&gNZl^M>*`6+zB^)gW&qdy->a|%mFPdDMyH;Vm!_nAYUc^uBB-Q&Hn{yd|r zo2v!QNXv(xsT6dxR#!d6U(Yj#yM87m&y0^}#SswtSWLjNLfEu9sbmsW$(`q6=S4%> zDd}pNn&k%qf3cvCvR^}^PAlFp-LN{@n{&MPSb|xkniaugERC3>^J}(=4Bz z?EN@Pj)(JWMT`rS1=t5JnlfGMlouj!V=^F+D`Sb;jLmb~_++r?g1ZhovZcsXuT3BG zID5a>b_tteOdln0tiNqAet~~w00KJ*tj#=3e^~! z*kD2&N?njVveFmsR6ZxxG$o5#9h+~zw+TvGWA^&@-_2@+qrSIlRe2y;x*0l}u#QW1 z>II5OBW@so0)#tnsrQ;Wr~aNnVvM}u>P3F4fLp={g##U&)Y&!#$&gI@04uDd&!X=m zFsnK?l1&>&79VrQMS+G2IE9lLbj#|$X%E0e>^?`=+ldp6KRMSCA59a1O+;k~HAh*`uNc`skj<_+&rX443vhk)p( z65D7P7mOlbA$5GoZKWg|o6LbO?CvscrC_MYplh~?5Z<${ z@CwvlA<;f~Xb(fmKs3Z5k81iGc5W}%xoP-#_VkCdR9)!Kw=_ESHRnGCYWkVRDcJ|Z z4;dmXxnO6@W$7nZVEe4FfH)NW$^ zlHggjnC@qwYH6wEx?$pLi1+`;(|bp=9k>7gi6FGZYEiqTRBb9stWu+`Rjs|E2(@Qy zqNvv1qc*k0-h0&EJ2thq+S@nx=e~cxbDW&xkNm~^^}b%u@wm))fbK(nB{C;662ruc zJlxzDH_IeXSTF%rlwW~#$e+YOrDU3^U(<|xYz;9xnp5mS!gwz433&Hd`YA|*8{8{` z#NpNBguZCiB9ZoR;a(ez()bBL5*$TL{|QV>j?1Lm@2q74QAiRiD60fbGQ$5JzhQ{t z`z|F}UtGIRBX^rXB=2rmvytNNcy;piel9lq$gD-pf?6!tN%Guim%To@e`b*C7tM%#yNv+?#QOFO1UAgfMRJ(lf{6oeHkW z71Q-Uvc;eO9FSDAMB8Yl;B-OhlU}aOqc6K!c%SVLN~Rt!VQFq;ApyXd>&tu%|eIf|A{$pGn~O z--#_BQ$zcEm~yD<`SF(?dC|AvEE_jAib0f^ZoWsu1txY$6C|%$-q7y?W}-<`BDIpyLXk{!nzV#}6Eoi6*!Chn z5O^X9lVSpHANpgLW1t8+nGtsm&!*EePB|jvITCtBx^Z=aRl5IP{R$&qB24#=ZrzWV z1e~w!Oa!LVhLlLNT(+98mxG1J)ivJ5GkzSMF&+F>nZCY4TK%tZvNy23HweFW4(I6~ zLAYec3c$8?KiH3km7I?l0x^Tb<@IcZpHog=gYe&<2-{L_D=|9_f5U z`+PNmRDQ;KW@2tPcqdtc1v`KNBm)mT zKRv&yQ~Y847OSE)sKJo?yorR!1mn3{vDTyBcrW0JnE-&ZpLd4W4v7Wye6_reXU)lR zT8Dr7#;5eRE!RkJ{B9-*-0-h*}J;J_sGPZssHMz*$4$={zVw;iFFSMnIP}I< z0Zs&}Ih(Pd?=iJI!ZTZu4fmy0wL7V}RT;(aJd+9A8mmr)>P4<{7^Gh$cItjod;I{K&~Hm#MG$kOtk$r*F!p=@c&|*RMlhmc`8aqxWrR6{2(d~(g{Q1{( zkBI*_SgWM$Na3vRiLvjEMSho+x2MA~3VV)KILy)|u%9OcGnPX%me_-Gy${O{Ng8Nx zIC>M?+)gK za|2LVQpUMU6H2mg6UZE?d7mY?C{~;kfV;9jF3m7=C<8j=0w8A;SesS=6;EAZChhh> z-fur~Yr3>YtZinC07$y%Qs0A_HQai>PSM~;>eRbTMd08UMQDlf1#S9p0(GsKUi7rP z)K#Rpb~8{C9)*7V5OUEvr^WM_9^+H%8>aB=9Pvy1m1|~Y z`Ri$fGdDp%FpL^slrl^%hTk*YUDI;&X^fJl9{XYlne6A@6B!q?aH+ht-CP0FK{JHg zr&BJ|!bj@p1(4fL4+s z%?JyhsJ3vkSMMv}_|guNVS&Xg?0+W?TPKbW_n^E2Ybel{ZNxKtjlt4Y`ao8?tKUP zb~nxZR9mdD_)QGu`wZhkmVDjoHmXS%A|A1fl$!Hjxt=cSHpG>aDX=^uYV&)vL3?|USiecqpl z=oHs0=gO~DOZ>CrPqi<8iNB1P)EY`Tiv$w_*^gGe{f%ja}+z-Sz^ zuTdSf*=9NsJN#Vaoa`Q*>VIK`SoH#3L zcQt-&x4$AbmMU3IsP5~yBe0v`wJc*0(i%Wc&i~_n*T~Eh=XEOCkUk}*i_={mn z;A!M$oJNzf);#^B4Yl^Fx{(LM6uWV4?WX5vIm7pNiNJpV%hCY1#(c#@S*(sr?C#Ss zrPQLVDFJ&O$sGLW9`JdO^j$B!U(;ItjHD)JzzwZ3U;2>v#;ffkN+T6}soueZfxw}6Zk+}ak(^lWGzxG4J=y^UrrN!(rW10v_b7&M!rt% zezx{B=QvTNvA0TMSZ%F>~%`-a;yIpECZ^lJ`t8huEBr8D_ zOBiJnE}TRpivfaMYTv-!TyjWETXxNZQk(k;i>&lAbP^u>a`|T}Cj!plv36W*qm(nU z7}ljE5Zj=!&gpT(zU-&V3Bg6K$TE3Nl8aAV8g%ey!Z5%S1y1o5Igo8@Nxp_TaObDn zZp%l!XyZX<04IQd%W<-pZIKf731HpQYwUw{vZ67OdFe@! zFcV!OF<^68i24&mGeHShQUX2!@wN*GKTiKy0^XvsdSI`Up!m9gV-G&seVCgMW%Z+3 z@Lv59$|#YJMNV^}3$?}6ETTf9u3bj}zxi(Y2K8!_zV}l?wVosjg_xVcTN3m!kjrH= z4gisGu__^;?YBTGV1B=0MM=!%q((i~cU~Nf4~{OkC;?K#0a1R#+5`E5IQT4*5#^hO zdUL)aipm(u4ZfmiP-c+D2wwUPn`VMzrPCC2I(ke z3BG#02^~1kr5X-ZQKRAx|ak z=hw+QA6P(m>#F=+OU33z;VVtDJCZM@z>A%+-ksZw6I z6M9`4%P{hs${>3W^pT5F#ButeL2hzpYgK-N=9`rqD!~$moQ%t_XgP4D^8uwmcp<*~ zCv83L@wt<47}(!h0nwohQEce`Gjm>+{rreowsD4+bT~AN75!FE6B1BG z{a?NPSk;B;KslfVV?>Cyu1*sF&+FznZf6QjD}ya&V`JTM^^RG@@j_oQNo=n+$LytL z8Y~11&c6whK>&U#6*lE0MdjdH02u+r`|U0FT4F@Nq6#`^pd(df>N@~ zE1R2SEu}HtJ{OJQZL-g*BO{NuyN|cnOssC!{iy65wu5&F)>~?h0u#4H^2!2uClQe~ z6vUmZfD&(buA)Mc6Y1{)j?AV7?&E29l%gf1Q}FfcU82(3X&L&ugCC&`68o3TgtN?S z2_Z>ae1{Z37n*FHrVp-n`P^31qWM->OXGMm+|9iXO~3l!q2zOFtLaz4xo{#vVDPVH z;E#Ft%@PJtq{4^3zTVZcLEJ}UU#N_)hc$2UFpSC8 zkP9y9V~X1XfrY9k|HQ}mdKp4+-iCx)m)&(2aa_7$D8NdT#5jmgqk9=YX>A>3IOI=t)jro@eWQCHYJs61X{tUa zhM6NCCIu^2)x>MtnX3p@7oIocfsH`$)oq|)v!qJqH1kyrxe6AnVZI3eC9?OXrT%1{)wl$7!NO)IUACTCGkrdNk?<)Ix-MXlHZ) zE4uif39}>4yY@QmHngQIMuNG>(m(#!&^o$_M7~&iNRD-?{D1Fyhr~s$6aDje^j%e4 zb(5q?j`q=|IvL$t$6q3KW8#clv>PYP z`UABq`}dUoqRatM1Q;2nUjzb%kw2aUO9a2%KK0wBHFUztgr)%13!>MQ)jPm+fUpZT z06;of#XQLTC!#@Z_0Jap)Wl6-G9$~MgOVy7R6Nxb z>b=tASH8=C_8_rPlV9%-yyJPafywzmJV?dl7%l&Ou(sARCrX799p<+{OmtSSqzNYY zxU)llSVg)n=UI`;KTNgDa}-0CKQ)2%O4BSRX6I%<{LuT;nM`NZ`WlD{Hw_VQb8}GX zY1$Al40CuGl&@6}m*zX$dPK|QnA>bKeC)?lwCZ&8=Uqsuu#uI%bIVVDkzG1<14fed zTu)nMB)uOc1VU_Xi~4gMjNTej0%H7J{YVH%{gQdb&;H(#_cvs9m?$bJOkeO^W3>op zoNYrkIzJAas>(uo-iDIdHuD9`S9#m`W29wDlQWVq0-fJPj&e7V2(PqqB6a3?J+XD zqAbI1EMlOUcwPICB~J}))eEWB=f^^<4Y=p;QH^l1)1lUTFA{s4Aa8<}FDFSQ_6b92 zA@teOP+T~qt;S+n*l5;y^KTH3gY5y9w|OnQ$|ucECem$C>@r_%lL|8S5Vv2I=Ou(j zdlvoauVId9pj4lhg67NS<$e)Bi-FHAc&qYzE={h!huUg-FCh|Y^A$|6iaNlBPt3}$Q6x`iL3rpCe2J@8hEuO&86cwG?|M}J4K z?CXl$9%l#J{ThIS-?!D^<6k9rNS}WN*B$b9YIaG(sX1x3@ov6&fQC8cx5E~(PRVrak0#%zErecP?4Ws&9NV_IGXe3ecWnvqOmCdH7ihJo$uEI?-7 zCc>s2TUz4)y6M~~hM65y%2u&1r0Ac@P+-hgH-O}q28>T>d#8m{OtM%I1Crq4jXuAm zAWA^_kXXado_Y~~M=Ze)R>s4oIfNnrP{@Lz=Ntbm+H>2Tfl($ifZe(pakXjE>EF^*L~6-6jM=1 z-jo{B8*t~-G&0y1dk9ms=N@v^b$M4b!=rb{q&l%GG+x3-59v}QJfm7=0c;v}nBQeM zB=8haD(QoJqi1N8a`}X>2(mN88uXZG`91BT|0qkD-#f&(D-?A?GTz(IKgqTo(Za z!r#bw9oIj)58{lHQTDcKl16?=sm6Br89(fHI=9?V#$t_?N<81yVwFFWk(T$Rl6;(b zgm{%5(1I7NDmDX@Osx8^41<2L*E4^881;lXl{qAEn=J7Wy6%%?A|i!_SpoU>GasmM zeBi~Ns80I;?_YDwGdN!Nx;_duD~P(LhqjJZnfV<(>KSXHHY)8=KXx0_)XvnYvQ9D? zeP+l?B0-y~=yCMx(ss=JL#=U;2S>gm)Jpx!7w6bOt`jGn@fyQ$OxaftpT#SxKw4&Q4+y8lQRkw6soY1PFle@44M9~y-=a$ZvXV=#&+oORS2!}}}EV#ge zIvu$Q_5_iSD7Vl=tGv1$PEjzO?83kPMhL#Z_boCPrvVV(S_?j-p`G2|=-1TIV)U$* zh6y38o_A5g7!a08*g_}Uchf?PW-{O5J`}!rT@(hVb3Q=RG}1AOzD4 zC5dOPbcI@Uh3?gz%@hoTVpa_&x*E#`Fw3u^1~ilPtdITvWmLOVv`a^9_5GR_tO`zf z*PzTuS*RzluA?!@@$BG<5ees3UDYD2P?zK>@?QA$#Z=us4o6|KSt|5Uhe>yX=M3w9 zUeMq2Ey{k!_pl@sKzIOhN;= z`l(5lFJ_B88+vEfR0D!M&ukbr>H=nt1bZQC?|KCYg6X{$i?`Ukj)Aw6^WIr~<=4TH^CD+#oY_qqGTN4*J+yCdh5CgsJPN^L1{kyqp0K(l91)pNEJ*!{octL?T1 zrFn@09}sL}@fPQ{m+|HsavZYN=zYTA`EOsiV>kP@?BMpR=K%-zCymt#uf33aeS_ec zFVVrdTH0g7Argho_v6m&<>JNO7ru*=26ITMujK^;HrIx?N7dem_^ET{4Sf_iorR%S z+tCjkj?HEEWHA+qb{QXP)4c>Ib>5#l)#`b#wB181&pq+*G&!O`nqUq-OxjaUBU>QU|V==l1BWi z)set1U*mZTf2Y(BVkzhBduarruR~9NZLE};&SMt*L!CwW~cu#?=yfVoHmgEGFhXABk8oY z6$qA_e82)UI5~oss32&Wd_UsSsaEmZttL1{OJ~?iJ@Y-6v2dTiCxGlA?Cg3Regb1# zhL=hH#k?Q5(k<^g29!wKjQ98ii15DJq=kG=LVtGT^`~cDne=L*Y>}9mnIFrtjr}zPc2C zjK~W*fCo0fwXxBB_+0F;1vK+YBtxv;+3fmkZ<4JA3c&mh@M$AuS=5RPAw>Fp!>m5T zD;T@-nO7y*Av`V(=P~!PlW{=gVDJ#vys5mZKX@d$6?!H@iSxR4k1@Voh1O8_&7<1ch#!~knD7ch`V$hOE$j?C zvNRkX_thWluRXu`;HV}&dLxjhWTWBx5nWskdo=$@u9>&;T+}Jv=;)ug{V~v3>e%${ zVv$DhTC{{ywfOaN^H^TG#&%cJ-k15yk<=+hM)9=!e{u(-Bn_t_f%9k0Ck7I+!?gO& zmHJ1W2je=69$B3dkyEqxXP#I8sv9*yBTsJ6hHkU-i*J;#ZVfK@Jf{kZhr7J@*j@>^ zWOC1b95cN;e|Ot`eXlEVTfCTG-FV6Gc^0-Saet+SQzB)0u%U(E}oZ1<` zzhq7xU#t6~u_3DidOGeC!Uk8V@~0)0WP12gwL0Jj7!j+s>5`=KUZ-N4gQ7Q8Ec^0$ ze{{xNYs6T4%eua`cp|z&Bh{t~HQN)qf9-xp-g1t_Z9WFHXP9B}tAx8~u8bS&drZ)L zNtoxG6@!Zm8c*27{QYO3_5U&(_J+&Q|6EbE&A93=FN|f@ZFXW3Be$X8l{uC7)+?eg z+~P2Al@u{NOf&XgE98qCx-n)G^*W5|UrOmc`NFl5mBr8v&Ce zqFu=!0US{1Hc7k!Kx5GIYYUChxtQxd=gj1o#hUOY&}FP_ha5O;V$~8_`W3){QHTZ) zuftxc!^y~sCh`B&Oj>sILfW=|JtLt~phK}O3P+lejnPU?S7aJDx1)Yq^M32T{Sz9* zQX4?Lo)!=C7WJM@VqxjHdM7_SJ{}y%GFL39CkJ3jo|Hh<7I8z-0*yNNgey8)Pw&U` z%YVM0pvW74DeerU1cU&r;5{RVw#~o)es55KHu)9J8y}SfTwPu7{o*ze5GIBY?+-o|1Dp>({K#Grg?ov5-8lco?Bx=r>xj#Iol_zd>qc%(MLCP5Kc3iz-X-R#T(mg;cvxD3E{uGnFr_> zj%}tM7!orG7;N_^2w1~fU9+RiJAB?8l^Mb?BvQR=);6MfsKyaHmDaOHc192mY{7ZxsK-baZ zBPWk)rKmZp-p*ovERXkm5^+aLQR#V;T1zQQSEE9^Q8{KgG~g(cUaHZ&Z({vvw#X zND8uSzzEUNPR-m`5Dwe_xtXIknpG<}16lqFeL*bAVCyou z8}Ne%wR~2CU+Hn&M}gld<(kqXfFJxWN@y|Ti+#`oxud$fiMY+x^!gZ^)r#=h?CQoE z1ICMKi3!2xli9kAxN@Tzub$lfyY@wm`<;ah#krlSoRh74=i;-b%ZVAw)Z_De^n$1N z+vYo)JAeLH!XpJ@3GG)Q^#xaPQ`Qqy_v;XPmxAQPvc}h@_b>rGoz}2>Qo#0 z{`XI2(-@j*v|~f=<*fMcPX>+eIuJ@?%zD})_T`j}H97)aN-u>gW*M~8TD8@xNafzk z$kgqzQsNl>_c#z8Xp?p&2p0R#X;4ebTNP`d7LZ)B5cstzVc4^>aKCuN(LgXq=cQg< zmwwn(`LEoZit*sYPhaq~?xV;YjCa# zy2w^tFKqMr=QrKs=lib2TpL~YveF4`ioFOh$U_b+sZ&lByC9VD4oVPK0HNlGpoho# z6TQ~hwF|Wh>R&mc?(D>2Wa|Bf*TOxu#xHWWs z8@YI_^9&O8@=V2rX>G}DLt|QoH#21cZYn<0TiIYL6+y*C5a;*ic|D>hLEnnB$oLjW z#8ONNAP0c=o;gM)-@FvGw-y{oH#q!#0C9=u29j;22Dk*CexFl?N(|&^X>sS4Al$gf z$i@tBd-FNs)F-d-9ezq6sx5VE7)Ub*M2rw^>ew`TOW=^-71?BWQR?sSgh&QU5luN4 z21z~WEV^kyeCQarTQ-+vX`pTbTOQkkV=)yu=L2Ed^Q{~(6gCmi|rqUJHa*Y<%7R6ngor=x7MCJxCYUityC-Y8IdLk~i&DHkAyj(>1udQe?r^6#FbL>3LWSb4dSELgD7+`!FUm4A^UmJuO0#mO zfv&JeWDRQK|E2O(sF%1S#swG)WVw2RLfjbu?(7{C>G$SJrJ1GMX(T$XRL4{dQWtFq z^u%Fa>RX)k8E4n)WPWFn0U@RDggGj|p7n^nyut@zK$T*gli@b1*q}Fd4jy9RJ&Q?< zVZ;~(?e7IzH|l>9y7yO|g={v}`YpIwsWaX!me<`~8$3qA<$tHUAKb#6=x!MH4yt?9 zk|#{>78^wl^?tBAVU=E&eFl^63&#uw zFT8K3yyx$GuZx@;KS)bUdkta-e^T{!gp7ZAj+GO`=WG}n@vo3lNn@g3Fh8MKJgs%g zqZxY2wX@45Fmpz~SUh+t&>Ll+<|gYuO1bB{*Y{b(BY>tBIH5eBJuzv$=h@M>+ler_ z{$)n;vZ@;`;i7pu$mc}-y+!lCF=gdqta0S;Kbb-j9O2Pip*~!i71^Y{KS|XmcGd5e zx}S&KHs(VAb9>J*00FlvO^t~dc6nANS)-9#(TxUXtPOL?jkH8RH@d~daXWEz_yJn3z{Jn%?@l$Af4~+J~lNR`e{x0!QmTsLe2@&kSNHCRwE`h~c zymUt0YC?ege-=zMEk*Ti@t%~9qpy){~_PMLC6Pa&i z<9URV0))R3izZ)J7KyUw9nms2IZ^{fPbjc|1m7UCb3BcJ)Q%-aX0Tvp$5*iG-yKp2!MbBp3qe0AgJdoLsxUqDM6+mH9y(@yTBxaNh=CXIW_A=Y|DyeyM z=J%@<4^s{Rnef;4k3KvHld^+RKZ(gVb2fI%peoSYd<}M?Ly1!779LA~jSMFyHqviO z3ssiT4QO>k&8j4mKS=3I`=+yr>qJ-ToIR?`l8&sB4@U)o_W36#+ywNW2=fBE57QF~ zwOJ7!>~8I!^RYHFR0W5$f4Q045HFs0M{YkZt{LeKcwD`n#($g6<)@5uh}WXmZbf0p z0Kn%j{;N&}bLZyd#yIch((Fo!U@M^9jVI(_SLLuUoms|OVVOpn5(!T)&02=Pbh(Rr zp=Zy0^ze%-2*r+R>pD_|Y-lEY8r{_dXSL!JM-C-Zw}wytU}okJ%mn4~Si@ikz;JGg z?D6X%92=Qp86&KZ#eZIJ9bg6iCw^O}!e7`}t=XRXvG#~m){4zy(>$Leor_M`9bteeVs_{s+ z@k-EUw7S_gRmpQ#tnN~wTHk(;K?j$ClG10Y>8$cDu1?}^MdD26I4bq#_u1}rxm{-z zpwrUs$J=e~MA1xn>(A3oN!nRY(ESzT<$~#L9@^4z)*2R`iliN$M{YdSRzTFyV%+y5BH+^_l)=xpJtrvYM z}YajN>3C%2()lkR@EbP@J|6%Uv9v7zeoL)9)yGoEqaviHykU0iwDun3_G^? z8aQIp9ELtOl&^OzpaGK#VW`J;6a9A96A;7%E zI6eUI8DKaL1jt}A1MXtra3IbE{dl@-1Gok!7~uF*7Su`0gjehbZS!b-1FkXOi1?P* z{@v0K!Pk`+cMKfdEuh$e*nUDNUZ2Z^`;Y60%S_?|vB&~z#Ruztj*+d%SwSE~Y` zRnQ}89uyhs2b!3YwP$pLDt0%?sZ{5AfBfa840sKWW5WM#2#uHdfK_jzmmMSEBFAai z47PkdV;<+WNT|08n|bTX8)tq;a}tpBmE{~<)0?nBzf@5bZe(d__|algAK79Y*JnLe zPh55GoAjA)hr%%IWaRUgDH*Z3$PiozW8F}K{Hh)ET-5J>!H-*B_MB4mM1K#EQ#HaG%#SpO*f4;46@g zdsH_fzE1LutIUGsX&^ue5z9dNzRVLPEvahn1(Y)E>SrwI-GN?0T&E&`l+A|aO*Eq(O^>fJAw6Q{TwX6Of;E4JoL??8{7yS>D7Qo^kkOwRp**v$Q; zhQ$Z%_opG-t6+(Y_GGZ*ZK!yjhr0Kng?EO9{yC##$6%fK{nYtZmc-@3Nn~H~=tGi6 zr%e(!kwtFp9~`ed@3oqbOUtZ1F2$WlY}D^!hs;HhrPd9GQ_LtnKd_HRn-r zYq347LcJ0vnevJk%6BIZx6IEaS|Wjgjunj(~1o;78h%zgtbuDtpEVb?3Y-a)^F(m$fa&e z>-R<+f|gcS6L-j(JKaYBDV;Kg_eNHSIuM0^yo&rAbgDWc-9aFX%K`{CG?hBiu{#WY zh+2jF#sI0?oq6r)EPIPZG)F8W!W%b-uE+gxJxQQS@O{>SW&9H}D5z!dO++YDvs(CU z-hQ6E{4j|NID9l$NK7>7%I;$8p^~^2fS^B-`%g<=mYm0Xq>?<=q<#f`kOjkJt9ccdu z1%{O+>#3XOY-O#cmjF!hcH9SO!XT5oX^a&<;;k+ZC6j-54h7fWx@0(ZPVRzG0x7sR zrF^ATD?(tWn))V9#>HB9gM<{jqoRmTBN z!#A-`%_D~7Opfg(I!QW5d{R7}hp~+BHVtWTe#H!Y-+BTI#t8>1;318S4A+iQ{ylA| zXwXM4QQo$`$g~vCA!na=o3-+~TZ=Quj)*WUCTR(R!kd%8l1U2q^=(Dy$Db>h6Z>BO zc#uZOyMC2F-XA+Q_)9^1y8j8d!&09VCs3)|sM>u4qUZ7N4LZItYAQH{gaErbmfLb4 zr(p!L{shh~$IIP1c!*3k_- zo25CpS5(qHP2o$MTl8 zwukfzm_vdvIXb8h9W|}nl~3t3>|k8VEl2<67tnL5J?d(o@lxDMU*dOIio(_aPoumM zOh0#jg>lmRdR}7W{??muQfjL5YC6>`^Sb~o$%jfj&oySb%6phTgP%^Ph|@qNbKUL1 zy-M?SO7l2a{GaQd%g)f2Rq^XwM~8Ppo}2n1p0j-wXo379`fI`S*5+Y@p_83}yVD>+ zhhu{sdhZ)A&&`ATH>O<+zZtJvHS#3fmjn1WON+g4cP17WoBs{89~t|U{_U@LR!e5$ zz6XSRDqUXws1ss~PR-B7u6(WxJbpPaE&Z>F%e+5Ttu{jKK2$G1=_+z?0ZU~bh#9YS zjmm#05Qq$Qlg}nzZFlt(Wdy6m~S6EP-aGkx)Yjoh_7s$&=ytBE6Ju{D^JoiCze zxw(*4hxvXVa%<8E6-WF2%;5j%@On=HayK|+x4&`bp3+Mm5nI*Khtzx5p8SqpD{Lpb zHvc6Q;9d`l4zwGXqP!cPg0x@Ck|bs1e9=u&ZlNB0S(liYIQF03nT}241Vz*_Cou>l ziSp%ZBb4LW?4mcQhit^u^<3i8658Uyj&TnW97)oDUGxbzp2dA6wSEGSiy%-a`7JRk zqG`0Z>`We0{Y2kNvZuW(@}12G()ajd900>It;oQx#t^`(3JO+LL#u)9FcFlLJk1n; zH87rFwtYFEZ7Lx5Tl6S5il zlbu>>HJeOdq0VWJK)hdj|4~}HeS3S??(7jKLrbw+V_wEYbELsU#)OPG8;9)bYQ9#Y zX#Y^>GyDs3<(GJx2sW1{=y8k)xm~fhlhZVt@D<9YEB;kK4`A-8M6|%!aMnbCIAAsY zA2J^lu_~gYtBah6zgwka?h)N+yK3v&JYX}WEPM%Nl?ThwWNQsLX;#?LGD_?TZ!Nt2!n>H5=Lak1 zO-n8Pe@DMzv0OJola?etuiSmO9H-{b&HnEG-g*J=Yelw&3iFgq!B_Adao}K=t;=3& zjWKqZ5)Ns{3QEzBtw_h<6Lz_S1C)9>x*|&WZ(6}L{=ptcb#qG-2=!>5;-wa6;pGL~ zAxXI&KxycMoj)A-90hoAqUi$hvd&pI3YY4J|V}# z0%fE{yCQgc;&lD1RRl;IM*K83R$b7-fip_+3X)ghdo?n#`p0ie9AIWB;w7+9&kTmp zwX9>=3}mDEu`#zk_xYhg`oHDT8DULd1Flq+L+`q!s(E3VvoG~TniTANbIT?g7GA|p zZpNZ%P5)`&->J4`0J&n(MYkU&EE`#sgu}BRK$myWx%R_uLQTYftPyHDqI6pey3Up9ptJV4cDFq23Gzk+w${d!cR7iCo^$#i@p)ru&mV_mRN97 zjp`w*XZPBZQ$;>2ef-5JqJ)-=(W=$xsa-Cb)v~z~#=fVRuckUk?2qBv0 z@I~$tOoc+uqpN`$(*M>Wj^-lk=9{r~h|_O>^1sW<-Y#GC$io8qp$^a+p1BQzb3QtY z!Ate}oaJnEV$?-c^}3UB<$CCGrSvrKf)rL4&M$=#ydljsTHlgoyVQu8brMh!QN>> zJWZJ7ykZTP^>n@c&(qg7k6SN2_(d#z-|%`UCB0rI?6FJHK}?=72GHo(JY0GNCs|y6 zyOLI%0D2e|NT;G-9U@J;iTgHS`@ar7IMX1l!+-IpWU>a*RqLHL)STme>CxKk>pw9zwztuy z-(Ji1@p5S?O;3aB=Vjkxhd-YR=_eP64|xFB8G{gCLfr5-p{((rK_K5};}))8d$fcr zf=Ib%6bAY2{mCZr1WcW>NLfgVXQ<-?Jpb(aic*q-S)(^S0vhnO<;BiG{(W}f3$ap$%g+YeQ< zz!p!2?gYzyQU;Tddou{AjG1BQb)-ebhE=qut5HlWOTeA75C(2sD_tsZEimnFt#W!|;>sdJE&RbESbbsg6 zjPyKxDbvU1fPE8(A}SPr8&`Fh)%lQL)u{5#0Mg|-G(aB^$R2kz&^X=#PaO!0p0v{S z@Ul}vuV3Xz^sqqZZU4%~(mzA%lkb2q1Mvft{fH-2l024=NDo>wN$MJ#k7A0k5Q|y* z@J?l;L9!I0A6~Lto4FtLsax zbY2Zl6<|3;of26LV@`%913;mf?u*jAhkHg%I1OK@_}m%!8rSSM=V`V+=z*JOl8gt?xR6Qi=|@dhyfCi(U43YX5bR!oZ`~ff|=r}3M>h?6@vV)1!zN#Ra502 za&-h;T#uPF9+-`!LJrx?vkT1ok__DY-^=`ZAD<(6VJu1xFy>K2n^k0ffm|4!KbEsO zULTkdu2Kt#%fCuJM{hO7)ZNWD6*ietg^GH^XJ2268d@%#RaI}LVpmSgFW_f{$cUkk>4UqbfewS0K>#Co9XpJB8tAB{=$NVF^ zZM!AHOJirLwz`YC<)`r!sMfj9^S`t09cpih+jjWAXM3Y$uOxpk zzZ?1V6M{w;xwtH2SF%)wNCeMf!CPuCiY%} zO@95?=}v#bJJaw|=9j`bq9nBa&&Jr_Z9QoRP(QTqE#*h>um1irSndjJ&cxUB06u(t zSU#OU9bXKSm$&9Q0d-TMN`1mn4B`E6*vdh>2_-{=`$=J2y`yEmN~lIl1b{Zo>*D5+ zPS5Z0MnzrZxtov;!$kMyk7O#p990c8O`*l+SKBlLDg*ln12FG*y_WbD?HS;U4`#e8 zL@oXU{8KZvIKY{1Jy{$tYX^sN2Z$z!+CgkNxDS=iC;4K>cbX`@#=^qYfNhlh2P5Lx zLZ-miw&%N2DvfieVf7GtFknBTf8cBeL>go*0Bz=;Y1Z+a*IJ{ZvZO;RP#Z!+0i`F2 zy5740?H82u-#OOu%aVmn`6hSNb3>-ewt_-Pnc{b0C4I-)K;AM$8ttTrqg?7&<wVWg315aagES8(ZjD0BoUVEvP`U;6wwrF}P7Bhrmr5?HURkxy^ zqrVN}XDx-<6u!y=|GTTdf3fI+l`q0#e+x$$#G|+44!SK^=*N@|lGL)9^S4g3mADIM zO0#3sbvqEBO&p-WzL#fL#rEYhiM#>*;u5h-yMSP;`8qZFvpGA_#bMZfuSI9?-Or#h zx7(`d{B=ux`9ZwSJM4S(&6KV~$j;f%2Sd)H$F~<@_ccu?Sv*@~sdtV9!FrOLU=bkQ zGu)td>8xE3KzOdxSSwliS4p~E26alfoN1A=hMtqZx;hmW>uU%egY(m4suzLZFE54F ztcY?Mts-oQNI8e~NMj;+L4W@FbN!i0(UiaeyQ4W2tu}d`A za){RT(o43BUmyCV1J%j0r{>2jAa{knDgX);?(0*OnFlxx$Q;a1C7Z8^EwxdGeBiz{&em!#c8G1hfIhTjJl(45Fab zH0GE}l>3PM2Vd#i!R*h$(@#DQ^!oU}6+2<Xn5yvjLwadYpv_d7mc`{CZ{9d|$-O0L|=#%Fw|#@WkG!`
    @1$p4}yVk#??)C5^Mj#BkuToa_9FwYANu_eGXvBk>mgKY}g% zE!^3;cZ;r+P>vSAzUt9{F6SCIHyQJOzwGpbrJ56VHzr-uJERS6m zF_xyrO$nJALga3?m2PN0@~gH+0-ylkkt4;Pty{7H=>q=mqae=@;Z0$+(Mr?I33L*W z#VOaeZ9*7i;I!hDS(I@d_h??&vvtkn=ob!uzPPs@mu4>XOPbaYIZ_j^6(y4qyT$#; z(P?+%q3fdXx71s`!5Z!){NdN7^~&51O*Lc>kzwVz?ju4A2emD(xt8(5tkC>C^!A}n zhjtGHnQxFYBHPb0h9;Ox!hlC?u^!m>I}@TOtD>n{BDu(JLII0_{rUNrbxs-p znptW4>P>6C#k84wSVTH&ZlZFHvxmJsrXVy1*8;Ba0hFm!Fe5}|OH1oWSdEjTnn?QSblXVlXjoxN+2nHN9MaDet$wLR+wrA(ow;*e3l#i(G2q+ZlS(VLsxZOS4OL*lY*w2v0iba zId)t^MNX6#b6-c&hhYIzE?7!H)tfeaj3np)it3!uE0 zbEh|arNU%}qjU_7=`DQlCG7|Xt|BPyyJebO7dK`eF%IXfOBbXG2_5h3Z|gTTP_;Tl z?1Q&=?DT65)CkWGCR9W7vx-yRPHePKPuB%fGCw`e{vDXPuW_9RlCXx#TBlF8jcVjH zvXn2hBto^w0b`rtBbphZu&!Awi|zQq1}&iiJr3LTHKFgeZMvg}&Fs}>f5UO+=l=(g z6UMQoHJ-Bb9;Rv9tlk!J{o^Xe{Y0bY|7G9vLjQM-rhbS57?{4pM zqP4EPlf)lJZs$k`qQ{CVPG`8#r(7zr0X^u{ zyVb57ap8oJD+wCf>x(|wJ0c5sV{Xm;@ds~@2Ln21mt&z=yZj9kQGlWVqLne|pFBnS zORkgH;|tJcV#K-FuddN#Z9?+lgX#D^N#FG}{nCnSOJ)2k*rDgu3C|*QcdsMmPk7o0 zQ;ugAaaGTDF#}9=G81`1!Kmki7bF$$%}8ZOY0$hw?;f z1A8i_A1L%Xs5FUh16bGUj-*tZnUnkzjmwMgI%Mv1U!DyORgfD1)+Q1dy{D?ce&fb^ z`>2(~XqNZ{&2kg`$0S~YmQWlpEhdE6Lm%0JzcKqlzw9rJAloBJvZ80ue(5MM*559A zOmR}&T8sNJsDH%-&;cP@@gI1j5;@c>`4-)mjKu&1NsSYtA~%oA(|oso5>Cy`*zQ$S zgnlt+>yal%o(8B z^<+rG+e_(CSxMg>J~DJBRiV}7ivWXu-=dIJKLjz=o#reVRQg85K1DF?i0VI?+XE( zQ6tDx-XVW`r56H$()x7b__fxg&6W`JUnsd6^8Mu!mlxGv8_1#<{`5xv!DTG2(vVYz zHQTW{`EL4d3_BWAe6>rE9v!qEw(#u++w6OP(MRLW4_~a2_~+*{hPbw1?U~W*t81U1 zBxYaKvl}liWQ`vom3FXbQYQWR2RC~D0BmdQarVa!-t`roCSH!%Fyn-F$X7^hUJs%0 zg-7v!9K9fF1FApOsbLvoUkWRHvCz?Eh^^ICrkdBr7nz$9AuOKE^UFN$^WKMYCOF)^ zZXcp4n9$Xxt&Bxfc#yHnt9h4GkXiLEqvV;dpMx{MYJX5Q7!rDa9(qs^ynG(Kyt!g@ zof&Fp*PCmQBN`Oe=s^}wvFyn>7Q}S-FIrl7_qy}`8e}4Vep933k(2koR@yH#@t2__ zHWi-**QQTWRyaKmR$>-s!@WIY#F+@`HWQa$MN-HC*a)?3&iAFU3%y5RoU5CM3P+2xbHTHm&qw9(y2W;#l@? zl+o=?O*8Ve8Bp@4D<|1`fD59sh_dkUrs{qEq@Yl!+x$&jX@o4co1Di6_X-FMs5I+V zt-6Jd*N{)9q#K$wy$vTL0hmaAYDo)=(6~heZ;^O|9S>5PBa?|I9i?XRa8@V*4*(w+ zOd`RL0;0%ib*=_31eahYmm(Q*yE6RPsAr@g^B*b6mvu=B=I-VeglS(-+wBettx9BP zrF$YGB;K#E?kyqv<|m6jWm1Erp>L_EsES+tsgElDXLCdMW~*N}v(tMC@cs%PvAth- zUvU4vviO@`8obik#pd12{=jzJOy#z&0OlRC(7cJs@K@O0)aE{ai%Ar9^XVse>h2w>EUUXTVT~)#)xr-8Ne10IV{SH3U*08xAwaY z214@Z1kpa)hBU3pbx8o1U)U15)55Ht?DE`a^b;>SR`BjPVYU*W6qu9LNru(OKP@mM zWVqrE;>>?mBQy7o;eZS>Yg$G((8I*`0@f@r;{uS;_K49ygN8Wc7sUN)VvarYu@aT! zyg<|E{G$?*@reueBn*MwDB8!;l)6k{dU)TXM|YObeJFRF5C{uA=&B8C&h>RKwj>#O zq|T{{?VB{_O?9{M5j@8|la7wN@xF677x|C#(Y<;JO-yML0L^T~Q_>cG3ib6`RHVPZ z4XdnX_!vlJYy3ZSFb%CUNdO5dA~^(mjhZ(t1yn5EY={OfkEI`n3Equl>CD+`oN{pu zz0N}VE;5(hGVx4#@`DM~C^)+{@76Q}MgrXC#be?^MF#mTR6-6K_Hr(7O+3L;#PJ>i!R7NoxIC5L` zU-0joy65HO!Eg2SEE+}XcZTUCW>Z&(DZ5a3wj3 zh~J2h%avmBO@9H8L2@nz(qD#Ugf!YTdsB9XH<){P+yj6as#!AM@#qVrmSzTb(POCr zff8vNz78(CPfP<(bpr;}%)bo@wEn*K3%IG=mp%G|g+9GWp%NN>f_=YDH@oO|POF8) z=S#RY3R$mGW2_8#uxl8DtP`OQ z9STqyNhgH#`2CTWKXXV?G6p_dAZF?h1p-$G^uP>89F+@F?$|GWFs&w?S(On0yVV1f z*Q(!Wk@60Xu%#H_kHxNK=xCnMvT(}ag@kUc1ku79&bN8Yc`pn|aLl&cC#yY`_1X)b z7BoPZGDv0vIdetm&9Q^mu>P4Q2AJmWuDz&Sitj&e{z`0M=dVqSJg=)C)zNE;ZG9jw z2be-OErfq*$`t}=F&=izdepF~u-x~hmikSh%6?$t>+9=b>_|>?30CUhcZs{P0vOwm z<{XOmHTU$e$#8BZpYcB*mIRO55p6|K+S1yScq6TZqLTiwOi~Qo4Rw8=@A_@KS6{VcSWoqOS96180svS35F`cyLpAEro*a z1XJ+Vp6zi&&Ut1t{fV>_bdVf*658*3ZeZk?N8P_Yj z?o++DOZE#8pKeU7gzwEabQYcK{EIKs1IY5tMu+85%aT;lT@LkJsp@U1kGwix_`22t z>u?{CeSLt-Feu8csm;Bf!`DwWQdz9`DvLH=?LYLb6cb*wy^f}`F{=`p?3f~tHTnnB z&9AyA&-iW!PNnB_L{!#t_z&L%yK&nZU*v(MGE_tteNuqh>?0v#flI5wvibnJQL-Wz zk_5A&05#cQV>9nvvi5^0##7F(j@n zqt8uS(={OtcN^|^%AJSwodpM%c?T1c%a<3Y1mjD)BKRLamg>26zO*`9@j&8N8YG@}E3E zc(7-HeTLSyi#?(pmyG}cBbga)?hO&603olLM|lb|>M4}<)x@rxpVg$G7$B-mlB;lh z4S{uS84NcqGh?sA9sw=h3CuN0DB<9vs|UY^gzH9-oa|26%UY*f)@7Xqm*%K%e-XPL zXWLZ1Zy_)e7#)k9*xXk1U4de9L!rADsA%M2NfqXMzgsdp^XAy`X>qQ3mDu$s=%aEv zu*Id zA7O$wMh4*L`p{R8drM78=t)*$*bfi~H-6{#wQ;4&%25r$*HAJtifh^tf#Kb$PeNH) zIny!QWLhyfCbzf1;==Do6>3?Tx#;>!b6aGIgK$As8ugkuZ&~5ec;ixr8T68K`Uy>g z)2lj8m0^er8xcHP2Y|8>aTM9Kc%c<}16(NGFi`F5j1x8H7q#QTQYnkinV z7M^TqRs1`Nedb3Q0N6w5m{SVmT395bV-}Bvn8%bh|7a;axYH#ZD3$};XWN1)P|I`E+Xd~j;ubQtwYyv` z`Ar9N11bI{$YY$&Iv%96Bw>{G$PSxS+PDeII>S5Lg^UwUV-a_WlCt6Z!r#QCl@((C|76svj_WuhCIW7PEB;7?iugTNg?-utp&Nso5SzDyR zaNtKi$z_HSx#8xgnLehUQF-#oAFx8=O>PP#?f(1H9=t@W2<3H! zIL+4vMneypXGe*>cw{DzB4L80>oL65|3<^!GD<>+-O-zBlY09FvF2YZ2uWH_`zs-! z?{9n7SFiqpVq4Cp1;!6GLlx5YM0a*ZlomtI9kJ2niJy`!r>Jz9!c|^%9a54`J_5+x zS3aHM5n=eU9!uc53caxL8!$NmE3IlaGh`cMOy;&&)is;UC?!(S8+9m{cSHV_>k~(haje;C7i;}f)T>qQZH4|*&J_IjU;oHMYN%^m_FNxR)2<30zbmL_ z>U7jiKkqvoO80v<;*Am4T&BV8-J)5(UpK!i0&0uVNJTS=dB}xcM2Bu+?-H}=buI+Y#Em~Jp|H51Itz{k% zf9KuM#CfkpKz=g#y32>zcDOmx)P`&R93k0~BLbv~xiLe$5c}u;J@4ffJLRT-&S4jE z$(x-b2}1J95CD-vfrUoFHo%}X^AL~O^qZ2KAe4aA>!T%*eUZ=vl@Ly?+zu|c*r=>p z&jm%S;}}^c;E-?=3E>N)UKKNTqlr|2m8>rxWfufr__LSyZ6JV=2acNP4mrg%xfQr>LK2<@qb z(%`od10K;9Zh62EV;zjH^L0P{E+TCSQ({bus_$(MC~s@_d>zm@-aQ#Yrst5(6Ww?A91IiSSsh z<2V^DgQJHGQghYlj>~hG5#lLY z=nci*lOBU)Ke+hBVVsZifoSntJ|Z6tfVyfV5t30NTtxxj+e*yl{|t*?!$%tTvLN8IS@Lr! zgG4+3>hyQ>9irE&M&<+4?cmNYf1mm{&+?=p>?T8{IFEu@VD?Mq6%<c?8Wot?c)2r39(&YL}P7ZEr;x$F)i0xW(g!smNFY$QuuHR^9HLB10CEx3y}SVct*C;Qz;k}nplw|! zBTL3uTada1DM#H$&xln4vga2;(Y1L30P6^vc7tn4jU8{loVQYbNoLnAf{T}9eolR{ z)l=I7LCOuayA7g}Wde&nCL{45qxk(lmzh{;pzGrqB`ZGo zX8&yn|4h=@?@Q*yK8e6F(LYcv;d|e{a}eX`xC1YK5r8W==`M3&YW;zEv7SmcU#Q#e`BxM z52;OjE^GFgvOljCdp1_2&BFw{X_iCVzR8Lk{n9i^oi=VP(S_LmHRHq3}?FX9=#x}5b9!hBG4eGsNr}umHUs&(4;C zTJ{YsZsh(oNJS#gRY{8cHw2cJksdf0j=!(+Yhb$ICX2H~5|ZuRZQu6UgpLSS;-3>L ziSOGA)@@N0b*HjKqHM%6U+7n8KXq6>Ea2V2UwhzX@G~b3kA$c%he16Oo_tTDmnpRN zM!${V6DkFwS3LPzT?cubm23WXWS(q0yll;elsCO2kv1RP%Y1L38xaA-4&Z`s6H9a9 zFm+v3ZZr1BkbMAkW&X#sRXfr@J@OQT?x4>p1!*g~Q*AP!_A@Adk zgF6S!PugjJsOli89WTEry1s z-k_In+0Ll_Lww)>&$1Zs<=evu*tgZ!bL}#*_0~ zTB6~gh4k@tG*7IF0jzfRg*D;Uz$MI7p4RClX!dQ@PC?mC)U8Fr3hgXQBd)Qa;~vMh zq#P$4H67GdGhjokj`8?Xk|-dap(ra^88Q}Xds^axRd!Yul1rH$X-sd>V_x<)1)E#t za*E&m8%M-B=LajkcN|!d&kr_5bYR)fj=r{Yn_SMoT^=}i!?a;gV&3atynj@+c+I== zSqW)-Z`K-lBuK6){Inp{LXOUu;%_lq>u}|;?&dH*>WxqAet+iYQJY*c0t6{(RCQy5 z>&z&2vf6^=vh7*J*EsD7LsRL+V7ovF%}DR(^v(8A#R#??f|W+`t|$hQSdtFqH7`@B zdG?tv5r`7HT{-48ZJ3+H{pL-^R|pdZ1%d9*SM$~c6l^mCuJRl&vrx35KUboJA&`yO zM<*5p^h)*aXjey|HI2Q!&tw4)*hJqU?IHGtOqZLE z?SETqW(IGgg^hQo@?7Z_Z<=e$uTdlo%>i$lG?Y%u)6Gk|4<&^sXeX2wvaWuW#P6Vn zYP4_Hf{nJtzf|0pJ3=g`&qzV5=#l5a zOys_HI)H2aO`zGkw%ELdt!6js@6|MK3nR{`AY>EQ8fJm`N%W`Nl6BzP{r=2-w@4tk zEL!jHc>6){!6eoNRK%Ks&8zVX*qu!kP-2%MXWv6h6U;lp!ZI6jzV@y^O8<(6?HdH` zR61fl>+1(^Lc~CMSbPm_$*$?_vp;NO2a^H4d5&xhXV_9_4JVWLbEzzA9Ah=LUN&m9(B{q;6jY0 zlHP`h^e54Pm3NE`O%H1eT~Ce1&0MG&=`dhe40B|Cxtk=R-oVZ8w(D%fn_6F1P1SNu z$t@;d`xiV1niaOUEG_*T2DR@fFK6e)V*wHd^nlz_ntwn9ESG)4kaNb>T47YUqO-Aj zJx%G@xP0TrzP`TBDgW3iralW`Mm9+!sSD99LswPDB;Z@?)Io4ZUFPcM6#FavW9oOX z!0>)S{KP4{%7zbuxKeoi@}eiyXB+{__LGy|#nHASe9s-auVke~R$+{{1pNT1y%FE- z!CVe9m4nGD^Ni^W9%pN*;!7`e4_67vzvXimY1z7QKFak)qSXV_#qq;>X$_ugN>)2+ zeJAL2w+SU{ab0WTMRUxrq+cH&j8u}#{)3@k`;RSBvn%u|hkv_<>sa#jFGTGr0is;U z)H3%x5dJX3v;@8@M1HUko}8APpwE(7)3(sT1V^JnCfxU0vX>tAWP^c}9ZlDpzAKh~ z4*LeLiQb&wjGWfYs8|5M5s;kyK>ZJ&k_2K7AR=7tr}eaOH{&v>5TW?|ZMZkw#0e`? z!hK5uuCIegKfc^;^anWfGGLR%b#1=HPz&$&pKv)p5Um^84m`#Y)E zBo0Jxg#U#dHsufr=ghI4u?uPp>(E6~K}am}fWdT*Wk-#Xu;Xgw(mv5fo>(T1|WoA@e5&#hc+svSU+5xMnD)PxF z0bN@Z$2GYQOo`rDD*7fhN@f+&*0#1w0h5rEy&`lmGcb7fbH2`h2vOa3Wt2_BR^4fD z#3*zr1B6Z}(Oky4Vmp;7taY%%LB$6t7dP}`u|5G7u~_e8bzsFSYtmH|^p+=UayH(Q zFJGp}ZcLAiJyt@p*+moA?qncj@ApJmnRSV-%g-rcTaIf;nS_5jc|O0RjZ5sKA|-W! zCsPwmN|LS45+MQVg_3m=S08G2`n$7~8{uWOFDjJXwC1AtxSa)E4-$6b7Y?Q_=9I|x z=h)^}iYwJeZj#H1g<=|rr9G@P_~^e`I7J;1h232}W?vRqczO5hZ{_F{y}bbA=PnJz z3D{b~|2sC%!mN=s?pgx$w7LNi`2TG1N;aDlgYqd`#>Ud_qW5@eC6L_8c(0gZ0o8Ed-qeJs= zP~PG4-C2_)Os+$)TNH<9!0)VOrhPQGPx7E`QeLQ=|KU6h=W_ZeJOPW0pI2;hki~F9 zMU~tC=1Wd6jan4OmwIv2dubg=Sxf#tgkVWxh7>H%3B_1QE%QAA}2W*Zff?zT!;*<$S4)`o1nysBLx|Q_8k?pT@XOqYux#rCV zr2o*t+6oZxBjk7^5NI)7C4-kk;2{Lybc7BaNS?&iu1mtCAcUD2V%F#p_W zU!5~ITnd^EdP)ar^@q}0Cw%f57k|QqErMbt$~pJXYcwmj?dMCoppBg44`DgY2P9W3 zvLSN$Sl-KEU>+ilNtB&71CYD72r2K!@-@rtE})Epi_9@D)DK!-fyUp8%NoSvvOKP% z3#%iJqm9|^rJz@UyZ(40pYU_DX+GRe|Dr-k!$`c!7)$z-*mCg*;2ui^KPIDp&bjS< z`6Xd9)8;=}Hu6a7QJ!<`87jXftI(clmgOjDd?%B#{M%h5h}wV&YO?ZhsfcV4#e97% zd+&Wan{b;Ea-tIY&iryv{{-FC;k#P7B9-$+i;)M$6nrcFdSxX$C5DVL{9W~D5ZrR6 zMT)r;Bvv%EL8>`2{J!o)*W1SPpJhrH;``dy*m~zpejUiC9<{;Zw}V+gIF<1nme4@} zsJ?s`8+JhnR&r!PuWe%CMA$E`dxN?bno?2juG@=x84))oiWncbAN;)Rz*t6 z!^NfI+A1~{X=G-G@CLl^SFzQ=;^vMus-AC3e@g<(DHJ}zm}ERVl}J(okb`yxPv3{; zjM&}LlS`cezx$pI(;W+xs59|yFw^9)5D-ariq*VrcGwijT~{#wM}dRv?-CXk!@v|5 zZ=^F6#8#}W7hLha=EcU|XfeLft0=Se_VD$5C3JRMzTIZPUuJV_I+C3iQ|#?bW!r_Z z6209CP|5{6vx1<(i&qb4CFE3489kbN|2%XFZ!kvJ@~d2$+x@{54vr81vGs>7E-n<+ zf{YuS&&l@|I#u*dgFj&1si%8$$g%m{sky^fiy;f9E!!IlzQ8S!ORsarml6zGXG z@8(B}L#18BzW*=+THvY@z&@c)a6SI`0r*Gp{fJ;C-y)oHh5`ZK^&%;U>&KAgb3FmR zrfR&ggEduUF1CpgV}{9SWei)|@WjR@p}5wluRfPRMOncihu__OtvU&Zu< z5qtgYZ=W9CcrDtg=u*dWP~?7~?yD{ZINVqQ2;9d@J_1XI>{23&yT4oOd@8RZK6U!p zL#?lmP!wg81@z-A%?1IAX;Cy+D=VUqJcs%nas~>DxcAo<88~1Z17z%T*b_;GlxQ;M z2b?ti{}_JPdlTspz^zAAi_|-dWwGbC)vpO_b?xRb;HOl!4xy3p-x$TbUPeK-%WU_yJM#J-tJH`6_ z``IDoO~io5FCzR^p}hb-1)i$?3~}i4bIoJF-_Qz;e5rkMX4h5jOtx2Foi)AOgTG3` z&!=C_ys(DfYh9TvYT+9Pj zmxob=9oQ_e3x2e$g(}DN;^Ow|PlGyoR+l<}&8~+Bv&B}%(g+;D!kr&L^eLPjhf?J| z$l@t8HB3Gc-dS9JNeVUtjFr-GHC0qBjI!vzrOYGd{lId4rnc} zXyx-a+vHc7W`ig#R5bfJVGnQ2xF3s%b~>!emNd`#tG`iqbh4YjR;(5>a0NyHJ3Mh$ zh*m#0L0|BP@uxsU`+T8JMz*y=)@r68Z4u{PqYPu6^i$jGVywj{Ih7kW5_dI|f-PAkiJzK+Ez94w_epviyPd+Jk!F zF#(`#mbS3Zip71oAr*N>71Do&wa68qv_5OJKq*$dq;EHHwd~sui#UKJSl&&P1v#Sq zg3Q>p20yh=3J3G^GoT&t385(W#)We($pcNrOt*@zKhLb63#O6$M8Gl(lgt_OCo*N- zWRfV(pHdPN9+pd3}tMF#RkFVXp%L5Gx{dFcx7%>u}At~iPnCaFRErV0>F#g$*$EGP% zapEM*KSg%elOqn+)SVHT%Di7qB>G)5b{{-CLB7HXAb=HhrV?K#H{hWen3;~rz;Ty- zVh>wlq;&`-r@snqNUna$?Z!Pl!d(CSpfn?J1<1k7XOQq#40RQ=6q}=;?8y1Sue)OT zr_r^hA-6(&*kKHC_mDv6Z+94XPT~M|bF;-04AwGPh#EYb_>Fk@WYK5&? z2p~d>y=a2()+jeei?2y3u#X`86`Ff{I6|cXL5|z59Tn%I(xNGO9?xTzG2UKs{B)t& zIO2@CR-&`gsiHKqtS+kQ)WI?6?a%mc4fd)<9}Fk$I_pNlH)h!8g)^pqpHx1J`>qV3 zC^vL<9O4iBUZ+%I86{~Ii!N*J_(r%{Vb@gH<(GqkYWTGP<6FnL?W8PWvW#Ng_mAk;!ucF{X6%5g*al*VB z%^b1X!x6UiPq@}n6;y*znM6D=qys%ZwwyQf*=0CPFt2679;>$ity2?LUoNKhg=vm| zK10e{Pr5A&k->4?ge!A(n65LPxOe8pLPGq{Y&?(c)QjGhH#{BXmM5$rrv(&G1?9YY ztijJNhrcX7G1?`L+1>LcAR%raNWmj1vfE@IDeDWfiI$#)0F*9l#IineZ5(j)Q8YIW z?$0)13=9cW!>hX7Ba!&cA0MFeuz@0P=<1m$Z3`WnCWZ~_95&9Q+o0pKIq zjbf@IqOyCWPXJs7hDdCc=IG(uSBsc&)#f#Yo!wn5!1;_$BhZfmQ|@LzP?4icfac=jIF``;_{7xZ zUi?IIPNr67w>jajf4XE`ndm3?rCX(PNKKK}OypSM=*!~o-{GhBWB01NVeE+<{#n;G>E6#cE`#dJo6tIFG=C=^G?1YI#irHa=Bny(iF=pek+w%3f zNp0rdMzsTeAgV2zf}%l^$N@}kJEIu0%Q0yqEsEEb?FVfy6UyXwZ@Qq3437O*#X&rH z5&0;~+U#+kNW|JLEGV*femkL*1Qq2BaBJprooo3?wQSvb(G+@ui+En8>Gr(8?P?Z(0b5ln?T&)PU)u^iJeq+Q9o(oT3T*{2_S4i0)Ae zKFn`^LveJ>k~AZmbbL<8zCC~L%^*7UyU>u{%!A@|<{wW{c_Pr`4Q*$|^aLFwzFIOu zH$-iLRa4`oaScWkAcO{ZMG8U@Y+PI=>V9^-X#Nc{YpZfEN;r`Wpuwwo%X(=>c5QS0 zxQiSK=RG4Q`t21Mv$YZyi+#?Ozc1_(;!7ZgV?icE-Vabjfh%Ez4BS0p?1r#Y00RAZCV^7til(zm!>wr{qtRs5^szwwzt zSX};9G;Rs9xInVPGClR5?pQoBc!j}z*g*XF5TAX=LA2E$TqakI{mv=F`&zRW>8~|Q zUaHeJ`PD5~Z`GHtm88M#Zkr3Lkw>cjPho<0MhMx=Y4f(f>N`xq(BvIyonOM&w?zr} zg?CWTw`JHk`Ts3PuKROh2`WS^@cUaWEN`sx{n0HAxwOQkj6&%9;@(5?PE9HMRXHg} zaIg3p0fB`$lPc@wowSu`dvOvqEvV zB18x;U_-|C90a64)jQv63eLWy-V}d47M^2ZGWA_NocdVtU(iU6e)H?@^JHw`Q0h|B zLgVSb;gg8txKPC`Iy28|;`@lXzZgDVm>~Z5F6Do&9?w1h4pAEjfE$eT$l+WW?3Z!p zT?`89VTERmo-YWQEULPK9y|(M{eimz4*6-7I7!j?_zjgDHvlI&R7W;mDE?^h0r9yd zPSQE|U-9_)%IcR4$~Mz6TnUdQmuiJW%7LHA9^q;iFjJGNi8J95s zr@81^-s9gne$IXkZ$$#tTCgl9|FVGL%XF)Nl`T)g{-+}_@t-)71dF)bdkd|`=_YOF z#-bG020yJf7P5q1n;-krYQ<*d=6cGxKttpwCy$N77p?JqjHI(wq8c21X7_SIZ|MB4 z_Vo_bwsEmrplYcqjsBixtaa6r&;O`8#5ud960rJB)>L-5tCfRw=};)9!0*) zx>LQQm>fJ_&Kw0G5aQ_hm(Qx_K5)=S9}zf{eP-2h1JVk0eg6JgkOa+3YvrP0vHHNm zp$2?0nlB6y)k^IYs?vsI#Zm|#yD^^X2yN#`v4UXe6hn|}7^{zd#4To>?V zqLI1JYV?F+L#yFZ-y7Um>1y0K>q|DGp>9kcQ7Q&7#3V(C5XeQVGjcO2vy0(nD*)bh zm40R1S@rXv1h~QkH(Yz?V{U6Q$<701q&EIwO*fH+nz;kI8T#Fnu>~(m^uTYz%AWnG z=x7E!d@T~MD|~to?)F3ts(SY2mn}JZYk3FAo^rpnN~!QJ{uj?gfcfZb`3#P}Yh_i) zhRVWQHc)toOrQIxMGZD{S1M_wk~a^a}l--+|{$<6*Jsxwe)_h?$nMhLkdPc7~%^yOJ&LOOp+JW-kz0NFW;LmP6hDgDQPjrX^;kB#0fmm_qRYk&9 zD&M27@xJ;^>if6L{;%FK-5@)sYjGV~UioObU)&u`cI8pu_C(884Vm3R_V!77eNTt& zPq&c~SEKa&+V#!f658)Iecx+f9kqoMfn|>}KGCq}p!>Qz4A5McH)~?r{Yt;ZQ}eu6 zz&u~rMgF2lGe|4+ya6UCT@><9|lAW)Ze~ z#?0gGv2OfX+YRq)LOw>iBZ|lb3HPw~p5q39T6L<5U+^^Hv(;M1Jm*?hoc|_xj9pQUcH8cD$-oLtV zJJT@~w`Yz$wNhwdTU#6^N=`X9`=a+kkDNdlab6s=%i(uqnX-~1?os#f%s{wAEQx(4 zO}ro9>*OT^bJyWdz3=??@%$_qn0`WH7ORB9yq64{qHfDQsulVm1gy%^-hnRxsU9A5 z{RtxG?Bty6y{zS&+!c1UF)@CbMC)Os+Ut@&uA8TM3zmZ}i;cQ8 z<~~VS2eV+5LB{JPcCm+I!KB8CqqF={$-weBD4RiA9nB`V~ZZBA;ll%BV}6%Vxgb)554;?WKh?a3i|_dISRwHkj- zJ#}K-vc-IJ(n43jyJs7@JoSx@)sb=1*1CR z&^po?Np4|H1noV~8N#{vA(rGE-=Q*+ZiBf13_apB8ay!;q%Yt{Q}s5x_Q7RQ7Le>C zubqadg@+P0B`*=U)dgcg6jTo=9Tr^}EPmaJI7|It0)XY1L)e(;It0WUGejf7RtGK) za$ACD#QzBTr)<}gWy!%$a}y6@Ri!c<)=arfk{hkLB7MJ7^u{$426|T^HZ1etY#4D0 z>c;b}VyD%mdgv29eUL$1Z-ihWlPm0@MS?e>ONd4Oige^DCsmgnZtC`PIcGn_DlbM# zE|~UrTJtHzamu236@7820vDUiXSj%EI{U)9ZDs}X? zpNjWiG^fnV&hL+$Pn>H);;us1b*{?jqcJyGGFSOaUqflHHLoV`>&*}D2mBn)R)*@` z!ByMYvV}T5H4`;=Kjt1)LZ61iE9@S`N!MY_-7blQ z?`@(u@1`)U_Oklmia!`*&2%i)Etb8vdB^ok%m5YuBOk*9KWSLr=)BU+y$rqAoVnXS zXff-cTib8lAJ^}=p|+=;z&J#wn)8a43fnc30!wfl@F%T{dj9~a+1>C-z zpm+YhP~TSTH}Nb!gBO&&goP0{_k4k+JuFJN!I_JhLL|<38ze4Y!@^`HwUwx->_J4d zjEtVQ-TRKXFJ}X3`9Dax#KRXJj)qnOnV-9j2L9fmFmRr8S()nYe*I&_zajcvj@7Ig zcoL1)OMBCU_W-~PAdq89d?1HAYXEq;MhJXt4H-8JOgz;B_bzw~%rzXU4$s*kLdR)P zbcA2%u#p<|4pmj_IWB4!;p?vB;6MH6q~zbtK5x+ESW-nEtXEb7U<^-LU9}eXO2`Q6 zs>L#r-?)PjILLSa)`T&eS*PvGy%M&k=!Sut7f@ol z9rkR84P+7KXm*3IqboyD=b)hOc%&YMMKJ1JAt?s9tIUMxORStb@D*))x!{L69viFw zfqk4?u06cd4lii{-XP!1MEGx9oGi z&kcTO$aI3MQYzFs{*lg-Vbtv~hS_4S;)hA+JB{erQ#IMECwrY2ADlSs8xj{QY8!ea z0ve6)|7_k>VIdjj*XIY5pO@;LVoQ9E^^2IUPMIdA&u-HMB)&+7oEAO}STOc^bp>rd zK-Vvw#QoE?qp08x4MY ze_V}oJ24iD(mXO=n0jOT?&-F!&!U?NTXsWRuw0yhj<)f~r>_FJP52fp{|`;) z{Fhmv_3b;mrkZTmWZSlF+cu}B$+m6VHQCmrsqSq1z0Z4|vwqnB!T#*E*ZQvOiaKoE z;!{;Fu>>X?R8=`dDI{f$O*Hb9X`Tw+8DI1ge zx!TaUG9CFc?+?6g;suUe!6I*h_;(kF|I}`(|5}*x&4*gr-ex829FO2R`cV_zaFTNA z#hG)W;>-G8>hxR**n3~t_U(1%{>aEqUkV+K^(G{7ksL^0>ojj_b=Wj(#Sdc!4+>&n zJLCE+y>gqtKL=#P3xyLKb9;Nk=70y01`8TtcXT?%O8Y4y6N_XRIbUb$%WdC4p2eq1WRnUafCv1E0LROujkJ z(i)p(&9#sFfjmD#8^UQnNVkUawwihB1^h!BG*S9D)wZ200E17^AG&2q1(x`Y1HK;$ zI}F))0yR^@3daY+2?E<0X6y8@8zjn1c=z}A9v2>%m(S8e`40iX;PxNhdx{gc6z0Jj zspiK0RJ1}4PYnzqU+vpvo8=b_;nMgGtB&5prWd>TG37(y=3$BXP9$S)G&lCpU(r?a zh_bDz4-O{?RamC^+yi^L0l{Zg&X*0?uAdib&bzTr()~n()TYjO_-6=_m*WNcRjECO z_+bo#-(}ah4^k)Bxx=n6wwhKadEHN=2|%nUb@$DU=~8H>e1JxGjt4(ER+END?wnrJVdV)yP^6x7wEWP!ypYaF0{gMv zF2WwhmQc6R^d4&;ub0`w5KkBsoNP3{BYBvjj;>A%K+ZxH;5Nl0`BLp3?VGkv*Y~DS zrvcsR_%+fwxG|DVSHlVuii8Ci27FaG+SqKojxc01HH5_AP)B$}z@G2*8z{DI@{*JW znO8sMs?JSNs{HzFeSOv#{0*o+T*9~x4dQ7Q?l2+z^Ay^L&f(DiQf0O*OWMn`>ei? zyVte8HxwQJ3&m5(?PjX-B?mg9uS3q`Ppm#kL3dG+E3Y?Q_oLTzi7vw$!CVU2&P(c{qxYol{q|Guswi&2YgwSqRlrl%!(&_D)~xqnK{DlgOYzyCW}U6jABZIw z^i$TmYO)A#Xt=%hB8T)43md;xQrcxcT7NOrR&;t-!FT-jnW3u?78!1AZuD2GxKTZ& zb1UcCC|VGzJFTXr*LC^`w?WxLFH63_Uj8SQcvSj751w>9-zs`=1*Ym2V~8=(SHLA z`HM4a&d$ejjLd@UJDn{XCQyQI4KwZ}&|r=dT&=#miQx5Jy+MtMs0NHu*hYPK^Re`UaSB*J#>#J?*eL%y3MPtz zKtBO*sfp|Hw|;OTD-#=)N%D}k&Q*EI7MmgTrO_IN39+_lBt)#lmnQU`RC?VSd1V+Y zXc(CDI}7{m?%@%LEs2`w$}63YMjf^74Uy00jCJlDe%^xd6Py~%^OwIHVr%%Oq6SnJ zxQE_jRDhHRlvFJ~jMc}B%@%7ju^a4q?L}c)Ely!B-2GvP2y53MQVr;Q(V?RbNr7Q> zjX;B^?Z7&t9 zDGIEM%>yJz_#u{_&SSR?_6qnn;1J3k-ouqOzR@3S7*RWq1QX5Nd&DO~(et(Iwvv|l zKtSwhY%EQ12PcNz%kBTW z%L!s*@mze9roLj7=C-{2$}06Ugh2k4sx4{K&CAlIt?Ef_q@>8 zZP+J{W*y7A+$~5E^RPAtxa=ZL_K5@e1<@~1Dj*B^cdm;+ohz!?#Dh8-EgaKO!PGJt`X95 z)PGSINuHbuiyl?wa7>ebG6#+4*9VwKjGfANfbI*y0xKcI;vTUzyjcudmf#*VKKTUI z%m5cwR#)Wv#JgxF^>pLo_UR2VLp$QZmg?Yxw!Tks#s&dsyfHq!r$>;6^ye*Ks%1Pg z<`w>8Ti<1i&t8e{{b8VA-RHHUK>psDLDlqGgxgm`a=^Lgb^&M4ZHmuu4CCUOQ5lcS z{%e%ySMTRbZQb$E*O}*o?p4O>?AN;EF;uAZuxn1|Q*fY)`Mr5&?_p8q=KGemi^+S!B>vY$wQjWp=e;K=g0U?mFW?Cr`zUF zQ5tE7$<*VoyTDIH|6@_21sH*AFvVX8Tr0VM6vLPwxBZVDxd$DQ;g&2C7ONK)9IsI0h+kKQ=(+BF2V)l)o#x#b+)v{;amIfQLN2%>lmw1 zBDdQA(cYbACf$DO{%?EdkH#`Whe6 zoFFrFO+$_E+7ep8*}}r)ef!}t4PkX-p^ZaUG-N@`4wDT4zXj?kDkh!#uT04Ke3JJL zjSnY;tB-UKFqbIokSyjtfYC_3$5_{HxW3s03{S9^t#0%hSd^v88yWdI&4vEi zkoWupwg_kdER~0TV?BkiBF6D#!v%QUqc4N!=F5Oc+uSG3aBmSL8qJ?f4Chm$?kPO> za$H%6Z-w{(4_-z@?P3%-zF8r)(yBx!^7KIJWC*9zrtC+Qr6z_VHbxLqDMrW)4va zYy>YS3`xqDfUmI=3O=##~On;xv z7*%TJt?2&iJBvazl!pk>`a!T1>**o?9opPC zrmCi<(O#-2oCNDu53#j(#YE~kf(p+8~9)u4y-&T+mX$Ae-r#59y> zW{z=(W`H(fh|QzyrqubYpRuPh(4$9!2z}*=cq;V)DF@7}p;t~ZV<+&oImPmB`jqk@ z%Ud$gwp8?9H0L;zNsYrM=)rI6fl(^|Gl)du`4d`3IEm*9=1MUzC0+)a*H-okD6h1L!hKZfpT`2H zy_1z@RK58yLR25MJX{BqCam-m6a!^y&K+79cE0nSt&wRR%*4^YN(R;*7wflsmSNZ- zAC`S;Bs_hz6e2wGwKzt6ucLk)5Y#+?FjO&nZRUS-P`&%3rA&$r@@L5>$F$kRy{k-~e`#6cWo~>(8I!3E&?T zMC6LenHVviDH0T*-$=Io25kQ?)$Q$JG^WT_sC?J@H)12SXnH?10NH&wvJMAFn9Akf z4$(9NpN86=OI-bcVe^e%)2UI2Afo^eWlO3u_l*sa*kV)3xU;#vH@B-jGSECeIyDtx zWu<(grBq`Do^S;gR*88hVhi=@eBFLO)58NNv?a>ArdOeniuU-Gj}r1$t0YKrf*Um2t| zvOQ9*jiJaUU!;vDzlVv>ls;nP;yT|~G@Nq=W!O7?J1=S6M+g<`KPtXm-_WA8Qr z*u*%18lvo`8v%d`xFSHHw2oDD#K*P`(^6NLn51<}Kd zSI6NeCtOVZ$RMH892RC6tQprl-Ytva--}qoFdhdu+(&h4aT?X#Kz01FTJ3BZaxKsn zY){p*svkIp=_kMV6FY})#F>wIh8EPTZtY5AYA+NqP@7v#1qc&n`TSK!Ri==0`^{b} zfp8=8v${y5rme%g6M{{G@jdo(%=~Eq&#)k2zGh|H$ltq_+#+g_7yJ3YG6!QG2H%cC zQ4n9%BFXe6DzMJ;W7%?P2V?Qic-MUg%;oB`V?Y)I1E|0G1X_rDBH23l{dJJBZ0^ie zbu^J7dh0^(JbiOe3-pjmJJ(rd{CeK8y*o23zR018xt~2H5WFLDq*}H(ubIc#zT8SzT|#vBSKcL#rwm+HqoIu2?#5 zff&)CKfpt729OJ;e(trH8!C&Hd5g_(Ibk`R;WEaS8l#8Uw~GEA$r4Qxncu0s$x&f_ z6>X4H5fk_I>Z$gHA^q#7FuV0=YTYOMwRins9KzHB#jscUbQ=p`TG}@@4^q%?$64S0 zWK=)tRjjh5tXVPFRm;^~Jg};}ALvuFIQ9`Q6(IKC{Y7cu*HZZ8CtNW@yVPwA+NM`9 z&e(MNR!v9>*44svE^P$pG#I|g)^wj^WD4GiKWyu&oh=AV2LSIfm8RC2xVo9D#~OaB z{=SP+g=-f=rp`rn{^NY^oC(1j*Ion<`x_#v={NdCbes;L7INxaqEi|77J+hZM+Qng z_v$Je;UH39p{qVVVBEI0erFw!coCT}`=Q)y=K$yqi_26C^9{?i=MX13g zp%a3i>*@eLlpSU_snt>so0+_)%+UUtL`sJ6K=Yq3 z;JXl?h#0C}kV0Vu@sq*gDZI-@%LPPG0=~`^`rwawc zi2opm?L*^9e7CN%_)Wf)xHv&av84NfO(!17w4kC-!h>tRrBWn#k-pMz9HZp0&gD zamm+?{BF2%RuFCE^FjKo;4 z4kGAz<*J?1x}oxe{oa~G;( z=lgIcrKif*^Z2Iwzk_On53;_>E3UZ;4Z4by67H?1-B6x@e_t$Z z9!qKSbk@=sp}n=74Kr_PXja$vtMx*+9Si-BEyp?bB4Pdnt-MzXI8^e8%>(9y>``Y!|!Z9)|!wttiYGdPizz=)H$uc&B@ zJ;duQW^~xu!-hHHLlwq4I@|Y)%#Z;L1)N=HBG)ZF@OLfv>}#De-(~tY$>2S=$MaD# zJ(kqT=-V4rmyB6{O2-V-rue`0F^yig`wLW#$=0S(B3FEE!z6beaj@5V=eW&|E}i@4 zxClP;h-+S|y4g4BtX?4nF|QFUjxM>+eoPSZ{1`?l_coWE=A9z>%m}Qi9l&6}GE_3N z)f>I!E@5{GTjxsi0)|i|%~S$o`8aen$MMG#xhwgIZuzojAn~|sfW|)JTPKJBgv7}< zbd$-+O3us~yI}qW$JzV?0}Q&EO-vBhW5+IR)|qSr{6E#&FyBf zmyI}FGKjBZIe1V8LSh@uAMK4=NT&WolN*zkp5h&T6#No{b>$SEeq-klO#`krb=!5iDI0r4!BPdVpw%3{gf=j!aD#UmL% z-ss(k8|;|`AP_{&v|8O!i!w4BoB&c_>zV?M6eSWd_G1vf{c6u8wB)%6Gv+XIQ9wn0aBrMGrk_@UIr{joRVUu zcb)n|Db1TqMVz^R+nP5$6gOJPhW+G_w>o?jBCsba229_Mhp+ZG6JY^eX9yDv7WgAoph&#v*U6$yPr%mFsUjyfm#GA`&>ZwLK zK!zYMuA|5zx*rH+5b%iRa-NRUo`mVsF|C%D;@H67y!@UPd!E=~b>y1IS z)D5*}_w$2_q|(st37~DGM8gT7noEeyO{J9?@_<~A)BIw5z@Tbw8)MP2&fvB&&1!Up zUqdsV4813F;{9PgehfoXPxzw%l$)&B5V_y_5}$`y6}%XK%8R-+OS~cr<8AcW@Hs@V znG{IG-&uhJq2t{5yCi!ZGZZ#gCG4I3#klPo?!cx9(Pj>X8M9yhPh2gJM!6H%+^qWw z!s)(F?w|SGNQnq~5LXd&q*unB|68ROo2}N+eJz6d{W_P?*y}H=BIxX_FrLnj;D@mF zlkYv!R`6=(6+qsp>Oj!8CrWaw)0V1*cM%Rv-u@c!}wKTLPS&U zy&uH$`B^_=_z6z&d6j2-Ji1*3tPs?wzPGpeTxz4aUF|D8zGtueTEhFzOvT4?WA6Tb zE@%aeS+zc_%3I3azEatTvH9J57M2KAF=;-C+|@xmtUWW zhR~YvVvfi%dkQ<zJ3>AKX2CU$Footmx>KE4UNn@=qKVK`7PwVd*ROe_`!S zRlx@djo-M==uj6^<+DJMF$X{hDaTBGHh6tVx174|U1m#9eo9NB46R1)L&19WvqfWy4! z7@w=f;7FmBe1~(47sGU-Co+a=V;|`(j-?^c z0~zXhkO45Yf0I6IpUpb~`Cg*|Rt4K|;gpX(f@{YdRK;eTrh)SC&~y@>Gt_a9fF}Zg zd?`Zf(tyVMF*YDnYfKLyhN-tWQV;U#H#~Lfst@gUJP18Ixm)Y>v4VO2 zy2tFxLBYYsc8?5A!Z)~&D%n%IM#1Q-;}Y#Z8tXr?MjogT_3+U&8h6_J@Q!X2{o?a6 z2f?}k-8uu+&Tyamjsq~e$TmJoTf`JB^S8^!`(N%cEiAeL0l}{JW6N2-hV$WYy;9*j zZf7}X?ZEerFb;)R9!UCcwcG}F$DYV_C#LA;JwB=`g09wON4Req;KLgW9<_|*SQgPO z-#;cKzjvJoh?m7u^XRHx{6kfD_-bE}9L4B*5XPwUPfE^6ao{P)jbhNScnPq6YOC;> z%br&BQ;Y1NXu0eVpFc0L*{`X7HCPucv#XN5_j-@%79pjt=+RQhl?m>a}F z2vSHbSP!7kDcv|5l|%fE+SAy0J{V$#cB7kIj1`+`@SoAJIo~|5bS?*n-SO#pT`y40wQ|R)7xGD|GAn6G1d)+oWjX=XX z*1vNE=BSr2*Q@IpDt{gr3R#F*`eJYhkgm zt!TTR?Z2Vb;#^pl#p$S_S-S{EK9b)Fw%u@G>L77&rU z?XU`k2j>N=M>Zx5HG~L&axRTMNw``Uo*ViHTh#PQjS%!xPxr#LA*a({!qWE4{BU(u zokrb$9*Vp%+`HkKFvyx?W(C=!g-&NDab+c!(1Tj8t2UI9&0pV!wNlFw2Yo|IaQsH1 z(Tf9}*bl9LL)$3GbOyR#4^W7Qpfjlg^I@LV&(W_}9EZS+2D>PB zoKayl7I@h(eiX`RPO=Tv`w5zDRd2urnc5Z3Z{^%M*{*~Iaa-69{wq|-!)fc_I`aoV z54nNQniaKeFdkV%w(GHurNN8*29L~&0)22?YTR?XTsJ?n1>;9xQXTTvj~8o#y4?C?^}ZB_$>7`KQr9VSGp);> z^TVbwTlH)NPi?bDbUo*-1;lQ8){{?3>y?>=d93tpUqqbeJH0ffN8)hzsIA^Ws#9^F zP5-wE&9>SnU7=s3!dAOpATM*ZQ8lb1UGjUKlA-D(CtDYcwP*?iNBpLI-5vQbWclYbM?jgSFPy z1NavBmLl6mDc8{`lh96xW$Apf>uw{#;3E4Q#%9eJ9w7H(_bME=)EX|Y9-0C4v-mT$ zvC%Z;d1X5Y%d|K*mtThhu)1$DIRq^y#X$~>BKaawWSM7$kkYr4ap@c$XOVr&87mKu z?E%SK)*6@UTAsHb8Sp{yspzj05^w_d+1=B<($^HGFY%;CgQ`vqAh(d`g&0q>CZE_>0^xE{{WtprS{IN$u#E$A zn^NFfYe^Q`*plNkp@UqaMHaaBr=JUq3BxtoCUjk{Une+1J zZ$p4&jll>}P;4vRM!JgTHyJpl)Mk%`m0bWA*?3=ItMg##xFn3$$lK#P{}X_Guyp2w z0kCn-JHyFKUW{&GSj$>euqTWJh+lVS$}vhUV0DR`4>$!tnjkYp0Mbu*`;7P3Na>_T zY>kb_*AtpM7JB2y4HTepk8nxJS8~ZV0ZX_ zpoj6}Aa1CA{3dPMxcA$!Z@%qqegm}q!FkhTg9g*(aniNq#>w;#;AouoeTZ3dhTP zCI*JnjA8j&|6Q}r%EF1#5E&X-0kl50PTW7H$K9vXvO1mFDmWcvtphzHj>xJuS<#Qy zCdtAW_Q!6cmDwW>b4xM>xV2XV6*WHIuC`KEbUlkxq9n~eXWEJ(W0#WPN)SaVbpYJJ zr4IGITo@!yB?E)hE{S__bsp)37)fDgHXL3NBDKt^F(9X2~Y#GBTvgd8Uat% z)?XQ%s00C0ZIXX;ysyl-iI8P+*xGHTpEON^eSZan&Z$}2+huIa!8~L_5S?dlG&%>Z zLpyD@CZQQc=np}I>$W>^~3D5$w|sQtkBpG!H6*B#}(xfW`8NfO*Uf!ec(8XJ-Z& z*Cg8p-2fCV@1R~VTX>=PP8|zHK=nbv834bP8)XeL3lV_VpQ@z0L%(!7LJ5MoBi!iO zYrs5aQ*^hLt-dbK{r#Jrf_~#NCa6)7k`tqCY|5d#7_!A|4dVftK45h-9^8kjM>r34 ziW-856&Yt5ih+u8uWzq*0qfX0UD~{WTmOh9$X%N}2?+`Jhn7|AvZfFgMq%l|}DQJ^iOp>Frdjbi!rxhE)q7cvN&gOnnsQIvt>?ndeLDLyB{i?fLOKFLWEMvVb z;Ln(Tc<9Hs+B?2qaLf_hSA_UQ6P?lgeVF{z`1O@oRDhYUlKI!}T| z5hl4aOgrg!=5o$UMD*+fz1m3}Iws3>$@=0-AYxYBg%F@id{BeLZdSAuH_X-D+Y5Vl zbzz~BcOLskkQm!WV{3+ghVyVCoU0d1jxZ>}W_9O2I7w2Rm~B!&VMMT}g${&{7k#Go z5M*I#1X}>xpw~6j{0e;BhUl-|=Rx^2sC#>~XY4P0nt{d)>WL(!sMO?bv>TOoKIc-f z`;wvKZp``PLeAStF_~&No@nYWQ%J2+Z3HI$4ImsuEq1lJxw*Bv8Q9DEbSXdw_PZDW zXWl!!JCoyK37nbQzPrd^t*jY*b?KtHAW)8q5EGTz7`C@TQYpj9A;8X)+B17{rWq|e zbka4F+K`OFB@9?zUZ-@%pkQ-(No*C}q`c}UV$xwg*NnwMBiYZ$Uh2`^AwpRu6<%6g zEGi>w+>zqCo=`)Ru7$kkajpdGz4nmdaENFMUln(FM)e&c@QTkUASA;DeLnAH8 zl2oReICU+Xm)L$9@6q!>&uI+Gk=7p$6R-q$$&g<3%*X0#A=N9IvE~b)kHVp-P|Id* zl++OqZ3RTpY$EiuP6W$_U0IuZWT5U7$2qYCUmGt zx=k8~1kPkdy>>!YRbGij(kHlD6-}&RkGP!qS(o(I0WF7qN7(a9kk2NAD0^~g#)62MZx^Mo>!`Th zA!D&LM=wHZMp5c*EeTomU{#gmXnIZx`CZ(7FZQE-*wQC?QI$mZjw_;1yUL1;!3 zP>P{-x;f4$u>Io0`(LvzjW%=c%0OI##!LDhp=~byphR!444%5EwBN@4MDzsY(coPZ zFx!%+9eSd0gSTCyA{yeQVaoPFL$cm91E> zOJhi+^|ta0XUNejf>(E05R4+wX=fgvFyV|7S+y(rNt^Glem@Wl zRYYtoC+~Vc4O8OgEXq_X9#$wtQ|<C?B(?a4MO%T(wp(8*fF z<79Cf@qVsw5{cC0Ene^jY?$-*_6br_kz|RmtoPAH z1+2)n2l@q?s^zYK8XLqN?<3qGSF} ze6_jgbxheqhJ-0=-2rx9-3O`vAzGmx(OTXmrX)dVVr(}8(s5Jm-^B5n(&!^>pog76 zs4ig%^|H<(cKj%f@od0uFqU5gL&fUiVnlAQ0KrxGSdl%a&2O9tygF zIxRhc-a|x#+q60Cp#)Rvp_uEPnt7r39E&9?PmwsHVtP-zAj0)e4?4Y{7Kp~=x(UG; zf6mR*_9iCNOh5m6rwayxVNThLYhW&b`iGoZ#GL-bXo$1IA#L)JT+dROHj&Ga7l?!UP}KuFPP4+%Ohn*!u_`vbLnGSMOWAQg7oeZgZ3dBo8^Vfol=f?!c;w-hYELBE)3BA|FgwnI-zzQN5$ zSRWMSi@*T^EMg(nf8#P|n4EUJmxhQ{guD!E+T1{;J7x zR>gEz9JNzAzlE*s^l|Xs3zw=(@stFTE>sNCo{NCjLq)nFwG|WN)LJp}fbdLVA?yH- z{eZIA(d!3AOP|*u<>59k)q;OKF_R-XO4=-*d{>U0JXX<q`}Ou-chO&=XUaW%NN&cmBVHyGVkM<=Ti-5hOg9ayztP4 zuG3#ea0hji29BlIar^E=2_e?r;v*wAGXU}kW)y7{b&{e%b|LDa)PiCZVsn~}F2Y)d zC9gZc8)v%`O&N{cbQ_lAG&I)cM~V5O92n_4T#BKR-|`yvS* z?=R+J_#@w1q>=L3e2RmU%IxoyXkZ{AUhc*(J!A0Inm%L%EPCabwv*jA9wMiWnq+*p z$yEBq*s{D(hp*3%POXN2EkvZzbx>GON-l(#0Xx&!>(8cq4QK6c`O)Ow1=+>JAy`o> zJJGfG27E1dklkQ7`6}O$zLe$FUJamirP(Lk7Nm<=wr`8x+Dhp7X+(0xV;CEEZvi=M zw|LS9ELijzUM`Lk6tWB_X8G0ahx+A$pQd&^Dv839H5B=~HKQ$#9jL=KiYB^W>A54+ zeJWGLZl`~m@ewETZ86N0q_@M@W#=z(`Y(q*nmLFu61}`T8NMY-#s!>q~JVI3-cD{6GQt|P_#Z(#{O7vx1pDdjTe>qE+QrQAM*21XP+sm2S?Rc4WP zV~;w{1^HP@467zO!S~j^ruX#=lcWq@X0)oHE#b-%@&69}dY{GK>PP}zedQ62tmuUg z4*v9k-y5@ncfY{~C+XX$#>Fzu-fUW{{XK@qHa6q6@myF#=s?RxH9bF~C^g!e8-m5b z5mJu9F_MHX4p3O4Qfu8!6-cyiE)!>oHUm3?f(uDqv7ktOdxKUtEpDg~Hbaert@5v2 z7pAA)z#yF$y-00c!Ax0>#pf>kgJw?aU`d|A#xb(U)G<9>YYqFy zCzl$e!7_+^)+|XlqjT5wiR$D_Qn-onWZc3cKh2eW?W~-%a&waX?$m0}&dyQ<3h6AP zUtAFgEN9ldaEHi>D(zS2=PTS*| z|1d|#zM-kdV(u|feF(6z6=w2L2xxBa^*r^;k4QoqzTEan<3(w;do?)NXN|?u;)s}3 z%S#LPIaJV3hzxkO{dHvM_t z;`i$D<=U+#Kf9x}RmAI}Sz`ecr?HsWn^gOeVwmGvqR9<$dL~MP52t@3-xajyE>PM6 z<@&I*j3B!v?y)wB{jZkFRQ4Wa?i8Lc^##XQqo+s`mHz&aB26i#+aVgb5v!4XMB+xI zQQOH8+|>-pXzj*Ukgv)Qi-|_0JrYLyLG7AWj6F#VHsV5kbk`5F!i>whpKC1_n3jA^ z>TKbKF0f~6Hj|5{33awh%A zV8lvD^MHCbI6RrJzfW2UZbi$;%`E%7KoHM?Q6fOD)uAwTd@8h>ouTrj!PjFMrkRiO+x|MHV{16!9miU&)x*Dm+I-u+C&e*pilzP|n|*3bRX zxHD-)o(h8NL${hwTXL5M$E5SzrEXq_{&(t#|nV|NbcOtA@&q$(cV1>&GN} zZI3HI{3eHq?kqJAkWrM$9WWaH!^$cv=JA*d`QhjRcH7Jp9e3Xtk#H+UUozsGFOJ=ok=dY`k-K7eq%ukyQThOzMRiv z^{w6JJ6m5M`KC;%t*oO{OcTmUNQEiR5;elqrk3ae_bdgCR#P-y3;VdMu*UVUh~=k&>?M z>H&=tO z?t)??J?Db;t==StBd~fj0u$Wly~!q`iQl?vA4D4w@_4&<6Sf*SdnTm z#{R^hO*LLQXRwB8@#|Lc}gUV5>HrE(7>x?Awll)2b-i5ZHu zjCZq0#H3=qpltM#k(8J=>VYeQ`aTR-E)D&}blqI(rI=!9WttmefDNI`nR8NW#4S@K z)sOLdx*6IcCsRAmh6FzSWOJAj!(%UaJ7WBJCr^TSCY&n@ZB4h_a^(QD0*h{!sG?Zr z7ZRL{+8BIAFY=zG+}#kmaTv}IHJl`03((Qc^rHGZ$b4Ovu#=7{&q;U<_G5882TYfFk$81B zBM5>UAupbNNb;eK`|DdDS^?87>G3R2^38iIXF!u31V$rbs-zwCVGLW%0^iLhDbBi) z(^3+?IkhL8{BqN=Y_3uDWQV_k_ z>rn{KRdXjuJ%-=Q?v2`^bKj!4Rq!`Kk$n4SCWBqzHL9BCR`6j7*3F+|aKGbIXugj> zO=Ii~!{#~Mc7Od~t5$cyw(a9cQuKbFS!iA_v1Y|jxT4N62=qCp{%Y9n6=qAxl?ZUF zYkrHdFRK4a=lcMV;G&%Phl4b1u73%w>`iV}$LaFJB zmc2u?aG~zs^U;ZssC!Qx|J#nnzPRDtIR%AUE-ub8SqLGb=*Lv!#}H|RGaki7WJ0{j z%U=np;M8J(G_;LELNw|4(!v6{NXw+8m zL|wM%S^E^aHZ|(1Z;GTpz1!7U63U0>m}08ps`P11zw;GA;z(n+)=)RX**E+==#bmL z$z0@WAt*9k;OB#jD~6n-^;ZbJi-c6XpEMQw7rK|eu}1n5pX||yk`Y%NB>R}%*(kTg zoZDt`vKKhwOka3zm#9IJ6KTRTf>Zd*`JRsy>I{J=X{);nLV?Y(cG}rx+oA6X?CiFTr3Z?uUjAUKMjsklMPnlT58Baza|k| z(t;8*90y4iNeevy>At)Gs32#Gj#yadI~3X*OI@bh#0Ohjkk*n9qM-mo;13^zD-ZAB zt}7d7PrV#m@OPQxHlGQuwu23ae3rkOfe+$f>y|b>FMh)HA^e9=(}-T;nI64ojLe3D z-!!>CoiJPA7@3D`zuJS^eHdSVTSQ`$b!&K-h-nxfqRa|kGLX9bm^AH&hSY50g4wJg zFW;hNE(QiO%E+5GjN~Ui0fDNeY#_K{!Zs?ebTxkD9ydOtUx;fuFThKFu7K#+QMbVo z0P--Imlpi#*pcVQ#0?O4=W*a=(_riK2rx@C z32Mh=z_oZpmT4AI(dD{aYH^%N8|hU~>BY|Jz&~jV62m+Z{A&9fci>&iT8Pbq>+!M9 z`eYK;+L}DJ;+#=Je7%tm<4klGflso}kF!j{`Nvz?BAPK>4)1r=&qzOZkWY{J^JL-G z{DrsE31{XepU~J065`LzNZH5w3Vir;1D;=}euQ!K{HrxKj z+|6Gva}yF`SsWYjQ#anJqmTW-8TqwT@9MzzH=8$v!eKtz#hsw0D}c(&c_sWhg}-2d zJ~oKsHTqxp1v|x*MX1$L-ai5Rfq86Vy6&*$Nky*cICV+1|5j`)$*cm-ddUa}X)uA% zQr6YOS=>)ti!?qqOLK<@#U<@BjL7m3Ee#AdP~xPi*f2S$U@{1Qn_ijbJj!2zx+kYS zZt87b(;r)HB8}eKr5_CoO(0u{%L}#cRV{#>;qn|I_B=mhfS;rfe5uevGgSj&e`X=L|r8&6u|h6|lFJS0Ef=u+0H3Ppx3L z+P`~aOp7bupzdYaQT7^M9Rw&Vs83Ao7gRbQqrb{`4FHYv0)tYkmwvp9Yzja<{kV*F z#}c~!9oK@GT~d_S$2NhL-t~x`c%rm!LW~wgC)uWsl#L2Ps5)d1y_ds|h82s4>5IRN zTWlyGrfL$(bDy5uBuRiQ7+%4K=U|;XGrkg6-Xf1Iz(^twORAZIEyw7YFqWn`5EoYl zv9X?V)AjagKKR9;BtNu2GT}hj*7(Uc8BQ3HmKcbkI1@g>6H}fl`1$LQsu~7t^TDMwko$Tp=vW{}&_L+eNVl=|x zE%&zZ<>{qofzaHb4DLr!8}!r0zrK3R2PB8vV&R?16TZ7i4ZhGS)q||U9NyuHU2YSQ z$hV5l&mive&xt-plA8)#6uz$pCnqTna79=sYuus4RzJwJ=FsAKLg(jdiwHY(YQrzi?Gl*Rl!jLc zU3R*Wdb)2HmYop3b0g>R^q|rw@3k!_&l$#zCqGW|WeuYheA}4CJl|-6<>#+zev(f! zE4$G|bBkX8Uag9vu>)((6h=0xvTb_q=xIeQb`zI87i$tahD&nXd!`FLp zGdu7LSa~97-XeQ=@tD@_0vd|HmrUe|L^-%&>Q@8`d^_{CGm z6_vj&hT!>Zr*sJf1Ymz6TH8I-75KE>Xb})hog-7!hE;s@l?s+^LTLQ7-RtV*D%674 zaGF*5zY*!2k-5rRf)_Q3A@v(sE#zqaH_yD8p`*p70jnFA-_g%y;bRjdBEC@BD!VW^ z!6|hTAJW9$d|U1!e)Ksds)c{Fq>vRe=t&Llo1~jcxCRs?LK`p18n=_wL~SPHTUFSo z4CHi*=3e>~M@CCLuPu)*Q7ZcO=hU%FgsvGG@KW7p?%3*_6!o&6uz8{EE>%VWL_Wh-`Mseo z0e-`1%40d)WR*5UyX0)kFp!_%(lL+Hqo11v<*Qr|AhpKk@{1_I`R_t29e6Wzf+PMU zEAo{ZBuwAYeRr(C)AxcGgSS`y7C~?OmaU5KciCC$7&xD0-)15=E`$4r$3ta9P-646 z;*6MDoXjFep`(-2!)8a3QA-5uUAed&*|=!!rFIfi?__+I6Te3`@n~A*b#y0%@dCw< zW@r#>|Ho*zND2$LPPcy{ZSg7Pqe*LQ;akC2o!)=?sRU7P?sxW z2rlyN?n9PKlsb%$zEz-W*N}K}mG*P#(0=MXC&kqwRZZ>{%)9GO(Xv@Ge>uJIGiD54 zg(;{Y76Gm*Zyync+l^Zo8N71$WfCyThlDM$yy`&ut1)Z3$wh~#g^J7Iykr^HMhFBw zH^`6q{{4Fn_b;MOU1zAvt|N|nd+DsT;{gP9>=QcK5JLCf5IC@xU|7W(J`E$RC8hk8 zh|6XBW|&B~@jFUKi?hUui~h|XOei&fQ26U#r8kNM6S9E~D2+Q~pWAO3;;(P0DNI7M zzR=d&z+?BuA~?POvfL{AB5iN;^2tngJqR2Sj7v4&aQJa+^LUTT6bOY&$whKnoVktK zDi?H>W0v;@AsJZbHyh(;%Zp0Rvb>9cVLO?8E#}UG*zPAI7m)2I3A=L1;F~bV#YBcL zh-mr6=i7+Hg4!e;p|qAbInAc{k``S8JX!+|jD`OOIE&C;d$4B4ZVbO2;v1C{_H*S~ zjiQZ{>2$Mv6{3sVD4aFve=b05%_`$wglf`8j^WA|T;eG!9_$T*}cfRcs$}d_ zLH?=CPAX2HcKKXh*s4aBaQG!RcljKs%;2<5tVpz^tgIZT@Jjuws(c}zbwS1wKmk({|CiNG|jz?wTjQ*{uLUzpC z0@+9PEzHpU+xGR0AoU5Y=`Md$5F20rZtcP?%P@mj&odv-Oyl0}i%wi;5Jbp{;8^ zZe%C3r=6GF@S5ZTE}>RUC`&OPJ_^k^y+u+2>}sqRW0WF3!ZXMnQ=>A*je_?_Sr^P>NX%Cfrba%-6%--oHeYX%a5+O*qt}7n z`X_)pwYF0-7w>mK_(RQvT(&DSZ7&uMW>X5Y&cPbz+rhdj_U_w)h?A8rgW3CeX%mhZ zpMfwG;#bLO<2d*+0PL$RPAFr3eHVthGm4#Fcx;BqbORwZww!xkZ7J=RqH*{pkcWRj zeK?-Vh>0fa7o}F-XWk^JKO=kQ=eo@Pd1?IKbfpcLkPnmI<9mI^m z105Y}IJ@k7S2G3%h9`Bn${tF%ajo6vE96-Z{9|h7JDKYuHwntm>%!ptUL0VSI?c24 z7|;^Hj&V@A1C$DL8Y_rEZEkAoihnl*#Gfj`c0}1G4g0tAu?Gq&m6qAl@z)>+p{IB} z5Fz`5f-%t1H*f3lG>l1KU<+A}t)$(Aa>FuuQcTQ)YzGI2X`UKLK&}G6Lg8&#KMV$G z${`k{k?N09FzjTjki7tMsL|L<9+1Y!PE9XXAjvp8*MdaV`v+;b0Ifhi{^lqVh&C5k zS}k_S7p_Vw=d79sT7aNaQ^9CMUovFL;A;yM zofU`G2habb!_urNT{|tr(4+P3gg(yq<>3*my^q%>>c@Q(&B#oJr!Gn-tYt z3APhmc`Jj(Wnxx19SOF zu=RNwkEz&=L6LYC^CKiDl54>HN}m9Ce|clHhB{+}e3QFeW=IOT%+v1vM?t3jmFu&F z!W>n37$_H#p44)2Bk=Ie>ve}}cCzd5O2;y1`S1DVMC?ur3CBy``IXEeOU@mb&i?R@ zdee0`-LY3>#*hLVl;rb34`{1 z_G|X|uozJGAXG3U{7E`B>)@vdFvR0c9L{<23+#ih-tC@hbDr76wQdDf4}@Bs*7faNG$Oq=I!4GB@|}-|%zTd?`&j z*cjN;#iuvEw`qE486o6EOaCA8P#o&64CVyesSwz>u7|CH0YPk0&O5{+cL+^CP;m4j z$v%rYBW_br)Sl&uGadC`a<`I!1$f9$)4fr2_U_Ix~2F!a}w*z&zHg(9I@SN$nL@6ro0VZk%Bfa;DlD0vO$wBZR&bDf+#vkiLbUu!lJ==SPFHgipENn ziQc7kdhfIh*ZCP+)vSt=Ik0+(FA2!g%3E1Y3tC8QDxAv_2BYJ^s*9N#>{crt;lWIl zbGW>+_y9)hD9)tcw8MlpJXJ~pWI)cA-phS0A>22e#J=84%U6xH_9x0lRQqoQ+_nUA z{qB8_=G*1&D=6*F2~t^%Sxy2!s%OyjCKd_$eORverL_DK?cvDETCG7hl63VFLV@j@ zw)6#9KrS9Y+CRNJ>t>8HP+8k83sdYsXx{4|a0NfVVZkn4dZpS5Q^?RbZ@SO*Q=Odf zQogf~=8OzY+yV`)woeJLM{_uhS?MX+@W25{?N)T}S#GrYzU|9zr8_1nJjSq$oNWrl z2gWlyecM{5;VfwxEK`<4CeIKLNF$|Df;V7reng5x%nSuvQ^%otf-D`}tImpaaA*6u z_{xDY1sMkHz(h#EciFUfUPf+mUITJpRMy>3C=SnJGnyKBDAg2)GGnr!BK3mnH;|& za_AaOTWo)kvdHHZSyeN-Vh$JT>t|YtCh^KF>Oz9hksnVLp0XA*w*>V>9**!QVe1De zigiwZJlhU34{@Sr?Q)_oatI%yUpf(AADMIjFgpr?E9|;4P>zvYiD~U#IvEJR$EQ^> z&K5qyKq*G?SX2J2e@K z#95s?4)8dXY};0v`}W&zg4sHPgGYU;C-*iHUN73=YHs+hZmWxuGInTTRbgME23P94 zZ*@h4YDg>vfyVANI>RuvcCty(kDm;q&-PM93Mp3W8`R&CN>a5`fzI+O-TxT1vIDG) zkdh~}k>dOnvRO)A+6q3vU#`PMI;T}tLBzeMK6iPdmT7@2LLj$o#Xa4HQ*3FnBsa|M zB{B7-R6;%gc0n)a7iZKUXPna5);5>k8wKjC&^zmzUb97k@$~**Ft}z#SHEMN5x3A! zO{R8j7l#0)9!{X7D>DGu4f-h>38R>MwT-xQqJ$gtN|<5)R?mQufRjVuYi=$%1dhtI zrt!VRkuqrHJXv9Jk*lx8WLoLF^LHKOtAPA)7~LX4%*chD^gNl)0xiu1B@RsRV|0W} z;zWLHsX;WmQ+~la!qvC!IE#kn28id3-}KvA{p`1_BYcT#o4|xe<5Dk0Ba!v_rwWE) zVE?8JgweJU>{()}5*m^zIw;bbepigCPW!><)vHoZ5X(1|eN|lHEqVFBYVta?=;Z{> z9`dpXe!y%HF7J97(IBg-LKLItXRcpEetrc7_cGQVA6RH;G_tw3&`ucbU6_j&&TXgD zIcR9yL^rh^4Uk8@L?dz*a?=;ackfG0jCu}zCc3}7!F$6Z89<<%_wOPhBlr+vW#%b` z4pYF_WH4*}#5NgX5GTdEJX2;m61Y#|G(|Hk;mb_v$yPb1fio;!n9CqgY5z`Ag2LzL z%LTvjrL6?eYPP>*VFTaiY&2n!-KD?%?6-JXNcCEE-+o_{Tct#JoN%l{Me_2?Z}&T! zzj|-a4lmls1)|B6*c)4dJlOI~?-7^Gt0et&pFF`4*sOc_T!mgG2j6PSzG) zSFq?t-Xk}%GoK~gisruKVK!!!w)v~_H!yJPru8wM-+E>04*a{AlaGwF&f`cRmb=$B z*Y#}Y^Qn7*tF#G&fE=+!xdyW&T9Bd`_F|6K&zj(S?#JiSo6TV7C$29tw3OaRJx?bq z2?W;9Yk0YibyIDNp6S<(11?1qXxNV3JI&Lx0NYD> zb%t+BS!uP+pWS?Y#Lb-=NWl2c$k>Cla(X1fZM)MD+y?g15EI$*wW+uL-}ze8rG^&< z$`4H*lnJ{q^6_I8IlJAQf9yk}W{BW)w|@Uf43CkU zE5dH3ovb}Tf4Iqofx6E@^4o6+qKz0xUoIncw>&Q2e~G~4j#v?;Rx9P;5n<}{Q99O` z`Yg%|X8`+mQ7KU0!|!du^or+LW7KN|cJCtSuRhH(1Zrw({F<=fNeTTe^>#-DnY;9j zP%F2aJp*r00Z)~9E^O$O@*oK%W63Ozrfuw(Z8`=6L{{n<@pU~PiKW#T>5@+mYkG5Y z4{|4(ODwgE4r=jjdS2EacFaSxa09|r!*8<#bX4X4d^M$H@U*Da#!hKzk?&%(kjMpw zo85rL8OM#K>ch9Q`)p0&Ch0N3CX?qJ;45}!6%w|z4q){2oeF!h%}HOa6GBuG6)Y3ys2 zX8E#wDPE!kRMPlB3)B2HJ0FjwW%_Y^y$cEVD3ZMmB5P{Ac=%>3)vpEJt<7LyBI?HJ zYkc0CqRqV(%4M&~b`D3cd!u{r1EcKBc++f>t!wRLA(O0KC7r-`!9~Z281ta#-fsi= zWKVy)oCuPisc=$9N~~6_w9#hf{}jNqzihZcR}%Fgb%ImL;jF`YCBxRJ!~~VG_P(Te ze<^$f{t>}!+EE3RM*Ks=1rFsJGAso*Z=VJKl_w4~_?&}gHPx%D9U}Cd?0{0oGf^*q ziE2l9)9WE`)oKkPP}}S*#D$M4yT_EOrrWw}bd}ByFP4Kii>uGp`?SrAt959@Y0_`$LBq~+7?O5P*+yG18hg`lstJwiNxNy|76_>_bpa}*BboaecJ8h!)j=t$y1NORu^g7Sf%>` z=%>m2drZ>Fz%{np-@1D1K{w`f3} zF%f=u#e3)^D*S0W+w3lWcZU*@DFWU;$|YI%fAZJZ2iGl#0&X&Rpcgc@Db7)L!2dRG zmT~g&dYCTj@`=VF8>Tl^VQHyB_(CXZ_wux?#q#6I;l5zGBn|NU_YaMasND2(>arXL zE%IJ2{*-XxXfu$W`eFDM5{8*On;LU0G26#%IoSwKE)jHbUIXd9k_dubjOh1b;-oQ5 z5^z@2LK>K^c(Zxgc9FHEv`=cOg6M|)c{p5G`aDfbpmYw^`wI^*FYu{?nlxe0t0o@@ zl(n5qx|waAB`mF(e}-Zw1#DK67f=ExL@ROR8;s1)o7a4;Pp&tB9cLW9 zC*Ht%C;0&~520|Pp~0d1q(&X*hCITr68jeOyAs|?BhuL+S)jG? znf*ijOx$yc_Aus27oZ>v*3sFNe@bF25A=NoYJF@(8{dUZ^LjAO)ET2tBiABUOQ!9nDQ({r}l&9 z5!#LDk9c3zz}f(M1T`ANnamg)x#UmI@fo!^7)2}VyGua?)KWZYuf&?7A4oZ~ZH4K| zc21OxCCHbNXXgtl(^=teZn}L$%%_7~h&J!^GE9ibHgmYG_sSCuRbf^^uFBsXJ1ra3 zVKE33B(ajDR0UFAb}JRd8|c?v?z_L`taRFw?X`h)j+P=X6lK;{FMgMJ{~~7q*j}Yw zOY2zjn*BI|7OFl_fI})g7p4W$9VxV9IyTARKl9NY=C83s!)JwZdKHfD%dVWyf&^xM zc<*wreB`utMfr+$FcD7pR>f&CJbF^8$avWFDQCoWZ~K^#9nPV}PeRewO|<${8=NpA z{!C=JFod!V@6;xnzvmB*Ozl{W8;?TT_B);D_clH2IQfa*PO*By`Z$QWHWBnB8dd)* zpN=KQ0bc6;@hqg-$mf8B-F*Ln)=_sO)VT9;tQ5QJz>6jBX8mDxHST(_n!z{gbZ%)i z0@+dPN$kqvIo9NnTI?K>V7fnDtlQ~R54AiAJn^4eT}?1>YL{8M^NZrtqroXhGrbDM zu4renW{=rqW$r)Sj+ysT`kTe%bGpESNvgcLe%$a=f!BDMD?;uXe`*ZiWv^SG|+(Q6v2A`6$mLl zqDOP0#akAID$ey4G_5MhM3i+n1o0|${Hq_3KJQ=xttj&HE)E*a#8GWAhYN?%6zSdumomKKJ zrNR)br3U$BW5s}P(rPo|TZ(j|`F3)$8pNt*d7=ER!to`tTCuTw74o{S5BM0%S(=wV z3RMB#ba=KWwlW;pY8b5r0cc5e)aBTyuFOQO;p*Ix>&wPO+F5b{q$VuVjZmaF(cSA) z>eaPQ{pd1?I$wMH$}OO6-gI_6h-cWFucu2!iQx4r{Wvz&@^pz(2!In1MI|XeN!UZB zJ9;fIWy-litGImV!T-t0!SMYca?!Y^W!ffSMF5w5=Tf{C9a>0S5)LlHf&1j%@0L*M z*{EQk?|bPkX2r^j59D0)^YNCYQmFncDlwD_#8r+1HYW_;9Hh0JdG!7GLC9v%i0a+7 zt&(D7tJ_o9h!=~`IuMF{!D%yY=;1X!=~(*?kTS0tp?e7ohJ?F5DE|0eNkKi`6`SpS@1x=qBad#!x*5+lpm+rV87KRrs z{af6PV7YkTHU>qqQiBV^X;8Q$Tv;^yV=URDnLsJ+$6ME?nmR-2yTC-TjJJq!>etMh zJ?2Ms^u$mF>)q`fNL_)W8*a{Wfni?as<*~XcTl5MrX>$=O$C>Ye1NN=m8BygF>&%a zumzYyO@$tDa82 z#Ro)83DR(<5J~?B?2mYMMvU^tnF?x=)dx zO#dND#fpmvYel-g`G^jrhaN_-B+IGbt6@A$K~4)2*~||iOsV6SYx}$IZI5&Bs#H@? z*LJA?{^)pZl<@{r*=H>cE4qLGl~{lrI^4@jJ^q0s2oU>cn=o1jm8*qGRHeSwToSp@3~k)am7JdFn`m z1&u-r*t4b)*$dx`gJY6?b$n+)1oh$LqTQ;kkEJeegM9i_TNkrA3}Nae(+uu*{)jHV z0}Vk=Egl#~FI>JpKU49_6lU^@u@jSIUN)&n@ujnRIfKz29jk$ujCOj*r^^ku8Q~*a4YIoq#`3c zi{(XqSZBLY+tal{{oh6Vt8gvQ>xO?#Sc4FNCCS43@Fls3p;LMBAAv&KgoC#;g4e7g zJUTP~*jxesjIYpdKx*+5i{{559=IV@?8tPKHHAiCCl>H zFqe|ej&;HWSqs0sq&q2+uK-wke4SHMePK%-Z7>V@jJKTsS3JDUjhkVgvfqyLh6HqU zqn%tF^qvjEb~ag-W=g+`$+(>U(1pm8gdI6LX_m|pCyfjx-w80dv7#J&1rtGi0I%Ci z>Q4f=@DJ;+51Kb>Qn(JbSTn;2uEzF-zwh>ay^IxhscQVIb<-H81oJ_AbA@&`YJs&j z=r~g6R%3#Xap&`aw}7_^PgF#yU&fWNuy$Z_&c&~faS9RsM8mjc-(3jzyP=$9KqFb& zQ8gc~Xl`?}BWnpdky*Z~G3f;}B$AA+Ron!U20!ut3q1*XPQVUaH#wd7cUh-&qS;H6 z*mG6wyw3@vc$kMLPX+JgN7jL6ndk>qvGm-Fb&6P7sYa`kym78A%mQCUx5))j{dynI zq8}zDUNIA`YCP1gXlcV??8P^V zF_cOYsq`G@;llSRRnUeqj8vfFiW`u3l7W!BJ3k-Au{wu(=zZ}r?xWaCc&2S;cegQZ zRoSPPr+Gp24VLOm*F~C{WsbRsUr~^fY8>N&!V}Z!rqXhULasxt$J4)IGK%9UmYFKA zizJO~6a~D$xx7A@lSh4^p($iazK}|?R5PBA11C`B;Ds#93EP|p;2Z#>rrN}#k)f}f zcBMnI=@p>K_RjYGRW%C-^y(@bUyI)UTXPs9z$H!YVr)&MG;5<0TW02kk3N08v-*H7 z^#KCT1Qda?Nn}G~41~+KZL+5x3#6-iA9CG$N1 z*2Jq<|1N>j5?XqI!J;6MW7P|&NRm*kas8W@X2{pMJ#OGKXvMrG%2PmvGdL}C;W}$o zd7A6pMRwu`U#kCmP|)q@jS^WbV9^fu_289IeAwq+r zJD#qWt}M2kpLd+=EQfLFVQZfDV3dFc5a}UXA0C>ibr`{*1B$<2KCy+r>X$l8W9*b@ z-1w_6oZdj}_UrmN?%ig2Sdl!6t zf?v$D|9*}kKohp?z05Mv|8Hl-w;}stF}i^}5N#pHDI`+0g>vjlCg7&q-CW^^YGktd z^}~LUM+`PunxHy%K6lRg^`QE&-lz2+M#vs%d(=3xOQJlstBZ@&zM>VcH5ih&gp)1R zWsnbGC9=wjtZ`@2=v?P4(AUcm@*B~MMolzx2n6*-xe5v^>SVHhdA>E0!{VnA=6qQw zc=5$`jHaSXRx*KD1z{-c+G!At1oatoQ*XBQ!3Fg2-;p}eYAOPlh0~1Qu~e3fT5kBmG-7}qFsRyh}lj^{Y@H$ z_d93^%N3wtSWTa1O2sL04yTnhe6u|pKY*RHnrP7ZOEkLp`xd7wY#(2q)&d>!5#0?f z^96ItOjjAf5s!up?=~2dk5POOkpB4OMjNu>zBsdt2(QWD=J38IC6cPvZL?*Yt1=GR z9!X6i~caWq=)%+0(Z2G{;!ScxT)i*@~pff<*5YdyZ@xwG+x_ zf4V&wv~tdE%`}atn9=<~JZa4*bKkIBAObYwd){Yzv)Iwi0Ncb&?kB^!tIP8gW0bv1 zj`r85`4`1^x)PJC$gq~*0o}#}SF`bY)ue%H%IxlG04EEJuy`Ag60~je!KSPHg}yh0 z>`NgM2sJP+*S2n{gCg8>nSF`I{nQGz1-t`GR_)_CTEyuH2wU!=vl_JqY4SGhL`jKbHl!6u>WMDQdvah zDuuMBJ6erV52p9BFM;)#(RVA5ghqGK+;efqqhMyqdZ> zl=hh3>_R4XUmqMfSUtY-D?05API1fM`BWJk&rG7E_TxtIacs9Ilo|d_I-&uLuaL4=aGCxkw9DROAooL$vVYo7w)^{a!xT>jCScX+FBd1XViTv! zT;ng_sZU_ag_8jEB=6#r*btRJ3lz|=+Z~Q-=dw>qast}|zJw|nGOLZ!?c26~WBoQd zO+A0O=r8KuDi_$f!rIrHb>_PGa+}ZUHuq-GTBS2*n1KQ*F~}cBmYM91w$2bLxWi46 za#=in8OL<1 z#!s1NFZ(P+M3$9jc%og#z&1P9;r*~Zc}wpPaD2(-9iUbBJ;?POFyg}S6>%EnREil9 zR#r*xt1N625X|*#xjdf3{eDEJT9O5lc*p3T#;#3jl_R-2rm1ksY$L~T?XMxPfPoDaM zMi_#JGihSgG|>v2tA>+&Xa)#-O*DRRG^lXVSXHN(bh@!-G5@C3GuTdhokiJWTNH#| zn_Q8eD7MKy$M6u>sK=&1Zuiqf0bF$~_CG+UF)lBaaMR?sYPLW~2Dgn6)yo}IJlF3C zNGcjYIHikCQ;vh9#Y~OPU$G{}B~)d=a7RXfOV!xkuHOAGhWZg72bEA*2KjDhC$-P5 zy&{t?V>Eq{w(tuohL7fa@fZAPevlTl&Mx^}j}6G}1lhW2K`qzFlMc)YO1QbXVGNO7 zGC@$HBI&ApY4z8zkDVwfL2K1KyPLArbtJJuyqhXRJ$R9nLdR{()yu?#8VrC!AcnDQ zPO0X(wm7J#xzW4GciOLPgd-vsuA4rrO3Vfnz%Z6Rb5W}2X&rOmQp?=E@DohKO&7028C`dZ~9wKwD#29LFgo^y{AxK1R7r|Di|3sCf`dGBZ1!@irEU zMaH9<&_z5U-GnKzW*o3>OS3xo+_;$NCReANb_ozDDKJbo)8V^705UXrJd%>_u)0_o z)OyrTD+A)HE#GOuBSs_*Y+saJ*%|Z zO$CCqgD(Seum2~{0pYL`1I0C<72^CYJ3k1ZXOznd0Py)zGh)5@o~oy|gUu^mNloHj zNi*CoO&zV9ZJ9dS5%T&E6L2G2n#NnuwbPBCaF@4vfUeC-FP9AUJwioadyd2j(zzZ% zQs=SFd*Rj=80!9)9d*SZ>9^k`B}d$7MlR@zc2OTwKyxMtVB4m#iQ5vHD@zdD${<8 z1hduLz;xl@nhy=e*#beN<b(dqsqg@alsbLnwo z>cA2f0XT+4e^;e4+`5ElDfGN850q6-)B+hcH!dz3&~~zHmuT;??Tk=!WI4u&<{jeD( zB?T&t+Exn-U(M&)Ql|c9Fsv&_j{i9~vQ&@QUoPmj>op?UbfUc)DZVA9pqcZndACn# zw;zU`*$1q&We&5){<_28rtlMWXzaGC5Xz=Dkg5IPTBaT3tMR@Oc^WGrJgG_}j=g6X zF4VEjxV~+nw;^vR7)~(4Ye@j)7lR|D@(x7|$VNPJE0HJ9(@LT@I{ogL0h`vkO7F9-VW z4bt!hIn(S1N-mkn#wtBpHOfE$e67441B5^`cUHjxU1PFMA~_5-kV(VIt_sqkz0i>UZKaEhzakZ{bWB>)xPJVI_!(%U-_zC`THlqharFK;9*@$ z+U#~4wZooU(-*q<%qA(0#pX7?=}xWbN~fSoMJ!&J6yxRbJ=0@eXy1QoLlUN{ z2*&xy_Tq%9Ju~p~`)BXl_mjVWR}+&{%fxb!NS5o%#xK=bid23ztf0iL!NZwh?sJns zT0jBEsk|uUQR2otUk0fIYd;yFo>x&aGA=2P-z1UoGO7fT*_Fm1P~wHsbw{XUyMt`& zOICtvl&Q0Pbt0|_5zT3Am1>p*NY`K*l3Xa^0)vp!0P*5n*-o6YX zBsPWAiOEXRsAMNB_pqRAxtUk7i7Q6%|^r>2$;rDU;%*&_}a-T6LSCq}nJz zGJ~KWlU}6uNfXI3aLrH3?cpSBVyT-*hl9!+Up>8D6*`cdf(ZqPwo@f)t|?ZNsqlQA zqd1knB&F%x2s-&V&TDlkKLTz^1K(=i@w{K63psLznrRbFumN|R8UdWL4G;hkFIzir z=2Ezz9MOb83H|FGsCAQg>TrqGxFshaU;O$y=dGm}e8W}gv<`!@qqtqKbp#V5p-hP^ z0oMDL*hiyS2PVWT(4N9&!eSx6Q$=nlv7x3f;i&3Ve*In^Mlc)XseK@eJ4b(|yXiu36-USaoUR!>s*`~1FkU-%f{Nx*K*&-q2zg_Z4f_FMDO&8v}G zF>%>IoxUZHoJaG-1);#%&JRD!H3nC3`S6Klv50#{q-O;$TKh%_G3~mZTQt zI7M*oC>ir~`BJSl%x~0O<(&#(tL=wOVkVI>Hd?#)?;|}s%nknnHC%(7eMI|_}YaTWX1;lL3NP;`4sj|WLH%_BDj zZ>KFoo*noLZZyx1+2hCd0(zQhcGu=DlBLptbWk|ZXshQd3H|u4O%P~%s$QvN>fhx` zc*d@6>m<9`BF;yad80++caxk^>k-LrGepo|mtj+cg*2|4MHXzz79ZH1h!6thJt(^^ z5-4eB#l-6RES@9Z!wD$_W!fMQyc3i>i%4inWJEtH?c(q(4@&q|{8lnKR))l{k&{pf zM{mYHJVBnPFL$o&#jbM>Ydr@p1-kvuhLc9In16C%2yl-kbX%07&%9|#3G8pt5FVW; zvRGBmibdiY*?443Zu_R;r}CU)Y5Y-9CZ}KKy40z|qs0&(ZD^O9i9JEpay#?ADwGx9 zDo8Qc2T&2dy(ggRzx`#u;blh>b%b6IQvc}kGj+i(k9HMhgr2oKs5{2pl`k+@WNBL~ z`uu!L);up?P;WrMmK|$f(?xu-%N}ZS4kZUjR9SLA$iSLB5@+O`#Eo9aiUaAwX2Svc zhHnJu2hyqfm`ZhXVoNmEU_1bd(Ps9;m3`|6(;36aay=0Ea@lrj#ME&XhUVv_TQ(+Xj7+ew| zi?fI(u;PwuL9NA);4gc967A|P35avR0_x8dc2y(q*W)xB@D#qdcX8(r5FQh&i*3zu zEK+JdSZNHO9U(o2yvoeV)GqucyQH0=xFw(Fx7K>j=(2%DY zE$Qe+2No>h0v(1^P|_pA38UGs@s3&T^g(uvuh+0GD#o^k);8zBbe}r;(X=fqdVCNlno%eYOzsU2~>TAOzXVQ zi_C}P2K0N{9LoIXI5T_Ik2XBdN?E`)Lh*iI-hCAJ+IG69Blx~qO(n*R_XNk??p(sn zWrh2jJD%Dv@FLIro>J}EA${0>E3))i3eVnsxWyaHtG3G8!FovhWjX+ zkCL6f5cAlQ|D%b)C2tO^#<$cEd`(mu7K!)Fvp-I6D>`u@^gQZ19>p0N`->>@kId_q zQ*#rM|EIYiyS_iDbCRZLC;LC1 z&axqnrH}HLga`z8*TLN#0>K6uf`#Dj?(PH~YzB9NLvVL@3kNpX;Lz34Zn_mO*KvIh9m!$(xI z?-YwfeI)uXMU7C~{_8|?O=zkEw(&MxbqbgFW6$VIsNUM?iwHORSfU!ik@zK(-40#V zXsp?sP)>H(_&XkuE$gG~#RyF;{4MU)_=NqT(&(z2woi+hoPGf6=9AF$FBFZj`Po&@ z_{H(#1j$U-bv{D4Md`E(r8KecV+c2JQ9%15Y6lxapsq?VYN_D{dY zw7R6dzl|y+B?&_i+b%zNEHw0+Ftp277LuCJupiq;MgDOQ>@KHvQDy~PG; z^SUO+AW`piGx+M4WKTJoH4n8f`TPM2_ z=&wy=3b}T*QZS`u)MCy5()mY8fbFg6n@Sr`gh6S~nPTX^PcSn``Q9{s($us{&=Ai& znIQd+_u>oN@U{~i()jP(6GaFZkWfrEW!=GwJe~?lq0}~mpaH5vz+CaF(X^pljI-* z1qNJn@0JEgAAxbQ`IDmDtddQoq4S%#nH|i!+x?m#E z;Oo+SjtN?Hm}+rhLz@0!J|e2AB(Usn5Edru4uvBl{x@|Pu#%B}y4i0njp>ySfHh1X z`|&Rzk%Z2Y8x*;d2x<(9@G-Yh_Uuzq855HN1C7SzRm6w?arzFZMVabyNHXq0X*NAc zUF&O(*$!O7g_#3aX;^GyQ}=`>x3~Z-#G?;!HgVtKUF`I)>Eyu4o7%|)$Ta_Z&##Wt zR&7YG6t{BwL+C<@Q*dh`k=|yJaa*BT(^laSr((rdTUsn3B7Uiycy1?{b?QSKgUnih zhS8xeQOa@Hi3qHUMb$DzX}NR)j1J4D)q5OsENXS{_9jJV{*tFa#1i#^4}0IiHMe3*Jjyd7YGbd-$Z(xRUVl5lePLYJEm!KeN3_qkWGd|#9!7>kN);Wm z%as*99(7v$qV*>#g1`rC^MT| z2^_VIz--y15-in=wdO~ksQG2b{#@@P(Z!0~q;xR5e^%d?s;g+i9DRB``%{>gQho7l zr78zJ=>NnlJwl@3gM*J3i-G|XWKqkOs+d!dOxn(e{)i2hJ>A*i6pNLfwb8N3Cowfm zl{o6poe(#F^6Ac)IqA?Z+#2N#p1<>jixTejKOYwi!RC=#zn@H?^?DFJrlKg4 zZ0Go`Uzo;ki<#_X%&y{G%6TO0|C53l0)kw)1<;KHXZLOF>-$prX#&H@ya?D%R{|aQ z^WFU5_ya~#_4-W442-NFp9)qh;2lRD#O&`Jkpku4P zff--bb4-XrVG#^{NpcWbRXt4wO`jzhJ}6xPoyHGBGSN=BiVupNV_glK_-p%BUZDIj z)S~M&s7PO2rq2A7A7e9ZK(*XyMgtN0n={I-3OpBJSa~v*zKW0;Z3X>7F_N^cN;FfV z+C(AseZP0i7t!=S0;P(b8#A&Acy=PJ99CyZu;Hck!C3OaLdEo}cTE%=b2U$1 z%%~*Yq4?<3Dc=Ky>`wdUKDg&N?l4RGpoXi1j9@Y1%&ktSf``3BF(lo)aSfDR|!kT>g-M6D#t-e{(7p@Rd7YV*>#NJ%)-b zhLQlSRQyqv9vl(jcy)bq$dFLoLeR3KoeEI+$r@-w8{OhTVtZ^$WsJ+duuf-+QkDcX zmaiQuBm+km#z9>W{1I!-$E5&=GOXFk$E?UT-JfOaf5U5|W+}v?T`$vp;C3G#AQ3S! zJO4~In^s59yd3g$YiBMiZEOH9%+f|rw##HX#NBcGmWyxQ+)|5@ghiW z`1c>tchq0Pr)cYQm6}$+4kKwTXfy*=t%-ta5}1_Y!yPK?{iuIMtw<4OIyx1c*?q(b z%W%rTQo$-*(p6E;B07M;6+itaX=8;Er%@UNX%@Cw$t^c7;OREUPD)L2N#T;-*xte? zuE~7oV{o<22$)&pWGC!CpT9%Uvc*!{_VH@4cg?6%wx5>La$ylLNua@l3{bZ#H&LNO zdW0?PalXGQ;W6vI$K2j88QGC@U!#BI}hyz16gt zb~^=7e!L^K?huZy^Hzr~PxZYs(g&aGR0sS+bA9&Ae8Y4(PXEPjxnDpr$eEEakeQ}U zHULPToMD>`m;}Fx`w|1pxG5RqnV?%eWSGFPmp%e(K-M7`!u&zdU}H9to1<@bg8p4a zbomdatc;knmy1jql{zI11NXLdWaCX)8QN$Z1Gna0p)5s{uK45=vS3}$oy1a>ffxaY zKLJa4TTvzp_49gVY-Sb~AGI57y6^6q&~UJf$4BS34q3_3G6|%8&GCg-m#aPP|FM7m zqt1WT7h8Spfuy11k4>b?woz^S_PgU2X-d2=(j>}Qmv*xHSv$FK)FR(nRLnX4xsf~Z zNxL~3@AH`<2^k9&PNfV#A2`=ZXw7SqvF+l_IpsO2ReAODW0nY3-|A@x>6b~d0CVpk zk5OCes>=wOc&knziCA zt=Or)P^cnFhL55NlBb73| zbUw_0K3s=48eUwK4j!|2CdxT5mc6zh80T%#zzNop(ZJqdVTY=`lI0T@-?C$#J&z&>Vid6pUv_E z2lI9KAk@OnN|^-;^<5<(gr2%$_N>CFOMnuA8A2hD;rFwGxw{0m_6!IVmVhOUx6qy% z=bqfV1drletnInLBRT=2Y0R`NQ16bM-jKF>ZuT}5Xgq{J7cGhZ&MPl<=Z*&S!>8FD zmg2H0Yh>wVY!5`@IFPBQDeS{<97`=v45eUSrsAm-WY8Y@%EG}iC>*9S2dpGw^ISx3 z=%zNDeiu3e8xR!f=U)?g?v2@Qm#A1OnP@L%NY(qM;5E9L61rsOl;~cx!ybrbxnea~ zvrV`O=%X}LKnVRvy&=&_smI-lEh7=O{LeU7VO>#5h^x65gdZRoo#}Yqdc37BELU9p zwaB(m380{wYA%S0Wi)Nk$^ZKT5qhN!k$aZDT;-hpPsu}li!WF~<%Xs^{LX#)?iqo*uy=W@P?rOD~ zI~gO7y0Ebu3>kKCdB9&Wq-P(mraIcEVrN7P!C9dJh}W{iyn_Iaek}i_uzs(G02LOU{*M!Eic0l7SKJIcnwM zkpOz5)7@x-Gq$cJTm<3U{ck335&F{ijCN`Sin0Bv5Ny2880yMf$?_&&3A`^If3=&j zNW0m0G4-N0o$n^{pZ7?kH2xZRfXi$iF!4Tfy_kAuXOD~OOj%aV;KcEFHcNbw^~vMC z^2@gd=OaA(tMy1S4}%=9E#AKc?*I+aE*nX%QC}HwHdqR(t{3syQ}*(wS(`i@8^Wst zDP1})D(OjAnLAB`K;ZuuQycAs@Umz<)xP~@-=>}yE-9f3U;Tc&aI*<=acRg^8~b@` zf*u++_SPlgYuu%iL2+PI}CR87mVHjE(xM+I_eG@x9jvj;sj^NH{#oNhiXC zWQR(rf|&w3PH?Uk@(qi)4iyLa$90GR^7IS_HA2$(ZZv7NrmlsZ&DYIi4|nuwNcM8g zQku5Q5x_PsI<`pNfi>|$RuNp%K;Vw7&d6P?Uv!~czlqz-R1)^~tA#nia8_hUnP5ba zMr1<$8Iws5$iuOZ|5uH zdJ=T<^k0k@UE1ayDWA&)tg?1Q^+%n1=ti;md9qQs`f`WW(_>Qn^xYl;Ho#Ng>BbTa z9+V@#pwgA7PqQRAl^uZHva0#MF`lc9LUv(qxYuX^i?2S7wAqh3qO*4e_WZPqADnoM zzwZWs4T%nJhqbz^N8eJ6eUpo^=5inF#x6vceHroRG`T9MGT$crtA5GK`Yl7*7##Hx z^@L5UPWDx<%Kz1GwYLRMmh~BN%;I@J928ympG#q!d>f(Z2==f!!t{8iJaEuV397An z!NW2po+4K;dPbe6a{nXHR^|VZ>)U!z+4B3d{Q*oJ$KE$>7yIw8h9yR+(uFiOFLn^x z&W7;7JY(Iujk*!olfogZB>=llXWSdn8x*biav3XFUMNAU8+_Ho6O;`q@>TX!D=HZ` znWE0s$81jR-BPc)(p02D`$Grae;S^fexFL{FZ3-@4X=LD(Cf<0LSoi&=SzFc>YBTH zvr^XtmdRcy8O-%+;|zZi+-9@OP&Bf6`HnEk(?I9@WcEO@*HYxUDQ+>{?B|6WP> z9zNa)F-s^DmdsELNUK~?B^AqX6G`cHR9>#!d}og6B9c&5g$~K7!zaD{Z$ptGQB7bA zX4VT;*>}@lyNW^^y}erEin8oLCt|jB20RiND0bEM#4*W;Q%Rhxs0%z#6ZpwXz z?UuWzk|?0?qbEpeukle7RG#OVGl5HJUCKkZ^;^D1elPCMlr*=H0LX=9%4%pcPy_ac zGy}o~1OT6TPWJOH?D*W)U;Dva4RIzZtvP4LW;-K^O`DNS2{_aizoQ*hq5Xj_IZAlH z9r(dH%tO100&f*EI{8C&TVr#K`(2wZCt4lGeZ<_3`NK1QQN)`NS2P{qt$2-If9Gf= zv~rmq-Wx995Y+2hnVtXBQt$jHzM3kR$Udvvr0D#T5#;#Z|9Ccn$FF$4K?E#o(xVKboO84vvDCQA5ls|ACtDXYw25A2mbh>iH^pL;21Y78akK zwW$XNLLK+d#CgoJCzF4#ixn41LjGY%0aFQ-l(aP#aiGoF6Ub0C^OtBSjP1apOaF3S zcof4`h1?Y|n{Vqx)19Mb!mL9)d0ez9TQhvQ%KznWm2t|zaXyUyhYJa*(AP_cPc#vz zNi>EK-P;QRB1h)z{Oq|Ou8H1)$4ZWyUp`kL0ErVE8oJA4RNETH;~=}4oO;Wp2cE^^ ziu$sEN1b)jOql+PAF+uRlCj`zDd@6>q_#Ykw`!kYq75PDoo5n*%#%vtVujqBX<@j3 z^|0UDJ)_E>4k&Dia0)~t)P$Er9a#6QROfAlXNt3D++r2^IWE}^PWo(4@vEYZnr25C zx4YQXj+0~qbaqA@2~enUB1cGKDM=!RSE48gkb2oRUgGY)7$SY5B0{DhN$`v3AcR=c z_t`G_g%FY|k8i_Sa*Sv?#w(yh3N}r~5^rMxyOIj}Jf%b0Nqn&nol1D9@11*K z#iSps6Z_ti(>R(ciLiEhp$^=(2lze<)Qz=bX-qI|lnnAwAIFQ^42_YAlriS$_ADHmjo zpbI%vj=6q|u;w%dz^?4a@ZW6LKN-OndT(%ZqBU~;Myz?*FX|~jTGYx96En!mrK9jU z?&?u(Tbb~QJS!g#JFJ!MCVi3p8gm)t48%4LhA*4Mn2XZ%BuVgY0o41RFBQ}%!kLX& zO1(j~W2vPFv^bMFG!AEnX#9c>)4g6bYbouO9s}ZgIlxttl_(Z4ZHD7gFOKk)q{mb#7k%%ZmcRkU9@V2_vu{lYq}OP0JK(2v~NBI zDwYVgy1<5-j-tbyKr>1D%ikon2u>cXE5@whF8}4!RY#i8bKNuP(LDXOzeP3Gr)DUp zs#ytb4{LHnlUl%yiAw-9#yZB3FmH40`(9!Q3s4{;nPd2Tyjp&o)65-drWDJ)u!1(o zwDozTC5qS_F!0e0et$R3WE-RW?rzaM+x5lDF?3=oxwqq2bTYfAKQxo&H~z`p;z1@; zWp5gq*n1hSkNwzZ`7xV6jvwQgE(_9pP7F4pI8J3>j01E$%Yv<1IvYgI&$!CHXNAY~ zC|8UZE+&h+D_S zr{=F{QOc4$|52IiYLko=@ZTPvjKln|wRiL7k-V=$S7xM& z*#?b;lbrs?Z)Vgjdh&N~MOP2$jgpC)WBaLw%sJ1(+i)tQa#@v&E(msTi3Vb&d*y86 zC5cE$yQ{Zk60SJ6HMt%h-?Ou`Ghed)x=2?VncU{2>NUkg2~Ehz`@OQb_OFJlT_=&7 zgFMqB0&&6;v*>5T<<@u?9mOTl?}Ai8$$aJib`CZ!-if@4Lrnk*%xIB2G(X2;qx4dO z$Q^b$&=k}6jYco_SX@+*@5@Fi|0!C>(4y7jf%m#>$03wT0elOzL_mVhZ*~&a2}qM` z0G(K${DzN`wSYulW~#~BAQlG8DcP2&=lu<7Ul3%|QrVm1LAmeIogbO|%Ejjd;*i z;`8Z23CiB7pDYBf7#(z+)qX&8>STU!RNwpc?NbUt`set=7O~0O&r}oS(o}e}UTULH zpC&_4NCF?}xbY-QO#a1bd@ctLSs>R78BK6{B46ckaNJ z7D1i{{h{rzjN8f@ zBYq937f|)&vZtkMV|*O(!7-$z;zWCAZWX9#^^pNp92n-Ox1KVy1rP6HM55Jj!Uw!n zNTGbc!u|J?m1)Ut(p@6GGmsuQ=-@1o?|jNnQ%_q-3pyoLQGf|~uDHx_axHP!6^++{ z%~ur&6}~vhM{qvSs2u&e@3(AMAl}a2=mKP8VHQf+BsebFD|DT~u1(8dZGvaw1H)^1 zVzE-w5q_aX;C7tKNj;>8phgfQ!F~bC2u=%k#ITFFV;UwCKcyNV%Ps8la~iy2!+Me2 zg=cy^GX&%NTx}QyMq~qtD;zI+FErmgdzro|lJ(8nHia(OVHwGpaaPkGd zaieNB%jC}V+7T;xdt|>GbA_}Quj8sytEtjq1$O);mtn$r^D(Nt*d)n(71yLCkecIRWhyb0TGq$ltQ_c(*n{eMYzBaQZQk+5wjEQJkGmZ|P zyp;ChjO|jEG9eurM&Rv#B6w*AR?NA^Y}$qUfr90E)NdbXkH$ub2E9w_@A|9RJdgTP ziSgk;a0bKEcu(6REZ7lX?=i(!ktRo$Kwufp1`#5fh+~KdJe@y70BO?|Br~vQP0WIw zGKt-hJ@m0pC9+uz6%+--59oa_;VglJ+-{rIJxU_?fW1}!&qRLX#fwPkZ8_-Ar zNsca)nC^93FIW*ig`0UCjXI_Ltd3XXd|%9mNJy`v6D`MDRM5XDg)2kmL*jo+*BL?A@`*@=Y$-3NYWv+twaXdiLjElP-XX88lNpKW#@9Sz-e{KXPuluM3eXydR zK9eKfW?0b52NOf%#}&sRP6@1CvV;+CP6eK5q2~UmFN4l^W#)tDw?dcu&~;zCjQ_N} zA3ypR#RZ{KRyHUFKYd^j8;H{6OD?5?EWc7*hKPBRRd`|~t|YZ1Vh{otjAE>FVFDw} z9~_+h{Cc;*A6bB9>o|@VAeHM933`4wUsTX2|dNgosAM zAF@T~#m+eb546=Px@q7Y%M$s(!gB1jMDxz{8Io^9Cz@zSV(2BeCNx_Tz+$O02%xoL zjHN85=bCb8F%}m2tZhcCP+tQ;T|TvQcgfsU_jj0nr$cv8By`EVo{#D1o5WA#InS+v zPGnV-9eTAm$=x<-o1Z3gS?x1CDj2n1&NVzbEC|e;{iiMD9h{#UN9)enj^noz&+{!T zy@Fa%mO$-K;X2o4y^ZPOZ3U8x2P@dP-t zMC`}BeV}_((y=8H!G$ws-vhp!9A^+`SS$g;H>dh_CuCGJ3U5i$0KeTE7!=O4>ECwEkvCz zmv4Mt+5AcAPVPQEb+^tN_eb(H8M&cl-_Jn5-*zuo`z)&b`o0+Hi+;VO>whEEDXHO3gl#eKwCD;_M9uPhu=F``&iNsWd zJCEXb+(b-b*8FLST);ViZYRzO@3Lf8`oQ_TQH9R5{O00ZB_2JQeT|nd!0TYwr$5-_ zBfr2masSfrOltL+FcJO*?XC_NTvTN?Du|uOuMm7MIr?{P7HFRAaU~Q`maUy!P6-t^ z1v1@<o z`o_*LoU^14w?-?yOzvE?xN`EuOLU|_ZD#Ngoci1Rpwd4v0q}SQUY?)j<+#_^*K%$c zPdD5-vaIA0J_Gp+AVSS2EkbI3C4u)qGrb+LFAhz8p_Eh!9$%?K4rstj-%#+yS8X)8 zO^?*4@18d2g$tQy_f=#J^?Ul>1*vXF$`{XIy>H9HA~O&OWjAMeGk zTclFiq{}pIGso$;ZL)N{zVc6*N-T5kCpdO7UwJy|2;CSPWIyoM)8$KzL3gk!s^1nf zSFlWht}6~km9$QUa!&M}lfOFmE{Hzx=$ssAn6jK(d()1Za*rl)Z_eAs)BZM@y`A`n z3(-pa-3LYw`fX1w+U!y9q;d8b+#(-Qjqa$chz8YVDg;Q(au$379iaO{OF&=Rm03|w-HGqdtmk27W(u3 zRh0Wz8y?XAUE-$l-&KCNo@NvSC6Z-se=}bv8lk&7fdwE(mr@t!YxMQzqpU6^WJ)U( z?P2pjx?b=x5kuZ#6i$329j5Z2(XMdoW`k}vwMOz8R_Y&??%na@*5@kuj5zy+ch~oi zZWG)lS`@;NA?%6ee~#}Txc*SSKCSBCarT3)`1MbBFeq{!-A}kLc=OF}+Q*Ru=A^T$ z2uSJddZS2`2(~&HW$&C#sCHTm_pgv%S5h}JXDSsh85@=MuRnxHN0S;=w~~0TEsX(= zWEF=lu^OVxTD`b5ivyp!ehF$)6jiSMe<4r|_t3}@aEK-CaQ%pZ8uoi-p_ny$GB1ve z3bXQy>X+awcHq_>PRcdTkP4>wuqp%YS9+5xA$BM*PmM9^pCj1mTwpiC)zxhdg(duk zbTfkA=$wG6x@xV_wIR>?hPkexJ{Ooph%9vlc*Pp;p~wDQo$OzQTO{+y@mUnvn#Kp= z$V3)xp0HboM~~aiYB^Uw#Bq!Mmps8cm-`BJsu9Wz+Tk+b8}J)pbgVPRK+`%Sl-wPN z@orWchh3ZF%$*ZYzg4f*R;M zEyvqKqf<;HO^+lF=|-wN9=-hFGgv`wy47|&?9RsdF#@~s<*8S6SxQ1GV*r=}N!u() zUz6k2Zw)|<(_sP_ro?Q3-C_J9dpCqd050BO!;o0=S7%u3&UEv^y#gFK?y-i|WaZDh2o*{?m*=F1 z?5295EuTyfUpw2;H;+0va)$X(M(m|%z_r5-@>UYbCUh(Sq&Yl{cw7y^*nSc1B$l90ff6R0@8v80J*yvAs z+i@IxH;`mkJ2d;}`P9GD3hcWlwB9|=w+NSXt2@N^4-fF3fG{1_C<3L}gxHp9 zHRSeH-{K^Z@WG?2d|9G}J>JfV3BvDH29#!#>A^`2W|CXV+}yKe)RY6Z$)cEUz_Gh0 zg!*}nWZ9hNl6U3f<@*+=lFssFEujNu9&d%&qk}||*za@Tr&m9rvi$OCUL;oJ;VU6S zB0F}Pw<&C@)c6EWV>-ZZaSH4jxMS)TMFEq8getulI-xm6dbs=64ctyl)XQI3*uH3S zune=*u2v^KIh`)v!1@(CL51<=M3C_W`E)y+!f=^{doZHL^*qRThO(r%QrC;@^Yn~Eou8I1&bfYbi-FpH`NcExahK(!~mhQ(wR-FBd!_Ed+e0Vk zuQA^0O zv2K1h`P#czMfoE7%Z?@QJ8LiY-=3hv*7LqKaXOATu@~e9(iReV!9u)Ftvc54!B8O? z2f#7n#~aaml%%nYh@7IJ&ps?KPowJtjh(lyPu)Vv6cF;+&dlT1Q%V~lyq=7A^P91q zH?~jN>3IuY>su4|J&sAy=?4~AVXXq|0|>F9@{ z!$YZl1i#BK_zSzu`v22+x_GnN?@SEtddw)Pf6nuC#F>e3yOXFYWq3wBoJ^!ToVgCT z2c)IrNhc||;-%IfDrs2 zUaKPowwy#PrLz)F5pHpPv+(RPKoUe*E`+etDoUUa_n5x9Apx9DRf$r~BNf_Q!RzNm zP;d4Gs~ayCHw$NPET1Mj|1g_Hcw{GwewoM&TKX(eOtk?Z1myW>r~Ak$$cn)f3-Q-~ zy!CXqDXSage~5;@!Xw{k`ec7OEZZjb5q@}UN`{7ZE~Gc)QQ~F6nhjCae2@hYq8Fq_ zwv?`D&?xq^VMUsh$z^PqSU)I^xbd{8#l#;0;`5)!vvyO2a9O+ipmcPot3n1=<8Ko-7RUzmQpc4({awCfT%R*}vh>zoFZo-sv7xt^MG6*h*^ z1xe?@bOt@9UzMTHljlGdX~B|O{fzDTTe{l}7?~#e!V&{JmwpP~W>fap4SB>40q0#G z$lq4ixy;SGQIlE4&#*CPJLA81p+yctAg!tc1t#|$E!|;15FlT>U6XM{*9K2u>I*)zbvFB(w^kSwL4SzlF zBoj9Pkx&obZsej4a$N4Z|0(TPEYf9V?R;`-JJLPv2@}1_RmJ1myj~!17Ka@D&UvCj zdSs_Nk>Y^M$Gu%6X6OyK>eWAcW1Sj;-hS!&$tqSuP2-Z>o}#}eCHUdjA&P-?Pgq0o zhp+;Y*aR*n+Nc`VD<>AUD%YH#aN%NaHPIdu4xMSL&O2*=>;GIx8H(SDjq#ExZpc@{ z*0RXz++7Uj#t5lqyy8Y3v`q+e4KRjH+94*s?Y;y=1d@82AMK!jkH{q%c|vWn{PQOa zT$q1US98$x@6)%?Z7P6T#AqQx_|7WL z?_O!=1+U&o#x~QWa>dxRA*sl*}#&rG<%~JQKT&S%=d$@1ggCa;GOyW>=ZhxMV0I{nS36YYG(*V+nUl?4Sm&>57Pi568IO7zo_^gp&Dw*$8V;zuoJ zMiVujAL%LvGx=B~ss6dc=Bo1Y6WSafb+{gZe?^(6#-lN0I_FXT0s8H}6Ek&%gBoG) zlGA;35Y5UvP@Si>&+Nr~h(5>!-;Kwz?M_i4h=0dn+2s3WXD;m1}=3XhkSLi0jqB>^Wa70)z_mAn*`e-&8QNS zqLu+SlJir1tXuU9LQ~kc5j!7*tyCqiwGizHV1x+EiIua`DL&2@Lh~U|VNS{E{G`M& z^W<%n9{FBtAO~M8Wx+}rL`}|XDk)jsNI9L!qHY3^@&2-ChyxmG$Jy!Z+FSHEeyKoI z{-LrB-~4X~AyrUcdP!rQ6c7=Df;L65VL}Pkc5M&;-4wEN}tn%Z- zPFV_jYvI9fOyt^aL>KZRcN=1X_KSiZk)Fa1r#jrB{+!*aQ97()S#WObIi{NsG8a})+8ZNcoopPAFaE<7h9_e9U9Opz?Ev81V@Mr=Mc6FLhhTV}Z z+{)*aHo=xDd~B)rLIn*Z`1J=K{{%j2n*3)!0DWcc5<8M}Ve?@V)J|6?UhUa58l*-S z3oqB^%~h%R>WAw%8wE!NE`9`s=RaY5%IRQ;i1^etOlw6>2n2&JZvO4bWPT9I+iO!M@Q=49t+9rM~@q+)TsMckhoDAL^OAY6- z#TjDd+~QRR#nbELas3t0qi1X3H10nTYJ4pmpf?;S?^ZfACha|;E{r~faq~*>8ZCW+V#83 zku`#00{2Rn^FfqYWsXIosz=-fIs)4Ya70fl!QN7y@t#wghj>L z{KR|$1N65mX8{>KkUBGLed;T^%bGWbRjOkbX zQ(k^ts{D;nUAZ99UT%burM0ILGl{{vbs{7pU=K?OFnwk9R6(0K)#VhGq!X1dYYEj5*eUj}!G9+$#PzjpzhbX)~~}im$u|pKg>CWvOX05TU{Q#jV0j zIh%nJbeZzTR9rE2A$!g=JX!0Di-7~7?|;9?QG3aOKt}9B$wa7o%evxeDAN>;Mkv>qD+=`rw-*GEJ!#JG>bjA1@IaU826?X(s;P6A zL#1@wDhxG>O)unqCLWjH_bCN_)0VbvE*dOx{+_F;&=jLgGx_mB(Gzd)ePt9u9S24{%0eO{D%)3JT-5~?6Nem|JZj0gk+EF z8sP=Rhey0h<{8r1t7*%3P+B^y^E~-!DG*H;5$rvsYQA!L(#NT~IQ16+5tf@Zn&mPU zc`Y+AH^*l!V&e^{?)$vI=rzOdgx84Ql=Egy&~)#E{Ufh94T~T;uuNi6kq+KiZL&(M z%Q4T;2IY#YqjtCz+_TWwOY7689-2CSUaRNIA6iCZ{c0%;#>lK315Hc9MV~688~O1) zR>8RXw6D|RkiQDW36T~lo$qf~p7C@#{Y30KFVUE@yHzy{(Szncyhwz@*)jpl-Dqqp z$6Po8*3V>oK;@Q%Q~SS*?0-Wa*txmETZ2lQ+YxrnSzQ}>GQVNVW!now7RaeOdP+b4 zTAcQQCsLhkWokrAmeESS8z4H2=<2C6|9MV;eoz=0z}dJf2htsE3pV4bbcjbA`+cD& z489Y+14P>e-i%!u+#^lZ8mlag1u|7vq18kiNF*g7yY zM{eYw_fU-Hs7ZIxk=&igjB?X#b3a*$sIIOaKGTXLu-5c@o8+P29Xv@U3F}FBn4fj^ zI1HrY_h-_+wePOr=~l+GGlXpw5uoUG9d;avYu@GbJQU>G&ic z02~$H+bs(0g#nzbDr3idqDLg9PocksYb1VeZ=u-J$yOFgXeZNkkW&6RIg5GMpm~ zES=?)!hd zuiwE@+6auOs-c0uJC+*!otZYu`#XM-QFU?O!tdW0Zl`O$k?&I}2Py`!UJY$L&e?ym zX#BZ3BCb9UBmR@_{H{W03CX`cB(KtDAm&T2MP}psWR|0#PRPIue&ePEZzxk`3koVG z#j5i^lePlka|KMw`m)q>i$TWAe47ih|HxNphHd}h{mVAdw}k7AiTv$% zdELMyC&cqzPB*dZH=tc)Hv}Ipe)+!d_V#R8-HbKZ#y2AW9l~^|{u%;5Yl z72@5~rPwPr*~9slKf~bb2mn<){l8w8nc2W?)&43?L9zXzujfB+C(wxfSiKYGRATv| zb3QUcAc)F)F3DI#2Ef;+H2oJYljNheQYka;K?SQXCe7z6*fg0a_i9H9nw4lpLZps6 zq1g=NTPr?rt8Qkxzn5m=N#WW_ySJ+{@njiX6X{p#fg9pjJJd9E;mdJpX(?{lL=8R} z$v4~Bd~wWOtTKH2{{4Ged}=IXMfv%SP#Vl4 z-u9!Gv&|%t?@qIc{2k|E3sc&X^jTe{*7j0Q+fWZ1cg)82Ewp@nFSNyqf?{HUNF$h$ zq;!MfB?q}(vm?Vzhs!^g-`IMq_sIIz{xY{+9y6UyKP%<#6bem=*5IPs34c@q1O>d% z^lhSU*;sk zMxb;`he49?T|lpa%=+-Lx05T2gi0+g(BtnLp)qj()CUTp6;VP z4oaeB)pv}C_Xb`64^>|s)>gNC-4-oS+}*vnYjH2`9!i1Y?(SaPp|}-yFA{<~#odbp zD+K@YzU}>e_ntq(^CThXoPGA5Su?X|E%z=ol6jGsy{8D8Ain!mPJCZ{DloC1fe65gqpV{^utQV-%!%CN;y zYrYTEJpMQ?h%;zyOWK0MYbUVfO6y+X%eJF4@hOY=Aa!qB@wW44(CuvhKbK;JTq74_ z=zZF>*yAsHc_;LFEIpr2{Zd0d4c}}v5{r%&kA7irv3}E3=($gIOxK+kSKEDOSorm- z*RhRF_X`CvDQiC&QbBbcGVhuPKdQYC;)4t$A}p1T>(l8ui3cK)8)~nDMC>zPs-gS4 zU*Sf*SK(2u&&^Ee)v#0VUk7c;X5#QTz%UfOu1v0b#+0-Jp31uzqkAsGk z$Lyut6~dpSJ$yIil2YV#i&!fn*fp{*0X3LF>{&VTZR|df1jiWDBxX(0cddtLhuN!j znp(v54%6xlC2enTNtM#Uy|rBJvc;THY50Obn3A&0)TF}#cyM7ID_O?V`1qgkTW5xD zJNsvcuU&r8pbk_;;=WvL&^C4W6J{2Vt+>1U?e3dmLNkTx-U1cgT>m@#ifPnUkEbsu z{%3N@%i22?#kTZ#O!$I#NIYP^fPu$R$N9vJ%Lj^B7=7b`3jn5ejbU(EON5%+t1RB` znBAFq*&3vwfgqE(LqEXSy z9?%*`G;cH~rWseWG9V@dU(=sJ`hZ2Fk^5#&T{*v|#-2k_i(2>mieB5-Yk;+a273?h zRs3yLvU~~g9nFuO2+uE{iVY;?w%fot(u_2(XyhdNlZBl4Hg5~mm>GIEuN3Y97@-_L z%mQcxN7QIF6Yso3%s{j zW)?Y}zvOLDwzgiVX~%;~aj40Nf5-i_8y+5B=Xv#6xOirpa)6(Fu=DvWrEfkN7ych&$b-Vw{l>%uHpbeaVr!YN~iza6CW_UJ`(9A{4 z_BSQ44fS0#+Y@>T(4+swjf2dQkxCeTbeaIvXn0LNmx zeTMivFEnW;Gdx}zSD7s;XQ$i0Sv4}yXF+4%zM23w{5uH$_re1ED4CJIyO5C`3e4(j ztZD;Biun9y^@judOnO6!*f(Np)_O?b-YTCyiumnaTA!naRX(6UZ_7NWkSxU*_w2)W zp03e8p0=z7_jsLexBJm+RJ=+uG*U*7gS`k&1P*CFt1#EU}a-M{2++{gRJ zp04%Ns`{abKKA8pS22UT$Ob_@-570$rd$^A5XUG zPIlG-Ryg$EoNWbLqNX28fD-jDSP4JgzI)tSi&n)akScq2d#u8Gj%Dp6%j!O#q`y z32kPTAQm0A8iU;=uYS8qtt_`a4#1b_s130$_onqk# z@n`|liyUYFL_mKgosNzHqr;vxa&#UM;Is;#NGRle$IUm3PB^lMmC3D=&!SQ1RGdHK z)7(${SlWeaOul~*A1(}gph8W;%4j z?lgL1@VmZf6qDdM&qQ0x3+DQnKknoSz69TN)Z)PF&RSbuRQHFA6e ztc!ALiwc(p#%f%&Ju?~&y}Cuyyl4s5BxZTtXwYo-J!(>66>WCEO^{Plh{m&<(K9Y} zTuW{+#D|nQ!6J0`V-QAagdkxjB$SplljfU#_B`Q#qM|>$eCPhz<(ntCzxK2OxkY}2 z%osmntX~A8ZANdb26&92)ojF{`RZRN`#-cm^d0kF`tTeru@Par@cG(b=RFzw2P(hp zS)31VJXm9Icr&FA2F7W&nDCQ=;_{);whh5~+nRkr`$r(wY5IzRg4?|5^E?gl*=eBv zmN2BjIA*KcACd<-Tz21y@9BDdWH}&r`(@P;M3T;K1`n-wpl$st4s|~rzdaC%<+0GQ zUR<;Xk5ld^(f8A^Za9P{_luZ zKOuKLlQUp&N}!zw%JemG`Xez_9f+)9nNbCIAxlSa!OC;KmhX zA|fKkgB*82f7m<7*y<>SH*ZIi187`HJ$423QvB#)l#AZUx$z-Gi>fNgwQ&&$&PBwS z0G8Ih%TLWw*&D%a6BHTdau18JY%-VQ35+9E|JGE2OMyOukQEEco*IVd@kAXz)jZLzhldK;()Yxg;<{SJG@EDczF6=N^XE_gkyF_|C1OqCW#om8 zfVHrl+HB_W+@@;qFp;I|J>+e5NS^CgA7gw!*8{r$ZQt8@LIwFX>$mDPD-IDBYmBk$ zZ|QkNDUA(V&wQ7BJANGjIi+2bBZCJpZ4epbC9HPHnPqx96yWhlrHe* zQ+rgK+6{Co$sBG2G`jxhuz2_Xo#2N}-KH;^RgX5NrYb{}kgb>38}+W|*jFB#>ur`O zJv_afBy9$$UH?GIt+cNzb#IMo@XW>y5nt}f3M+lT=fAL zuYI05{ljJAQ7DeCC}$jyp|X7&q4S2-S}Q~#kM4+m<7eh&V?QLEp27lGcv#^d4dslT z+qy)rIe?63WC&;F2!4D>t82Sr48}lbOgHsPgu)%olSEx_rN!U_H5_6VZ}hhsG+lV! zG!tZ(n@C4&cEc`WADxd?;0h^N?UFv*5>;>N6PR=hC9S*{+-qwA3M0zub&&t-E*=}9 zC>yb+8@{~5pMYds>0XBSKQrfGxwV(u$Il5LtzE()Vg z=TWl=Kfy91-#kY=3S%8nAm`wvu?XKZ=Df!*GcqJiAqs;6G|ANELfwamt0c<*e&6aG zMlLU7jJj(=(wL)4p?(_T*F|lU*y-Zx1pa$b|L2=IJh+`52&Y;-sv2rN8qP-`44)e& z)_~DIEXekuUWPSjvlc1d#zcMsqBYf2UuLsWn~n@R04|~odH>m#@yC<^BNkTWs^mWfOI$o8D0xdlb`%icwVXS7 zAYo{jgJl*`C+vN*3AxxQO*Bgc5us2K-cSjO1lCK~YIccH7rfrBC%_(=&y)3l>&LkJ zHX^Ur(RF+f<}4Ni7j&+{ME?*xB*m8tabpz$#GE4G)+6rDaNN9S_*cup@u>Gdt?GZz z{ip|RkB9oCC0SF;%M~F6O+)od%%q;X7&M{=8uC(HtWW_B;|>&k@C&0GipFLo zE{3rWmPo4|e6A-%q|>M1TUhs6IHA5GY>U;UKPyYe9SgSG6FTdy=hl^?=A@Efao2u6 zAOqO;1DapPCYI2&+w6#-fNA)`4g41&v#9=etYB?d+_|4=?Er-{G@!#gZtGOc&vTfg z2Ui}~(=zPPLry0F-&)U$#7^gD=mnPk`M?!|>h;g9`mAc;cMog?V<;OL*(4P{5*6+{ zm||jD4o`_h&!-4r!MR3My8qtz5ZLdP;6s1|bqS$ms3KvTxZJE1wc*r(7<<}$Eho>9 zZD`PpX}0n3#%U!li*oQUhG+Rg&+fM5D%U^^W)~^guN4`q#%buUf9ar(4lj!{Fbo_siU} z9#Q9VnY~Y0b$2T8Ow~r={B<0I(KuYxM0K}E_GbQd$O~15u_`p-0le|HlijZ-V@7Me zjNY{Qygh>QCwPL{u`5I>`Q4iTW$h3fXb}w^%h%q#xXZ!+V{4+L3Fe*NPJ1e_)!oCp zG&cYLvF-#~e~C$eEzGHN;4^6O#rWdk@8e_852c)bKe}M%=<#Z2iv>I0rr**>L?B3F zXntI3Z?OSi_B$|TI0@3*zp|O*33q0=5MwK-uG7^>pe%fi9`KQrL{%?`sxEGB(0u-%(&IMtnla6KP0+6nCbgYnR_F{dV^-+@kx_siP`(xg zADKF)*{IRa9_&U+-(FGL^f(_I5_Vy+ggHi*6p+hNCQ?f{eE@#7nWK56T503+~Is zK%yT@l!N#8Y@A>*PY;yy<(9t{YPoM}p*8G*Sow@l=AZZfH&xcRV+Qb>`lvrD7Z>g0 zt1_n4Iv;#&V&bu17qVGv*Ni=1SjM+DbfnS>LEWhnHt#&m)!$O+3L+D&e|KfyO2SwB z8sy95Fw23)BlJw^0~JCZgrgCxC`6uG{+5JnFc4VNcF|Tcu;P92cG| z8j;8w;y@o^X-FJ8hd$MbZLhl$caZCWDdE|(XE4Dtfy>Ur5%P1=4-Hsq{6_pW-QeF* zE|Bhy_z|0y|Kbj9vNCIcCN};Y6Z+W+_*4YVc54FMt;*styLc_ic8j%Qk#$f`oSnTi zV`+h$T*|=_8m=+JQ2t&&n-$K0Q0*ES8wZ4DVmY&|U!$8xOL4xwn#?+maH(ToLQ469 zNc4>c>hj;{;Z_Z%L<^`6qngs60;irW99;@fnX21S8wh>q4`k}DfFxy&%%BlZrE|@C zzIvGvL6J8er$_!4Bo;~d4;^F$t&aa>v;RFl&(7?)2PYx6E6q6oZxm8AMj*5N{Hq`_GWj-?k#4p=KeVXOHx0V5hnO8<85**P>{7DE;8_Z(k>&QaCW(uPD{fl-mLnyU8ankB(Bs zdT4+XZzm|&_ZhTRsvK6c-3|@0&po=z5^I|>WBzpjX_Wupm;`Qe+r}hZ%Tr@UNK$@8 zOljz($40^@B2rhX*A7+;(BI8?s%>Si{$@nR;@c{s72TY-M7&4{z&nxyEE$$q{t2Ga!OJBkyEbaNBYZcn zE|q^xa5QhE6I{3MsjP7mqH6;EqhF=)fA|3Xwqw~zpyDsDy0Tv0`9tOrHX|j`Z(MeW z{I5YCH0r>C_3(?>mj~BfnryeTLytxAI(xzAqsi{@gl}(0PhJE>p6~1_;)zM0X5)9f zSHg1=6+CVl{KIO5{jf<cuSSh1TungCTN{?7lhV>mLQCt?2{#-!5=Zf?tMvWNur|Kn-i= zyX`Go<{KQ3uSXyD;EyKa1#?XiEvH7~ozpLz9 z)F+y#+tfrISW#SUOb`DyR1!@z%o(>5zAc9Bue`w)T`!{E;Me#d$F&!K_uKoeDQ|EJ zte}*9fnNwju_)yquiI&TOnfA!i&G%RTS|PduLagH1$PCKzeewZ zLD)QVaCLtHkFO<=OI2KaP}}t>!@2ovVexrmqTBPz?K2N7*^`|%%wlmEMp5AjN|u)R zVhP+-A^s-LCM`}*Guustn8%U(s_N%WY9N0(G&uB7{Ca65dFN-K91az%5Zt5N*i)d! zjFhBIkcIx))sxs`6&z8rJ6K`CX#zj6QF{AFDf?U|K}z$wgY-!sB|3XXLesy15|rY% z+(myg_(U~}KE8-V`%(qW7kr2hVKEf>`$SJ)F3xU>+68Bf8pwC7|$t?0vGq^<=CwEs+(e`igiHC$Ci#johcx3+D= zr{9&-f!hy53`(cl4;d`AeAl(E5VO7w+p4kYv-%717!DQi;wnU_Yx-t5{Kn|Av z*x-lVaFxWY=+$guMm%%^@W9!cE;MKI68Yi^qVzyJm0tSoUXcHFrm+=c%^x2j{;S$MN^_D3&9G_>#E;}0rtcMyzMf^mATh-&jZP;yeGbW{w3i9~PobqIV2 z(7?P7ljBu<8#q_my4qEGq1V?g?0P5h&xi5nH81xyQ~P}Dl++Cww)R~Rk-}cdc)~!y zvdZT#5sa$Dh3c8_;OGv)l>K3~nEi;uHF_ogwPbvaJ zB+k|PNeXP=!q7QR%kqU5kF-9wJ4T;-Q$B*s9@KhNyuxHkKuD#(;a2u=1jVBK48lG3y)QxM%{+R|B}u>XsyG2 z$M|{A7?T1_`t%(`pSGaS74CwUKarVWkm7MVKzue#U^Ym~i%{$6x7$_&ja&VD9`bc-ktt!@(2Q+iS*pxcl=$XJf^ zeuxaaSbeDYdYaxLy`YbU6w0=n^WnKAPs-((qAU~1UW#R|=Gi`Z504gLm;;gh?E7*H zqW9fnLs`*xhv(XAmyaXdiA=b_0B9{A^!Oz2oC}yDJ?&f=5~ua^ee}U55S-jEapv)f zF}q}6Z=u=h?Mkdd}uEJNJC_I7>rf zo$otItVFp1(m(c8X1jaD+Vi9&ZoM?XFm?OWvgF|f1=b=8^X4?jeJoZyyYi&CXUh5a zuK#s5l9X*)ZQsmda!fKZG8_bQ02^Blz-srPMEhP!3a|8M)oVo2(mubE3H?z;9tyBMNW=T4kJN1?)cZy*9d)j+>5!%|? zmQ`0vo0?KU#Uq24m-V=~xHh3}kcX$IO4$hmA>}$>lhVS^ukj!A({&mc-#+vk5G*+y z`YGNAO)0^pw$#BV?P7AGsWX_ih_j~3Leeh;S(9c$_7=|7;n)*&#| zM~~anCYhD^w@>?P_$v^U=3L^y5mfZq5WB+&DV#au9$X+NsMfzPEYkpa`Qr`w=K(xU zi)~|xUCpm30(3^55HQ4rowT<^#US)KiXqo0d$RZ{@u7k~{;hAs1P_K}Pm}d*3%hb0yL7&HU-YHXIDos&NOwJ>^WW=k`|>r8{Xdq8g-;{8^y9J( zkLl3ZQ=$qVF)r26o4^3bXwM`ehV)B)lmfdT$18W!1W01OgOC-^ZkpD&_JZ_2#Q_vJ zj2=7*v!sCe(C>=zkV{fly4;K;n6wnN`jY&jPNaEFoS|_Cs={wbylalgdW`Z3M{a#7 zsezpZY8umEl<;>Mq2^`P%n~K)SnAwLI$t#Ix>4+hRaXl(O<2`WZe+8DE0fy7DEaxzT9LZqe>*NFvZ`<2 zHlrh-W^1X+%FE>x^TvjT&*BN<>7k@aeN-iGR->)FxZ@@n;4O`DFFNt=Zt!<51&sP>>J zR5qBFk#fypn>704^K&!RdFe6~JR?T^!ll&D2$@umlrpzE|2RpG?O5o#C*BH3t{#oG zG(qbAnu{Ok_AVdvt*JUVQyUdHbx}9SytV5?ckW`~Pmg#Tx5L&R{y{thKZ=gGZCJ_9 zDJg5U`s}^Do22gRHw)Z9c3g6PCu;shg!0>+>I|NYRLVI9ogQ`Rs4Zq7)H+0eD=UU( z`wbS{E#o#P8YBNF*R4msSTSjpUU8w?5|jttQ?dI#?xEYWK?MY#)}slc>7FA;V&Xbe zAc;G9q=iZHrL}f`AmJK!|XURn}Y|dm$YxhS5vwY zDDKZ`?~+1@&~ZU+=! zSX>NucXzkgY@4NHYy*tKS*$hf*NtNrM$)M2BtYg=Lh-UNar{)s#uQOiLn^j2&NSV1 z1m~ipKV9qf4yiOAU`#H0hJXCiQ6dLHzxh;*JT)}y%rH7~O?hiGAZ#WKel9ijl{%e6 zEs2h!0>+JK1DyJjd8?Hb_p+OPZ-i0Y%Fkr8m$1`wtF~4@B~F3n6N$B)+aEkmZ?H_^ zqA;airqvzhSw9$+;d#gZ{!rPD>Yn^@r;UZ~%$Duqv4jc$n+=#0w{?b*cQ!l}ZA74x zfdRa)w~oT*8>CD?gl?x(G0;Lv*}xuUDF4@a8xYYWq10m_Jlw0QsZpjL{Fh^>QL8r_ zJN^y$@5cYhHX%qqk%{<}*;3#~ClSk!&Do;Ui1^Qu(jL1*E+@wm3OejdMZ+~vsL@V0*+8?HEvvQ@gWnHNeX9S$g~;7s;UuP3R#t$!*j;T9%^#FkExA6!KB&%c zcbvq{&AlDF@v}-Fc$nu*VisdHfF4UwyL_Tz5=B!CNI-P4tkuH~32unUsKDuyl}5cTGU{eqs-!V$~Pa!eW&2y>W=_(9c^giYj&TINNMqSN71h7aHR>V~}- z<)lYD;DC95*M)X%m%s6a$GPqP|J?1LVWZaO$0J^uKxN3~7^WKZKon9A-C=O-oV1p{ zSXKoOF$~rgM)F9hVw?y@(BrL5m$ta+J%Z!`*fk@}K+uYyW4Qb-UESmb+>H z`@UqN_^!kIKX&l%Rbviw55wVYq#5iKIb1wtWDtx^OpIUz{pZtvzpEBEdn73>J*cY? z&}EpMnu>c=^|doW7BLQ*Q)7P5Ym{teV`HP}(;B!{lkjJ4{e_ANMNzw%5Y%uOXl@a_ z$X~+6%c}rN-;I^*cQ7h4V*u=_jl{ze)5(JJ&IK|ya?*Ult|RwQ)WUCLcz z^e;ZzK!I#=)o7$!CQ*)y# zG&q{Ow$uCjRX@bd1qA;ajbIMXhn)OYU}38GEcWR$B7&Q3e{;^m6!=}Qmt2l268g>d zW+2re0jf&iB86-gspM^M*CAmBZd^mORFjTrOLs?&*Z&My2HCn+d|qkqaJfUGM&TF2 zH(i1k{oogTK~(pGt3?)}$6zqPxfD%HGqB=IBT%OLqKt!7sbuPNoz6hXH2ZUvRbwRE z>GcQRkAjY0whiJcbNFvvB$3CapCAuC5GEgRc`PD>ki4RVg9q93-K1!6UY8es*k>H` z$UJXa!vvXnAvufOzPo}3Rc69?D)arB@g3@2<>#|hmdx&I## zN>XODp!)ZPAB@XxOnc*y;hzU6NKF_Mm5?#9KU1fr{>6w z?k`%VwJ%?ZJoK!Gr;Mida<;>v_3#9yK)YUToL+UO@b&~NrsrnZOC4j34-A*mOpfO?etUkiWty@@DJjq}7aQ^#5^qOW&nIW+Xr zYin!M>GI;Pudinl5kak-XCx*S3OeyY<(TE7*W|6x$IWl6hTkiess%o#XT!-`<9%yt zLrvKOIxtZveuR5fiSQd4FTcE+P-=+<)}j+}a3ZgH7n5Tnjve@hdo}#GvW>*(6O@fH z?BlJWl$IWLmhnbtyQa0{ZXN69?+oeHPU^gyo_OQa*a8Y??3b&n19se>UyU`w>PSTU z{5uy>y&YinjeH1%zr0P=F88=THkS79jnz>*`*9QA6Kf$TOyAV9vn69J{iBhhun2da z9~EE4RME|3G?M&RS^D%C5*Hrq`K9`)#;qnSF;1(U96`IgZSPMQ83&h1c;d{lA5lP3 zp*!A}h_nZ@bQ1ok->l#ewe>fXL$r@QHIJB_A7O0uje1j)OdDAY1D@Z##L;y)*EN4Z zdbzE6#-b|_kY08(efo*2!Td$4=+yjidwBftSR^P<_!=cBSDIN@10|Y5=F5LC%gfIO zF=i+4g-K2j%|QP|q^vig#vo{EZVi-3q!*~0MZwFg$v=xp z$9p;0sU`6xcz6gZEtRg{(P?4SX}u|gJeK;CNp%}F-l76t;-04TL__=`(aQP76}ZTD zHbLqK2`T?;qoa9UV=k_Tx3)}AmYa~1l9K2d8O7b)crr6HRWvnm@@V-HgyEC98p(wn zFl+1ugV@2a@XIR>00&I?Vspu0K<1*uEjuw$TmhRX8EOm3EKDhz5C?Nfg%SdT@ey7J z{I_Ha+@Y53#DOvlvT^LEbMgp$9&XJ zUQXZARa@(kOwgp+M%7(C^;q(lvZ32i+Um;ifwU9c9vonTn6kjcpYyWz8<8O1>-^>l zLKdcP=b+cLg6E6MJ<%_B!;|N`gM|^2tz0EK3(Ty7Ni*DEGm_rHzCn~xDzdPkP~tRg z<@jpByLBa_tcA029z`DNIZeAW#df%8yEB(8D&a~;hff|FsY%dMgAQRuf$5C3f2-Dw1th;nEqq` z*eBtn^b^q-y4;n(eIk2_@|BR$eKCJ;1TSv{$HvNcSO($WS$1`T@z03DSkXhFm5U{3 z{3qY1#V%XAxe9sg)|pK=J;zJP+nBiQz66Q2Dc27T{97{?Y-}G6;2Fq|2sm9O`zXjO zNs)!a&mnbC*(!y5$C|8yLh$GwCKa%vvJ%=gL)o1U`pBMZG+a2e zD2Ho|HWp&KtYTn@8iQuyz!oc=aGiKEukIS`UL2U&_3Xp$j_#q<|b?=`+kGLYW)z3{EJ_~18BsnJGz@#~7!_Z6IM@zf z2LDyx03KWyyXa7hSF9uyT92)X<61Tp30S$uW3w9%HS5R=`VuhCz7 zs2HTiVs-p9dx#|9YGjd86=VOE$*5uiUwhP~bY8shEuSl=I(7u(x0%h)u+S={Avax< z&sy92d+#C?V}Hoj{MZH}en{19wB& zi9gv@gR~Uq?xx(T=H})`$;o-8BrVDSkOw%uW08pWZ%Z~~s(`PYrz}w=JR#qn)^bst z|BhWPCV^e!2R>f>z8cl@bWK>+8{sf_X~}G)Jtln+l@OENQa;NLlbJG6>{TkmVCNLe zE)|^9Lrf4k!$Pv47(&HfhMNV^qmI9>*RicFqXo2M7=y=%dnNLokWR>6WFF6c8A#F_ z2a^Ur+xGO`=3Q>TJX~6+Y)3?J6>9WoMw8$Upig_Qi9`<>^WrR$pbiY8?riitQ87PM z^?=@UyPZ7FzW@t&MlXs*+ev;}Dh`SNSLO_J_|CLvZfq>(+_1Q`lumqu^niqY@a<)? zoRLGGOz1^BAp5l-KP@e7NPn=fgQ20}`NLBwiCIO(?1e7&d`m(1)VpX-YNI7-VhlOCv)s_K$Pc;BkxE{6)gX&#n#q6;X3{T0(4G?C zkHqx-Y=@m|_PPLHX4-7qSt=OB(vSU>%mKjn9xByd4E*jctz2@f1A*dS=^n1Ggq47y+2Pc%k z2(bf4QbH$%k*{gJaadUDRKoc9Z$C7QOasz#6nFq9+bZvIEjJTBIa>TImdN+|f`K~F z+Rua<@6=$41OPh}Ev&LS)PG;}q?K;}A7JgNzR3IAPA10C0TG=}fRB$}I@BtYR>)3B zk9PPj8-Sv0+JGe_9F)8wY^&G*H4WO*X?3bNKdOtE1z_V3eZ)yyKCgx~LF>>PEsQ|&_h;;>hDW%tLq+pF`h>o8jF3@kw;Sym{z!>ZPxcA5u5CJlqM+CS)qDC zH%ec^HTnym&E~r6{Mevhj1zz9>r9RW%8M4g`6x_1s{>nG=l69Cc?&;Mcf?)9B!!Ke zpEecNyHuT_*i6yMPi+%_$Mr~BS{gknWGm-V?LaXOQIV!Szp&u@8_$N)Z{aXAe6rl1 z78#}9v&k%587sretHBEbS9S46^djm$Nb=cJmj_#T9<(vf-Ep&%?4vDHqspqi8Eu&} z1IFclgs|2&hU~8O$AuC_jn-LvylVI4PgQ93GA-PYzgfKO!?Yne6z=LSr{;E88?P5s z&B+K|)9`=)NaHLgZ(6$J8d^*b76{XcI5lS2(dZ+iY?x;att*Z8lYPok(|K)8I7d{8 z@vc$K^J>^T(H-f?cz%EIQxPnwG9d>C2PVQgDKzBe7iDmYiH(onX&NV*cI$kH8+{#9 zifMEJe!A^J8%6L79r{F8vzf;St#eAFEH6)rZ`}KSK%;v@!ypmgXH@@+NKYi51V+7f zctTe`5}#HJuZe_&PFn3ejNDLu7fOZ;~KNC zPKQz>5oz(zUB3#loVjw*vmgr7L7bANwrDk*m=qt+!!ls3^5m*-8%dR@fe|5fKAr{c zed>YWKAORNdKr0^Vq}k{=McG&l6=`$t(cmYETg75S8(sZN(K94cXxw71b**e0M41p zF-g~+D{sj;%Yo9VrHZE5o2?$S8uKjE;_9&b~I$+Pv26dn-X!mPqVc@a&9Z5}+U~G9{D+T5%5HMT!1%ld48PsdGjF1e zlT`!SFh|vFcp#klod_bvpvgV(0@FXel=wd)NBA8r%&@0^NsOzr_eFmWB$EZ{RG5O& zI}jW0^1QU;*sX@;CZbQo|Hn?WEvptz(?big&Mk^$)mj>c3lzL z6KBss-^F71h$Az0_|CLHpsM`}*n_{Qo5f7@5_^C#3GRB6CfpVYn0-m?Nm}5-LoIxn z7)pDdNCCH9u!h}s`;?DmO4rYPE2}6=dt`7A^>^m8wGadGDas9~zW+I3?^qy9)#Px; zoE%SM#Dlt3PvdWJK|La>-TemDVkw7;HMJ(fJ0JkTQ z_I2`zE%kV{mYUL!GW+GyH7_phF-tu0j(T*c=#d~pM)D5JTsigSntR%J;aro;}`~kUVRk8?`ZfnvG1+MZQflnWaAoOpQomloaWtxit59=@M7_ z=)5<|p=dPQcBy1!aoO4So0lM0{@>5{VkX|t;vlZ@;WE;$@M}0xkjC~w+-H7fB9rZ~ zb#txfDQCr)J_KCJMkV^uj^MKLI`1u6Y2@LoT(-7n)!W_b;*eR5#tjY2KDNbvQ`(fL?lxc&bzGMD5Q>9RFZ(keYjp zmpAG!WgI`T(+!_D+VaJYuzUcJ|B%rdY0!K(a**>42OHamy^b{@TP$A8+7N-ehBzvJ z$1GOYK@HB24ypkMO&%7M_Ml;5VO`hey!f~&F0E>|9j zsi4D`bNjuDEsG0EC34vKMHq8)^P#29R4v2xmkt!t^vjzghf(#J;wk5mxJUZRC-z7V z?j2ai3ih;O$(qN_*dw9I;ApURVY#ymi(7!m0Y#>2zgM08e!Kprza$GMy{^MmByQv5 zYL9B3V1HaFF%?=63DymVQPR~?jPbZ2Ba$&09{rG_K#`&Lshu>Mba1DGmJK&%`{Esp z2V|2kSBN9hP@;jJ<@yIEm6g8cqU^L2m7Rr@toY`~rkp0y95Gxe;!LipqJ{d?wp%6S{y0mm8GUcxkew3)Q zzKX6YG;ti`V{t*Bwikf6#*U1;t5+90vSPZZl4d7Y?(;rZ=z8BUT+CQ!E>`0kd04_} z&p>ynU*v>@O#bfAUV-{|54j$Qpcb3{?-{|XGjCMEkPLR1F23hwZe^1e-})#3j)nD8Uh$>Q{pN! zHMt(Y$G5upRKE-;EMDy*J80C1hw;dJcEf(sq8zu4ElqjD*Ma%d-NlSfTwp#@V<>IJ zK8&sPqIB^VDlFjIi1qX2%coBrN9|^Z-djBmCtu^Xf6AAAZ_z})j^rU;X+}|cBs zptAJeV{kcH4hhW1M`DaN`Rb=B*ZepSpkPX6T_XZQwM@2YA}e|U&WMHYS&S2_xc%bf zIbwT;w%W=1A#pOb{#Wduc$q^-Pe9WL#(`RD2x;%R1rkl~etuf6>pq|_>ED_gN}G)s z6JP5hSH9MI0lzlKlQIvWw_{J9|29?7kPWO64h*ByQ%vF1vwmxuS+Pb32# zgI*@SxBi%IPM0XAZ$SIIPPh8g6e^ko$#Gb7@UD0InS!99_t4vhskc)NQtwixdJX7+ z#?nLg26t+Ux|hYVJ2W-%aSTs%rc2V7!eSh*`(J&^J0Cg%gcvQ5M2$Wd9#|Rb;uxKX zFr1{%eZWJ%l7RA}EU)v>OUxEYI)D4>TL1~V=7p7N)Yc%=Ma>3Fq76HvjF_-C8Y1MA z2)+Kj%RrA&FIivqTptT^+KC})kDzRP`ln+xAsYGmI#r}GSL~@^E5i>6{AX>Kr(eRGpU96YRLSYkO5$B+8AOFGGA^9eVf~wKZY~MuNLD1` zxfrDUv^Hpb2w>Dj9^DtPjfheEWKOkGBzgyPmH4K5*6-R730f+Qoh{nqIx$=RN90`t$tK zj4z6m*^vUT*Iq1y`-PFlk#CezT5>)IrwTLV&p;GJLnTpda##^X!VY?U!{l z@IACRch6G=V(0JRi1dCXNt(ArGHX`zZK8MUtnFcF{1f2`$0m&rZDq#s%4sUTvMr=b zV*`i8voiMS2c^6DJzw+TR2j<;3M_78%I6_@AVR&v zRMaCT4*|E+0!$2yU$hLU&;2gNH1ORIje(*0IiK$e_ev@%q{Tu|*W(d)wRv;62EuE? z2{gDG@-ma`bbIa|HlZ2g_bAK-xFgbXVp7{a@veC@605^cWw#@dw%l7J=_tuBbiR^4 z0&I6?y9Vhc%%%8kY|2zq(_%6c7`QaFDQ4`AdIeFxNwecI+e+CeGp7LHptwukUXow|Q#1R&~*#hiX3gUf0ligx==DFt{BqQOaNEmO^KKa)9 zL50%vl>8nR19Eqt%GT)MxIh3s|8ii_|Lz;vVT0+UUsA~fZ!R2Izw{U28!jIATzm5N zE5lB50(-v?6tf|r*19-k2_A)tq58yUME#bXL}j3^x~{`EnSmt!d_{cPYz5mZ#h#V4z+pQ)zw1VJQ{0qd^G1VWH5} zr4zj(55rIgf_h($zTxQvMSVx&-tu~Q4R8sJ9`q88tUsJ5~bkMcG60V#K>U**tf17sP*6s+(zvC$o zESaN$aMc_f97Z$s=Lw!mf)#K>?tv0pui5?6M0jGP%TYeDl`>D=g$U^9K@G*&YhL%1 z7ETnCHHaTQ7hTEfP_%Q#Fz{1tkNhZTaPbBjNX!BuQy+y+f~C+dRqUn5rCEo0jPsR9 z)2fcB@FDBny7hojV)V&(LJ-=Ls+vB{?#CAJlU$RjBDH$a1^21DHNwc-VUSbS`$VPf56>2WldbVaPBER?s`U|1qr%GHZ^fcuCb`$e~U|;k1D^M))%rN%MQ?J3KP^1Z}Chs>Q3VGbe0T-F0UXv4-ps$iSowR;PC#{n|~_asm3! z{}%5!flKY14F)HU-jf#K(WBR7BzMtK`H+*Pm0*?#9xX?dim;C*;QvO16`4MrI*7z*BPF1#yDo+?zv^-4>}#4K~&o_UOv3T?3s~`$M;K3f+XL zB#ha5Y^ob}x&qNUi5?A0n5$+s?}=YT_RcK@*=06gGM}bZQUjgRUD(FBmeF?~% zV!{R4+=TBmr)igan*(K9oIcrg&Uhuqs*Ev};h55O;lZjPQr}7O(~82MF&YAOAcyIf zq+>T{PDMstk2A9kZd{4A1vKgogd$Fv;|p2 z))GQ}G%Q=^9SctX2&GsM6CO@2h^(#NZ!{KlosI*-V@5{Nvu!D(V)%v>!$ zR25nhjkYrYnimMB%UO;Efsc3G9S!S44g@UYAO~XpnEjDE>`W%lF`$-`GDY(izyLt7 z1QhgisWa-|F;voX$MXk#L;?vz+dA5W@l>QeceLm(o7n7t&TpizAVD5;62j%InU)48 zPOB)1`f{E0iF=XTgZEA8mwKM%M13i0Vcp_h3^MI|FsYI2B1qv)#fVX(O+@b^i4nHy zHW56PP^n!u4naAgr!|%V29lbz^7N4PFw#KJPv0mwHNg6VcxMe_K4}Kc7wRg^{5q!2 z6w>v6_1x$kVqkClJGszV+f}RZt>8(R;qs-yyqWdrO!Ym0`p|s#5owQG!{b#8>Gw__ zWZ^-%hVK3QorNk?(}gcMxOGc9Dppb(TdFTM1AHN<$Xcv}0iiBzDQkHIW;1st&3T{h ztA@Lxl~{-uft{$N<$Vs!$}$sK1}|zK%UL7mpC-cJUB()^ALC1O)uKTUTk|%h^5kWTBuN8 zz4{%et8<%D&lmeN*CT&KwH>WtP@*1wXbOunLB)%wt}Kp1dK4ch2S`+#i3VO_?#(6R zVdk}I$qiqO8*H4RVPyIA*Hzz{506D5g&vO8+In2;2+b%eq=(i^X`of(8_Q~2S&S_Q zer3m<2-EKgNzIubz_KbSFO8M;=FXW1J;{f^yFu^R) zqCQRNM8!XuKAb?@qD>iWHs@YV`My9xh>@Q8>8I$Ae+s{N^75#PR!)uuR_(x9DmlS{ z=V`9;*9=BgiYv$S$wU|Yb!||dy$h<=eTXt~`rLjT68;+!#l?EKGy7 zJz^p8m0vgO%dX%QxE=p82JMT}PRkXUgx%;pVhIV4RrX!ZhKRND7*h_KvaeRVLXy%{beP6Nxk-MD& zZP?E|=LLUT5513#ADGRnl`i`HQQ=Es*?vlhzLPX=e54kLU2}ec`fL;fSI4`Xs`$Oe z-@@jQ@{m4+Ik znLyxCuE8$Xth#8bnH<=w(p#6b%&f7jhCb8#8vc+()hO20WJ0+klzvwXxE2mwbsiYw z>FnmFT+O`v>IU|NggnM2yg!jXU_K|nDmA5 zPnEvsG-zhT<%A%ellm{qL`;By-b8WhpKldpJS~vqgRm2dNhC}k)!t@# z=+v>hOP!^9t}o5HGl>JIm4CRXJg%j&X;n#|8o1Kzcb8O!9&HXwF7PVcP0L)}$Z9cd zI`1ifM|Yi_%Kef`9)Rz}sJZZ}y{*}Z~(Hi+@@dzX~|TpArIPGBEe zzlX2}Kizi9x5FfNkt)^41`)!HxUN?7)Ce8pAewbzV6F4h=JG}*Ake6K%8gQkfNN)l zk@ERsZ&%o@>;l;shvw_5A#w}6!l1i`Ptx_=zIK*FDT$OoMW9Td;3qrmp;?e;67Z(Q z(_hij+icGYCiSq;r)Rq?W-LvRA!cZQe;o zE-boT>|Le!_~V;~Y)ZQW)6cHd0H&4@`eQ1-BYq}l9ToGr$(=}YCYxybOnsUpUX@eEcJ>NY~oDbaI2tdg5ZiUIun`HqUm`GRyE;ti%7wc%$}UZ2_;JD&I&|w~?FYpNhR!*Zi~bjh>*G{u zwkZFMVo7=&%>WbXhUHP+^YG73ncbj}r^~TUn4vL{HPx=-x7vJ^jiz7n!q;y=}uY{{ERn2z@zjm*Y(l-d2R?*C)C>C8D3B}IU7jgfLoi^UoBdr=J zpTRE>K%QEtbsr#J@+xQh-xa97aA>~PE{a$TbpLQAPsnVF6??@xAEACG;3-D>P8B3W zde*n~6AAt<|NYGJ^|Hw}RhT`%^54u2FttzFAjg$^0rq`}T*yNR#_t{QcB1VAXjqJs zvUbGof`)<8xHmlIt#O4t@}+?|#MplH_c{Q5Yd0|yWS6A6)BDXuaUenl_Pakmy! zH*#VW`jDHKNvLv|49N7e5uuspG(fLO7-NdK+fW*K+;L|XgqG#x!PQs+*nI^Di>Dq{ zec*ZmXAop)Ca0W;^KVg{_ep-kl5mEgsiBx+?;xlVJjDq==9MFGep ze@+&_!S}YP#3=DD>ha%bDTR>|VSRfFXAxQ;rRn=F(f&=sTR;bDItA`OI+57vnMQw5 zP&RzKJtIMJ#hh-VsTj?1DXXeseDrfVXMCk38#{J?eY^F;!+K(r+dnuqJa&u`$DQ$H zMW#Joh)ahgxMn2|bho!@B&#S~JI(KEgHm4bKucLlu*7Xx%{ia^D`ui{Xh7qD?d|1= zpuM)KKOZkZ}KYkP#DWcCY6{ z_Og!$4Euf6oHAr)Mos<#FD~X9LepI(**F=jIjNm2w$y+-uZ=F2R(LY3P(1z}{jYYz zmlY>0`6QNrDoW{)CNbqdi2`U2G=}X~mS|BSHiw$C;XJYi%tBBMiPMl^4jvS{pe!Js zmJ!Zzr;botp0`s>8au7en*>;MWew3;Rao)7ZE0u|RZ(o}sNHbty3n#R2dQR`TLtYr zXm8I)#d~(`PPv<|T*6ipch*PdkhhNVG!F#piXA(^rYtZPU3=-{)C_L1)eN#(|EC^l)?P4GMe>xUBlf4dzS^ zc%`D9(ca$gO5{y@7F||07$76gXcsBUxecfU%`g{52U?9|cS=Pqxla75k#uMaF=~i9 zqIwjb0##pH^xYS`8;L5~M-HY9YlacrGH=x5qz(1NKxvzf4o@>2Wl)G}+Ifh>XlUq@ zWwk?y%T8uqtPG_Yt+mnb(_8aw=+K+U(IO_^dECPIvF~{lJ;C1;gy?cahTNGVUS|yv z)qClL7rdawTtWv$YL}~pL{WLoR(h@2L7_6@De+MgJ};=#?;VF%xjBP@0%{)$;=csb zjMz22N2`Vui`JU9jGdONX^WVAF{}?ylM;Iq`JOwuCwYV^VV0d131eTLd79BzV?vK~ z_v)>d5qj)(WYO>|d7a`*9KY5&rqp7Ll!zYvG28ZCc2MC~JXR$}^Kwekz&_ZE9M6e1 zo8V`uIoPq6!Mmn=b@$Lv70Dtac(0fg=5gc_3VKIEAuBH;&oDGlcL?%yPTf3E?QQYC z9FbCRg?l^f!U|e}yL8*Q=se#7*xCz5aF*O6N`%d2(+>E%*i;?NQ)WE@{>iW_y|yqt zX9#7xpwaFP)tl^1LzUZIk!3$2jilgi&*Q=0K}-S1S0)>aOiNa96a}pH#5a_A^o~x3 z4q!9}j-C8I4Nu?t57=%`g7~aOZ5zPN#lrm*K}iNPhtEMR!Q-HH0*$Ep6z98*jkuN; zUUPGEwdDlK>1q>pC_1S$A8~)4ROF^>_P}D{M$x|H$uW^imQugy+Gq7CmH9sid;Bhm z4`(fG>8$8_;p5C4@R@U4engi6$N%!AnJQU-zM)P08ub^3!mdStXO^9yqzoYetXTv` z5@HJ<7WUJv$8X&=Z>tr-hb2LDsN&wKvq*js0{>J>w(W(zRM(bqE;`XuOnJ;&l~A;C z#u77%lH_m6k{sL|k_%%8j#Kr}kIn=f@(H4ETh|<99P?Pp#4B-tMwfQn_nWk*xTW{L zVALE^&4Jfx^OKK-x&5|R8G*idtGXmFTd&*?JA|-Api#0f0Ro2Hma5k+3k}!kH>KXc z*R-U{k!jD-hgij*{O^}q$!_>W%7UU=m03o_$d~@S^v44^ZTZ;J%XaP{`GXFXoo>GQ zP%+_hLc$o-{OTmOfYGJ~Z3d=|)@>&5tw3&fLr)A=mx%~WqtMt`la!9uoVGOomIh>%+K7D8e&- z#~ZB7^2kF{u)LosH3u_NyBURNoeG}DPj*e7}8{QUHG%a0OCE zG9uTJK2e;%Y;;6U=4R*rUZBmqyd_g_qau%ITE`Kwua&5ca~cMDc~&kV7CXOEw;3JR z^p>OpnD~)vHeVY$L7oydW?d%Xh?cw7ji`BNOmrUV4kY^A4Vy(1-l$;y z8NQk~UE-x0+`tynzVYJhp2exVLxEM9U*Qbwnj&LE3(q{e8T$cJ(H$Dt*K?)J7*GDw zY1eQqLF3vQ_(LhM5QG+r+-|3DYAqO3 z_Z7jI0DpP#oUN7At%Mt;>ja096~eI#U8T2N`)N@4!Upe@k9R5%gNid3r7`d5Z?;hM zI4?hQLcZ?Yr?#fBZrK=(;-z{1iWh$61bS~ zFds+Y=;WuQT(Z$yte?eP2j&SvrInJsQhj?=B=Xxzy^NEmIK1SH_NR+-y+fBG4Th}~ z9IVzqRSgw8+e(o4{yZMgeIMHzssjcf_e+W|EzSvLzWRz_eC^^R8v(awQ) zR7$}ZuZf<`DNaU;W=G%H(aX4Y`6|3${6#k$x8=#F+OlXT(H!J1`^mm}9IBYcRwG1) zrR}cJ5e3yg;ak!P6QqYb%8og=nICRQeb#1ri!{}!xBjW z@({sUuH!HY#KDM8g4_i$ssU!j>xDw zC5V(xE_t-Pgek3tr5V%E(2OTyugX085(nu#n7W`lb0*A80G(lJk0AhccNqG>T8w?Q zof7`+5h+aQJ(iH6SXiJxHi;k@gT!QSN6L#=Xy42 z_wP`j?ey_GrD~unC=P?eK4 zjU~0Jjt(8m=7+LBH7yNuODKAJ=L$jD$j?vI#>VDQe7ustyOOd3a95#J!Z=L*I*f)2 zo959c>sBJmSSF@v+^kYm0}w`0U8e|3z}g=V00E;?5foTbLA;RdAMRXO)cO@O7rSq1 z11F6YX`!UKd}c}*-7wLX z(1RY*f>0CPkjHP{tpwg+!J>AOQ^7@$>%X-|hdXfNUH!MI1i@%%K{V5Te96)HXxQ%y z+cCpPe7#A~q!y@xgun6gOIKM)`nw}CoL203^JzBxYuZ^9A4~@s%e#T!=W}Uz)%lQ6 zOp!huS}UR%kJ_E~k&2*Wx?CIG;o3A(lDRo9zds*pIA78OV7sTC@MQ6gqpc+r3z?D9F|xAG67fR)Z6jUWDGle zNoY@jL|W{a(Zf=dzbsctz=Hha&|?=)r1!B;8S^qfIm5hfvXg3_G+X+ozy>Y}sz|e2 z`69C36)%=H!zv&A3wf)nJ29*Jql}B-F=sg+*aX3FXJQ00@>FB*UwmUOc%5sD71F> zSJ>9;QGpp*1K|}Ja@n&Kv@1$aKW&n^(bLRlOn_f_&}5+|OML`i^MbMrAny_ZQ{F{S=LBhfi6mAjeD@pMK@gK@XV)uLk>(GA2?9->( z&EA@+Gx~?C*A$@hMStDKIDb#A7VbB>w|Wf}D&w$r`IiKIq?e~YCrpn$7cY@?dtzlF z@YtWlw*oD38Hb$HrU7#*2Zqvx1H!n=H-H(J#0pOZ*;rjsIZ)*(I;p; zWs@CHlaO0!>dv!Y+_y8+jw7j7Z?k*^CD>nw95#e*yijfH=c?eU(Rfq{lyyL;3>EMc zU9(_h_w{$!zBAH^=YeXNW;jZCiGOzYSZwDFlv=aLmAlmAo35G?2V znZUs0w&2L%L&pI;RausKFhq@{7Mh1i-5RE! z^{MCTmj5yDlSxwT6&geB!0JO;BUSY|GBk^!jD&pEkf5K%IAU)lF%SC3FCsXwSW`Ed z9POD<5qY|VGDm}Ve^A$hrPWWw_K>Accxp==3)-Y^4mk+yIpkrss&`xg^wY~zW>4>U zv(UaQ!j@*Ynm;2LEOYyBm7xAAN5)R+f30j9<6HT&sx524|6Xswr^-px6_&l`<0L0T zVfo}aBm#Vo{J}SnL)81q7t;-`B93FAlNH`CR5qiLT|3P@c&)-OyAhO#{<({jI`eVq zVcPQRWg5IfP5pXcdI%F2t`&eVUCMYot+XN~@`j~-0?j`n0_lUmKn6fTg4b15#Uvym z>Z9YpGqbd${qf^Ruhi44FJ`FmftK73h1I&RPAv!fl4zK&x`eMBzoG*xO+K2A31?~% zn!?N|H9oxk6CSV=N1iY-eu6)l}qS~aeqzWq6|b~_0qyk zuF?t9`v%xaRM)tIl-L^t;6`S|Uql!?&LYcvE>us5OovsN(ut2{Bgm-9lwS3C9Uhn4_nu66kK-E?=tB=zrx;67?avQg-e_@p7`dw;(PIVc^;s zXypAAxfXHMo@gaF7w8{va2q|=Fjky@e-H`xXfx4CZljm%5 zT3!LoaBysV9}X3UQQe<5dfB{<87SAjDH}5r%A@{0vma<=l|-+Dtu@UD;s9n4}Qty)(MWsDN>FK?Lj=Z4h3%XU=dp?XiWn(jM6!k7d6x7(jh}hPrLY=v! z5MiPQV~%dL`rblAs+&7adDmrhWw^<$=m^-Y3x`XUz-|Ur%$d`OT4FK?El!HuJ=XwM z-$IFc>KYfjB1{HEOLw!=#T9kuLG?nf=+(@e>ZkG(LzP6YnDLOGx32j!gy-k#a5&|U>$ zh<7jYLY*)Ivv>9jd{GI|abY#0zwjA7Air>n}M=UCYj)t7$Ehz zPU@v->Uc<6OOBpc2r3GNR7UIbQJ6U2YMSf>vp+;Y|6i2286FO@Op`DtDM10P^KS)= zQ-_}2AoPEy90itzJ<0J32mA5f6PW3FUFpft%D(ic^JGsvtxy%7)ba`?`4VT}8H{>3 zK1N2nx8jAx=>j1bJ5gzAMAJeBQ)OCLw@h!bFv;++HY;6gauX#@;)Dp$#I2~XN>hDZ zU6N(3_?fuySi`qPl~%N87JoiL#g7-Kct+I$Wrlk&)0Qjn(R8RN&sqEjr?zc?O{#gQ z>%h#iTkOyMu4On_Yd>$&r`8f@@|EGI6tam?&rN6dib{HRGrlgD18oV~R$Eq~=2o#02Q>Wb+D2f-LO11t^qZaNA8ItGFT*+2ipQ6f?6Z#5=zp) z-B#3(G{rn$JziVIN#e2&dQ}2$9DaQF9u6k6DR{^;_9?}CADsP8 zQf1&B;g#iqUb;SYk>rEvi$~5+I^H`vU?n#^#`x`CvyfD_-28bE8R6Xx8&T^r z#xw|Ic*NArP^o+yYYAm;gQjtbUnmzk|BVRHt&uq*8og(+Xr_r^If*T}{^H&7Yg zh9$pqwuw<^?0GlW>JtX0FcEQNY@VfY7K9>`H&NxArqV5xHm(;;FEN!t;L zNSawkRVsm6c&q45TPhryB%(mIZ6v>4iXHs2Iy=G4kkgJBY^f?*5cPzs$6EU*6DKPq zSPJjZf#_6Y>y1xIg4Y`IZzBQOwSs~QD)Df#;0fE5o zw0_N{$&!4}5%Iqrt)G{^+XvPj__5)?)-0KrTPfK;7a6raI8*aR5Ms)>m1d)SY zRN^-tGM#FS$Um=()h+PI_Fs_|7Jgf~RrI#q5gK@bkyTuQ$-5xanR5fCueC_nGQ9bw zLP)_3iPpVwbMBN{`%yc;Ai!$#dDF89sMC#B)ZA9B)x|H?tv@jKMjXV&s!_kij^*4H zaaZ5j;Vw9;ztI^iE-BgFwNx!?Q~f`@VjMYUzw^a!aUKGUi=Yoy%+-~X?Q%Qr8SOGQ zcvt)~tQByy;SS#IOWWaqV1vNX?@j{JCIw<#6@Yu67i_wdC&c!5wGN%dC3#d7^wQ{Q zr(A?ZG79RU9uW^5e=+p7kKNUE2%3Txck;qP&dsE~XX@h}fOO$74lR1PixS7W($Vpw z?vIG;2i8{QosZEe(f=NqVLITqy-i#)Wf-rtX{ETHfJKUreYB*4zjZ#Ev97!xnQdRId+`TfZIh$~q)>Dc3XJ(HSa zctd(mZXKRvY=yTA^d0`1{yp-0_5PQM>bC#V&?(vV{ssI>!y25N8f>)WzX~e=DEs_f z?ByKm&*~B|ipecLG*-Mr?>5jtq(uw@BV^+*@ZYZ1>PZpKe$MeUih~LE-TZK)$h<>3 zBE(F&Da;uB?iUw^eKme>kZ?|UgvJib$q`uUkJuQ&ILM|*4Ep>M;%T0XJYx)`Z8dJr zE=^!Hq$T<*6eYsG&FHVAXUG}+774GCW9^%iYY*x2Ob4H(y(m+jBNxWUUF>dBaSSuay%v>S_wRYh z1jGB)9I4)pj~0wKb%qEmXjXCyc?O=4pSVuBPPPNC;#<)YSP9ODADF=2rJN&5Om5vC zT<|hme;>Hw;rjOEhxT^ae4|I7%Uurn@t^acm7lk>XtuBTi*vaeZM_Zql%I$)b3y#V z$d5uk(VR-Ct5>i0b@!VN_3h#U*FyIXYaH6`#UIClRgta}zp6-bPVzl_#|e|kN9gG{ zX0G#nv{JoUiYJC4_kB(R$w?nYO*LR)(Dwa47fzZ0!BrxbUqCpfX_JeeR1rRU@ivXm zzu1M1fDaj`(2>_Tr&MOuhyHG;Nm9bZhmA9~DmLt+X8A~Co`m2RsCY1VS#G%tb-ni_ zuz@bpls#;6PC zKV77LSl#t8(!J(4L(cS_m(tJac+tBQ5iH~vUO#wv$++1RdR%qhV?15obyzN`L7>O=J*XnbYbbev9PErNMH{;Km5+ z6hFg^9p66L7afX!;gOHDo7qhux4rq}(}SiC3cdH>A~@)JZiPXZh}-4~9*K`~W6483 za1ZBdY?X6|@h)bCY8XKydC6$(xgb0zD*nGJO$|d9HjZcJ&9`*OF=C2Z)ULp*w-et` zWM!~K!d0V4F#UR(g7%;m>QB$blDWpSSVQL@Px-+UxjvAX%VwhjDcP~OSDB-05!Ts> zfu_4nM6;k^@`?u_?@r~|dc`(=t!tHyRkx+H+AD&iRy$K7)la1Y(cI!ZaTZ@|A& zs^6oUl-#&QB{;tHL2LyO6ZbAI0%&OErly?QKfmyX%UubZpIR`!#g}c%rZ#+EYJ=2kcC1@tHj99SV)>V+$0z==c!N|`|R`IUx z%E^gPIBM4F%H!pi6eF)=W-@{TUmw6mF<-s78hk(!6~Zkb>XA7S>-Of(P#Em%tbf4O zC!jU7lLRB!13HlEM`TnJ2`zT8iHPy92QIo&)PZUqLqeCwrBQN$L4|PXw_i zA?(m~4=U_B2^cQ-KE8Y#ydb7CI`?5a)MXfRE}W<5$*#`DK~!z&I(g~46Ka5Ge^YAq zt5lELVkI!wn(OSkOEK%7p-M#av^VNY5_%dKXTfCZ#-bs)pan{_k|L@-V`1H^C+)O? z*h8jwxEh&~xy&>*yT+^JHju+kqDI_49%XF$^jAHK+@m`=raZ!Cy5c3V%IjQXc=zf1 z=_!RS^`4+5!`{*DV9aEX(_=&(WuFh9;QLJ2bN7)dgBJP^+4ff7B`>HlUbDDMXr+Zr zI!-~81Y>boIV;1Op3#Xs&m@Fx(02}`Vrny~&o3!k0x}c#N3TJ?7|+EwIU7UH69H(K z!uVHKlq>Y@2yQkIlbd0^N1CeFTQEeX9nWp`XdomwZio0WE1A?z&Jwyfdli2Gn?p#u z-CKDhN9Bl@RFv6pnX9>@+uFr`l`-jNZlj5VA3q~;H=|W#na|)_O?iY4lcjrq*d+#K z!c%&jKRM{aP_16>@hiQbt7q2uEt2Jbub{>#hE*%joCCm(1H1E&)$@n9h$y{!<;KuK zzMStLTvP0mbye4=SGIDn@pJU$OdK)s&2~90*ezK~#fp;qM|9G+37-cUTSj ze0>jb)wTPBCLfV37#jgqnF+LJj|SfJ8;XRYPegx+WlNLFBNFzM?2Q@J(*|OQk1a-< zdQx!P^DyfA#FocD=AtVIQX`yrC9Z)!(e8rHGZqa;;=$q@pGgl=bG1||RLo3s=|m); zj^QL8-;>?%>XZii#wT-ou!n`m*17=zb)r_ktk^j_Xx{q6a?G)Ye5 zxPwQdaTB99@Zm~$W?`ppd*?N*u{JU>@}nhhz+8~035_c>w3N8ZQOHolwOQ1iMA9#w zp{~zZLSGjt(}aE#RrszzB8oR966uI6KNM!@ve`r?mIQZzO9^|xT|;G+UmBfrwS;cG zJKXMD^}(jG?M5}wKS~X!pcY$+ihOg?RwWoJ(Q2a>Sk=}J>obEH*3gusCgv+%ZSzV`5kp zNQYMs@mlHB&}Z_O{`s&oH=|+l*koSKdji4uY2``E@ z2%>(!5{iez>+%OLUCj3KshC45y9^X>mQ_sG0GG=ux&}-|7uBTn=bL$?Wx%XVJq_ME zqp3W+r0Zpr(?)@_FGjRl-lA{ZVl`g>+WVl8yAO{J{cHb{R8%lq+1rc9K%$JYVhXxNjfkguh|}D<$X}gqA}mrVfq*&8x%MyJuqe^ETLqyZ;kx{{jA{&0JvbkEv>J7unt4 zrw|qf=I7^kf9_XD^Kb!#a`W;=g8SXa*x5}KRgGc#tL;Y66oWMuZSfYlv1#vZyQkDm z4+Z`L^-Wb3GZ%w}A!4)h_$HT=2E=EFy*jlW3BMm;(Sk%dPXehXe5GG+CbP+I8J7>(J{O~Frb5=dK! zA!fF-*a}XD)3LTPN=K)eoLhT;{_w!VrR?ja{YMY1QQkUT+@`psXfg4mdfkMb(PTl6 zrP&TM2{RI6W|INBlkrbnoyt>_IX5bSM#A8l)T!w zL=}FZOBd>Gd#`o|cK-Y-KylURxM+v3_P*2(Q@o9|{J@^NU%l4(!TFrrcSQy(sG+d7 z8~zu}BoqRzUi!`3kYck=UJJL09T>C4S66!t3$poundqm*hOOFp$JK`^UMJZeId)k^* zPzK)b?`tl+=kI+Do1{d$nyuI}RHZ)`-bWvL@iAXlWJ<+luyYfVj0jauS#;X(F&~~f zp!ZBZn5>!6xjhM5QAS(Y?Z5l(Sq}lGi~JuG^z_uWps+C9hlHGmot^vx9iMaomB;|= zCtu4Znh^zV4yi`($xjSRYwh%)NZ7qjpcq&j97G^M6eub#mU@jZKy%ed!AT(#6hffn zP#{-pFAcsmv}Ya-x39;-GEPVmJBvJ49B}sp(gaS;sP9sj`fp&@j9b9Ruyz|7%M-^H zz$825t^@>{`lLonn?EO;JW%f@yigF6kYYY3%yt`Ee~ZhAea)9BATnE1qF!~AZ&*@2 z9_qv_>zKCA@^ty*_w5Erb#Z}S#FO%DW48OZur6b|5%F0usrFjL*A#r4@!p)Q!oo1v z7P>FTp-JL*nzc=An4|s!iOF9Fbg<5U*5)a9qt!%mLn)E)<3%IxBrt}}B@m}kH&MvO zn?`k*G#_;Oy10VHv9lAC3nHwjB39tm(6^Jh+b0NIUJLNa}s>n zEDFyd_$Ao|Uzs)hut&yZ)sXJxxTn#(QdySy|U37ZrbhdJQ*B(4e@xcrmH@x`ht6@yk>( zW+QP_u>8|5kMcM1{{N5vvd;g%NVy*d5HzY2f=E*KKk}9SCtfUk*GAgf$|^3BS9V>N z3g-Uem9rdqUhkIBG^5_(*Y~I~Xp`ugmUFRMJyYBD4=nE(C6#(p|Kbbz0wBY1myq`+ z_T$Ezkq_BIW18qLq3KQJY{!3Ji+ghOZA#_tPoh>xmW`CSmd-QQ5qY{-A=H+LmfBxp zw-Ar*%b~T&%PYarPCT(}gH8Dm``r)N*LLT4Vk)h2&6xy7m%*omcW`B>;c&235SmPR z$UZYS3dOMF@`U1AaLHds``O9Ol~;em2~uY=3^w~-=v6x1gO_h9lI)GZ3QILJvJJ?8 z`kwC{y_j~Q$*i>~+a8ZGq#aZM*Y2QI)`Fz}J?Xg07m=~rC2EW{rNOi)Zp$)IO5KQ1 zV6Nh@^-#L918?pNm8XY5)_;aJ5fR5qFFg~c+Jd*kdRm;+IG!t=cy4Hxb-t0|q$_Aq z5Li(VD7PoRkbk4nfiqR9quWk%Bx=LUYChAir!@c=Nf8Lq^8*V@Kat_`UogXKYP)CXf5%$Q6FrddAvw*{YE?+Uw#~pRgw8r*y241vmAb8 zADaSjJ?l+GQBm=W=7gKbo;jb2nr`S*8Ind)avs~7e`g~;IfwoBQ@{w$#=##*2vou` z6~VX@itC?n=b;knd@^aE#CXO|Rye-sjrdU;{^Ss#q^d%~02JfMWPmk@p%#$8SZzuQ zHBXG=Zi`c7T;#@DPjVheTZ~}OxKY#if^AYX^Fgq_WAYe?orrhezF+m~JfM$9JQZGq zV;07@=CSidX+`er_lgo=PC;q*<>dJw#JiacXN9jS(l+joqttEv5-yHQ%T~UoCdi~@ zl*$MFJfxy6Oyu*`3KkKJy3c>ZJYD~TDTwYSK1L_)OGwa^qSCqQv1yrTKDw9Yuy|An zKTzW~f(MfcJ1AGHo*F)sWxCkhhOfH^>ljD8^COSh!{EyDW1B| zAjZ0?JkWUC#E_>a=ppl!mslZ3mrD_yxX-_x4C#ggv~Z#@M7_{~(%|HY0DR^#?HLa| z%$SYWjzbj`em@wFxKA*4mU7q1?7eEDV`E$Qfg$=oY@KCTThH3=ODXPFTndHaQrsPi zyGw9)m*DOWEiNr?!QI{6-HSWHPxjgSmH)ZUe9M)U$z-xd);#xf|2S=XBS6g8NSYT8 zt)73kzF$Q}XnySx#LP?kP=lL1gpF$BL!9x@Xh?1$Zs=R6c?s6ly3*&Pf8!i(es=b| z(Tc?H78(?`S!shFg!363(7L(!>T8zR&kfyWQl&|)Ez_=*yun+TQ`?7-{z8NXuZ|*&dQCk`D zw7-3^ZN2FOUsNbHu*2YiCy;}-jptrXfBA6M%bM}fbrKgJtX3Qu;O_?;pr}gC>?r6$ zviv_ zJDT5XMNUDIi9x+3Gr8~>_{AkN8^KF`U`2nhwpG5*bdVU06;W_l5Rc_Y$J~CddG~K~ z1_DH*R1*?+-O`_@JmIlYiDjM8oln!fT>IaQ-)KLBL|hq8&w7kEAHR3B=84YnBats% z-Ev+v0v;)0MM9?#SW3fKJ3bhxYB2o9rIJ7Et*s&nWg@_m|K0+X?;Dn17~g4m{8bNY z+u%cY-w_-MCC7pf=EhHygpM=tUr_}^KBMN+eY#(MO&xcqUQmL*=hWC?#M{dsL~fVL zR6$00AAkYq@44SHvpq`FKtF!8qoW}bxoCIv2!uNCZtiJ(HT7) zT3cGXbPb-oI!-`nvdML$m2F9~mSzmoPRgKPS~; zQwsvV0w*jVYmA4&Dpg*?tvHZLfuA=$y}lU@?`p8SoT(E(=R6~1Z$OT{Dqy17DXwmp2mO|0_B*EHkdl2wObB|h| zx0)7m@C39djGP*hina==PRB@Qrxy`V%{m_a+;3f$3Ybv^6dC$=$fSaU(mcmzPHai&NMEk z!Qq>}iCP1h`8}C0c=mlD8=C(p3zXYY8NEjs#M+9Cq?48lktIm#d&8WEoGAXP)UC1n zmImy@bA1ci(3hQ%HMW|H7&yW0IzH>_V35Rc;53-8h}t^cj3DK|b}ok;6?~H@mQUlp z>=Atr$f?*2fztVsx=-lw_bO-W3YXJpar+DQB2#evAr0_QgK2AMWA}0eQ4x?z!9%ia z8l&mC?po|3XZZX^!dBUas`c4TNuOXZ9Q3&F6s@_1YW1*@R_)z_ne(zISzTWE0kteJ z!MOEusJFB0iMW-;c39GN1=;s;>b*ZTh~nssJK}EACa}U6p>%E5V~=;U%V6UBl7c|g z``do)Qrq1JvpL|L>OrD@t~E;m-qD4mggm1}0e+LG76X0SB|(zz6Nd3A-mIg^O&M3D z1n?M(v?np0Z)py1rLjFU%g~xqKZ?R@O;xAUo zt20u*Pwsaj$hMw%f}VjZ&Fh1CW~l}F%*1p42|KkAt7MqbR0i?$Q-o7KoZgu~2ugx6?BC`OQ!TUoh%i%5Rl>*wA~vupEIWHvM%^`0g>DVurC`scUvsUguIOjq#C_(Lln#lVswPItGtZ%o8Y>t&~a7u>Oov!Rj**W1XXl==y1 zUlH!KKV}Gxw5PG->QgK#asTv$oy}4mk~jlh0wGVJ-}Bk7v4xs7am6DS4_;{LT3eqprg)7-hx zA&<7Ua`^o*@i$4SPGMkVs2aEe?H%@9ryX9)CO2`$z%@_P)*;+A-sXopbeLOb_#wwd zA*vtUwT!l7?~c)_$14oq6ZmGS$&dG5PQlpZS%R-~|3e`*7RUiFyHs6QBPHTh;SEut zVl@g3u`1eFa^$^>?w6JZQ$bb-gCG6DHJ-jG+@#ycD|K2l|L_CTb?1C)vx! zCC-ItrJBUH3HALp#;<3kPM)u^3@u8XaWKZ+56|x&t`qv93--mSHBjMoeev?wb6NG{ zauG8oqLBfRDC+zL`sGbeZYrM#zv=hfNa}9oN&42DEW~pj7PzjhPh5Euy|pxjOtsQL z(Pr@Fn6*ODg;d|?Kn)M2Gr;fh36Kxmb8Xu&@4ll;cUYBt$Mbv2(_!g|%MRKmco|>p zh(zOrz3Lgwz{o#5QGMV_KY!!$y?EQN#-DBqu&!4rVu}S3F)aG96Ee6!VLgAb3+TA@ix;@W&OUeEIv`9n8ivm4 z5%hVH$XvO{jGf@vChd4~>!&#_$+wKYa2_JLY^ix3=mt}4S;Y4ZF{7bpsz_j|?Z zczJEN&~hgoS%Y;c0ZgF9p-1#fBFiA?;pvYSU4`;aVJ`=FzV_f=^#ll)HmZ1>_nRj) z+^c}Y6v}%$#!sf%afBfmuF{p>A97v*oniHADob7#@Y4}kTms6WFj^Gg{iL&|=eUkw zCZFTaL~AcdM8r`MG|RB`#Q;ZMb#+sC$=>>)h;YN+npJzrWpETYs`J&nZH)uUrv<6g z!xdNk?H;f@c~0M7`&*@bPU2BMI(MgGv!C>J;=)kL?VB5Ej=y^@@vIlW)5ox@(|hK( zE&I-Z$qkjj!$rX$5Lw(MWtqe_d&6nCC-2ovrCl;-(wSkNmtVaG&})Fg3ijOBf!K`G z4>#wz=)&OL0dK*8)A#D8UGsK&a=S`!E!sA&!+%>5StZN2{H0=Y2kW5{LNqYPF#zIa6E`|H5v+!wAxQj=;!my;$K^zpA-w(NSU)y@JA(z4Gt| z(<+{IL?8MRV^U&JUFyyT&ZqIQ=Qw)0?ORJ!c-aZXyu?|C0iuSUJWm6meLF3%gs?8a z1>Oh?DN3hPo;A-9Y>sG933DW!jAHf$#>fL3AI?$w33Z0*p`K<_%jdy|^Pbdpp49o| z2pS)=ufdL@5UnW{@_0-lCJJ#-LB41|3U1s?W_EUHMLrSZyqLTcqeM{{Ia~F0heN|v7p<*xVQO>ZK zr6Z4#Hmo!v3Nmth$Cr8oW&S-&%iScUrt2f$_)|n_R%Y(+{$vQ_^HY)6Y-D53b6mJH zI;E_Hi|hAFF9$wy7OQW_^74Iq$w@c47V3SWXxoBsccb8gNkAxPe*az59*P6pX!c_C z=KIU$uDktE?1zff9 zBq~=bAg*Q!FLaz1+q_J17BSu|tE-rkOrnLkT!C?akh~Hb%&kDDA1wGX+Bs;?P`{h- z{)FK65KGSIg&pU2VGV8soCWl!N(|JZT5DmYN9l(5M5LyM;H`J!ddCt;Y~OKqoe_$6 zX+_a<#;0b$v9gKT8XMih@D9id>U-T9BIB+_d)pTWO0_&|cjb>>9UpA-rqL+p6#f6kS5z=9bZ?f&zs)N<}14o-;S9a z6>L8UJ}$iH+IB?=062Xi+;;y9fyK}L9ER(}r+ zN_ecdQnH>HJK+!mZU5;I85PA#&q`ok*5r0cC9@NAWMzWX?Y)a3l`OGzNzEjZU!RG= zMH=NbY zv)=@soY`**Ar@{D4lvdh7G3G=)()c#jRp|NpOGpG@8|?lR_`oFQvt-*J!t~vO6K=- zL#_wzesF>FZoyh#T;Har*dFKRFWs!mbgG0cWQjou76_vDXKCU1elRO1oErWwk*h1g zhGkDZ1aVL}yI}qkI(e!M8}@#@qiUpd9ARWhcfv{VL0z{rEVTkZehwn}!HBSyrvM@y zlHuYv^z1CmI~^6|8Wo0o~6ZL;46;z+~% z+&-@pV--_VV<2@teXRXWh`fzl`#>ZzX@Z>OvtF$onQ)R93-Taz>^L+(cLp*Th{Q?6 zYt<6{;`I&q1})E)e5j;}UAP`%r1Pmr{{9QWPoc#Uc!Ckc;##7hxV>>&eqK((?t4+Z z2TA5B_VB>+?@cy{e+?2Zh+g}U?iF0^dMC532Z=kMrRbSlbP0(KOMmdp_r4rcS%mq8 z7Y)!(YoF%EiXgK{Qdv2*SqQSg^K(IxfOtwrif3^UD2_73#Xxz*T@fW4yFaghvNhyX-Hg%jkCdmZpCnse2IW9>6TT({jYCMA(NO!J-drJ#MWH=RqQir#b0jilYOi z>?evgoEYD;hG=wxA70;bcC7)=1aE(n+`FNPr-S9^<#1BQ$GgB-9;WV}?X*-sN~$wv zvW87_67+$E&{QQ6YSuX>pa{s99_MSNwurwyw#a}E z7BZBui6ob@qE>dOUN(x}A>e`)jmx4=ABvfA_@-T%?wx;N>Jx!g zqtmqDT*#Fo-fIz$0TY8b2|rROzWA7SG$o~7-I<_&HUbmulh<~f(?*2RkBPuV7y8z7 z_sbN&H&_8TXCze;P!1PWvqw{mwhP)xY}Hof0T476{Z%}k__NAs({{IDH)qGKyQan= z_bdBDSqi5f1ZbsPQBeV5xeB|xb9#AsDXOXlLsB53<5Wbk5VK78ZU_g)j>VgHQ%}&( zdB1EhUhc#!?DT`XY-KRAj{-PPg+f;&sa^9u!DktUj(;d(PT}8F?|B!RRNZD1LkB47 zKt_(N$5tnbrxA(y50OkQ?ZiuYgT$_PXMIJmx-=Gj=?C<;$nu$#X%Amrn3(1XjH&Rm z{^0zX@@YRJx(vi!Ib`~Dn5tgT0U`;BjPUOyC0@tCPSu=ptsxesL{gh`AYJOjN&?B! z+uMrR%2Ag4@Z;U;C^hDic&Za`$HQhYM838@knIfh2bxAHsvHaq^Jh5x))7{V3F2uS z+>ZKF&{F;Z5}q8y9q~b1>l}q-4}6kz^cd;yLcf@>oYjy_O0*qO&bjV= zRR`cJ6UcWh#M{0Zs$n_{JWQcr+y#Q~eD2UOM9b^};eV^NFU5)V9*KBM1d=|}_`WP* zEv<2coY=iHt1liV2(+`+m~L2GM>}dU9h)vu9ypad_A)t3pmhenKW$H5_B0ew1H9nu z08(z+N*uA3?=TQ3$mkKGX?`;sF)?&daS0%l4|my!<6BRG9v5~=PuPV;NN-Ba$P2vw z)BNP+4iwYE#c+AUl*1do zhXQt=1s^H@_FI;FZt2sPRSApc1uW)xeCh;RvJT9Xv+YYb+Q{~fED&hQ5tn|$dWz7) ztE=pSwm#XG9+k{nkNW0!#oXX>?6K9j5tgdUsg+D1`%b3s`w|8ot^#y*K;b;R4Zv0B zPPt0u%#PL%;4yV<-XE)gyG7%+?x1@u+An$`3|v-PJqnMV!?>*yxo1O@`CMAoXn9{y zLk)(dG;%2&*7n5W_IMMjdu64hx-Y^E@XQ0e4agtQiHq}ju}kJ+%f|Lct{G1QxD%^a zSQUo-A-!{dr_#QW0_Ym~_3ck}USxZ$-e*%=ea!RQq_d7jSe{7*d;W2T97y+Hk|bU9 zm$MYsH8f;D@MwMD`);$|;=0u8&h+&3BnCII@3g(3V~-PCLm?TPxqr%Rq_oEdh+9qL zFgTiuTJo?6o&n_>j`PqnNe#X+Oy(L>5$-n&0WQ#chTovn5aq)*t&|&x$c`gga}i-y zuv_5Tja>b~EV1%grXw5zk->D>q`7Q$tbnX(6r31{Z%a%CAya1qu0U_d8Zx0s9+>E& zc6O(VO=)BJH|C?x>`a0vO7{`?6R}Fa#fPhI^OeIAKXVCy;zlG?y$Qm3NzC@LoTPZm zg(dlyC4u|6sdRgPOqAW`2emI5o!{P24F+j=6*+A;Bk!@!jE<*6wi@S7t7Un9FVPG? zQ0p^+&u96+BwVkGa&YzGHhSdjIO~~u-jwWs{y201_*Rm#sDWuV?0vNatpmp3Dmq;xq=e2>4RH|RQ)Uf3(~6y#>*%57m`4~ zd}&tHM$;iy62)oW*2Oo<_Ib8n1Ml&q0$c6(qXhoI1!YmnULyY0R}~IqFo8&IZ5ktB zByYx1|i zwJw#wN6ytRS8lO>Ija*{f6TS6W}1rtx8dGyf48h1;$ui}AH_D(2)+RFaF^ex9+h=c zlB?ojY|R(>E32^O1w+mtB#W1Nn^dNdoG+E$NoU)-%K*eCW3vKz{Kd`DJn!A>KTk6I z;iG9e7hoAlC6X_j9=v#A`x(`7S{*h;pfwM9y3xzFGs4j{a!Lrbba;QEbMd3d`!zL; z)JXH%(}PtQ0P#6U81zXK!oVTFJ#*~FFouYd@xHUNI$rNdcK5@S;qtAwp(_@!q9 zwzpZ1&dKM@2)UMdKihk3jOx~47&~g}JDYMmxH|z}u>8c2emQ_5x>y|(JFy12g-!>d z6~b~*WilW1cWR>XWa8NZH5K5Y=|Q9rIb{vsBP5^wh3<_4BRf0+>@Bcyx&(CkD@otS zO@YP1HJO0+y04c?85S|sx7h^T{m#$uK3hcTHW3iSZRgaQtb2@MEHyE78!haY3jC{} z3q*LVkriJG*~@tGW;Ayh3)vIQ8LCpAU`liD3oO=%;2F6DY{)Ed9;`Vlg^3GrURXap%Fe9@23vJJMMfrtPiKk-Jbdr7)Zm`@*|XQ4>nqD zN+uUV9Yq)OkFn!|r_3$46ay2NX4i5~mAc@EU)6nYmiPmrn_VzyV}chI7{(X;8!8k7 z8^)K;)Sc4Yeq*B=G>?T>z{;^Q@|iC}6>-);&;BUJ@lr5A@DY=Wl>n4abvTwG`2SFpaV9e$;PA)(*=-0M zbZTzy>%!;V{)gF_8D^dlfQWYiMffCZFBGyYSV>bUbZ5;)HadpP=<+tF$vILX<6I!v zSRd`Y?OlMrbWDPtEz-xkRmpMJr^#52LKm@r)|15;x*-!eSi*aI-WI~|GvGTA%kD)m zHpAvW6{-zo*=IEX-M}L%!PAPO7asVpPl(QoPg66%{3YQ820_Dj!OCX!XfB1U>GB44 zNJYoU3)fm*j*swSjNX!x>xDQ{UJKp)3YIKT55ssse2i|~eeqwc00>I*e01)EmPPZ?d^G2RNnPn_~K z%~Puu!QrbDci_bd?Y3b@VgaIr#6D9`nTIid-xU#+!Dq|r?8uKwFz$9hw&donra+uc z2ty8w^=ImlAr7yH$J6H&8T(b_;^7ma>9h{L!bRf8&t&CD!8;xjZYON##zWqL?^yZ2 zDR7t(d+pu-`V#~CPr^~q(4v^WTxm0JJK#Z3ct+a$kHp5G`scsFv0#G8c-#=Nl=Pce z9HY0C4DMfe)_fP&o2<{Isb_=mavTkY#~XJyywAl{QUe0Im5%s~qB#8g2zg$XoA$Gx z9WPqc!SeNnWZPprf_#kv;X$o#-9vy#?~4vX_YFrlbq<`a)z#2*gU@yyCjx7pt9Rip z7m|~|J=Guk9!n#B4I_|MVKkQO#Q@D;oLAZ$n())Rr|<2OnOadEHvQ1j^^%s{jeaDn z{X?1~cD=C`2>2u0BVS%#PG7Fyu3diW2fj2U;vWI%@pY=mD(wJvF#u6)yMP-^M{b^w zD_jMSy%fvsD%gP{fpplop-4yq#fP`FmwbYYo5M3tg5N2f1#+DQ(?1>Nt~8LjJE#%% z%YM=l^9O-P{up5Z+P6Q3SHbifO_j*1zda#_NEBd<3_7idQcq}rN9l*FV6M{axd6m0 zw4!`reYnVf`A9+r0K3sj8+=~lx!+56+8(%Qz_gUSN`nIfmm`HJ7WRUS3q?u4QQv6y zpCRdKNGF7S$>vhWj-GrwWqeMKi=O@_BT;cR`tbTARm%Dl4q2{TSvxYe*Ja5iVf&*` zUx<)Ls`AIN=r^_AXw&C9X~OQH{9Nta%tHOXicppW;`%l466L>1uV;Aue#`O;e%r62 zl2(p|D3FjI=w9ZS%sO!Y1X3G6Kf^gph0I8&N}b+p znh@>CdQQr_+hsn`(>O$fR9qb#(24c3=zj$V`4f(lefaQxDAuH zJ)Bt5;f$n@gLu6K1K^WFh=lH?3zfx9XvEyfH~z`a7b7Mv`Ks*;QOj2yn)OHFns37k&OEj1{(SUGmwh#_H0fl(%KX8Lz6X|f8wcGxm zQJF5rGw{y|=8C8Qk%| zuSzV#G+nMSg;eTEG0j{T_rfq$O<+auq!bI`Kaz92u~q!DAr?iRep^tNvp!?(IN;Zu3^+US2#-&dykQ_N0ID zk}`9!xdx0tcwXM#hK;NH>8Afs;T^za=RuhFN~)@#ie`U7IN%mAFfahwQ<<;kQ^r%; zi^Ah{VMa$_P2!bT z-+OvFGBnf$vCe~FqeCDx^xB5&YbQ`HKJO5?EJ#WcpSRPcKOnuo3{={Txa=ujTu~Ot z&lZ4TkLSrQ<2XAav3G!zTgQww3+=;9r?Kl}oxXi-Qjp((q4p>*iyT94QVq?RP`)>l z6v#f{qK6Ck&G-II1xK@-NB?>9J*d;?7M?((T*R^khQP%J;;FsEDrhx$$5|nit%8MG z!|Dpje34(Gu5?VjIX&e%47yMc~}_(1txw~J~z&PsEA zlixZrK!0rh~!Hc?+XmqLEp3C*)nn;~~ElNp76lvBwY5Lv2yrL;NE#CE+X=Q86%Eh3&2#YG#$ zhf9yZo7WmGC*`+o4=?4w>xLo{Boa4tBrswLD%D3$_$hy<6&FXQLZcw9T*R!R)IA&) zBphsf;CUT6w)%tfADgX`{XmKVYNCW6pCBvqPUGf&vNGdMX5iN6IMOx*)cA?6e@AX9gwa{OR+`3A;90|t4KjunTuk1d} zPOCnAH@{%~u*-G+8sO*t@MBCib*zS-br3IB6oqY!MrCF3zP>8CZP9O4!w%7M#5TRd zpm(g0%gij^l%+QIL9lZ^t756fINs*(%j?&Z){OPl_1Ux2u{S%j1`d*tdt&hZg}(6l z98Iz3jRN@Q8dWwUKF0Ok_tQIYo4tIknoz=w#Yxu`y!zl9BR9XV*=h(^GaxUVNZ}FP zU?%qOGMDqz-v9Gcn@I@fZDNYLnp$2%!vdmHU1OsTRBd4)m35*iLm`3+r$HmMKox@C ziRF(1LSZnF$H>TMsosv#t&xkxbK+5x*_JJ{`_kZG5GDnc-U(LMSKsLQ0c8!5a_ngc_(PT>w%aLeQ?6q3)G~ z?p2BXjttWGtA(VvJSv|A?E@&?gvHoS!F$FQHexumxvm^RQozg0H%0W_Ms2@{+)c5k z%ZTujaxu@Sm4jn~(%ccD7s?i1K?v6g~==Q0iGM?&VA@sD8uuEO~l#lIF z^P5lG{jsvgY!pi+Gwho_#wV2ujkt)=_0^|E34@}sISW`;DF(qT~l43H8B z6*E+copq;xU(q_l1o=8il&+}SvOgr&)G*tLk!)$K)+~tpS2wJ)KpUfmK|`jn1ukPs zO3ELyvV9O=z6!_wP&Cq5NIC}vE$y*`0Wtw3*bMz#mcUo@sac8<{3`VHQ+e+wW@&Rz z5@^I{L`3lMvKLoz6z+A(MXy~&8x>|tcBD76gkq}NTyUj=UHNy?RohE9b#xZrNBg%M zM=}P|UkLK9e8n!_^r5E5#VZ=Hog`xY0Zv~{Vnns0VfmL(8dsxo>7YXJd1xQbG)6xu zD!HLYEbqo+?n_RQCI>whr-orF-aMY+@tY#2^4)W_>^j9$43_c0nrg992R)VT&T51$ z<^TyjNjp(laO`(0`w(Nb^^&S4$w_x8j5M=jL00Kw;wjDW&yZgdTX|WFaNP1ct#;_)y zM4oDC6&|S|l8N#oF@t08&|oiIDZJ+7*ds~z-(pkU0lA~i_;6K*Z|7eVfoFt^_;^IPmXE8Hg)7tv1Xiy#& z;lGL2xi-&aA(F=Xp;XFl*jG@-IZ>f3OW%6c;wfig)XaLq3QhRk7t$HQMR?U9h#VE2>r;5?*lu~vuBqyh-C5O1cV0H zkII`|x#8!5f*F3~x!~R2zIc@Yh0Vh{;bIUS{_k>xohffXzlK++fC)}aH6Bcl#lgnH zga;K)osi_!Q3QSsOXVle`p?DT7P&;6%o6_@g<{wxcz6{5bqhLULL2|r8!qxZ=UdM% zs3&3F59@ZErKP3uNlC`*LjnJ(r?_(%@3FqV{>P6W)rCpjT@cUAoR7wkO~}ybsPTU{ z4L11G0K{1n9T(UAIsl|pAi=^cA$jA4?!Aa+!1Qah3lHPp1x33E2QP!il@{9Ag)Il} zX|NL|IvZjA!t{S?`ZJ3d9YZRZ9l*kqzKC*I@jhOe{GZ0M6=%sC$S$&>WOCiH|EER_ z@$dY%KmO;}aBsINhqm@e-LUb%W#+XiOOLX(u9JA-XnhRuXXhr0RYb%?=l00di?h{rmZygPaLyR7lFolL}bD5E$A>FXh z{|1r|F2oN;kbANSRaVtz4mYUETAcT~%wwx>%PaE}lwH6g)b6A4*|JX zyFg~A!56bqtl2ofx7zS$pqQwZVhYaiuoQR%_q;df{Yv9>y%CK=%?*8eYwH2-a#;a5 z(sJbc^7q@eOU*v}v;i5)=S0k;OHx1^L}!1v39^2$TRKD5#X|Wk&`Fxpe3)cmWjFB7 z|LD<|k|U5q`mp8(7a18^))FX~?6u?%Gw}6i!q1=KFi4-f_MNo4nU@0~sYbc_YU(Dv z?J%zbzvFVkFc*c}TF?EpTVwqvL$9J3`Vi0Oil!D z)Zof!Tm%Aov}csZeg#|B9+FkI62$nTnCY-L*bBnPt;E_qC`Pf@D_}Y~N)#0^GaI9UvW!57yDBTt#j2;W_5SSx_h4 zKn%SwJ1+lDZeP56eR{sXFn4Fj7Zy8C&uKd$nd4;J`g@qY9sfxzDA?8ZXM8x5&;5r1t7KJ=a!{Pci&s5?E5pT3;;c5fd@%Ymf!Z5%^rZ**T%j)EM`*=?jse)58Q1T zKH_Ycj6qLPz^3N z+PO66;WzVO%?odXg9}gKVWFpbjoU1E*Z^1yZ4Zq1E(1m*filcRY*=!pt&Tz!=HoT) z)$JoO#ni-boD~C!Xbt)6Si#Y+)Z0viZPc6f81|j_i0UcNELI*IY&S=h!2j-}^QWQ8 z{&R(i=x-=!@8}-<)`gPx9v+5 zI`*GXq41;}RiN_y1nasyx|ZH7^k8p3p( zvB=m6aT^;Vqk;m1Sy_uvxeATc2=VFQ8^!d4fmD8{QQ$ga>auZC{IBd#@RH_l6DsHp zyQXz0ya}#8%8_+?_WE)|{!k9&UPV&Lb`AG_3PCz(kRuHqKRK43ob8eEse9yyLi}pj z?b?AtBn0s50x>r@C8x|JQ`8k1+_nJPzVX_AfUDRgpUV06(Y5lg&)S_-7Tv3FJ(?Au zT(X{NK|rhO)k?W)U-LD59zDyt{KkVC?HPJ-qEQ)89V)Guw0F^~CDo2vL18ej^FsEQ+z&F8+JfMa}u8*K4T_P%8?>Pec23PD5garIyn5;_VcBrZ4b zns?}vn5yp9x=x@Y`#s1IZ$aqANBL32y(vC{lL)4{d1!Jp^t?n;hm63pH!?mWEvha0 zs|!1E@anI~z!#B|*pMr2ECJ09#Ckm{8}(c|cm^Jr{(eeoT6!TbqH5=HE7dyhElGNb zI1(6d4F;Z9AsH2lwT|2sCOF;u5635~@jtcvxzbRUL&T>}+>Gz;oj$RP8kxJ~tBUtg z>%sFgkfxXZT>DOipwxgBSwKRbLdb2m7mMzb#kRlXb|a^+4x5;in2?YXlFWq_3s(I~Af(Z_O0at=2J@$;GL>`Aq_k~I1qYS;SKsI8 z!Mc1rwi4&~Z)6q9qW16!yR&BQ?9|ZcXtuAEf5_-4kSt3gen_dsNwL6t zXwQ4f@>&tIG4HiTL`L>Rm&}43Z>UZt_^%6)QDCXq)(ej@Xwk}U%+0hB^J6|}x9~}3 zjhe!T8X8lPF%1h<{EF7vMcT5hkZ6_E{xe9%%S7tQy&Qh!k}v+}kJ;fD)(I$gYdCbA zm~9FPa(-^q!YY_`{e#YKv2!4&>5PdB#9i=tf>?b$X@ctScHZ#=H?4wHhpd8V-FVf= zteq?9v~lEz-u${xsQ}~Q%!cPMEt1|b4;d$%mj>J#l-i(RoxisIR7hPpaIfqUL6~r7 zW+ovcDX4r*_UjR2-?t(PUK!iT%iMz1vW?zoFOJ~{8Wd79`HWaO9gc#M=3o1VWM4Mr zbj?tm5;KpEEy6YrMAYrRV4kg8TwFhlxRd@VBAQU$ckp$C%~awLqcqJEN-4rG8Fu)@ zZ?U+`4D`U5!7?tl=FU;j(*mIrW0zk$?|dzD-)taW{ntt}$!Q2IVXsT$6HFuu!}N;} z)pM%k!6)^kN zeDiF(J-}3TUr}m4x8=Jzz45pTIlLN}skd0Q4^1Yn?R@7%rRVFqG+|CuWWzwlGO|=rraiUwFt&GR z6u02FP)o9oJq1sZl%A-wnDKPVqS1zfD~QhwwzBhFI$EZ>gl}ec=l3CS{iY0j$?^xU zDwQ<}iP_kSX2y8#aWz?;s#()zd;cd7ITR}Q;@}_S?Ucry`?5(%`8Msi6?NHD3tgw> zl%LE*V}4?Te@4cIXb%9lESa1j^k2P2JG+az5lVj%@OV#vW8DPt)lL-O)soM=6^8k3#u3a5#3*iFGD7gQ4kN^=Of zjn@y!#WZTiW1_f{;^QR&pwiRRx9+?uMv7m&++`CJY~)=*xN+bnuD+6C!z1QQrDI5R zYG-%8-vAkTJa`;G$m32sHNuTsP1}O_^Kd(dnD}6+smMChe75u#t7633di@Njv|hvd zrv#S>8{WD8s!GJI*aa$&EyY!p6So!0IF-KZg5_ONkps=Wm5&YwvBE9AXmNFnY_5B9 zy5YR`t;CHRKsW*4ZTe{1%*dz-fIrei=O^6BF)`f~vT?^4B5-%+4ic+Be!2M_i&+f4~q*0YuxkA2FQG(#pBv1qW&wpudm z2a7J+5O$Sye~gmGw4OJuK2vrfF!V2YCJQw>|DZY${=ra%nflfk$%gIz1u?8IcE2Si9{P({w1{-Dl`&9HAr zYFu-nvuk}4F==uEtD3GMTF9hHmt2O)FF5g&T-F;;F6=MO&4pxUf`%5*a*3qy^fkkU zB#{=%*CIpJtGt+QNT($eZ7?ql-YZc&UdK77@KZuwezQfBaH3MoNE+W~%2Yd?!!%v* zh~p*v@^4Pt2!yB)5gPUVa3a+xH?SP?ZzJPMzTcCqxjpKB#e<>~LUENtSAA>;K1i2W zRfGv14a8QIT^?uH?*zTBf-D!QPK&J@eaF7$8z+4UwYsMtTzTRe%jPCgIgk&we`sA= zPl(8{Z$;u<_uxJ6H~>axdeNLWE2ZQiz?$jZSOO1LBA64C9P_jf0t1_}a~odfPENW~ z<*Y&N*C(i(%Cj4->p^B?$6}2E7lTL zwSj3zZi!?GA!wR)A#Jbkv}x_(X%BTIDFy?- z$;(O>L8G4d-m3eoVOZS8QBw`3IO=wm-9ri7;f^JU@#&oY{KpaGQKjB+vV@^=ylAAI z$Fy984+b)}#BH?DPcJx2)s?We6&Y$;kBBWvMMeWd)NOCaHy#Iff0ho>O0U%=?@BqZ zE*{*;ODyOm{#YJ=_T|9D3*>bs&sKLjc-^Sq#cIzOkf0F>s#tfR!X@L+!>0J2n2^r$+1S{bg?uBR z=3pbBGW)5NJ(x3}`Ff|n$@gB9?R+CT3x_9De!-BYCKGbJ#%amU(PUZ8OT^DGCPITf zY*Q-Hfa|T(s;CJ3GVo_fsnHMaV@tqKYTiU*5>?`2VINn1?bg$9`4KfZi76{GgCia% zOq97awfv4|{CYLpaCw><#$+BHtLn;9@z2VV*eIUIZIpV<>9p3QAk*aA6os?wnf;8J=NE zyzI?V6mz2=js$nM6PVUBSd>%=n=9_C0N||Xj;E*Q1LQl`sOfG)H-49MycU-U7{oBR z=jN%+AId)|ha6>^F3HWEuLjkWejuQGFcuZ3OGGL(xNnnjxC^uluZ5Z3XXxFKCxqZD zF&4E$j$xsb2Ic)X8i-xj&u9rrejTcwqk2J3>w|xSJzN$}#cUU8K4FBza+A!m^_55` zpAX(wxDL^iM7R`Stlqo#8qQAd-{-M!iKzSXBq}FiklOYX&|1w%cm3ftP&s^Dal^8N z`SnBj+tb|GCl8&`3RmglWUb zdg)y5e%9lE*iUo^CogS3c*I^KJ%&DphrLjBD>Z8-?`=FTl3UI)M8z!ZST4lr{|z2U zvMB%!<&~DBXO?|r<^pkRY_h?M6hxDR4isg&zm0V7Fu(hv>S!mj)N-%jS4V{@s7-18 zC8~7ccBuI%f9^z1fM;QFla&-c%gc+3s;=TW^I1|Cz78`FJv%*`qn*ygj8y&M>!Z=}4ayM* z3LHOi()qcVKb>OxiJKv$S7SfvcfOAS`MMsR$wT}OAUQar$+maR`hg6%ONK>xve;rK z79Zr#ia#45g0`OZp{=|*r>c^`UI^0s&HI@anQq5^$bhX-VFQ**R{oGnJN= zl=#%y@m0@umfiG8(2Geb{priU36Bz1tGCB&T54nQ5&ObfsReKU@NxaBR(9KJBV7IT zv4=$M&?`CC@W2htn*{%z>q9p4H*!@>rC)l%5efu0nJ7>s6SI6a6Q+)XTCt3oS@NB~ zjPSlx&V)TmROn4=@Rjkd1ai1&V}lO~AfLDqxt zuD^0rZwsBP<1>5*-9#X2Z1}Y*^MGFSdIUXnRETOOQb&|AW+u1%NhX~^*(qu1?ZvXk zhu=4!$N&8J)SL3#-AB)&ay_Dn39St3$`|z^=jC0iEv`k>i|cWjvfA$yY>e^K)hy*F z06f(I=RDP3Fj$Sm1UZ^zOco11=Ow44+{6{-du%wY-+YML<(c*-?f|HhCg@QwLDyvd z*4ERD?&#pR{@X@A5>2G7t#j2bBxnPfb+Fy$kt>{K5SeEZL2HL3Jz(4Lq- zdP=fbG$t^M@A8hn8U83GqSdpiRHn;&P+%y+dujGqrWy2h(t6&39I)Z#9JD(DX3a<{K1jh;P1j=N;wp+z)!x;wmj1PTQBygusebyBl;=*~`eu*jo_O1`s}ZXlT924>TAo`Th z78i@08XNfIt5VZPfit-J4POtL31b*9Az!MiRXx%|dvbOjU#~}?MN>Yauvxwrc-(|B z(}cVko~ijpI~{bCmFu6!=tz9@??;vHnML*T%e@(zebmS9nPR=N5avI53s!aB^A@yh z4b7U-RdY58W0%x%2k0ZPNydO0f)B~dUw-j}`#6)^Jya{}r6+5{5yPPyU4&vKiM_DA z9xlwDc|QMoRykn7yVMx%a@c^zC=B$Fq%RUriCSd~=Y1+)tZ7Wf^cHMq!ds3fy=L01 zQ8;Z@!U7v@t!VEBTVoQe(}OsYqKE@!|H%(J$G*erJT8^m{#|z=LqX0iBk|ddX`fl2 z4WQ2U;N2ZnY!z&W6zM3bX_+oy$50IU%F9Q))PsV8f|O3eXS~oHrovU-69NtWf+)WDGq776&4& zH5$({s(2H~qtEN+2L}${E2v3`Cv}u?_Cu7z-L_H)e!EwIt;@_R&KTac&4j%;XpReH8K;7lHxccxV|>tew1J>5AhJFEY(8)(LCw2)<2 zPK=|LsJlFZ7Ny@PIJXqMA*CR4(hiP;$ru6$f72Rrp4pX=vCqe_Sa=qR>rVyoPayjFE~ z*jQb|-}4eFu_OJK0yow;jW$9UOH^EtP7(O6vrrY?5Snb3{i1c;@^d?>TO`CFBI82oyl?wWo##8_ zoZ(R(=}dzCu=yM-1i;LcXVVo?)NdqG$1U^V)S2QB#Mu-xPe5l9eWj!L0a3!EJD^pj zn64}u{mV_n}{M{0_Qbw4yV@nvZu8=|IEF9tmQO2z-KI$VP!KXH zIWjT=y*mYCy9Hj*padzlIfEKsY@bRvyXz3Mq`Z1ab?S|8*N#h(LrwbmPf}XYtKj1& z@ZS4d_=eZRf51;{zp5*{?Np!R2iIOWPzc-cpm_cHX;Q~dRM{wAU6VUu0Ox;`&CvgS z(;dI}q^-jXY>Nu-ezzJrJ24%J>-h=@`DjvUTlsWK{vOuS6F+n~=)rDobTc6R1j&9I z?!le;j=>Qqr51e9>9!s{^bVmI9UU{`(yFD#XYhs*x@bB6#=*h48?31xFt>v|L7G=D zJvtTC;_kg$<#n}RuV`ZM3vWy@PhziAN2z(uzu6p=m7=EDL-wpj?n^1nou}A;(r)PyC5~YQ_#Qwo}Yz^x)YiX zf$EmIg@uE>c*OGB5i82vj;Ild+BF`Euz7pBC0orT6J6iOg>$G|iUQa1UfMUh;9EtRd$@%yq^h>07Lbf|Ht} zA0-`(C2jaHo*;ZMUTuvyrO{KGaTGIg^jU$0wZZ?K->{fNsDA@7O#18iffK2Kz(zzH zPo{v68YMS&7U~ROd7SBNLod8yzj)*){O1#cRHzN6XyYy!yi*xH-AyJWOR>UcCHSe{6dO(eZsG zmcI2+7cZT70av;@{)6=NP6VMM&lm~3#3>*vN@$euynlK=zZ>AAxe8<`@a}aJbv>}soJX^xlqcL3i>rn z;X=&qw*dr`uezPrHBtAgp->hjEu1)0#E`_sXTMxk|+L1b~%` z;dR%3FJv_fZ`92{CMIw`qWmU(%36{HR!WFxUo%{--hqm5Lz z)Zz&aL|lxF6INjyhAz6v_NGyf@>>w5yxUvW6V>dx0144b3C7l~OIMS%DPMSb$OZ^< z2<$uCvr9695aVLjsr)JEV|V^1r>3Dn#?C(1hP&0`xR;xlq()Q0tR^p#fwTgpA721@ zs*&Q3*B0|tKeM`wA*!cas_$#6A(bvLQQ1mSZ9kYzB7Htq;ciABZmxaVxcI3p@vY&4v&Cu1 zSWOOgQ>T?kzee`J(#X(8DUsjpYFlIg1k$eLIlcq$s9xqdNwO2WUz+45sXo?Q8;DOX zQ>;Hh@N%(uv7O#5Y;DEu?5Y-IJZR$UR0E7}@SwJ=pQU2)qN4yF5G6Mi_EfGKNEXuA z-o94GU0hVu_q#s$-&b)|TA{)!nrK4!vp%m6>S}6Qy`5=kX-Z#|_v2o2IXDt{tKdf9 zDPqg&CfDYJemri3-o8C6(jU7sR>HGeKL5Ks8;EGX=p(%U#i2eWm;!?sh4`FMP)F`o zV50)mYW&PBIy&^OCg$SoQ3Hg? zvUes19s-8kalcsbc}kU8I&GJ`y_nN^At$kYHOv3|N*c^QTyDiW?ty|;jsW1@#Z;xP zMwo6bpd`(~e1(T4Gcn|WP4}Tyy5(wfR*5dN4BB(8lN4I8N=gb+2_uW0 z$1F4tf&(Iu#mYp1Do2kSp;ypDk>B5M3MZYNL)zi2v%DJQ5i8`oUJFv7W^rBb#okAw z!}dnBlX7D$m69@)6p5fVDMTPRCeX;zGQtPD` ze!jtDr;5IRv&{80mDgUD@gZfYcVi}?vRuP(B*9FpzW$5g1Wf-{$oXlCj-?J-lW=N@ zl@4XoWp#aCaQf=+gDMxTCR4eT=V_`xGwjt%(GeqvTeM4_a2=u)vg#f+;1X<+k5 z^S}{RAzjP!rMGC8+@xN!5|X{~e5{d>n`=fK((!Dp5qED)6uUs)*b{ieW|FKJ939qq z?>*$GCEDJ8n753~>Eh1_eSNV*d1ZJtJbyLz*{P`TQP*}BNMzi27Pb`NmFsnGD@VhP zRDsSJ*hfw+d6fsciyM>&XgU3OGS15jsT4r04fs_4=DXFRF{8?iBdIoC5I>4n&F^zg z0Kx$`>O>feEuWk5xe!t4`e-N4Fz`l;*N1O_N;YazI$FlYk;<^uV010FwEXHu%g9` zL^Fm5y=BF3Fguhf#1BH8;8W(O z2_bz6i1Hn{aS;L}zPtaSxx4RS)X5_A-_CZbuGkox6C-17u0Xk=jp{++xDW?3 zAh&WY=5qxRD=-exr|*rjx2h{0PWw3baA=CAae!dBvL|R6FMh+0LvcY>YbU z^!f9$YVQ#%H;d2Iv0nRdypAoVIc5jGyHMN%`qpc!&xBjBu(hM^)(XABE&L|j^u1_z z_tf;VK;5=o4Ur^yM!HMlKU=;+)n8c)2x(N@3#S$owv*t<@_ytwvuY-%{ef+H?5G8q zXLols3v@Xb7Av+}+UxG4AEWzP;Z6W_zxmXHrg!zJ_IQV6CzFxr>dYG-t@}xES}*+l zZ4=4D@#7`rMp5h6VtAb!@xUIziBY-Fr!Dt0kCa}qA@U6@dW|0NIr*~cLQtU2rvF1X zny5W$i3ex$Isf#5L=;TpU$}ljcNncUf}#dC)mB-1^;>TdVSE8~yMXJPJr?}-+z}$& zd%yH8Qqr9z3ZP;Bd20WL1-`x+rYAk zl?MktZ1CxDMWz`ERC7yzRKLB8#0Mg-@BfgWh<8q-VTjV z8{=Fk3M7FRL_2rnBW;vNIQlVrnr4qCFG?FD43|L-?%qwL!-zcBPDmuR z(Q*gg)1-j2)(jOdH~39L8I4`i)og zqmBS+S*|v*cAr$vpm#@2GK~C&fIn+}J)(~4dd(2-wDGLr)@lC(?3%LSqfY0kZWp$r7`{${5)!V2{maNT?p1zeUc|GJyvEt=pbiI)Kk>@s(+^ zDDd}>29ZUpD5y!6OG;Cx6+e2Lx2!=4MarCwIsP+FMQURQ?ZfW=aIL3;_?bD>+s zY47Kh=Wr9n_CjjY%f)nk)}qccWofQvXmFqnLbJ~uF5p0Co)<*aiE3#{_3Geo8oESk zxpS|&RgiFDGM#QQZMgQGR^luk> z^jH@p`$mwZ7uohi7}WyN_kJkf5`KH*?5NNGbam0=EQ{ng@%QgELHLoHB_~2c{QTTK zUCGVwDBaLdx?5D71jw}$l7a;c3AmOwVK;Fnev{P7wdYb&4nXLXPw4QXUd0(`am!;= z&uSZFKKRjc;RRh z;{QdZ2AC7hs^;&MR0p-5$}e|ayTBRHi#oG>uWc3yhF(v%v?3RzBdIQqAL<9+xtAx| z(0_vV66}IHsS$soQ0=fz?at*@45?E33nLCFzq6?q@^2q9FNg(7_mx;*Z*P$d?Fqeo z`IofcYvx7ps@<`?T!Xq=FjEtnB0DuXbX4@i;@-Ws(iihgoQFn!G}LELAJCkf+h-&4 zTbrZJtt0T{7v6B}?jYBU<=h@?Z8^TY&e(K=8+qQ4WG+h;wWd{!nw<4|eCJEL3W6+u^pOrQB`*{E2YEe((dFkC z|HA1l`v9*+Q@Dg#^fYg5?f1u23$H6ly2=j@uQ{csQ^G3nAM?%gZ@q-XPf2_crxp?y ztU9Lo^`^nX-&s-ocW$TOI^V@ltAWvzr$yzDC{^h1fbK0cg}*Q9f+ryeq7g3)=^McV z1r*Eb3bFIk%4*tl2?@Hnn)BJ7vCNBJyz$q4lMS1U!wL(+jX`{=EBU+e@dQ%_1!3@* z@)t>VJ<~4B2}3(K<&wJy&APE>j;VVYn%KEk2VU+c@s(0cS+TOReAmaZ2C)nN<&L+z zwP{W}W;Ar~2zD(8-K_sYyc~O35Kag-w31R`Ib}#s5Yl0ty8)PO`mZo{@7FTx4zC+h zk7uB%Y%lbM3k%(wOoH0?Sc5)2VC6uuedm`M%fu_l7||0LrP)|-F}TG@2A#_Hgm^g{ zOl;@54ZHr>m=QnuGwo=3{zpAtM!?1SWe(&aV;V9|V9{|l_gQW-kn+-r=_wdIO4||MMSH{i1AUF$>#>B&OKOgD0=&==C9MMrp+i7^nJ;}V^QVoENvqXY$o+Z(w1dT2^NmLfFd4DZ(AymD|libk&Ge9istkNH(7$wm-zdl~bf>Fx^& zf0%hT@Z(mO6CI%y_A^pf&>9Xi|N5uIFoj5Z6SgjJs^s;$0Wf+nKOuK8y2nS8NkRkb zYbGDU)^m696}VpralkI^j^zsrdrSxYOPcvXj=ms~-V}Gf|%JjEI zrPw@G3_Gmaf7~KGFsu>uNK4pLi{P`uXsui|ztA!-_(FgxrymlIX zkA0xKvW?xsra&NNmpneA9pL31FFO%?ymW)*XdE^M0sUjz@_+f8S z(!W?2O)f=l5F*aX;i~&!kC2XyY2B)m{4_85BtnK5*6Q0pp2!(qbGWD1IL%$A0wE)r z)CU5c_CJNGMYM~CH@w0urW4v?jc`M6%SM}bobF3JBEWGLg~4N+QssQ;nJ&2+nG#d6 z4~wUw9%l}bQ=+tz2Xo|Gief`#OCxOp@I3hvM)OC?G{e%84Ks6E5>@&6dvnU%R>)s& z>q$`tby-KCS$>t<00#-`e1`#xD4J2xzhg?5Gw}(6$o)w5J3l{gYVv zRPN+jxDObo&1-{hnw50tuOuJ(+WwwLT?s&>8qvdvB{Y`<-SEbLk4KhchAF>#jYa0Z zr(RiNemhsO@ht{V`wF@r(l0*5c8nD;@c9~bVRIxN^!0MA7#vg4_4ZuxnkJYbm@Fxi z@!o1lekUV~5TgoMY*~PTi^0v-0ga)+&tu6n>xZ7eE^4*0Da!BA1yuBVGBT?fPl0=K zpQ+D~#TpxDXJ->P7MWKUGtzJ zMPA^tO_S2e^!JUK^0KlD4e~#K&YDExB}ea|MRWs$gQPq>9#YBI3Cssz6-~|1^>y9l z^PQdhaI(O8^o;cMiamZIp)F5=c_|{UA3qj&hrWtqK!ufPhI_HnJsHJHn34Rlid#2; z;knOa?!L~}&)pK`Ts%?Ljgy6C$m^ELizr&K$_tgtReC!9>3V!z+*cU^R^%wCPj>S`eoZzP=BQqK|o?Z9;UzJ{U zwK*h+Ohru%tFFGjGIAhS;-+|LuXa?)gCc@MWoTk}SXfSO+%F}!ZFSP0I!pLqjG5fz zLib3a7+i;)&L>vloTlhIu3ZP$f7y!gC-PhG9m%U*3iKa(H!-x4iW`MhrXVO2VI>W| zRoVpR#j+*E+NVJ0)cq&o6Bm1^x^xT=enL%lo*>}Nah$-X&*7Mt5qw6%Q=nEcpZM9g zT)U|Cdx+i8pY^$Jf53A;)pdL{2(LlAy2S0iL(P891(vhj@h`K;OHCPCNy_OZYq<~O|fehCD;}Dz4E&4s2vdu4FR3CoLd+E$%gAK;Hl!c zM^da4kxm_A!Lykl&J4jrV(tq*WbT7z#vOJjaf~G_(f{tiETOV`!CR^(mh#2(Ss~Bv z0^kB6kHMehQKX;qSs2K_!L(xLuBQBs?Yo-Ek3afS@|^oA{QqdaWOCDoqCJ-+vvc8a zg9=N~JY!*DVawBQq_UP)7^?}$5EO;CsHUP~j1ofQUu`*8MD!(Qq|yVhUdAsFne5bb}V;0$%b8Hl#pSiA{?x* zy8zt;&Jkk8ACV_mm_{aMZy3aiPnCznzZAK@SQUC~KfHX+h>u;zTFUjy`0Y$uob#3S zq2EpBYiN_nxdAt$VWISv>#y#Ly=kXh0B$(0D%-bk)J6lV?gNFGMeq9#^B*VmFAHzM zDUUDnFO`7*Bes+AuDzVe&{p>T8~+pd_b*{XLxYx^{O4wj)1xC{4UNTIkFiwdW_Xr! z#5n2iG=6DG7~|R4vDnoN;)z=^%TfGTv2=cw<-{4yNu)*t0EV=*DCnjOJ*IJiu&kKZv8wumP8o*OJU5(3{?-ORda$HXTp9Hi@U!ks_;6RQ z2ivuf6IZUNGyqmCQ8*2t_fjsT(}-Nd#y)6b+E9$r_+^}yyXNJGTEm*rkrhy$sI--w zl}-r7e^T3Ks|m;U;yZ@Z7uF&cBng%eaO>PPZaC|X&$!7MdHM)B9&0sT29$)XGZv+l z!Q_=6ENeL_ibvj3Oir@`k2v#LZT4yQ3kOP?;kHk0`m%`Hr%#q%JJ&3_`4aVL$r}x< zxkvF!p%I-D6JkpIj{isr^FPJBUi#Tv^QYT;5n~kyFDMPJ=l4{W?Z$+dwoCYxp2%M( zE?99pdq%f4?OJ2;>YlXKDZ{UDZTs*_|JdK-4CCWsFjcnZZGzd#wXv|BND# z$$eQPjXkR2e$WUD9ak zfC3+<5#D>;pz$ZF;|(IBT+Mh#$xQb7uRy znMFg{yv(VOn!+b2CQ6F6Sr$2!5B>#t0MjhAjp5+^y)E=7j;OD|p8fL!FKs6>Ar?#uv z_Qo`xNq^1FmCr4^thNsf4K_Xm8EEiIbq=H$^o#jSE^I}=pKGi0@FwSXhMP%xbk>l^ z2^alSx7Ojjev>k3vk)+1^G#nU4B$3KyU21HyE{^8baj42u|vr>*Y}HxLDA}}%$@2< zd&!~s+xB7QoZ$K*M8+Z5U_0C}S(%^aIt1RtX!H-zyjW6h zEgewCutN4g`M=}*U$Su9EIB(oeDOz#Lbb?WHH7EB>9_XV+;&KXKv5g7zZe# z%d*fQ*{7hMd%E6>Pf7V5P0eY&$WTyRY_i_ss1eD!QX9*QXVnI8;KpY~NAKvcgx>)M z@dEHUmr)umRpAe~j8G<+-KrZ_3`-WIk;OGnU7ES_>+&$XI2rp1#@za>=Zs!_KCdn~ zok0ABx$v#%l$Bdi?7P97qwN878;Ff*+SJ<)%Q0_(Biv?!)e9JthnhO5&|K2K0*Xi@ zlIt=D=G%n=;05-msvMMs0_}^n{sd6O;Z@U?yce<2>qNGG2_9zoUG!41XkPQt zz-q;=xoqAgx6MjOgIO;?V4^D*9gA;nA2(uvwxZhOFVqFlu4?ZyaX1h@x02cSl0FoU zSzOO`zqsVB@RvJtgH}#p3ArENdrMCTNl|_x?r+Eay@s4*{fZ#?`DKMwCu-s^4<@wY zW%1VGgB(@3U`RF>C#Ug90;Ps5n+IdXHjrXs9&Y!zOvx}@7 z$$qUk`cc9Q@Em}ZO4h+L-dz^!7Y7dY`JO*nNalMQ9j#S}?97=6=JI$a>mu%JR!aKT z{p(}qInZckLs_?$qz^WJyD^J-FSm`yt6qUzH(U&?y~#Z>8fZK#wBn&sYauNNsp#L1 z@QTRk<)W63{|jd|_8r09q-kVrO3HNkFsTO!n`mRs*ye-Iz^|cMCGMtrVP(=hqx(P_biY|em(YYE$iG&Ve5f8^W~X+V(w?i0z>!(k4Acv`ajArAO7dM) zn1!0ALHaOWTlSz?p(Jvk)5mWZO)kDuk3l-!kE)UUM6LVc-|_byLrdVNnd8s${TjlUe6?Go)K~tI-JIX zDc-#P(Kal_O-13-^N6$oI@azOKu-RkMM?MUx>NH$n~YHyoW;wr`}y(4;yq-2h{HoJ ziFEGYSZP8bjOXePLUV6P;(rEUq zRq9s5P*a_6w_cKL>Q|`QSX19b&oU`;R3`o}ppOapEIT`TIh$Z+*48Ejp04S~ZYaGy za^Z(5h$)JOU?&25HIaXL7w3YE&bt*}Rtu0a;_z^{>0Mw-h7TQqlWY4i+x=GbG;c34 zWq3hdT}nOKUKHC2V*8!`p{|N5`7-l_@OwX6NzgQ5-tc#r^0HBxWp%-b=;+4Lf;Wm& zf|8!J3fU9t^Ap0v{1a*wG|C7L`LdYhqLU>{T3Se!(9{5$tP2W?)Woo`x3@PPC|6d3x6*I?hsb)$NB6D7|ECX_>@j z&Gam{%7XZv$;i2IXlqgFOO{mX(UNUZv9SJ;O&XP4_5`j5B1|viHGDMkiDxQoI)dB( zXVzbs!V1yjZn^xxD-T(QZAYPkUbJsKcqpcZ3^`2SP8K}>GY!xJczqpDWofon{R}F) zp$hiiTV&Rmhd0FY^jhtFODh!N()*LMpdkK|kMnPuMtenw10@vuU>bne3Tghv5z7d? zzTG6d)jVh3e6Dpjh`likqp{z3l=|bzN z8BW2NM zh^(@uZ|$g4K^n(efAuvN;NeqnJq z#a39OwUuafm_?1nTI)w4$YS%=(Bng}3aYi%Ew69RKY_by?4u?X@bc4m_I0JbfFDlE zQck-sIkDPp_kE@Po);RwUw20rDvUJ`8L!K^`(7@|-dgt)-vb~d0oAh4S?JZ?`!$zZ zdGA>II*EDEO`X{LtaCyDk*=8uvVeAVo-G(~Qyfm!6XNM~UVT~dwKQ>?% zwSRzZnr^Ju6_tHdM6@Y6d`WRLs;Kl^FqS&~p@^H?laB00i8_H+X&s06*Gqifo&)zP zr>P8m1}~q5u9cv=vl(8mtO#G(aWsbjK~pHadgJO7e|I7E^v`0+kKD7`XE)69sD*cx zZcCEKziDEP!F}NTHp5XT=ufov*hrEP)4~@&#A8lc%h?T;prywHAXAe*N#t2RTw33l z0n|C5@l`fJ2}+4JLYwZ7np26s3?L%P1h>0~q$WbMAXK9Mm8FrPI>$F2V(zW&z^-Xe zBGifz@D=}`0&6P+f019!V4}XUk(Vi2x@uyrcS1ooh~_mRR5l2df$k$EhTLApb2u_R zblrYfy8}1-+#1aVd7A z)SC#s-TG4wXZ%3-db{E3Xe`HW*MFkbx0LN~D5!io$_OOG1Da^jyPU*GS;E?pgA3r?k0FedP6U~N=2;y)VXuNOd%n_oM{B+I z>W_EbSnZEyG9M)c>9CHdbrqVAL%U7ZZ9EQhu(7_xB2dL*1SLF@NT(nnBn_-*fV5&~ z15N-^Ec6`^q)P#QD#^c}P(v1<2bu&@)qS1uMuWcYhN~~^&;nH)%TkLGaY#&|B zY2<)yX6%AbWhm*t)!7`%;v!7*>}_n>O(8G>y7DzO)}K-GRvCW%cVtP^aq3#I<&4&r z&?M^R!`|=!%i{Zh$? zv3}N*1+XJ%`aGPbC72{S<7MVK&{H8IODi1?Uj!7>3o_E(RRDtnjg2r$60T=nFo@aZ zwLM2}I~-{jPd6px#u|vnI2Uwchsa?XzzOry<^6py;+CXK8F0HX>swNXZq4P9Cv@}k zO}&?+y&Ku>NOR75bk%iE3V^0ho#!Rxr9ahuFw;@hjPu!16x0!9!rVwp>p$)6L}~ehkmb|OCMq_y}+K-E(G>=g$V;#+qg#j zIRRocZpRbrlgoCwO!*K!$-$6=<;~=%=S0a~Xj?374B@OT-z9NLqn&R~1*J%X0^_s%e? zd+nvb@p7?1G0A70rxCYqe|zwWGGPOC4#iPOL%VCcJYe;2%{>FWo-Am9wRv~cx@z$L z8FBgf2A-o3+h`w!WN63^Lh%JHO{=T?)6r&>Iakckf$H4PONuMp?qC zzYw}Z2#9y~FYEAKDO`4&-(&lZEJs{?Lil7!mhP#WSKQa^AZ1q6mX5M%6nLe>L_QEZ z6rTS4`D<`d=@a|LC!h<;$BeAd%M7#}k8VtPR(y`+A3t2stvJ;_B$M>KcfS7|OV{Qo z80^VC)gV@gXzX9qLaVpo>39U<5XllK<6I6HzWQi2!>1h%9EV9?Y+K--d>4Xs^TX9j zkLrvKJlz_6HPe?%7sONcXKI1Od#K~zz3v=hyLHnDbeqdnHZqe4d~mi$Xntr2`+}Cj zyyrfWrq|g{jrtpco@8Bqi5HUok|JRYAjTXtdAQX(N%j2z?fno_YW5}E9o!!B`2SLRpljAO>{P5 z*z!xixnDN123@Ud0c@b}g&iaA9NE?{Od*pvHr!ukzG5W|LLex-I{=3@czguaTpNmw zJ%<#MpnE{|PE*L7CBA^5Q}|#6r%kzl-w%798jE>3WM;;pB0WCk#vLLXg6v>r>A>>j zFEcqN@Ht+cEc|x3ItKntpy&&pxvx@Vp*%*c<0Nlt@>?)P`!IIZ>I(3)x7#EaiN zaGn;>a`gC#pooxd__k7CN2Hz8NDAJ<(Y^|%a&HyRT_J9}Icz1dwicxRJcNLw8YB#oz=L$ZpO zV!LV2El#cP}e5+o|6HqX65y#ihzGHU?$FBR!h;VaM}3vLiobRj?WmBWE0aG0udZ@biGrXan;u zeGGr2AI86M_&%bYJRewen^NTYKA4F?o=69lUUE>HSV0BtgwzT?@}ga}X)J+PRx@c{ z2boWxRH4u*?-Ta_5=H*9#rq$9@9{(<#o%t?m_>@pQkD~Cu9Ag>0;qv+wsLaLrG+lYIt~O`-e5%UL)FL~Hnl2O ztlgN<_Yms0C)oS9fvjW<eBW2J38h0V?PO_Rw861T0?PVrOo$vjeEPP$lG;#^1rTyj{Mq0ky1Qt!GpK z@D%g(%lW&Xm)Lp^0c_X-XC`I<%yAQz@b_u8} zFSlt#3N{%*6!ITMJ7E>5>G-?;bQpZJf%w4sZ5EhiG`K?R2)T2pMFdyg$uHSx$7FKo z3E_}|oGS*c^hHti-}FNP^vQlJsqd}J+95HZ4jB$9X(Tqw9lXix&YQBR{F|M{Y&vpp4f6mA+7g2VGQ?v=_AURoOqOKi0N!xT$(?4+>{$V$S77qLxbr{ z9otvxThTQFh6X4?9gg}seSF=v({ccVJLsJA%6lCrW# z>ib7Lj>8|anHspbLRDU4;U53*G|VY=N{fgkZFn@y$G8ccNnFe%#Utc(S!=eJ{3#bj zXF-&k^p;=##YtBMgLiFp`_}XI{-?&Gp0avye7+<(T?7|Z&am3nv>#|yyP&v`s6I+a zT_prWMMYLJ+E(@O;5(6BR|WOb*(y-q+-mY{;co2nwTeW3T{S=Rwn;v5D3eE)w2 zUs8=sppBF5^w44at*X2{%I@xNT+SOR^jDXeBRVU}e`PKqt6P|xn$~m_gpmtPs%fhCTGo?NQT-Ej8F>4CN&v0X zTK8zLtjGMt!{e}gp35T^pI=*xo=JCEKt=uN^+tHqlV+jxnw^v$@#G#eC><|((&ADU zlTk6sW4W=MU2(&Xg=<|7t%rTR99m}fK|EG13QEEC+(*{9|Ch1+xNL%Z3%MkxV!Akk z1MQn00(gb)3Z;8Q>BN0l17V(Ei#!czM7Rv+prv0za`#||xurcN61K0Oe>UTVrgzBP zcKCTxp60Rp`Pa^oQRn+3M@e_xy+SNhfPC3g)QGt}04iJW+;68@RT91Xa11ZTMl{&& zue}iNnkwvD!9TG(^@&iyuTSl*wiL;(lx2BA+#0BPGWe%txw*u}&E+;G6U&35d7xaz z{OkkVV32w(Nls5%+`UUVuZ*m<^#E$6@F8bvn`c z^93L@omGhm^AWP-!}RqmTgG>=#rfCPKm&J^F%$OcyDKCl0@H79`t2NdQ3?ySlLQdx zPzN&2gss)j>lGeteXE)d{e}GsgB*qUPcgz2_K(n%*fXuxP@xp3l8bIR82J;Z0G!0i z&NntX-Q@E+jT8}lr=bRgBM5+keUpoZ_~lwFyfPi{&u~BXlgE3~(%?H@dtILZd}kO* zs%uHY>BwbFK%D1Y$|EWmfsGm+f1d7D`|#1a6Xyh6Tt3DG#Yr(}9jL;@pR#4lnUQ+B z2UtQ}@;uf4|DYc)8w=I5YGRADklPA>B88UO3xq{IQ&@0I_!B4!`u8e2B}5^ec~#(% z4VX*ll|G22=Oe2ez{kgjRtOrQd|O&wwfdB|AIr2sls|V9zjKq5yMSa4;8#h^S60_R zm9!Gn-B>8GYBpMLxMguMX1z%uvM8&Tbn6MuyH;hjK7qq3T2(ij>9y;WFT z+qNzmJV@d04#8c6yIXMg5P~}dhr%6#ySuwnxVt+94ekWFHP@PR?tRa_4~K{G!Ut8O zjowF-{!65c(f5b*jpb%LlK6y#N^I~ksoNAJ@{M$A)NxD5^ixPF!PQ! z<1@+#BSDR)FC2RQS&5yqDHw2JPqge8*kqid@{z&YjoX%gshI3+q)^q_J`7!A)Wti}Qn zJ!qrVnGegdO!!cck&A8WSm9D0$UUo-s$ni2W+AnENP&M+02UgI2y8D$^iiL@3c<+h z6&sx{0iPP2Z^PfolIHdL|9yNFXjo%4NdTPK%(Qz3cq|Op*r;m%w&( z8*~4V9$1$v-ra8V#^vROqBqp>$DZq{fj=~spBL$P^MNTc@MM(aeb_C<*#yh7L4!}7;dmgBJoi3&gCuV-%?XW#=AGBkYdq%V9y%g@iR zyc*cIO+;V*c;WY5-WEd7(9q7M@w=53FXnA5wJqy0jP%@^eN7is+eWZ4g%s#}mETYj zY;rSlblwWCO?iL199QqpG=Q!yQ5)f>VS5+j_g+tEP9jNX$ZIvC<+gfk7z)Q3$L$ZX zi7^2jfIkmJL3o)F4*6=zwdJtKAg39FE))PU5oj>dzq1qlu9q@$G)#n>P*@iWpFiMR zx5tU#C(9Cgs=uXtXO3fe7E4_Vf3we$`7^ajbU7C%`T@V^JW%$s!n^j5^;mMPg#-{^ zbC~XbVbE*%h?CuoDs%q2th-{u>Ber9S6)a|)gU^a#tNY=1H|$xU9N}IIpEQ=ACb`F z@kY{f#fuj51J-dauVO}xsD@3@6PDpm@$CTvi8I)qIZ4==8sVL6dlC#=>qqz}tdjsIB*l6#Y+B%Ty3- zcv9atJ3KU4WH0Y^2h8Pkvkk5Kq| zdHF_5AF`J!4bm^4Uut;s(az#Y(@8cq3~*fuAc;|4()?+Yp?s>5F70}b6W95=9f#!j94u?-sZ%Dzx)UCljmQ!a(2ndnR~O{D+aZU!r3+fObLKo-rcS6e~hsd9>m1}%lr$c zRJ6E_)l5!Kib0)|NHAg?-AOIEh%wTP#21wxQU~~x$_MG@lx8ZwYq`nA-jyE$tH^M_ z$d#ZJm2!kxjX2hwXZ9AwGFxe;NKP8yETn&K1Yr@+h~pj1Yx`>g6?mlzanhn;#n5@V`CD zoYi9?sr?Z+7&DYyAC6-YGu?VH2g62;uM6+qcJ~nh*)_DHtSnq5GH<8n=S{W&WNy*s zKEFu_vdRZni_2JkwSAZGprcRpG`VN6>-Xwr7VAwE*R$WUr?(l{8moPs@YH+Tm>I^! zvo4&GO1PHvi5wXn6$QibLPoQ5#m`q6gecJ@$d6S}i5*Q#;@H#%hm)=xe;ueYh<%!s zuFe7@ugd*F$`ns3gRMW==1=d~d{xEammJu^r+5Se{PyN0que4%F^lhqzT|)61cMI^#_5eM0SZX^Qp2DBb;WDr|EC1VAv!qLFL$QJT|k&k7~PfVK2I{6Gc9cO z!^M_eQg+3jDrLO2*(Wh4C#Oo0T{y}ZSwHPexJ931xfF0wx)>w;O)NK6EV2P#?Jlx# z$uQ>T?c%+HbuJo=$v^Q$iUfRf98!Xh#KOS|Q7sYbxGGj~e`-E;SUIHL>GP5kD=j`R zC8_Garg7bk@NLHo#+Vf=wFH}7Y+S#B^SFajc~kHAp=hE-=1uP?OWu?b=38*n&{ty& zLIvN1ELAuI003AFZceA1EE40@A=SVv&Q0idqjqVo8X;%RUs#< z_zowV*ZU2eD>ceb{ZH`7gdkf_PiybH{;*tx(V$*Fi8=wP;enkGwJ|##L&O9%JnA4F~+vrwLbN8dn%O#5343;cKo=AZ)hR?$yU5n6s&qn_}_nV)RH+a6a zSa0p63Q6Stwxd+uFtr^#F`j*XYMt`E>W2 z%Tc!%l4m19O|Xs?UT#jRo?N;0ckc~3mY-)Rof>1qpLLJ;))whosF5dxTqCOMWs)si z|I(G0fW6ZWAZ}=LiOlq1#m-KSc-Ybkqpn`Z;S4AVf4=7?9^@9f((kB`!Mb~+hA7z7 zr!OSPgN_<)<_J<%G`u)ZpFLAuWQHi&++YDglmxEfS4yEFPkKLPM^p~gfZt(To}c3u z_39$O)4ycZT=H!_{n0qBU13Zs(2V>+YHELSs&jPl!LN zx&3D64gVn2j$lze>c7%OKtd=zba?)Ukd6Bl-B)KV;QqQ%E5VcK{Lk-S%P%*~rV12J z>@z*^CKJp)(Vb1DEgtc3zK?&lrn#IwZ7~1>ZOHXL7?1>`wU&cF5^1=|E?+M|JkwS% zjSWR?xaArmc9&Wr4co3RnYFEuMbMpmr=ADu4W;IQqjE#Pv%?2alVfw+c@xCO9m`@@ z^=^21|l85sm4uNLaB@^H_8m zcX$(mZj~d$Qrb;vJ`j|37mIC_SG}Fk@EajvI|F(qn({(UI%2T5G9>Wp5c$|}owv=Y z7DUe*Zs3{Tj;-K_5HzqWl#~5050UxrhA`@xqPV;ml2*SX! ziU@_Ka;)U)L%sJ*{Wz1L*Cjo_+C5n`J3HYJu<(fm1-{-mSA~^~*jru%>-#RE%9RM# zeM5bg97j$7^>_d}roICnn_Uaw+_-LuxMRy&nX%X7)K||J!>_L!F-B_!OE+C2;>qpa z_PfsWm^g6heA6Mjnct&}M7VV>7cYFnNZyVa3lcFYW^yGozK_TGBigm%n5xP@K7kF~ zKe|~XDa|H1vczud@r1gTQBJ$Io#vRHek%idB_k>-1PU-BXI9x>!rA5Zn%+k0I)KKF zSze{yNNE|5_^*ztyMQFG?8Fh0lsZ~jBHDS&IXnGvSyLaf*UnX8+ySJSaSeJ zVE={;mxH1}t}rYoH5BII2l4yeK>C*=z3|LRL8QseiDJdBvJW8!xTrg|ZPA3j)-^{P z0l&Z84e^!Osf6K$;_vvcqtH&z`{Tw?>`n@ai>1!H1W3UQh&E`gzYM$&Y<022_&(p) z3z$MvM-M*uJn`5vl=Q}AuUjyJWqFk9r6{JdVe{v{z?2XesNaRx)tk!JMHdN+XeYfd3}8vuv1>h3T|_z;RwSK4q4HIs&`;t^?gPBLV}dz*)rN()Q?UW z>T<-Qql;Ft612GWIrRCAn(ihZRv#*(7psWk#15VD+9m(F$KcBXS6){xguWm_2Jk-D zL7ZHo=QQ|TE6IzG3JgB578vb$2#i};sEt{)uG^YTWB3o7Z~0ozbC8|iG1l9I@$~1D z^GRO(&CCvW?aQl+yLoBYexH>+@BnRw6b&h7?X+1ZA>9W>=Y(&kT07+8^%u-k%7_UU8X2Hxx5|GkdI5Ww5_4IztvNx}qXK9pe()=~rUR z_`wU?+4xts!8Sc)2eqyM&pqbQh6$iBnZ?(ax`SJ)y^*Wp346}`&u@COxe?ybFwkC~ z>`2eO-u+WrPugUba$OesG-d*X7e7LWTacgM7)q@BdIM$<<#J$PHBXgb2WfZlfWU)5 z-OIj&nBC(gF5`XkWyNGNMK|b28-vs6rAW$f8qY1c1$N+M{@58oSf!pD|e}= z?9)Icvv!PejE`3;r>)k12so_tYhUaHfQ%ic8F!Bl)t#0Cz+l6z*PGx)ip;!a(I3Zy zay2J*D0!aCPml8od+N4SdA;Itv^`XNQhmlHasfYI-A}_5F3l5nPi~RN?J+Z=zn`u8&^Huy&IlIn0JYxNh)# z)x&{*mL5Rw?L)>K&V3AN5kFNjOP-&)Q5lqPsy_w4KWzD5X!`nhZo=8bx)jcXMI(91 z(TFBafqOsUj4-GC4{o*#%Ms#!^R>ng|2x&S^dR-cGaZN3PY}}&#JiCZQr-Ds?+ zKmz+RH*<|~mm95dfB*tuNl8hTc;mYW zUNr=tb0%IQunP!;1)BhAng1|~eLeB|+*TGk*5%b{uzz?Mq8hxf!ns8!yb$a^T9r0h zUgSB;-q63(VO_?jp#00KbpC-siK9ij(`&8C23NrIHkJ-NJ^qs=;H9jpiY^QPi}#N9 zDVaB#y!U*g9SmItf`vT5WF9tgzxFO->x*`jn=E%oh-{=I2b1v}6h@oO%aV1AW`0x> zB0xx6G}i*3_a;+=v*(9&D0tSH=~rUsG+6XZR~PRSNheEg$TR@F3TtSc_0iFZaIvA3 zqaM<&pJrz>hR-r84pHFOwXm2c#$RV%OL~Df#9l~gWtJon85I97y(wO>8%9^bp0~<1 zTudZu$q_9Y7H-7nA%sXYiTKdJt|`Na;A^z>U)Qu=LR_^ApzSSm?yn&-_OHYUMk6ue z*ZFa2#xNCBTGVG<`$OcM7;WRtK3`RDC_iD2H<>`>KAlVmoC<`+cvC}~dN&y+FiUBq zB_^7A8<&=rdMkPxR+I>dE33!Ohy09ydUBaS$SnO8t#fVmhA-|Mn(;fumv$EL%T({0 z))zHLntJF#`PCuOoK~VO*T4r|qRoFYe{t38urOg%6Wl8L-Q_1Yq?~saYtVnA7g$cH z5)8q@L=-|Pdl>1kkN5N`5hP5r>ui3I6&l6kqq$u%k#}t>Dfvht8L7-~ql3l`pLjJ)*UpsYx}wOFa6CSYD5aQ(R|beqxcJHn)G*P`$Kq#3h+0Q)CUD-j01 zo+jrt%^{oGyRcF8RPqvRym5-l44!kbG zeF33r5t#0!EfgiC-^rq%wVqP)ELj~_3w3|r>!RF_O1iFX*` z;_&G%qKor)*lzO@^0u1g1s*)!|nwbl*N=61MrDhl^%Kop0F-!EHo) zll&y53f7nBi#m7aYn2EgNHtvFMm?mzt@xpM!VFr-6U7LWZ<-l>X8|{~(y`;rSU>Wl zDX@YsIli#^s!}F6dea^%jikp*g^|bYPvjarSm4RVoyadbP~k4>s|8L%!5P5CgT>o5#?Dg4fKHuZD%{DbTzH z3n|b8&ykzu91|D8OZjBflde3dj&MftmP_y+afI37%ET4$5Ugt1b!6yr zM`knmtq~h}Hu8_w+0l2N1N~3tdL`h&`gG5;RP*onoRmoJCetBg>nBjaC7k>b-KURt zv?81eQl#6OYRa8Tm2%vkgP814=n7D4Q2 zKqMw55pkYvwBvv!$&M+ub3xR-EV@e8>>CJWsT$?%U^&f#73Yan;9$-_24ZNLR6~DJ z)Ox^MbOt=j2ekO^QwCnkMX*L={A<%AHsb)dm7J5zAyu#AMr8UAyNw(_JeuHN7c}zl zFG!L9n262rhW#r!N6tqBb}#$q;T%%J4*naDi~_LYYg+E1c*y@(@>TNdL6}4PMoCqb zq=5l(K(7&P(trPs_Ikwykk)%I{R$E%%_%b4B4f~BQc+V2Y-!=4q@)Z|RYHO?o#+1d zV-(YhsKs9E+uE??MhSM{q1Dq0W=mNXd~1;jn3&{2DT!K-ZUMZx+?gOgSNgyXejfxxe5Wu6^&;5o3Ng`E@1 zCJP0w{~7Avy&(R2jO$HP2xla$;2k^`&3U0UCWY=h-5_`scil4a*6CGE$>o8S8(HHzgc`Hkw09TkxzCGVgi zra1nMRw!%=P0rq~gSPu|_-DN=Te0R_1P=AKt%kObleh^1A;mNlLPmLVg^gZ;p%Jou z*;7irB`Ksoa&z0wJyMxP=sgn6<~S;yWt_@KaCAbT_ddUot}ixu9{dsQrAei!2Av*v zDk@C}ZpRPeBnrSOm9MPYzUYTN9zU>FtK4n&+TK~}WdO8wxviK2I`nYfRPwc79zYT8h>fzMAvbGdy4L#$NQ12J+ zVo+qb7qj|}&3oaOt<|g%hg2)c4h|uh#@ayF)DEC9&il@iAeqQ_gu#GR(Rj$eQjbZ$ z^d39+6~1B91Ty}+VPRvpps(Y1Syq>#No>AJezQQD)rYmPpxV3t&YY#)O7w?cVR@nM zlL!3cmt26Z;Bwf5jzH+5OL=foEb2_+IuE87J{ZhB7N;K@dTN@<&K4SeYEAwPd$sI;otT`J*Pf>LFUb`HKv^c$ky$h()K6PGBaox z=|Sn1NMdae4Fvi;9|@R7qW!z807Pv>+=UYPwT)2xfzSI(9iM#J2H^2kOM9=^f&yM-tfl~F5A$OCptqRh22qBX^lQ<*x`FtWEEXQ+zeM^S4 z^Ec_xMhe-&yJ$dZ^4A3p=y?n=fi!>8fK5`JZ}&S>)m1$-B)Y)&x1PXE+wA~jSXYe( zqx`j=AV`2Y+>aVqs)VHBz)}jMxr*epDq?`Pc1lCESp)SmM5oT=aFW5`aoa|ky&WIj!M9+Z<4B1>t|6RSVuGXZo zwh#c@zujKXW-k#v(FQ0iy&tle+xdPmh`6T9Vls>LXs zf247&o=EC66Ku>lOs@l^Z{fC`B+2|}8}JpEUlpY9U3wd&K*ftIyV8M6NM)QbahN56 zx?{q{XySTq{J)!cIPj@ee?)~|wdC@~Pyd$p6IzZ8vL#tHncYEdA_bj^i8;~ zxLV?lP9>WeWo(*>uJj?C`ziZunkWWrawg14yV_wk9ArXm>?E9=>Ds){hB={1-1z4;jRX zbB}D#L=Nr2FENgdOveKGZdL+g<;5XQrCEPKQwyeA?j+HA8d)Jr%wy#tVt+`v(PMvA zcqj6*QKvRwsww^Qp5?1(-uy%0Q~A~`9bZA;K{9Jn`EYpD*$st-n_z?fcb%ppREsZv zM=nAFj~g8LSu{WpJu%KNPC+1UX-8O@M`3f0pNF#IAsBt1bv;O8*5;d-Mzh4-v)J12 z*A5(O{gbOj1Mv=@;SLN$fF!I&f4$c=qk1;xwf7hchN6yEEL zRg%87zf&=Jo)4-iyHVP#u}|NH*)Jq-q&#`q|F;F@NnNL2~5F{Io5R zHWQ_!G%VrSu&1m!&Z6)-LG`xn%(vs%Dq2bdGzIH~@C^Q41JB4HHlyikYzDa@bM>8} zX!#THan4RtPa1>FL36CE6cGM`_?z~Z-hZ8%{T;VVHnF7&hi2rE(WCj)#i$Pfi$w6z zgS}u+j{p9^#`!ttA`MgOL-1y9nh~?py0-n#`y}uGZ5M3vuT^j8q|CpcfcAe>&{klH z3@G*rA%KkmH(~SV5BcuMV835xef3bYWVAF7lOKX4baZsFSy{-%b9l1Hd!U%<&utfR&Y1T2T=Q+WAH6AbuF+4UHvX^*_saRkU)9gJ<44 zy-M4ktGGchg72kEtiU{NE_ahar+UI~Vu$Z`y#@-a+@Rly-nHaV<=aZuqIH{sjhfAv zPOv927Eu&!BeC_`3Hxvp5ptst6OC^B-$4ej{%x5l9s={iB8wxcG!}x5wEdG+CbTY7 zkB}4fV@_);9#b-X;%r2b7z)RBW$~u?bDpmK@o!cz#WFzu;AypHr!)EL;Llnvl?565 zh<_QQuCj_|Ow@(1-{>mc@6uaxc5XnGaI&m!6t*TE`h+Bd*Q*4Bb~BFjsH8;)hDa+x zkp=0r=LdSOGpU75b$81Z4QRcYuN$4{)gAT3Z_CbR)KdBNU3g7F-+6Rhjh^l`_HoSf zJHG>d+F6Sz`XH}9RQ5$McZUfm)EJy*sxP%R+U;P;HutoXb@bfwC zS0#dVs~sF1G)&VH93112^WIEgjrhP8U2n9XAIdMbliweZb$;OgZbKF{R^3MtBM|86`vLA}H_&ZS zgPfW#R9)#E!>+<0=8)I}!F+=Wx=dp?Td6`)bq4qGo_Qd_?jmSOH`w>}vf16s5T~x5 zeR~=Y^Y7sWzU*HMks7tec$706i^o*Y*XYNqM&62-tv7&cX z05JU>Vm~@NTH>ZC-)xjz9{+q`HR?}|+ZrDaTaighIlk`0BkM(9gu~1)oZMwyAomhc z4Wy|6M}I5ObTQzG$F3L2jGqWsz=o`<#T^a(lt6iN7dT-XlA9XJloG{n%QTR%^PYri4H)-L=2i>3DQPj;kg6t&h2L^t}g{G*C{;ZP!G#)@C*uf(P zgbzT(0mP~y&2C2mLVk_hiV;L#?(Ia@uDn@?UzN?qo5N<0-XfG#gFQ%(s4RJ`4(mMg zc0O=pOGN#{+D@@%B@ZwKYXwL-)ne=uC@`h_r4!Pk4Iq?ip%2L$@FCQ_ycm+o0hZSW z+Nx^rsYl-~fb5@CY?={$*gyIvxn@NW2}gdU8Pf1)4vB3uoQQ`N z>^AT1XIxKP^6k4G9O$&B?r7f*cT~5x2RGJ2CthODZ;aPPSutpePzKA}j{T&9ToA~h zm~&fhu-E24Z>Zb9655&{N>_F1yF$aFMs8gZu{3V9Ty@8X6;>`Y6p}z5CBVJyh!uL|ZRC*gw~1DZLM{F02{ zB)W6(6e-Ou@=2LtTsNX08|3$~%zDkaQPbmrF9F{v2WiO5NpY%jaAZu2O(n1FG50OW zwh_sFUpVB48~3)mUP~@6DL&Do9LqRJOHYW~icsqTN3j1Hby)TuBXw2(}$*dLUg0KiCi3)qUPIE`=%t&92XTu4+vYObD?uO|GY4`?g`o}edXnnwFOTW1`Y5AmyC^*BUT$_&za^Zb z6}Y5>tCq?;U40I(>X5(75g_6JjCcNztjzN$cvndRp6>ZyJQM#rTs*oR;W=dM!iC!^ zew$GWyhsKoOh(42e@A-wsBDiuYHAp>b8||bmta$X|0Lmr-kb9B@;I;?xY1>3@8!Q$ zg@4s)NolFb_wNko=;(iyU;3X)?OvyoW-lJVh)PiSV%@+$1q1-vik12b?pX5pzlB=h z1;#(A|NnBL*x#wbN zeJRGwODh;_b&dIQ;?^D3^4HfNs%AQ{?YzQv5jg~zDhU|FtbheQzN`|REO%Wv8TMP- zb^14+E?sFA`;fU*{So{F!(jL%__Mp4@Lsvb|0_#^@Ojjd_c|Z*+n(Y3zJpwGfAvYU z+m@e5E>3oyrC!dWO|I1 zTG1{}w?`~^LGT%?@^&BISKwi}PhwsV(cJn$RK8UC3mgv76FtMH zm*kq?uUJ}bCM&tvE#iTx4H=zJ&jb}3roLXcXm85G#o{N?*)4mv^ep%L>`GGWPf91l z&0Efh;Rq4W0xW~bN&;bE0;gj=<|Q$L0ypGWgb7)!@T^no#5mtT;!L85>OnEGj62hgVc?bgtMcb`t7wY zvulwsA=Zz!_-wk4Mllm={_T&_B_V3Vy@>bVv~@VrV(qWfR#S~BCl^8;L&uWHqthO~ zNe5dU5Aq+BA$N&rQe7aVd%~r~+QKF*!9jB&N})T3`2?H*Z@XwH1}_~3OA#;3JF%(5 z)Os=ndn#jH5-U9lNc|iarx7LM)*-HHIoQKBOf(^~6i}OTz)~JcEsY-7w9*J>bN+Ep z=<4{p?9frg)TyV``de0;d+nkU<_;zEvL3F}N>t0~V7mQWBlmV&gax?oz@JfZg?@D; zzJO00XbRUgdGY3#u+l><@TEFa&g9XCA`38Ij}UC zk0s_ytXf`wp0ZNwN=>6h$l0~PII*jtUbcA=iBTg-VVdL-l{wm$fkYNGEBL|)GB-as zPPXHd7%D^0Ex|YQEe7`H@MUrEWGH^6V7O!Blh1yX3<2wTHu7Ovy# zil-SL8ahxEO&khYz8z_~dLD~Kue?9Lgpe1DoDa;jqOf1#Y~JB=nd~?NTC=iBg-B&i z6)+iR&h2MdF*4l6WZmesWO+S)#;(FCSBskptWrc#tvlQ+vc~Q+U#e(}5X#BVF(b2W zapy9bzdDp92|2av#E3w2$|--a{zPFv(Ac~at!q1!bcj`Mx`o4cpO~k{#1?*^HDO3ZS>`$=Km?4w)RVZ64)6;pyC2MT|o;z2u29LN{wHl<#MB+YF8f zpRK%B?mF8XD%Q-T0kmUqL7liLXENubVVIYgj+-u2b2k1E9z8OhM+_B2fHLI>k|84s znXQdr;j4vb?s_KI_`d2t*!JQ3l@)C!8={kiyoiVn=1Ub=L`gH?YCw&}Yn4MjRXM<2 z{pl8eh8C9_4K$Y-sxUs(fLHIenSk$95+LlnyPpy!>8e=8*Y(@p97)Vd=2KCrsl$Ck z*l=_`1syfSp8D$kCw8ysMoj(}6&bK{BeJ$bSzei?ao?kZ^e9R6ljdf$myj!!1x}1` z1s}18_-t#>ytB*8VNaI}W0v=U)#pF=It7z0*bfE*X!(OtBFC4`%K)fgDm4}^dTeCN zZ&Ob`2Vaon!c?)WNXfjREhaOf@TjP8v(lq@N?ENToF55{#^?qs(2gEl8n39J4;nQ!1seL%Qg7GfobqIkgan*EnsN;DdFb^&LvD581$1jsS+{7-& zM}uJ*%S&RW8%rb{AR!*R=@o+cF;>!3>D=)w-R%N4dJpor74Zgi2bO*Hc0I_n-12C~ z__3ZCPh;xd&Q#%Z5>l19O3D_r;9c=nko!wkiNyJI3$QwlnfRx9@bM~tI(&tn?3`)Z zdSklt#;Deat+h8JA>1DI19n*f@!1M1qS9TA{_p;M~t1~?vKhc#) zBK9|9ZoHRJ@rUDcJ)XE%aX@sUZan$rszY zkH?iG@7A@~y)9~L)l}+tJBoyF9`CW?j+Q#q@@*jY#5hl5iM>1KBO6`<;M1bccOmZP zukVbnu2iWC)$r&2&@26r{y>HLB?fg68X1XQ&|JNwgu#E71|J@+Ygm>K$nME}i~kuL zY84K&B80ssg(R$HMhT4SCSG!mvH<3z>4(G&UD?4c&rf?qIaxLb23$1e)Q<8gUqAl1^4x)qy+u74rWx5OOfd=+P$CoZLbCS44rA8ha@%5(zi88}fbi%TI~mK-%~kBxMPO@Hs{9fXFuus* z?bBIQ9U&?6HiBBLhjMje;!-&3NIC@cV(lk*kiH(GB>76o;|f4SK=|Vd`k=Ro!+;se zAAMx+^r0J*IEC%Z7^iW8e(Dh#(OuGhb){ zB#rYqE9@&@yU0+}LjF5vs2u??+Pk_ph4^g6gO`Go2RF$QnOx};?pi&Ta$5A9<=hU&MwqsmD6Z2NGd7~pg@ITP zNzz<(QpbcCQuXs-Vi1jqb2XR!4g5gK)lwcseH{NCURWHwiv4}4k?WwnxYUrz{t@ff z)3fmHmfn^oI|fMdcH>=_CDQdZqBk@_a%ZQ-IpA(pj?zu!8N$kex*>oM$4wtT{w{x-&o39Avl7!4gMeo5UVDcQ(U$U%m zsoY|8v}`>?Mfy=dyK|*Dia8??oyFm|Q49a4AW-0T_(x;;?VjPBFW>BMdvv~kP7JA{ zupQ9nu8o#WCvEsf1gW6ScYRZ~je#9i!omWog$_Y}35@bWHodqqX*kD@+Ad+bq?7A& zaN$^m`*w9P2zc}wGWhb`DEd8ex8qNcJvR-j5 zmN-{=^sWMm7IchpTKgJ_AqhAI{_cF=8MY#Ewj&953Z|lEo&;LEGkC%|i#53MzHKz1 zoq{bh6tUP{3qqtI3I$O{@Mw0<=g^j%5ki`4KbDTPDr06!Tp#NtW~qrCoItuUTa>5U zd<~x~U>C?3|G1PZOC#oIXDR;lHBLhdR>2%A&vaK|syG3Ca)x+13A5(zZnll1A4Hil z$8Ia^fz~+=FA^%p8%>if-r7Mppd*l{C$K%~N+<6&Bt@+$oUHEm!T?ykKM$Z)VnjZZ z3nFh2=)(|Ij!T2nm-Z5G*USrTgbN<94UIzdi%1Y@d!JN9yG*h)dgx{3(NhfzPb9=7 z*r%OZ33MT7+H*HS>v)BVOHYqtbAg#8<_oW{==6(g#F!CO{=`vI#vnGkLf)VhDw0mB z>F)7dZz&x?rw)_Xj_g;Rjzo20($e}!8gQnT!XN!{rB{cNNE__($BxSV2s@s^25+PF zDj_yHN&OzOP`*T7uNRgR>Ju7;B!O2SjELa4eSj03)AiaLju<}X6q{Ww?EL*>fM)|x z*A~6W<^^TV%}k^?w%*ZnHC+`AK3I?_3Fvr4r?uh11;AQobBGr?HwlVf2yyfvYk<8k zw>Q5djvb14dkp4*m7Y3 zQ2qM0f0!{CmoQKfrQY+Eb}%b2_2W5ebPm@Bs)aP@?XzKjGeF!zupUv?X&Y|^f+!<% zs`(gF#3dA8a(lT(a<*i0@aKZiUb|s)AL=p$yn|xATNKiy{cPcGw)#66l_o^13ZPO4 z3aeq5&jUBDhv{gA5#ebFL#32U76od+mkb3W&D6D0SXszyTzXzL$4(_m6`|@cim(zI}(=1quVdKjEd<%Lc|g#&C}b8!EQgjPg0Vqu(FB0M>F7> zvMy%3fbRp8lzh*TAnT>8u?^Ta1Po4%Axm%_ydP^C$QDl>m%v}#+dT=o-QUn^v_dg2 z5Hkbv>1J0tzLj#S_Bbh(Bq}P?V)8Ve3Nh$3!VGEzI*hgWe{?NwF-wejbu(^;3;`}| z4NJIMK|n&9?i4EazU@*Bv%s3fX5+AhJ1OU>idq=`3{OC4Ej_&)dQO-=N>W{6s^kfu z!$QM#nSgelEi(1>L8ia(Q`D!jN%wT0|1zxY5kH4ekr|tFE%qzC)hLDVU26 zl`+wgIJ;$PcMg9CXfP#~^rZQ|^_9M$)23wRsW?O5Sx@Oq@W#nR;?da$0va*zxqyeQCi#^1G;WGkjNFkL;{476i-H^e=xRVacZ7GeqDzAI;Xf%dQ`mtavmP{swX@D zZAecdOn49}N~8%ejd+glu}@u_zh0(zE*H#)*xbY{d7K>${cJXm&*^%xM*pf$vuu&6 zx3N9M$9XW3hFJd6c zrkEuoLpq_GV~_EZ(k>^f7pz8TU6=dOdk{y%$o0NxiO`*Z8Ys|F=(pJ z%2v;&tTQ;OEyBg-D4WB1q?|Z4o3gXQ%7;0U3d8c#!uZ{PgJ&Xgp)XIBR{yh6#dv?% z{ueVdi(DQ7oNpHPZMY4?BcFt^=%w-~8-ILl(O;U>FW3S}#Ypc?s|U9F5ooO`yE9?% zj+Z3qAvxJh^Lq7WFFe$hp=a=>M>kab;Hhuw z)%qEcn24D%F)5PjakC$+t*jG0+VO>uCpD~WlzbltN36&>IMU`~d4#<}U|7l_6}xpM zmB)z=Dv6D19jl`LXMB(vUMf%K&)~>)Rd>%ny>kk|*8%coIH#l`*uN@DBahdi>LS&Y zgPr}Vt+B5WWF6>uVJv6oRB|=RriDHzo_zkjQIC@(qCdm08ttvyoFi;`joYS^Q@2sA zWLS{FH*zvwfvvtc!Y*Z4CgNc(SU#tepHl&;mA>hU_BbRAhLPrOkO*YEj^k#sUCN9Gh zJ9Yexl(}D49}J6cqmWFB$hY$N%{OLTGMn?L2U}iFADf*$^qmmql=%zU@w6?WV7_p1 z)o&goJlbJqaa9w9SvK|@^%jchDY(Hrj^C?pumgoy(gI$DhoiUlj@L$GFWcW~hjzUA zV=M3bb9VIOYAxAS>&8}`796Sco~7juTij{2Jp}9@r`6}~>3?l1YnYq9A3IynkL8rm ziKY(v)z!=J_)rtD(J=Fjq!MKeJbypbYE3B5VXG6=*B}dbtcy$154u*>a68BrLASn; zTi`P*w1i?BXS#F@5z+5|4u&cEf4F+*AW56x-*&(0;WV$JK7;t5rE%4Bn!v$DVw2ILjHh z3*)zff^Q=v+>s05Pj(mT+1ATEMPnEoexM$o=U$M!K<&sY6fVM@NpYk2fZOVJ zH6nEiDr5jZUX7UZ2!8uz$ItZd*EGuNS!Phlp>b@QJP7PN!J5{JYK1?^b8m_7oHPTh zU_x5N=BMT@S{qC*+|Ar{zFKcA*(&Jx^6KEIQK5m?%9}QoVHT9|i^~TNrY180J^~0= zA4)+154Y1*7K+8^BeNmO7MO<%$%y!*XRJ?)(A0kv8)&o)-9NbWzngkb3E&i28rcKa z5Z3tl{*_)Tql0_dYKF}koiynP*}z;zhx$^^u@}JbjynS)Iw6EqVQwBHg*l}L!dG7F zFR_YSLvy0$@NznygXL9;pYSKb6g?h!4STKVMiUDKM(rAd0O87pN3|5w(b zM2({IoMH0-bC{e$wU+ybzt}S|5^|MNPZ4jHZ5|8K6;~ANGG?5hu4?t^bf~_$GW)Cz zzWs9AO3`zVgm%3+q$x6mMa}FVqw~L8CEbZuT0F$n%~A%WyZwTWEuKP{H_@M7Pxyw1 z3#`#SB}zkUUlknN&}M3Sz3-(7Rr2A@H$)RG^IZHWtTcO)zPv zku$@W<7Um*=0fNa=6mKuYtu&}IX-zSeA1U>oqL2NF22&nk*Z{zU)|5(@OjO5on|!p z){yXJRX2@x2hJ>iH~Tns3ce@qW#}~fSenU>n65shi!ue`b;^bkhrPhK3GUBsiMjxRM>|sur#QceD%1!*HS$88vwKv7UC=v64eMYVcUw z?eOjl?B=*@*yDMVYOQXh2UP*&AwZ-42^S+D4Mv)fr;tX5A39Fkh1j3a7S^M#<^`22 zi}q6Fl2?j)!*hq^6YW$=S2o84JXx3IQm_awH{#puK9%S6>s~2B#>4%m>(`FNrINQ~ z)1(Vys<;aNgP|bN>iK4rm9Ect(nu+bQ#2sJ7HX&E*y#(s+~RAk>8Cm z^tcRDNrd7qMIK)0Bm0AQ>bX3TEMRSP+N~qBV$>2{atDXIUAj|WrLO7Y zb0JUZb|RVG?F5w8=0b40Hcf(rhyZM?Gw-ycoPp4(^#XDRkU1PAfEMATyIE+DuwrO& z5l+K%a3qhF-)V~SGuiv&v+T8$#Px@) z8_LbXbg;-}3u2sIKA`Y?rSI_#0AufoSiNB1Ms=Od!hLuBrIMVtX`WU_$CKv zzjM(5U?4o=Dykp>|BVFfe}4p4ArnPI{hx3D>&IH@V8;L2_`m+yPMrX>?UMS;XaM>` zX}B^A29Y_7A0}FGYI4?a0vPAlp1SxgS~1ntw4&nT{RUqPwPX)mz$25e_sc4UxrNXu zumT+8UZ&M-otu8w;}#Fy)dv`e(7sS!VUO9ctcpcdv3%>lWf}0m)X+KeK~?t1Y_mj(j1)tn*ch-2Tw1td(XYIXSr_GLV4J|CTmS=@!I)OZ)8#hiW)qP(d4L zy74=XeGf2D4Q?CB=xV=6a6FFiSY~T~@tinwJDq_`>T|kX;qvnF?OtBm$kkv8W1_5- zLIpE1>#$~CqV>Q!gYfey(Pe!1mq9((<*p&{=yUdLwOzu5!?k`9z=Sk5I|C}d`@P! zmb%7)%nC=h8CrZ_bUcU-93(66FVg?tn_dWe0~q&9DF0vc0VE(lgviY?aJ-L#J8W3o zJsQf|m;&GU0K)QG<#?RR+!ME;i<3D)?FXsA4`(p}m99O+3*}Y+Tr!_+KBHK?P}{fq&8cn5u;;OuDuo z^?X7IghL>RF-G@7rlI3en2qc0vo1#t3~~hHLmysC#I}-Pws{ceX5iiOs-<1VwC~Lfu+I#<6l8VD=>kXA`K4amRIl87cfG<>eKEl8D^bC9KLWb zJ)4{PbFy6;8Z6O-!w|wYRx=g^?v)?|Hc@mnu^N}Eh1N4zkou(q=d5QEa(s&e!$V_Qo9>K@wXM!hV zSzmC&Flr@m@tMm7GcL6& z%D)PF{G+0xxDL-kYQgz9xVX5EP)CSKNx|^(@nacc8{P#2=eI@(BtDvE`a5-b#@@$~ z3YPfnuJuTLUdcRX^87R%t;5ACjL|tNGBQ3bjRLREy=dh@ zVZi0?Koj#06+${XIGeR*rZP@?C7g_`sO}~+$r4m+d_^PR+apMn4ZK9>3e;k!BcQ5r!VA=I3w3~NlnLfBaVaf#QK-50GUUQjbw0+ zIYdg%uc+@I3J)#IS*d$0lK|#XLzm;uN%8RG(^F;-pO9jduH;D86D>%(V(M9D5w|`By z;zYob_+yG8Z1FVfw%6EF_7|YfE^OLJI1RIUr5ltaOirRWj7t6&mCR;TUh626u_uQl zsNH?sUe5LM&hY#1qL|KP@G>{wkj0Wu`)xqgeFI8)H6$b?2}MblIKFYJ&?D5u-#6aY zbhhSSca06D9X<&oactfK-UOevmT^+@Psyp8o?%F>u|$nY0{CC9$sSiqdIaA*(s#0f zxixX%H$>T~8eVWdp2xlOcHi1-c{4H&OD8MgXRQ`kQB!Yk$m)@c;v;ekChtqjOO9C2 zp^Z$@<&8cfP8QBe=Fb0pmdH_Dd_B*p_jHvzCnFhUX4T5oLp zF1;SevHeTTxzqmN9r^Im`t+N#q@@4e0FD%9{us~bWtW1G5p+p{hEV)p;d@dYjnaFU zDijrSEGTra?X(t3WxNkeNlua%CLJl%qWgSr)*-l<_~{f8BQ%Wk>0`rV;p1PzIb@{O z3VOM5q8MxV5w=Snan&3VoI2?ZETRue**xiqZyzkM($7|Qm~%)7w>V#$XHwwqEpyJ1 zEZ$oVO=Ah1j)K3(XBfQwJV-zKC8H_q)L19Pb1t>i_A0( z>?seJ58nQYKIjtU#(y~ZnEcRa%4H%f$2OGgWFq7oQHsNAH>(%(eIAC;F4I$a=j5cyzLgNv@YZLp zMw>&2=aNhI8KLiVz|VO1%&)(hCa#nu&u{Ky@FUGgT&3Vow;%#?g!_#?8 zX*KtI6Eg9obHp~EuDJ5FMl>l#6MHS3+LmDB%=Lz2M9EpLY7CTWTNkTMw|$TV>B{~- z?@znAURMc5VhiZVkfZkz!EiDKyK5sIQoU&?wikHFI>g+%i0-2(Fv3lB|2{Wj2W` z#$!9{+>*U!ap_&fFTVfc^iK#ACB^ZbSvBzm^hfS8HAF^a_YzIcgvxXe(uX~MR!lemGO^j_Sz?W!%6j+HhPHQmYy%|MdoX)( z>;`89dgGF|dt>=LjQ$4avzymnZ5{$L?$CX`8R54-A6Oy>C$s|ckIY$ar!28bV`BP_ zY6OUrwuZ(J>>ZsX`fgP@v)!e~UH6v7I8){DU&&T_-ANo*ozyZr#2SnA-7jq}%%D0h zj9)y;#)c^cl7cs@;)IGA1_|ZIc|3ol?SfT{kl?RCX%?RKCU*5^UH_vMMPZF7?ll|)^GfFLAihZvO~>`8gW z^cWx=g})w5>n#yJJq$&$a^2Ul=WtfL9KM+O7PMVspZs=%8-IXS`=&9ZltT1qh<}C9JZ`@Z#```C;gLCk!Yj!Rhvc zX30BbJ85B5pb=HS9ko~YvO z*E~a56lyH4dh{R~vV(PmSK56val`0a7uA%~3h@cHCJbk@F0yfTcXM?eL*MgM+)(EI zdK;#=|fsM_cR7X>uT5MVf0i zSfJ$`xASoWf#PodskrgMH+lBq&iy#;FUU<>wp+KGrA_wh?lM;W37reKB zIC_I1F*jVIV9On%lq`}&CJ~v3Fzy5|c>4-%@)}BL_6|bHPX2RzEyTjo8hFyJ_W~K< zDH5sYdGIv!2Utep;tg-c4f%Zq$mjm~nc>$JU=i0HM_l(54h1XN`DC+ufDy{x-OSl; z!@}Got*BM~+f)|j*tVO=cO0crC9I^5CwZijdD3wUq-tfAuM03(z7exjX7I$pN z&u$jS*~cd;^ULu{(>(KshsVKPJg)>#a+Fu_l<*4{M9nZwGdr)Jd++f6M%P3a?;Ln- zu~*Td_L8ML{RDm=4WyxbZzn~VEWe{4Qrc2z)ccp0m$R#$W*J$r^?q}40q^djAb<#C zXMWz&RI&rM-#%NU9}CHHK?5Zp-WvEGI+~HJ-rByqEwIjJp{?@vLeXG!R!HH&Y!mx! zXi+gR7CONsis6IY$j9yrWz+ z8b184ce`hL2DbiLs^#@WT&L0ZS36X=Kj)}&sw+VgP|-(#K&V-$g$u3*uH`T03r?R= zp;;B7QBz9ClrsbBL;~`EW7hA_=t{m?QEd77{fs4L7?{C9XmnO1ICr@@pM^mh$@ui% zp$vqC9mwxeUg`0{d5gP-V8|d?i@qEFDjS-!Wd@clhy;OyNLZ}M<)(_Bg&=B*e-3)isVH=8F^kt;R z^xW`FZbVxu90Ohl#4l5=7qh$|>wBgOc~klScKq*AlZ!so!gS!Sa2IQM8wHb4<|v*O zz_A;2eO&PV)SIAE2>S34LWLFiRNH^PZAQdSj{cK>t2%wmz~s9>TW9x*JZPg_gv(j! ztz@*ok%`!JwUg86Bz*Zw#y|ToX+rhp2|-9!7V-h_9qj7lUv5{lVuhN_L<$5PwT6gs zw^&9$=-d@P;DH&gX_Dsw##gHet!Ax7%$!G_GN)M~_-Q1#(&vRnB24X4B42q9*}Doi z*mkbv`KS`!GwW$ig1~S*nF;_4I~a*ZGh3-jb3fl^kI^}a%%2^PAVGS~bT`--3M1VTV)wmL3VW)KEpE}^gMS?rYI$c|W*D(# zPZSf(bM+`@;r&jU?r_~Y0atXOBh^f-IF4TrGU43-Z&v|QU>Ic zV~+oePxgW3v%`u$IWgC9y0@X!YCu2rY>a7{eIMLiTCvga$j6-n#@k{vV9CI{{*9Nr zG?-iuYe& zzD606B>q+cT~podNuf9fCq(r;ZJp6@wTBvEJFXnRP&K_?3`XuJ;K}|=?`FWg-aBk14ma^qhRYHg zHl`+4^=!Ez<4L}uUzv?=bQr&GC`g<2$IWJ&M$0j3N9;og%f0%nsEf$c-Ch63>wSaIyX%;H1&xg-m{c!stBOp>ApRZxzAzL< zB<;TKA{ut7pfq)3W@UDhKT?5Kou3M%us`e#tkH3$8pq~sk{^3>-!mh>$i>H z_FOmOrP29Nh9F`6(ZZ7{XEe|4&Vf|>*V{Rh!=z7 z&BY2-t|i_)n_M`wgXv5z?rfgW5f>YDqjCZDbczu$MASOW=Ui_@?b-gNUczDKjN@ib zpC>`RFhE-p;l)!2dmwVKf!$`!V6jqFquD&+;ZQgLZpB53lpxshv`)c?hamGVmXcr& zCbV{05FOLMJ>Foj;T#kB1X9HUIJ=yEbo^9Wo+NO34F=n+!omRpn0y(0Dvp?yy-$Bv zJbx?zV=zSW1@<()3sptS4^n>rXWDiUM+e?^Le4|~PW6Nm!(5Wm%fDwF8fC>U&B=I@`JGqk_E2uSPkMDYpw(Mzw) zX!mCS(ux)Fhhr1aJKB@Z@(LduIXJUO`HC7~nhs z*2;K0f@Jhiu^Q!F-;Y_ome8i4TZ{FDx8vskNrOi>9$|Y{eSqgcv(IafaKE1(V?0A^ z|BP_EUC~gUy@y}!iNd%}50+%0AeHs}i2xsG6>pfl6wi4Cl$6V@!a?Q&_#Q{D6a1G_DW#W(_;0qg1KPnGK=5o^34d4I_ypgCE+T19j6lmTn;>$oS*8mQ zoSy5Y23MrCn#0Y+L=p4A<6wkNGrUK&E);$6ZT@rWdYj9opQmfpYhBdt0J&6rQ#6ve z-@jSuOnQ#!#DNg*2`f>*`#Pn&o$sZQzT@+=5Xt8rc85Ofb55{Fv0-bEKLIhtFaqn?D@^|2e- zun5{EGiK}5$C&hTf)H*-J7M}X?Rq;99D7m?bryYIYBT(u$3D;h7MBxL(Qrjsr?NAA z>$aCExlV*2i3f*}b zZ-ppVXqGSFC}uFinstVXV9nuV@`UalRDeoyJ3x?O(;Xyy#&a}K#OBF{us2gUx5Wva zX|{f>P@$gF;|cxS7zHN&1*637C{-@lXFf5b=0FIRE*cyTF5Ng)=zGLZs3*F*c%>%uA8DE95n0tTR&kuGrKF_7V`9+qK5QV$bx8lWi_P(8(VT%NmJl2h z0}pM$74lS8szbF6=gY7y*ww%cq_E-o!xr+4KuvD4X5{NFyl7|C*?-63RbJ&V&R z(SArMsZ@Q$gZOk&BPhc^y4o67QNj4wt&)1Ys5lc#Oq$nm1du|7dM+Sgru>1|6UfNU zl+)>Cq-vV*6va*?@=ZWbdWJH6h^XkDT%%r^@%h_YN9U0uzkb{@rHf@m}6w@fYE z5FrWeHC^wM=&!i3H*d-2#vcBUOnYlxKi>{cokyRamBtJW6BSpck2hlSa3vYv#h#g|Ic*^&rs(YSS!Hh@ zUB6)2Vm}`Fwzv*Lm(6}j1cy;=K6uX`QI_{6t60V2av630a$r2ss&H~@aC@?b)$2fg z(;8l^Hab_9N^O9VE*d_pCJ=d!2cDuc)mo#$q&u8gOD7^e8|l$1C!bSNsWdWkODr@q zSq@G7tmw7$oXR)1+y~$=U+!n(b;TD*>Hed!i5&TDZEajFzyCYY;qagiU!dj4g$)jh z5=FD2u;UmA6$zQVxn-e9v&V7=UP3Fp)6rN`06)M z#vY{~v&iD&j=5UD8FxJRoQbl>b#LS_-&nx&p&W4-(ArZ>ml;AULm!@&W`xYJ+ISBm zh1khxr)Ar*)FM=?U@%ZDh1qTr0nDiQCCdVB{IIIysVr&y7w;$Y7O+g%Y^^TOfBgdb z#^*6iMXUXXOBx%If%WczE_Ouv6FRWFhsMKGQp6RW#JQOZSY-Kf7HV_NcsfZG@CjR6 z!)OqfBp+%-706Wypnhm#KJgn!{Fx~QMVWZZgz7Z?1<|5ll@%vdQG2_F=heW#fEC@w z3SM+7bqGzw-swy6^ktNw0mu|LQE1F_@}kGk%RoNEXe+ zlQhtW&Z?#x&O8O0f^fGsF*Ow;Uexe@w^yzZB&~l{&?rY-Jb(imct5~b$118ySZ_9} zm*1gZp%VGl8zT5buo@^NB&5_eab#^b3e?HTFZ70@hg=jgAyAB7s=||KofzvW@hltS zJ+G$cyZN}ckBSt&2tp9K39h7=2sw84 zwUmR{NJI0UWb23>PGwq5(+(@#Fd0N5>;k-zL9*SPzK&REe`jxx_}A0ymcnacY>%J< zULk`$Rjg&&a_Nlab-bDCYX%GF>l6nizpqYY-!OEAM@7)zHIF|^P}{Y-b5~cLy9d_{ zP`-;q!A$>)NQJ@bNhn-|DEtpd6T07}dRiIxz z192U?#u7o|diz6~;H)r`sqQRhxFeZ8qv$$=IY7&ktD`*529zmT2}q<87{$T0w}nA7 z=Yy!qW+p6Kj!=OOmt#E~5*C&$#ew{ks8Es$xUWOy5G5>!Q>lfm)`?KS2aynN{tOHi zq?TA1u`M7dDF6yr&-}kUQPI=Fu)w4CP%tpBs*@*MM@K9>dDw;vTfs zbaZU?84x+SRa(10J`^t8zv@f^zdV7=Z*FbB+64k_DMOCSl#6$_K`m31FzP&jiLtVF5lAd4tKP{k@lqhi( zGH_E%N;=Lmiye#VFS4qr=J)~e8@W06g&?L=Iz#|p@)80PU$Zc#l~(Z2IaY;LbXNL} z@&bJzH`iiTX~hAu)fvf&q8^)HBGAUb32iCtGeKLkofym{!T0sHHF6Xhn+Ic@Vrr^H z&|+||c3`sw+pR`3bmB;Q@{&?p3&7^b<>&JP;l|teuT`Z?Ma&||rN7V};zbVO{sGb@ z$a2(+VrW#Kbioa!C6$%XZcZThl442itgDAj}}S~ z*EM+*GVA(^V8YUsu?cJ!X6q1#Yw=G-!FlMBqgoZAt(VFUL zZK~F0B_mIUfGZPRi=wi8aR<_^SGZ$>*>mMvdS>V-hOM7TeUQa|u4zsJ94+@fL4; zSP0hz7ZMqT+|JH<9m!RW+kdPY<)18&RhN=Yj?V@- z_ATrOhvopo=$?~QWd;9OJRa#>QeetOvbxHSige@xMt*B2{j4XQ5N6T+C~+q*yV_l$ z6X_@q>**j=aD(TFVnZ_#jOI7%>0ug^$ttr2W(f(2vCGX{1j?N0m$!TUTQ^fMlc5;k z0@@PfM5r_}85>L@ePd%|8pbH_D4@27Bn3+%r`%W&g|BFl>7w>&{yO1NbDlwn7{w!D zQ5?03j&wAkUI8Vww{g3)4F`_^j{;+;GU!R<9YseMS1*k!1qWFH{ORYSSeIU-s#(OC z14U!ag&`(79!$t&JwHEF#F(R_lS_BCjWgSxYypS04vkl?`9oZL)bEu?P61tbs<_wd z;bN#<2H=vtAP^yojEYj!GtApx5EC)a!@N(tS#o;bYhAY;Sn${;(w2B0qa1>&xJp$u zx$5s95+IZ?mNQT({)+iC;U}c`1}x1oVU#_=8R&-Y8=gdV1ly8-Fo@puHOH=!d7R*d z=%nZVQzCNeK6>DLdVt68l4FJozlW%H-cGY;NDLKd8B0S|9}Y{%DCwyJw9HxwU@eoA zlQX{1SJ<8`wNI%h6tpx=b5Q`Y;XQ&=jOciSUNgM`psz<@=JlpySsGcyXQuCgDP}R) zcXy7Xi&}yem1-Y}7Su$_=hh5qV?RUYd5ypSJM(O-9PLfW6AX4gZ$)X>`T@R=!XuRx zKp()}ziXBiu-q87eBW&*uj0d3>pmdpA{*S#Ospr^kDCfBDbYHgE&`r}+c_(2W^tlt zG4h7jK6w-i*)l_277Ct{F>?BPapW5J8TT=wzIIJtKK%S-EHVdGUv6mNARc3x=qvo=V`Qm?J&=Y&C#FxQ&Y-kAQswdm>B}k;PZA?Uw%h=Ijmr7Z% zdb6-pym;el>+x;uQ#g3Vvd-KCPvB!D;dzjkVNWB=Wya;P55^(K_j4xa8!ucpr=6=j zQ!?~|r^z$S4BM@A@?6@>8+X`u5v>kfl=8n??R;`mCjh>6H3h8am-jZhR~^Vp%Tr4Z zTJ&}F2q_dD>>pqEV~w~9xoFq8sb8hLt-J_fc0u|WnY1%`srSyAv=jCD4l5s@e3(w> zy6x8mBMmo_{LNw+?#B@l4kLKW`%Oa<1?9tbP zZaAuZL@52d=pG^sW-dCnd2faaS%)a z@yK_vhARMd5pNz@GaNU0Pqe-lH@v*x@%^bcpEL$5x}}L(*?t5<+RiaSZ~r8HfaG>J zY!;~9$laknq21y7ii_MRcHo*qL`vm^dm1JPfXL1-oKuiT(fD-{4fmunbA1N*@%t6rY{3`c;MoHe}152UV3i8Hi3R96D<)91jzPeYimJW^H6fm}6 z%A#J)NfL5>AsE%qwnCmy_8di@4!WydC-U<^GVw$+iO4E&f5f6pwJ|)WUiq|(WJ+g~ z02qV350ii_yTT^zg`xf~N5npbdtXQgcMW0w;r8nf)|ftDIMV>dPQ=X8fRChCbHr&V z|J)oVqdDRMxRfN%PRxj2dXOu4S-pV=Gpb%KXX6p#1E^i!!V53&*O!rr>D9;{oi;E( zLXcj)ar~Rs_cab{klu#TaLL&HVA?7{T>BB)hwoK0(LMTjqf7vEu*3@n| zDGy_>RI>?@iU%&{%?N>3RnU$1%fzbd^MLhYf*?GLVo*rU9>fp*ZNHDpiLu`b6um|| zFv*ev9gh!SvnFKC{YCR7O)oJWF!Zvi0nTyXdIkz!0Sf~&fMeGckf!Geb-q+H&}{J! zn03J5BUr>O3A>}m$eNIEU$V1HsueFNO|Z?siF59? z2)?1uwtEka#}L$6I1}i5k3bZ{_qCdA`xVy(U4^LJ5&XkBM&Ct*y}PUIKy6c+Cp-Xb zQAyQb*Z1qj0_R6txx300-N34Jw?}~>VLP(e$Wwo}4C%0rpFk)LUxH)i1s_*cUCK>D z%6^fJL;;=baOMHui?vVC9PY-GAH!bj^c8UTbW!l4QG6K?E>^{I zF#o<@$#?4SOUW~Cd3SM-U3{+{NhA3;jzr7Ir~p054x}!37G4H5c@2f_{MhG@*;6esZk`L8M4Eo+=fo9TS$7@nK$# zn0PM{CGP_d>Njc8$otb8UZ-!6PXwkaQ8n}U=$^^ zSd@4%O{383D5|4u4#XxDS@>J=@|L!JGZ5B<&N2KryKEU!p z+4KE@av??SFISY*v$D6`DmnTbC)=_TkRY;zlfrk)1UA% zf={Z$0r{^J()c?Sbfw-x;OqGmIG{fe0tCN=hXed}xGCXDxLpTVvdW5bnv%wRK6sf$ zpY!|;$y9;i!j8ZGGaI1L|z8G?60mgT!Zy{!Va?yMXYpuGKxpb`e#id^zljG z%y8uG<>^wDQv;K+x>2+q8HRfySrjvKB6bH>y+uJ(I??xw?7l?*G%{$Qcp-g#eZ8EP zkEL1R?N;XRw&<0S}T%z@Qa0akY^K>1oMNU}j8yHR7<(HxtPPpwJaRcs-$s zF;@~a*-?$5k^6SVb>~Dg7;g=#ZWGdw*B$-JMoS1CElkaL)kk)-@9tW3b}INKD?XDvLRAIZXZYM6^f8W;t;D(ZCUQM$y3na|m+=Iw5TVKj#i#Ob}G);IN^-&QY|2%MPP$EbQE((64G5BT&m{EVn+@*eV2MN6qJ+ z@JG~%nZ8+}06_}FBxo=;A^pV2q}M;`%*T4N*_=NS1U`AQmp+1$w0?VGyUcny_doKv z?mY*YnqMwM-YW9cznIfPI9q}mKe_TgUtz(fGlxt`WP)3ec?LiBuU-obmsXz7l1M^4 zKXu=3;4tjfW`!Cazp2+>+?43`5fKq3a=K2jE$>`)UJr*6_)>Z#Kvgp};tafzKIAUN z!wmH#%?`DM%FzU^37|@>5AKaFyvNT`;4;_foh@TVL!5wuI5evA;PyPiXaA|iiN^k2 zhqa=#1X+lng4qQUkGhI3F|r+S0JT|+0sjOPkp}4;j{k!s&wtA_9+UBM)a~(d`iz1B zk_H2|xN|`el7B+l#p)GH`oR0$|7_p$h&2f5{&$Q6FDkWGG$M*YMGWV5WbJcwh7VNC zg34JOt5F`ee-A_8?>FBgm9X7;2t0i}Z)X?citLS6~rV*6mW3 z-A>t~#GL5|V)NW(-*%PSZq>D~xK=9!5ufddfA(klaR|pv-`=5u%9#z=1)HF%tl%7hY-VHHu6Q>osY{u#zB#c^} z9-M%H05D;%f}T8uEjdgSl)gA#QhZ>;+JlXYd!s0}77p%bGd{l=7DZI)@fUswN9$HJ zl)N*?aXasZQM%kjCN?jJ|s#1YvQsF z5a}XEORn9a!2j6@$O?TB`~LczGkYCF*Lk%g&I3z%JT|9E|-ZXa$9lgWS` z@}v+2<763F!1-A@pz*n^hAWT*9XGE-)oMHWR|9wJlPuON#2-R9cct}*-Q+icTFv^; zpk>BpxcX1wc)gder**rRlcKobG7XneQw7{L=tYYAf;V@5>g>0CBX>7U&zO)&?SNWv zt`p06qRCB|;Y#XJR;?41P{GY{a3-$TlTu^$yfmEXuU*E}i-5Ct7sl3Zh!h(VB>nUd z`ZMb0N6U7MceoIs7v42yk_La~>zZw2RsjFj!NDBmk`B6NXMD7q>2~b-X2nJ%AwJ&U z*SKtdXasT~=`)M*nr35x1>`4G(e0R5(_E7XF8<3646nDccKh4Yz`B5UzlAbVGi+bwyH;JKH87_YDn!OTTr<;_c+}^Q7jb z`r7n?5xSL1IN{rdqVt^U5iEGyQW==y9Ak1s{){Dd(bCe~G{B7^L$xS!Tw)!j2^W7?aX^ucnvHRw2LwmOEI>z08 zniLFREUX~2ChLvaw#@}UK*1O7HT-B3&j~rR3oA0ZGr(O=-VGKCWe!0)+gje8^j}f{cMG_>ir_3L|7)1@ zGlZGsz?#RSO+SoeHlMnj1=dY3&LjmwqB5FNVT=I?XeR+pf(FZ@yn%CeJAi0B4*dO* zIFaqzf__A#1wh6In(ljy!QpS-;m2z*v=|qY7m4SQ`YkAX^~%}O5z1(se;74dVuajl z2y(W*=4fbPas#2p8?#q8YK_C|e7L%Wg*$ur;V&nx_D;`2BPSZc!EM9kiX=>O)LHv; z9PHVbDiGVTn~bSbahFT*atlJnfe+Pawmi}1Z&*bHj@qI7f|>~k)p{ohFlM^^6Gc2Rq)ugzh(UE z!3m7aWGE}4ni;Nkow>|cic8!uw+S#zPqY&3g}2m});(?iGG}uo+U0gKAM}YWXLof} z8zcP{yCz|CwKH2CZXp2xmAqSptO8sa;Et7;TV(kc1$CjI@ z!@-L>Mf2nFW2-lIE z-%+3&?<`r|wLXNxMSDm`W1eoc0paHfKNz^0{`D8mR<`76awZVffByKbjUXX=4rso@ z{Ap&4)#}^!BO=GEP+dFe7-{v>0d%B++ZVROW$zr?GHTAif1?eqpTGmGp$T7Xq1Y<@ zbN?roj2R!c`!i<5QrriD)+RH2ZEiK>za9kPy#a%T#`h(|A6nZSFqd|{__=-6al~#C zJL&7QPpyjfYS_C=9gu}r9a7g#Z`{rQnLGqPQ0vUe2v;z?wEPUFwOS3j ziD_{9$vl1fPdc)>`TJAci4P24h69#g^Tb;2{Ffl?cbdj6JKnyh+u+l7X`d=>6~n34EOD zj{9P7RO?&3U92v#X*sMH`ndjklKZk9M0YtoOyJ;8G7j`M!GOjmDH5@T(VOHi`4cLZmn9vL$<@TyU}EOxbwg=+YEn$ zDEp#PUhmG95y27NUwQor6_1Ao%Yp^VB4gwsTY?y&3A9(!mC2457nD8PgniiT^uorE=vetU%?BIdfZw}mSXuExVrO+ut zaDh=-IRBADEe#F?Ora?%6Vve8md>&=F0t92dgdC#8P*gx0lRBYa2hhANH7vBLw{b+ zc6SFhuX%;f-M(6;&(yT!^k_jI|E^rg9ijpWLUX|XAi%=LuIvoFGp!Vt@v4eSVWuW5 zZs!vNj+uyj!_lc33Hl}?k-)&p79s}76dE9sWL<2rKG8g8D9itm!|j4RPz#n;61^x= zCYLMfE*ZYyx(u#0^FR2|bf`3ror^l;;zf0O`o^5KQwJg?DUz>P%Y5qA11C`Fx6`R+ z=iY!dqr}jBC@r@adIUpnbb!Fej|?TMAt_hUla-c>E$iNM`a!=BCSGr#sET9a8~KvL z_rZTz!t&n;qM>ZGM$^?{UUH<9vVeD`V9{tyQz;eO>p% zNT>0)5IHKI3}F_XYQ+(CfTKS@zi9f1WUD8J`>!vw!djupSu=ep_zBiU4G?eVgvXCT zMTl|1DRzL&Wg8iZ97A&~yixb5oNIhH9i9w1gMb+1k<-nw&f#sk> zb>B73Fp}Wn1<(XnSZ(V#q4v6&d>zmj(x6nd>=8%mpp)&q&5fuUps#uG0MY%5nnFA^344nmpwjF2c z>Bj*id7u&$Rt6c$fZ9K{kExzbF)wM}|3d%ZXJMOq0zeRFMA(zs3=X!V{ttTCJ}~)T z=3z=f>i-Q_JS${o$JHxy{a?8qP~Gn%WWbtZV^Lm~WB&7=Ve(NH3n+t>mjBGI9}mE- zVDG|`^K7T!i&HU2%2;I@`FIj!zzYiN|31TmO-HDsIV}zkc~-U|JuR231IM{)HZyyO z+15TOEs1_w&>hlfMFRtma4&ao6kP;TactgYz!tTS5()obeB?)tMmZV)Xic8nIq4Sv zO)a2y|0U|T*cLZ)@UFf`AHFc)Gu)_D?BCkTjRGa=m-yhgf!BXb4=3sE4%(zYJ}f!C z5z&2daoT;q_s?as6wx#u!BozwS#7>}OkLheJI*&^gH*3)MjL^jXEjZOn=iQr?(79z zZ?^c zAGF|9x-2LIc$U<9x)2p0@ju*)kk24%I9aeFgn8N9tSl&plG-yKuLdc2U6Ia=$NhZ+ z(YThOt($R{r({TB zmzNBM5Gg5u{0yX{60j)@TG-%B_lHY)7C1OK;mkod3?CWw!PrPXD+jPl2PN2r@Ox4# zSf1YBDw>(c)0P=dHRD4`?VYt8(o|C!#B$Vt$vqD6sWY|46ZB?_PdDn}E_uBA;NZ#1 z7I3;BfeT#3Eb}92P?oRHB#~u&CK=yXJ<}Ns1nF;9`#qd)e%|PkJ_g$_?=&uV#sYC#tMBh$yje6jyxR)0DX`CZZ_1rBIOU5z z&|Es2;Q*4a!<){JEjtr}|9~R^D?r_Uef2n^6)yc*K3aSai+i$EYckd0>CQM>hM5&e z&B=*bU0tm-C^6YYLPkbJLj$w)4+v_{Sz(F7Sql^#>!A%)3io$+CGKopT-Ms^u%ND? zULQt!n;flm9k7*Op5JO)=OsGfJ(-oBNxeMWpaFxw(=>JB_D%ho%j3K!QWq#)?T>O}tEAVWF>>8Neu}vH5dFlhT?RB_vOPH>sn6 zf`-l?cLc%;(#kG?HFQ6or3A#?Y;|2Kh*NxX17&69)Oxu(^dUNVNy(UsfZV0M+rI(N zD6@t34n+|v2mAULr%M=Z4wScvS2cDZLoZf4|HIbZIy=saV<6YJb)9EH#dkhA`iHC* z1`y1@UN$!Co3Dmor4_h^-S;Y|UO8m;?>CPK_kiw^5{~`_boHIHbma<)^%x1Elh_9h zX}@D~>$K?&52hOLgO37tsmjg8i-0|ze@yW4e$Zz1$u7;+^`}zG$K5!2xFh0f;F)35 z5-2D3!kP}4sE&M|yX{vLK!D=Cfy0^Ea5cCy-BH-S^x?7WPu@bDlbcBrc~y5z=5=~& zVc{w)lMWU{3|P=(M)z!rp3nQdgj5 z&QF6r@sudN;G63~&1X5=wAB49OO22Izv6bz>E9}Coww4LEZ1{3w4UrKbMVrY2jkmmh6fV0gj>0bJBMK)}7d(EN0DA?i(?fo;yxKtX#X z>UW-iGAZSQgW0S4$CoZMl-(Z^H_y`!X&iq8%htGUiIj=+`{7#PVhY(e%e~dfn?2yy zKhEh_ZBA^oXc39+)J>~7DT?0B=&Gxnq9vRpqCnigS?*~>F#j4$Ln zXihTWHDw0MPV;QQZ-Be{FZt3JX2*l@2g+Z(s-{%JE%WWwt|pT1HV-7;`~yM@*#y@k zx2b!&M%m%s>W+^25qbbGN8udDeMhg9f5)Z2)eSXyc?;+CQ{9Yho&U9kZ=qPGoW*nZ zrNiqtBwtDsnr>SYR%b^mJUz@C@`c>$pQsAms4u@vn(y7k*3Yz0J4cM=tm1kbS0?i%yZB+wC6RXrCJiJu-_{OHt7f4|z0!d}pi$0lqhJO{OPez(pH)f6rYsw_QJ*V9)fwtq`Z+Kjs<$b`ABOc=B`i}Onj0zg&Q(0GHb-@rglu^=f@kGP$(iTyc8xIu-a3 zMG`f|S8}XziCE|8RFZWBl#Q@yiV7q_#!f&Z8FA>acI+iI!vsAif9x=S{vquJ^JdM| zAGs#Fd_g~D)XwG%Fr=P!736ils?TJ2=JGdED({i5 z0bxuIM-On{mdJ$pe>$qcHK$B49yvI|omhcGa_@_;1AG|u1zQOqA>t$=?bT;!W;t8o zAaCpU^IwjBYerYqoyKb`@paI-I>ne89&w7UG~C1N2u&{$H}q@Lg`*lKt&3<@$}b|# znQp`-;={Yfm#f?KwcUOrF;{#Zqrd0NT%ex(p|OF4)K8Iqke!_gQqF$$;U?jY?6p+@ z53tQGkjE0PP+q!!Lkhj0p(Y-Nd%?X6vo>-kwnykY`%0PJw-dne`yc0N4@Q6mb`}n{ zH&3{K5MR&4L_{}!XN5?lLC`58L`uT2vYO2-?hIL0?eQca4)*n0Lce z7!fa9J2QG|6k2Vkebsh-{?H_Lbb}eAHK5Nb|IQ5Ik4ns?vcg{1aEopTeeLDG9Bf=s zRLTgA%1j9?RyN-Blck*0yu*yb;q4&61|I#QzDmNP)b*&iMN2$n<-p@o56T zuz7*Gq&l%~dS}_SlLzPhT(aNX{3#WTvZU0acJJI7J)SYb+fFz|td{;*N<#nbZohME zs`f-|NC4fbK51FeOkXpdM0Wv$!T1B1nOIRg*ANM`nt_;Qj5iMtmC6W8NRC6$VIbt8 zH~r1`)z;I$9eW~(1pq6Foc{)g;pkt+bRVH!s6WF9!I{?VO5G$$kA_fB0;#sRxO6A@ z&&(JvP89FZuz)#jT}d?q*Cy~ZRyX5c&x7}aX}T@BjwYz#V8p}r5!_XqtMgPJ%H_FOe?`2 zBuG6T{_cRfF@931PXF?)hFxBr>Tjaq&MU)*1LH_?tDMJ3!-&MHL$mv50I2@tfB+rEP% z;^9YR=U()HpgWV~qgAPZ!ia(T@@ikrt;Z@Hq<2ML%e=PnLZgOw@0cVbeGS#mJ6GI_ zpXlsQyE|E~*`AC+m_HRG}4Wl+HkC&ORuRIUdqaKg6ug%_w^LUKSN+;6|dPZg-Tuo#BF%3=2et)7zRRY}R8+kls5}qZb2bW84sAFr` z5RUl+S+j&5G{J@7ds_#;f5PEeXMekp_(w^?e>i(WcKr6DnWq38-~BQUeB^*WMm+AE z8klIzJBpd&se;yj7IKwieOKSeVcN~mGTfdiZ>@hb5wL=}wr`hTH|d~gj$oxOP+clf z?j)lwNV+~vilj*0%qpdnzp4`LxMbJSp%-(^52~%*9h^)t0>4BhtDY_&&B;leFQ{dl zPEf}=a1eHMK0T~p*nFnoODUS&e+d%YrX>-jI6-mi2W9{^EQr}- z6U7S!pXUyu)`{SNQzjvf;kwn6FfKJhToyfemUZK%J)d;ioh*;0W8E+y!7Om3k_G6YZ}jyX-ufT#lwK zT%FPy*jnD9H7HS{b##L8{`SO&&NvC;Kj;ilMi0U>pNiJIT(zJ0gh^sxg8IYI7oL>| z=P#3V6Jm3Pduf_E#10Io@i1H?)H9u}+LDHZL#}VO;&!zSDRZu@uC|=(dnx9MDZNiF zZ97FDFQ=#sJ5z(}a&Pa^E@8t3Y=XJnHIlM>2|h-s+Q0I3AYR(X3!A~^X=Lb9wyTgZ z2KRADPtcw-qO#vk|9O~?UP#KX5>>XUKn*eQNFtJ5-5J%usI8a9(;S_T9!?SH6)2Bd zLpq;p@Kg`w-18;JdB8ztfuY*Kkm*RAJBnHl;kfgnS=5chWX2z;y9axH`^ROfX1125 z4kaq&y+un_#7hT2;JIQyA|rp`lnF1W2Pi;Y5duhHa0LOV36#$P+GsEH1W&{R{~L_n z%Ev&p6tRjJ?rjAwgY~8t4X=v7Q}-JpdOdg;@=C6J&^&{&)c|y+h0TIRzg9a6rJxf9V(H@s09l^Y8kqh zz-7e~&ve7WWWV>XmZEJJB(RmGSM5QV#iQ&U+*uT!*xaRUPxkqDtjsMG2jXM!Yf?BD zneN0lMc-de6||`}*Gj^K!q3nY84IF4!SU(_x!O>kOW!?GytUzMaTbiY@*<+lv-EQK zCTd4ug|Eq0fWWt9-ACO@`qI17BgD6qA`$`*w$`K z5xAZTUHC;Amz#qS33vO2(4vwux-C|fWclT!>g9s;@$`ni>I9_!{TEy8sLgvmD4;u? zboCP={i6s>DF5{|uQq^Qn}+wg0bvh^%zDSP+l$_uh>i|#>YdfB-2%jk*yeCIJeVq$Q&z6{hl;`^lenx=$g{AmKaqngs zwTR%7pomyd(gM&x=tmy7iV(4e&*QtI`vhu07Aa(UmR=0%TZ%v&`TOl_&|9INgqCKV z#R8laQedw0APkL$6NpCsSGRPSZY#H6C!HTcOC79nq;%2Uka}KJUBo!J9u3>E>>Yg# zaWs#ryS`=7KfiMkaUQAeK7;#}&DoQ`_h8fW`!(`Cg5{T79U>mlovmTf)6;w0jIk#% zn?xe?mk1aCv7GQ$=(vT7yYLFB`Lk7og99(TaiZryExurNGDXXYs|V$5<_}j=H|dNW zWV&hi<;%ydq==vj94qtF^6wR2>p^*9je?$X26{95j&ZG1d;z7k|W zju-h_fq3+-ruMJfgl~{)ySzWs46b>$@w7?&XVF7Z6THds(qud- z;BaCPT1W=lZK&|YvquA`4avvqG7yY66Fh*dJ- zR=^RE?^|d>vkEJ)6IC`tM|H4Z*W$TjI>SjLqytS4VndVWUA!(wA@3-yYnJZZdfPjh z+v_oBHfOyby|hKrRZ%Ta)ffG&S$wU7uAfTP9{&hE1P4W(3gE@u{JNY_}e>C z)_*(D=x-v08sXqKfv{YYTyIg?#bVwsiRa0wjpN0M1Vlx5K{*(KFmy?*V5S>^?~4gu zCo)i?FQ~L(q3F1Q(&YLt%bXnnYaX8;$ce>?dldIA|G0J0axn9NQDsIltn%Xy8syqW z(~da*5I|i0{sh0_*IWLoh>8LIq^%q?TMP>)DoQx90?ER)mVrPjw28stPB=Z$s&i!t zqKasT>hVUrS@6q~5T5@LER{#RP1tYqoBaJt{J&UQ#?mohQ^n6Ry8>me!0;K zlw47H9xF7q->*w^uq7uuXs*Ar#vdAl^`Cn_J&Fz_5N8zIsmknQ$IFZ$myeC<(>|o1YFaH3$ zK32e@9u3x+bb?)^1AkOl$-~*f!U*b#(7@3{BbT6IaNoR)C;-L@GV9A?eqSwZjs>OMhP)K2A(fV7F?3h+P1@FYyDa*xw zEm4bS2edUWC>@smZmTWmQ#=;sl2Z)eCUepp5J^T_6j%&Rw5u*x=si)kVw-`8x*1wU zVBR%ub9-^TY@A)mJBXFtUs}$YSyCM>HTGL_XEMG>CUe54<^Lo8_9a8^UtA(~=t1I< z?8u=v553@sqvd*6;sVZd&8@3nUCd`cJNQnGB4E#Rs@)tnb|b?qZvd~ z)}DaV4^hzomET9jv2!pAOMH&UafTb5++p;|P$h*;O&AB`>Byd6nVXxNi^|F@MSx%$ z)st~8E8ypX%|dGA(%KrXkB^Vj!I+AL8g{Xf)g54ePd=1ZW*HtBSr)X^bqt|E6{)9I zrKU@FUUV>r7|sbe(es97WMtI8|49OKs~A;kOjuZ3zdBq$KM#jb?8 zBBgUs-32jO2Y-jTKxy;giU12-715!xh;HA}T=?c-RU{5wMelkreTCedVa zr+~pBS>fZ)K^^{fOLM_iWMtPw6kcF!<_zhehfP1{sdh$4_k(Ee+LsxI)!)_|L5FyJ z7<{D>EWalda1rqE)=%k)i#o`+8mp=ls19=8e`8LzlcZ9yu&9KB&ZeEgE}^Lm3`L^u zNh{#aVisN>A5-az*x^jk6*iQ2=o&PVA1>p2zF3(qwFkQ%5>lw8S~)OmC5SLsNkT@p zKj3+^ItstMocqPZmmVVk8Ss{wm|nPWd@->Ad=>&!3VsW`?|^t4q$AG|L(a>*nlK0& zZ=*I=4##!|2TXfzE+=XdyIDSp?nyl@d$RKJAmCFNoT-Z2UZD4mdwX=PKW%3?PFIbl z>Kr;w4I*dY11m_fm)VP*d{-~)`KMDb_Wh;DqDBgvXpr2!%+y4AicvZg@{bj7fx3woqf(+yU(z_S0B75 z>9hD7=R201zkz4*^(0}q19H*-O;($z5b-`ihU`H#X;|ao z9hkb=8)OKOh@c{V5LIX;^}=jCV1GV~5CLFY5E1u&P9oIZ+VxFLpy^ZO18+EyUO1E! z>c|3;Vu?yLH45$hf2HADyQeh$%9G|S1t30Iph9A;v0=~-8nm|&x3&=7bCB`W03f3U zi35ph@gg}~gk;s3g(tyAa$;anS~5yW3+*OX^3vo7oXxQE$dCqcIvQ%G85W!hM!U!R zVC1T*aVRKB%Af#HIta~|nRpE-RYWI#33&!3SBzj&Vd?(%PSnV?`SS@v{STND0vrIOXw3QH`tNY53nf_* z^=e=qpA$eB8`^R1QpMjIN&PGuZN`Cdk`rsk11tae%tXpd{%Jwuj?siq8A!v|5DTCp z$Rf?_DKWb{-iqXIl3(XmY9*nch;l!Vd=)NPHB926NprbdA zKEoQoOBpr|Zu8@12lCk(dt6LwVI}<39+W&_1I+N0uaEB*0i|r>*v2VK3l7&EFS6r> zPRl?afzy*~b+MN0KYj%WVp+eDgrZiDXK@#IOXa(UyeVmDK#>Q0%fQ1^G7|Z;?o%R( ze(L$I6I2bzU{pkWkGDK-GGE*s!NM|k!AdRX&+G}jh-KXRH-6|Lo5Wdf_T)4V7q@S5 zdDug^A2$$$&3db;s~0{$r}88F&s?qHC2PN@1q9pM1xn;=YQ%|dgt%#VA!q%*A!+<} zBYNbo$KEppZi>mYWtK8GcEsXV=wpvl)$JS2Mq)1&2CxZB135FdBF_gyD;&&>wzX1d z6}}VV@EBNNc9plu{JfI;=X>|nl`NKFbN`r1){)WxkmONoT9n7Rev!-qo$W=DO!GfW zi|7@ixMJolD0?vOc1(ApO8u7hNcJfgJumeix)rnS`mBa>ZXHO*)5E-=(F7#lRIV}X z1r80I;t$647RuCvKQ4ujUjM6D0Ll)ijpK`bQSXb2D1uB;sFJ7R~?Ks)hk<;VS%(b|<=fAsiv=C{v@%*u<_5!HhC62H0PZ9C>-FEt~qf6{zv zDH0eUxmQ;K07<0`Vy<&ouu{}i2-w&s2%m)@(FF0f_cT31LZ8r?xG;b)MI-?_{^O$y zKvyM-_8#XT4@MFD-hm!#kWc@wjZe~=#>>vq(-lK7v6CwvNx;Lgn6~XQd3V5OsAo>~ zcYnNpa&IKRlAoK&E+6Tnq7_cN?+$tsb##3P>S0a$;03UR8j~dljlwQ@_BJif}I|nh2Ico%9HrUhbyTdWUQJh!8a*| zE1gNXeZ+2xX9TSDl>9s z{<wC^z?yy`m*E4fO8$P@nhMTcWgRg-gp|A$dsm^Q* zSv;d==3I9{Nc`Ez4<9?HvE2w=@xSd-2h&Nx8F^jj#lyUTRx1s97e1Eup#nCbw*il@ zF>*~eH{M+v%m?Rhn7J!(JXbK}pw#FGK8|Dx7a8IsGDr@{v z{ujdG!~@#ge@w>cf83MMPoBRK3^>E|wvU}KhGeMH`sfeaIU9HjqLN2-X|)d%wSN)V zY@{^pp==h&-|{zbN0jn6_VaEoZ6yDU>kraaiABY_HyRAa)ZO6vT))OHw%cPjSZ#!a zBMo{P(3yHoN1gVL6Bi$xfqjQFXWgo%o_hMS7tLpa$Iqw_@_e?inOL$Dj2{~PU ziF1Dtib)gunQN6AwHLpaFPNdNF=iJasb!DwnJxVemEXF<-`|PifA4y+H`zJa5yC;9 z{bGfx#YNM6+Y&8zKo zff3_|Z8N>|e!Ihcpxc%hb~bXRP+s~9l}1utp8ewovxl%&{zi?*lvS0yOwQs_`^V%@d{1Pe_iS;{r>OD?R!=3kbCN1Tk>0siOpF54LE4I6) zNHtK4%)Q|R?r{T6zeK(vk-s&W4Rtt2huw~Zu)|O7jYtwukEs$DeB}31NYF^H8sl3j zsFkrZAqOxxF>;a6d4XqozA|^bZHu-w9u>v4TzNBJjyHO50VTR(QWZssAdcj3ouH4e zWAvAEuc}vPEq?V6J-}|Oc^$|73Ea?k9-GrB?Q5V9rt6jAnVSU>4f@Z$nFcv+hdIwY%)sPzIOUNAZ8rX~M3-#~+Mf z_7Yz)o5-=iC~d3!2F#+cUC?&c8wkgwpr=oq?sx$@*|Aumg5dEJ_AP|AIAbplw=QVj zkWgB~c_nu5^9Ian*9&gu9)AvcyvmAy^k`sTgBowYbSy*pD zidGlvV85~N!+n5n@b;g^%bpMM{`^xm6QsCg%woL8iF$P&u;{^puE<;2J$uxsx9sSr zVCO;2*J*s;%|k4BUQa#q?hgd2)1us z-YVd}=q8q*=#Or|+i&|OXhqpSu)#caw$*sGr;J?f){kZQGZ`HqMX8m&zUdmdY&BrF z8mJy?q|q6fF>$I?oDVHtgC>;`fA((ONQj}Tkr%E3JB z-`!E%VOe~wi1uifiI&m!tqVJY6KsT?(M#a)8-K7XIx#EDR)eU{;B^PK%X}VipDnLvXq@2jri6jt20H+c zCRky7vY5;PEWLa@cTU41zg8$vuq-wffAOp^i;`}o{^r99c6hgb=(VO`$(7Q-(YFPU}Vu8Ym*^EK5+^$!EZ@ATG zKl%-4#mqAB;-P~C(uC0$WH!ww3A5#D3A>W_<-IO^I|q@c^6tIF557L{ZSwu`c`ltA zQgwsBS{iD9;%1st6Uv_?ZYl`!+@YZ9+{N|EuxMozUJWmYzx6OPBnrz4dDf?XQLCO`EOWy zl=ny^DsPMz2>P_+?9|nZ1*(|Z-=z+oOmkdEEQE>BwfS4{c;L|=4}VL;H&Lfg%!Tj| z@UtR`CysZ!e;DdtJGN(0afkgFWWHQ+zG1lWald+@bWhejg)?fY^g)3E z_hTz~fT!NTPV!3(wy-#=ZgL?d@$(=L13+$wbz!>O&EnZfH8*$>${!&}*Xz#cx46(%@=QUqDK-i(-oW8= z+-x&mgaf=5$duX-fsR`SJ3LoJ&`?^-CmjJZU8OkSHqa>w2CMANgU+dB=jzt~m|ON+ zw}8$hv%NppD~6en#%9zwUIDPpd=w zysL#~P(3~6wo+LO^Xp2#LdCf~tU2!hm+Arf&R5?cJU57$0@>ceOfR>kFD1L4{k%!0 zM2Lq{x;7-;!F@QxBU?fVG&a9 zIH5B?|Eh+-Zs4;QYW>h$o(CTb^gUtabQd^!|N57xyE(5(zH@UIR<)_>)=g>R*oY=)h0O50D`~kL z6B^9c&e&#-KW|OnlP74afVHZSrx`(BAV1JL@*t2M*DE^*mF?+SWvz-tb(6+eB2Ur+ z+lqS@I5Ch3o`jp*wrDguHU@hEY+jvret5NA4^sobUhtPdC-{G3Jpg;3RSfG0 zinx`HO64mQ>n%APgWoQ_f7>0Q3U^I5p*%N~ko4C_W%ydTZXFP>TQsfrC1^)E##N6u zf(J+=Crt(|W+WiogYJCT@LM=0F`YKM1#Zhhd{Yc4`k$lt2E7MtU7qgDE}f826M>re z2)CxEKBBxkCZ3yoW-;doy<)ebGzX40J7zcDXP6G%OU`}oCtSWJZ=$~+D-h{q=o?-& z--rv_Bjt540?t0%af2#yVx(>z8{IG3Rgngb$5I05fxDZEih?A)IlZSJQrFgmm1HM` zv3LC=166F|f1rQuUKyXH7$yOpwm-BGe0O`i1Wv8LdyBfz3jtvuPalUCNfsB`B#xC|esz&PVn%{QE(- zrvCz?{Jxmz-VV_Th>C$mr-B%vlZ!N|d`wFKOi&ip3&=F|_p7T)Xh!e%1GTzcatEGk z_WOk6Y=1bnAKWnbPT%Z!@M+|XGoOEK<+$*2oR`uew)nzwuC^#X6Y+PS^@8@7^Va(JS+)n` z<(t8N9nSe^XB6})4jwu5hd(8dtHdK2gx%2upUn)G{TR7h2?;vR{8dlO0vUQF(>4;p z*(W3Ilf%#@o981iIMg)42NybT-_c&1K=Rii4-qT615r<65)wjD`Dwd+H|BRDP8zmS zUz~RO-=(WJDR~|Cz|5?|Fd7o`DMoI6px;GBuN$^6>3QuYsz(HcVQB+sQz~ISf{8Ml zoD=G!2ci~`@PbCC4a(Wn@YrQpU}liK-V`m4K&6N3t zT33FHSfKMd(Rso&ZrFmK>uQG=S|6J$9)tQWZ$@T2-*t7vUku*Se?&;K%L+`+A^NHi z6p@SJtaKoRl>ZhKDuSJT=P_{i|y+{cGAP z!fE-RQF<^xVz%w%*31F#LMj9!n&=KR{CRS?;rZOr+Xep}DKc0`>CHAbRWtjeT;Mt#x59CzByI$YYM+h-Q&N%g0A1NX2<~=@Ko}84V`({V86E=0b zx{-T1FrUh}6#^}MO9%b{vy-7;7llE6QFAR6rV1ry+{GcTx1HXb%xI?6VBO-#Wu3%; zi9C4kAGV5WaN&s*CD)0!W)Qf&`$AIpwAtJlxZR!Uwlk$0q|KyNRWPX_-g4pa(JUY$ zOhRd`CJRD7@~GbcLMJEN89E&FODrj<_4=k}uV2)5=-6%DzkH`41pa3Csz(B5XCW}D z-Zbf!x(SKy(B@|Carf4w}&u zzo+nKeGmY710VKfMBOirBb;N=tD^-i31^Oe1>^YNHtug8CdEi3Gr$I7F7&RgLHsb3 zKfGxFJ}4eJ5c1Beu&?KDe0U~-zXC}W#TLEc4F7i^qAy0UUGeY$M)cRW&z=W&7IrfLo@LxyWVZNgTUI*VFjDgUmDm|`si6pYZJB2y7@abk`xSqvgyYGUQC zxiM&}pK6A3bT)SEj>g(Nyqm|z-|(Gv&6YrSFYg}&6%-hFXwZgs=^$V(gOpHOuzGnr zoMpqlM6vPQPi1%qPwe1%u2FV`*=P-FKiA<8;fUqQ;ae4n zYz&JVW<=nfQi9yyWTT3oT|r6|OO1%ueHu_iP?Yz@g=uKbm*jpTpzt_0wymudZ&Lob^~D{%-o4P3!E7UfcigtI*Lg6ua{|6rtZR zFNES0;-&t5TWTWqZlDm2w=138prd%A#7vlV@~wxGHzSl6AC=<90%GnIM6)|Vj##A7 zYZ9aBN;`4uxfH{W0v72e<{V^o?jUi2yeb1T5*=YVBHk9UXYw>_6YMfPzMq_*d-qD1 zPCFGM$^t$v7$7Cez?*DP)HNH^aKT}J(dCb?qjv`;fPNF?Mf{3=_Pt%l1Gj`S>%^m( zX~IA!W??$M3Wsl~umxHF%0ue)X@XBu!1XbA5uBxA#ld?a0$cuV(&647`KkK*(1x zzpd9v38tT>>(rAD<#`yo`*r#D4?0LQrEF@0Pc^rZC2&X;c@}rt)1+VT&9q1AjzOp` z4#T2VjICWdN;&&MJQ@D9EjF=ZRvUL52}2}gn8ihn_uCy3dlJq(FGnwm4I1(~{Eb|C zZZqplSnwx1sdPi~z@KMaNP(F;hs45G8~}myKZI5TK3bqGd~Y3tXNR)QdqT~HeN!Qa zDqRl390b$v^c~aeuVpXvw*;2oa)}I8Ml8u62?hV>pTWJ;|0*EWth8LsweU0 zK{SMf*|rY^HZuR8CjU~SXvP0$MzB;mrKWH@OfTL}Up!BAlxS&$HU56_IC zjy6+F_%IP-EG*MxIU#t@_-Q75^y0^8sg8_01nK8ck`VC(mBb*P3Jww>^+94{U@$3> z8FYuYoa4gq^YUaO8KhJ#ADvfZf*KyNpiojd%gNgc*I+?jT^Wp#B@`@N$I!0|T9pP~ zPftb3Grn3((+)OM^>me?j2Nf06=_=o5Za*8QJFZV7X}7`EDh{yJB8-yDz~VDBViWb(o`Yi6O+6`Vit;`aYv%^gYi>ps!F5&en+~-F<4w@MhpBR`UMxK zW*DXb9H#s5>kd`nEaSTXXbWkcwY4!HG8}j+alG~Q>EDdhu_5&B{(LtFy~%SSk#2G- zfy3h&{p*DpLaQ$q(g%fkY#RgZ~Md8d`u39(l z^y{rje1wqeb%37+4{LAysniGR%cUeXCQ)#ab z&3mScwtCb&v(8Ye&!Us2Rs-(?_4u0k{)Xr^BRd@i1vpD7k;Z5P5N5dGrYO5?kujhCI4fuGJFJ+nK3z{}6DbB}|_MEx$kA ze)%ly^75ar7=asM00*-q4mfQP76ajN>(II$tAwHYyjgnzYu-viZxnA+Sj`I7FMrE- zUf)bRn<*h#W%}2O1=OR0+Q{`pzy63`-RqMX(c~O z1G0WG&c7d2L&uNxuI>Uzr4C$@i#rqlO>_uC7&r#~EQtT?1sH^^_1EVEc13h=R_CDE z%?}&%Ar1V?lgw2^Gk(Ism?j`#C=rw*hRtf@%{ir9b26 zLxz$e4M0$B(jpdP>BlSnuQP8WEH;bpn*bN@s5lM^8v(TMi;H|V{AcAS5_@?8gPK24 z7a@SL|Gy|lRt4bJmIBwe|4Vm#{sXuuaP0q=VowW^tOXYk8w*eg;u(iHhgw+3!2E$< zsm6Fxk_JKlP^S^Iu2%GmOmBqu_UsJCLGOZwxiW!=?ZV4)%ar#`@Z(+j+0%jWU)F~r z?qRL5>={RiGP%3AHS4@V`1?Q(<7gFUEYQSA;(XUXOVDp}|9&Og#<{TaAsJmq$`hyx z0QxUe0jazQDc|wt<|hB{v|Y*31ilC`SrDL85L@nD%eEIxS$bToNDi^6A6I;Jp0)Z@snNmwZU>TA4fd+?hFNpS^bm zCyM0CmL@b(plv76rA_U@TF@ZB9M1mgfAsdk-rim-%q%2&7PS!p0f8yH;E}*w1$O5F z?Ll!gB|oT%w#g7$RNn;%;g{-p*6Qecd|Lrl2G~r=MRvc=L7hHr>Ti%gce4Z7ZyCM= zeJDFM`M06eUPLL^{_%)wSGP+vR7+*<`j-Fc?W3NHWp;|>thZ^3Wd&q$aj|#?RUtSH z=FgAe;o<9>o1~KUE4fdY94zYaI>=CU*o8*L|AQbM%zZ#s{8H#^)2hP-ALo{xrk0 z=lLIDY`U|WF2-_%z}Pdza3^R3o!N)ck&#SQcqVx4k%q>``4&6fabP8H{_9Ua0s>3= zQK&M0q7>zyLNx;Y3qKh9^hFmJUYJ4h0w0g_HKI3hm761e)~6xB%^K28vL z_XNJ@PyUbp2wq$mH?paqZzI`^y?)U1)vqXMF^-^B=owX`^k1VZ+5+T4%)gi}o%8E> zfbnG|%dTx0Z;*4oklMFj=!iCcCnI)xCL!|u-V5aW8u}3(`Fv)}L zMSs@1rdPv(1dOY+Hr5Hg25Y7nl=8nHPLx%OwwH+Bjx1#1=u;!^1SL`L%n)A< zEQk{NuA7cLY+#<)r>rdhA>1oi)z7pr@(fnJhW-eKG8APy$Rg`*G6Rh-s5I?o8ReDkETKP7)=^! zrI!n_@;-Yg`pRIacRZ{l7FL9e=Watv>jgw}{&a-m+igP<$^{i6LO{D`;SHU;7vXu^ zFtm;Dw^dS*z@m3s_KCguiqL)8WoIDhZIQ0|Zg#oVt^1^mQrgu;N=HXGurZ4redXtl zbG^hMt>20Ciyv^DK%CX zSdn6t0i$X9QYy+1!q-tARq(DjZE$ScdyciDD6$Fj06@YnqkwKaowzKG*oV9=9pFte!?50==FD zKoIC=(gm^~u4_LOGV2>(#V!b(ue=`Z^w`r$^Vrg4&>rj~hC?ws&y)R!s<{%G$k1c> z{S$7O`CP+&A>f~(03V2N)A2RV(`Q)4B9uX!Uv!Y@kN4qrcyJHwa~~YW&S92=q`iGj z%01Na+i0mw5drfIQ4IZgwIfx_8?tAfMvo#kl2={X0U(>fF-Xg!f;+-8-G?V zmxHut)45>_A<82~vG)Ma?AIz3yEnOr6MOz0A8?!4IP{2UH zu9i9>$w{CGZx^h7v1zN&Ncdo6V}$BFTMxk#xRZR*r}3!ymhp{ujToc*KETsmnWsmq zCBiN1V=$i)aqJQ$kXp0ZS8s$|982BCA8p77rrOOd4IMzrBrktit4 z&YLo0KeqWo)bj)+%dZ`3`16f5K#nV4VOR=-`Fn>!NXT|?#Qf@ZFbR!(A1$y!#mj<; zJg*i1i&M_u24v8-euT@P&TFtA_wEYRoxD+Qb&!vJ{O$FbEvWkaVLw6c299p-O$xS6+MX@A`tq; zf2YoKl6I6AKfJZ4BLdH-LB`Fc*3|z6zL`PWew5VQ^a+o@=d<>v<0RYzdoyOWmZi0G z`o~T8(F@0Nda>u4*8Nt)fZ-I4ng^FVx;}-dqS48@v*t%F@Sc(H-6i&K+=E?tMP{(1 zi!YNtk)q}A0m4n3S!Uhvt8GtIJDd`ug*j&FHy@(-hq!^O-naO1kFZO>8K@sC{p(YMk993~|HTFE_ z3i5fE?Z~q;@tWF4?m$Bn}jHSRF>WP7nnzfRTe?S1Y7tD2A-8bTmt89EvD) z{&GneW3 z;Y8rU8_X?oG<$^-ajWR#5}1-Of&7=mKAJ@u$!NN{yw{<|3O-%C*Z@o{gna4NpJqIc_8dl zqY9=jCSE5F*nxH}h>0c|riH5I^CyJAe>eNxF70OD{VX71#(&TF+dPFj&M(iwUEe@G zv)xzxBc9*DNpy1#*PmC1-9`v2%e!M*^EGw&!DOt+rqpg)y*ZhkXUiH`Cqy}H9%AIt zkm}*Bdl{`>8jMF^&(MUyFKN!Uf>yNtQA59Yf?5Ic?e130o~D}P4!MK&7+l-UdoucP za9`S$@X#T8>rNxf_5i%yh2zJZ+?4e0y=aE(1v!@8G+lcYIJ2c6A-6p@H=9&Dy{?}Y zPq485qL&2e2jS@&X@R+Xb$=$lKMa>(J;ZP62BSwj}tOVNfliGs>nzG@_hn}gH)c8keO=))yssDWCk zjgc@JcR3i5A5enFCKzra-Gbz0&k`HqI#M1Y;>(@k_Wg#q>un5!(B-a~FvFyOL?P>D zdg_Gd=)Cb};Du95UnkZtE3M!)5%&ur>ajQ2`q;Rh^oMEx(R`6YCkzj8iV(bfAzIT) zz)Z1%}f8YI8IHICJl}sBXj?n%Io*Izx9VXL=LyzP-KOa3#DhSsOGi0RPmYk!8 ztL^)?byibQ%pR09yMXICS7=xILHXJdnQG3F*MT@8t(YufC3U5s#w^fe$?kR8Llj01 z*+d$b5NXTfc04}->O8g0w{FFUsd^5d%#!Sk0SI#Z;z(~b1=h_!)n=A}C`z%f)5)(<#D`E!RGDt5*ZH z)^^<@3q9<>`9ADM*leYTNixaf+5FjK3^4%>G@4VVm^Wg5dxQbJ;|>_m$o?yg%`cjH z@~B1RViH|~OD@P`h?fh4YZ;S19^9Yf`i8LLx3RnNfJ1fJOOSTORnS$Y*3HfR6&mLX zy5owz_eV6pU5}#*;J{sO2fV3Z)nkd(=a}U`PXh2Oq^jf~~B2|E3*N%%=v&fNQ5LRZ(?PjEahT0YY4-C#eQRRZ?#~)9Q?bG`|L75?$-*Ku5mct8o*U{IOO}7?%yIpk!@r+KO1qJO^B{59lU&NvbUpn2JzPN|26@i*>r5$-Uo#Wkp@INGE~ z!N|Rh*wfZIJX4wF&XE_)nvGN##}DRjGUD2?gt|b8wVpQ;?e|$3OgVSgI`Oq71h3x` z3{CH=v>)7Oj(BV!q%Wyg!75IJm9u^Gv=@ColZ|tf`-HAgOK`(;MTzZry8<(oftc;) zepM<5K_@NPZ1i*h%BiDmDf8OPQ_jPf3u8wZT$Ts(;C%A-@Ty@~7+{D5aYw`ap`-o}Xd>LIJF}t#Ev;a!k}-gGD=Mj*RyT{#x?S?9MEF zlDKQ=_mCA_N26FyyF*9MRsYb&;jps?#Fm|(h_e#%JG3M8rtxRtNber77J?iiXyDji z90a8TAV7!I2(@`69832DJ!wvYgfIli|ze$`2xSoy`e>%H31! z8@$7GTsw-pbz&xaZ#eB9yW9+I<`7~MxQrP}qgtR048~nYk~D5%hBP|#66=;K4SVRy z^Sn36)q&gDc%B<*=MH1#<{5ZVC3Oj_EZ`V-jU(&S$eSt{CO+#q_QTuQ)t{2z z*vdh{XToVEgl{KpKk_4j4I1Fwk*DT(`e79Lw))RB^u2#_RyT2OnN>5|F;!J?9NcRz zzqFK`;&cJ0TqqybI1cCp?hDc+bQ0`iv%K97ygW zH!Hhov-#jymJ$~H4TRO1KBy3a<7LthGcOA1EJtJCLdMS0JbVOA@@UeCrwbUSpeTO3jqA_23H`Z+p=eID>7j(kmlMwoUy>-hdpdiFfVI`2K4 zs8%@g-RF`{zQ+QyP*rkg+#1^Z#hp7!OVJa;fY=n)e8%JJ3yQPaxKry2c=kJvPc6PWkGrsG1Rz%;EdUZb9j+nAuJz=l+)|JytT>Rwx5*5+Lt$fzu@nG8ORb|6H%m zrT6VlQP0VQAlq+)sSQ$C6I4!&Z;o4m5v%+$Z5TfVp*M;>-Q44vy!} zKWlF_nmAB3E_Py)X?tCExcT!uyBCj0KKQLR9&XuZ3@k*jzsxPH z0Xkq2bVXknq_3Tq@zO(&4l5}tJuan4c&!zTVOlka(@!^mAB3l+p4tm3j~nYXa3O0k z@M3C-7lgmJg0I109(_~kHfs9a@44K(=D(b}<~#ojAluN7xr$~EfwE%=&?ES1;M1Hm zjaJoHjX`Z7l?)MuMK}~YDjwF6Oo8sLSSUM7JUojBXTV0jbaBu&PI*yLE#t9|;;SnH z%D{l_=^`0giKDngczJ-}!s32J`4wvjR+=MQPPXJ`m%^S$X5LL-C$w2XW{MUyDaqu` zglJdeeUavl28C)E^66V#B|0{Uvtn?7k>hVcxmGE6r15%IE4pMQp2caG_*9=Q4k!Wl zjAZQt@#<%xMLv>vBShNDfQ{-NRYQe!QTA@LUfE_lMQv@I#>}77BTas~GS2#HzKwnJI|X%badNVqH@A*59?3!`ol8{wjr|Fh?&Obxi1{zAIg1n?jQ~`bFHX}AOM%a%!UMlEw zQNC3Y2dQ-1)fSd?0e1La4mT~vj;SqcAodx*J)%E+617wsfJUhjmf;$xA=in3aL2e_WCqOc`N zx@jvQ9brS07V_8S(SOeHJ@q4^+^pV1oUg?S_?KeKdxfyvuaY7)6R;cwWATe2d7ILl zv%wKzROxaGH%%}|r-`{MVKy?$@bGmN$XxKrWIqwPbAF#RbDo+>9WCv4iJuWyoRryS z0)V^oUB@Tk{RcuXmyiEWJAdmlFOL=O6X+Es+}D#zj;8Wim);!oRN4MYE!e?SPzqwU zGc?CVEi!hM56)6q=$OCWDJ5M9A*%4XrBt8=#*AxTtKtDe;tOo=%O%c4Ks6PTzXe+Q zt-qI;UJPP=vDvD~q4g_un?tCx$;2nw*Gu#}unw_v)w96{e0A>H=~*H)jcsO3QLjonhSq$na&nz|qW!SQIv*XxuDyW~@GJ?zq)WE-4K)5>et60z(Pfhb``S$n zV*HnszMYFgyPq(u7jH;-eaHqL?Fu>t@wD(lfVQvm?Bx_J$b{<4O-WX(Vx8~*dT0yo zBkn!uJPpV078I34>YP*~$epvT3E|BSJPS&wZ?&u=5U-@#(QbLvQs0VqIKBtf?7Wr; za$CG@=OMyM_n#R2+z_we>y2%O^l0W^|2 ziwRuP*A?Bjpw#?^ogTmErCVgO(e<4^LX?Y7@FSn}kB?1cSu$(tnaj|^*!S&*hr=^l z>ZwB(J{5C!6x5H1ag$W4U)&U^C&B#O*+B*J0X|4Hmj{PbrNVQb6?Ft!*{S0%*;oVe zrJCVG5>))=ntR2~ULaT7wFd85-u^+$sCd%lF~MAR>!kChvXdDp_B+TKf|8EWIBAb((QcA4l3ec>nvESZy-wDWb5H zuAw9%lk>-iSXg58(X>HDC7w12qlBmQ%cQCWpx>^~>^T%ue>h;$SiUL|@t2%%Kc2dK`1%+LDXs|9imS|xMc*S(ctd1Qf(=dNQ)Z!w!3qWfXtWsSKT6PQ> z^Yh!EKjBWw+DmEInI9F8qULQ&SWa1)poh_L4?;Lo^S!<8g*h3yd2i&{=Ak|c)2f@X zETL}TH_q5*j+7Q^Q`6->!e!!p=ma4bGa$!0^`&wWxXxlEME_W1cvp#CPK9dj5N$xK z(cSZ9=#Xfist1+V&GSf?expW}oex5_nu1EuC`8YrCM7J&5^-s#oP&=v&;jSbnMS1N zE}&Ra5$l^Du|rMHRK>2K6$U1v;*0Q4u_}@o&5Q-N8qM>GL2QbKReW~}wV@>rGC}ng zzgP%H12aE!S*FCB8C4C~N0?q2oImZrso8GVysd2hNTpi9)DIc#be9+jMPiKt`e=!N zL>yT&cKrxv>PlUPxriSFYwQ9D-Kf$SLdX=90sn#y1+kc*b~Q#cDaz5wkScD%iuJSP zZ@0#AS84CsiM%}9!7d2*ew9r3{BvkaPyy58e(7r@R=WGh918!(@TIt^r8%FnzKqRM zwEC)%@6QEx=~jAgd-Fk*)1#fOFJTM5wDxa~o<^U5R_j2~JRH@e-i?senkV={TGxTP z7(RrN3L-vkJ$vqGaiIa~OSr0kk)JT6QUGg9U;~^gN?23&0F}=R=~>Txrs{P%j5gZ& zLV)Vl(7p`st;k#50v?A<-JVSouFBD*VDD+p@6Mm0kKHyYzD3{;*M!eQ@~E;l+~8n8 zYr}nBd&h~V?(L7|?!D*STS*os&BPjX&Ld{AkYneEmv&tXo4QD4#>ZJzM!gmE3=GJ9 z_Xd<;;C=-ad7#IV33Yt_L@&$L&<`<1!y+vD_v4LeQ$iFeHW)d+$(yp!lB$PBb&fH7X446DDga@oE3 zHeFz=|LZBEvnvUQGj$sbsu$zD>sw23U>tS0vMpP73!XuluuO^4T&>ZE6VsMcp+YX@ zZ?zM%k(JHS!Qc=#iiNFhr@~mR)U1WBF``ApVZhZYl}T9Fs~VKdny(*6toR$md%7IH zO{Fh()atZjm)os>4CfGTLSx6!Zu8^k5`19|pUp*c_*Q!-+h4yu%ZK7;7(j-#_q0VA z#AeSin~Cd%Vx`Cp#|JZvjM!6O@|)F?pd~8yF8(D`@LuPJPX*cul6S~g=}8J`+1SPD z#Y<0*ifthI`mgwUX*Ypcs5L_>3Y2Iw72OHTtKC_rUv<=Cw^84^S%ePZkySY_>pHkzR`aQ?5B{E#22fC0 zw~+;WmlLToit83WJ$ty(UxIX>0pD434|P1v)Kx(mv79(529G+f%EdmSH~C+BKOnla zB4_^_c3k?Z`uEe4>DZ{s7c02$)h!2dhQmT^(c5tmyWR>Sb&^6{zN^O5p%|Tq@6kE% zo1<`*NZc!a@09l4AejG(+->_e;}4#%{X0Fl6Y0;BP3pF>^|!HRu+!OhbXL`Pu5M z(CcvUa=t{JA9<+lA3AsNbA-G4@x0~Ga>m-jj;H>Ev zgSZWKv}Aq{-HH~ipAzL6w(LNB6hM}hLm7V3z`m%Yv|(>>+!Z}vZ)RW>ugaPXg9^e{ zPKS{YbCwnobKgpE>VMHDIck(jLkuUy)q9qUuk=$vW4>@$f)IGU#|JE3^>f--{aHV0 zKBJoF07J>IH&!H{@D9rjn|IcEI4IT;E?Oqss5yjrvkg+0g%;v*D!4Gq&$)@oZG>%( zWLPe|lPcm9@TYb8a|M{y3%uZGYa2|NA+4LMUzXS~3~KaPs+AX^Y0f>)#nrm0*z>Oi z?1HARqvhi*h$xD1U}VV+ssyGBZr)sXiV0A#4fBs=8Q%C!hk|>=q(y7P)MEH`p^GPt zG@7O}>Dq|}x4KBrn2yW4deD{igI@y4uV2=Y7&yP2a7`}X1p}vZt!(o^JVJ&!XB0{G zd|HsV#RqE{A-#>BeiFkMY@ptcB=2N%JT7P@3`R=dik#I<9l*Abc&x$me7+yg;Blfdc(vs2dVU`v>3xZ2Pf*c&SGdNr8;%g3 z9Z0jQym^}D-fz)$7@(sik3kgHMK^q8o@zTn&hvW-13p*(8{Sl?gUjJJmdq#EHS*vy@cvv0`}7J8TPd z>o5&1@^IMh00IKSmU^-MR`2~JCV!g)k0>J$i$wXSb>nHDA%#NaR^$b?df6`ds{Y>N zZ^;19?~CKRP4*lHjz(4!C&J|-+`I;|=>WIwPd-_OP$A%R zbD>+2UFyDyp}niESz^=zh8@HF3=0pdP7XBPWYMA3X>s4iBu)rV$Xlnh>01=iL8FsFqO*%ES`W_Gwjw{kI@94AC&@2 zNw2nDkxCZ)`r2U4?x9=Ksj|+uVl%W&j^Z6$o4t!cu-Ac zjPrF)43AAGCj0I;`pxI9RRCJFUafW`0#v1&t)}CYe(l2j;OMB*>y^a5O~kK(ZSlHe z=gf`t$5k5{8@EA}^S0=*zX3`PHDWkHNxths+%?n*7W_}hsW){orSJL;2heMcEigMB zC{&AinP3>i?uCqe<%f9b45goTBR&5n*~z#SKz*KgZ63|UgeDR+4zm-6n5q8QidTs{ z32NUo$n-xl=ep94fa{HhTOD==*pBv-;B^y)4s7-2S}{iSo!M*)F*zTWD%ti2J)8_i z0aLnlD0PH&baDwvO5M>)rSbjgi#@|7KY!q+J_0k!)dT&Qad8g^*DO930>47P*`3h| z3ybLhp5{(8!^r;qqqjWqUzFURq~~|Td%=xLBE9wLrZ4&8QvvV1;yHI|T1P}}HA)|4 z$+w$&C9ES@KK`k5@SAP;SvGLRC5J9_eCMFvw_*dzM*syLn&b zLujy$+uf?=+oAb-#K$?O#OL~w|5$Er%kfehm^SYpI!148uX4~w~ zI}*7TejxWNef>OdiTsJ_@yW<;)ClN5tFhg@IPQu|-~B^bs?b#uwEd-}wIEa$PP|0I zEBgy^`hE3%##|4^mLaFa;@nM9ejZo8)N{l=OL34 ztQE;W1qocD6los@HCS%-Uq*FCY;2AO$c~AUqhs%-cEMxLRew4(QI`kLK$JzM4lm8k zA0M?Vl{b4Ckhu>{-zQj-+-$jj69=}{(C)rs2o3G0lPAC%zM%YuNEnW;YN_lDujB~# z2^0$7zdU_)FE$82`DQRUWKfR?#{~n%jPto{N2CaNsULGN3f5)v?C zhhK(fRBG^i{K(sO|LFu}|NDW* zhayK}uD9ZxAzG)Uj#j`s`lLrVb4OA`FE;B4O?3tF%tb5KnbG`;R41TLg>_1=Je zfW{5~jP5QOtMnUT-QQeTD#KS*V!N`%V{<&o$bI$&eZdD3YmlLw2U-l)W8Z7!@OTB;j}P1p0| z)wCDoh$W*NUL_#iB+*MoBG;aGCkMR^c4;==zEC{A!jxs6r>T1VKiD0f)4Ht%ifwi& zGeLp%qT5dVi+~FCWy}L7EBVx77|~H$HM{X0KL&`OK3`RBg`vQDZ&RLmpIo$T#k0S4 znW<_skKWssYuD3QTpJ`R%jm_5^8PdN4c?wNz5gAZJs?SqA-$fDRU4CGA^GWmEDtf) zkxX9QO?sM;e@rv>F-B-0-LN+SX`gwp^PL%rNlk~~ARKquAAfr`(VJm^sr!s#9RH&pppYKg;@4rk%Mwt~R)?Z^NfKeo+=Wq; z!ovEt$8ddsD3=5jZkotYIT&VJ z-=px&OUX707<14jFCh6Q#c*GdIg@@nCjkP?9AH{rkroA82k*{kaDTbhX;l?=;f4(j zIcB)rfBysi7W>Xk)I-ryB&{dajKL2?{tr~*kRS-#^4qJs+YYFwq^0O|w^gm2X4k;W zGi52!=f=uoW(n@cjpt&sNYON-qTfVJSKSOm`~J4@m|^HoE|h%-gCO;Am48ko#&!U z?)s)m+jDOZ}< z$_Q%R_9x-~>zcgY)ySsoQoWOD(GNH-LBmvLrEF_SIe(Y#vFhQJ2z#G^)rpHstJZh$ zUM`I?Q&@J*0y_JihGeQvy!|%oi-8rk>l7#ZBt3EH(Jfh0c7?rcfo#xv`c(20G`9l# z`%&4kf~H?!A+etGg>H;1LY? zTMzr(X+gzF4F{(=HEQ9cu-#)U)RDVHkfiR4DwNGHS6$EfyfN$Od!xrV=H9pC(qG*qk%x18y|Q3uwfY8dm0u6KYQUN6 z_QOtjmAl>w<`8&1f$9|ZqPhFP3s9B%y0*rzvA%No?hpmWYZyH)u*@I+Ji7UF-a5y1 z>+piThasO*+6|4!8)#7OLt7&>-#_auQv~QT4Wr}~;{2of-V3Az$AETuI)uB}WUkS9 zP==KRB7PF&1@33K2M(g;04Tgnf9_s5Gfq%=5)V5FU>qI8m_Sp9Z1>~t!Zz%jPYx0L z%1?bb0RKnxlpKC>`PC+Gn*#z0Mt2ZZH{Bqv^)Z0C8_thsaPMWy)32jj>9j0x69ET~*&wx41< z_R}L_Yy;WE2J9Jb`a*_}F>w;6hQu=%ldRHHP#eF(UZ}Dw*V(|7yw@W+2zq37#3Bl5 z1=d*V#rEIB^So!fI4-9H6I0RxBbkqkqqPn>j}nHPdN+B>2MfY{UCbEQo8n5!QoLQ# zS}lQU#Oy^?b*@CA_LKfYa^JX34~7si8?R~VyKXWXi_rKizfcNN>vSh(QST=*9;$A~ z@Kq0%m*z%KGIyfJJ+}GUy{oUMw?rAP8jsubg=YGx1Z4$NaL5;aMubl;i%QS#p;35j zBBozc*?3g`F4_5aU9*-L!KTSZbrOor>m={1QZ%&Skm*+V(E#h`Z&F2=|8%kQc#0`J zh*s-5HtH~G4=RwTQL8H~uAOGxn|-g~8WqxVtgd^?HNQ_3IAPwgp%?TN8K->>%1bX-xoqtAo^MF8iyBmE%mP^5O=(*8^df1Cw>vR zFIHakm2lT1Pq>+Qg%C@TSg%O?Qh}iK zQPgne1{Q-ie+2uUG8Ee+vYP;GEYZ*R)z~)zhRRWV;!shDj!w);Q3Z^na1l-R> z)@E@H>-iR0{V-Y7M7TwnP6Z2rs2>)u`hy|Wn~;J`F%2oM(Nq{QChtD@i=*`wn&dMV zaQnp)WWBIS@pRK{(MaqHD}6Uv$#S>yL}`DBLni?4M?zj8cki#b+RIKw+y)+u{!`|v z3zfFB5T)zstl8awoIO}EB2)Fnf~%7RlZnS}^p~4-QA}Ec=TDd2u9%YgkH{nUb^Yt+ zs9OP7yx_={BG54d>*EL(>tb06p?o$w$+rJJv3<|0;wEJ2F~2e45N{huIzyfzX&UAG zbmHm$q)COv5LC|f_h4m{9b=u zi;oU+-Tyexd-;67<%}lFFaG_=PG`FBzx^JqyC1-862ua#9+B&c^Dvn*Z^e`74j>~! z1MAcJbC>td8zz94G(Vx?SI6Z<5Cp0Zc0o^He-LdKh)S^%UJmYN5G@pq~H7(BU-?3TN1@jh{w zv%ceDH}A&!@Kk9qxO~Q9>80)Wcr_aFn`K0+8U4^2;|GIKq%rt%c5k6sCtLSaYQlwr z)Nr~}bxZTG$gkZK@=hL7dZi4OMS5WiyInkel-a+z>!|^#6?02OzDN+bo~+;zS&!%U z($T3UPnCXV8``)ARKRtAg$;JPcq>OymQx6hfGlwwg=i zAya87L7Z;Zx_E;|GFP86*`Fc#PCf6vLihGx-Fs|M=eUR}igqA(tva;G!H+vAT}{?mPdXYAF&@N<+jLg$V-7-Weny32hm;89 z4>dW~3Z&utg=bKaTszH}W&~!$seSVBf>Gt;O~omqzvNCU>ux3A35L$kZGV@RR?>b4 zaCB828>y03#EB6UJG0qA{jqhZOUoz6$3>#n!iOF_r^7^oI2lnbD)EZLI9V7Q*NZq* znHS_`tjl$DV>q#sO6c?>qBzKiur{w7-I6(r%W4}txXzXeUrDjZs(aGYQ_8Hfmoeab z%QW;IuVZa~sU*e)$MuV}brhPb1TyegscYhnrNUIEg)g|9*)q~kOy0~PZI=Z#XRa)L z!7XC}FiYx4A`IAWR{P8C;;i;mRWY^=cMB^1#`x7*fhMb|$R^l*>Wx%1ur|t7jbab!EXT2{vbfL$^L&2@DjlEvHlc>=B^PJ%zQ5Rr z7#ouok9k!lfuf=XWCeYMNd!w&PO4VuQH%7N6b5T!{MZ~ITL{>nwpn8gJt@!P& zKlv*Il?ry8nLPt1;z?stp5p$&vngrRn-*fW^0D4zRWVQ$eBPD0l?0xOLQ1Ll5Iii3 zeKJIKD|zGO( zKXrq$EaN}D{P6KjYhtDR54y(;Vq=10_p*2L|6%uZL2T{^V*+1N>o3gBPwN(zD^;3I z!gQ!>+KcJ=Dp4)InIK|FnyuEHayiDaxqFiB_G!6D5qyQNEGr$#*Tt03RO$Z?V^?`D z`sv%EP1#{>TzN6#$gPLZ^}2em(L<;rp}WdxA4}}AlGuNvw}n1MwB5u$E$i~kc<|DC z(XZAA%nNuC;$pgLIv{`aBA@Vy;q4NZ3OqPHt6PEcJU7(0x zY&#&Z-#Ujg5iW?WGiMPGh=06A!Hj%sVvH1K(RS_Jz?9uaK$S;HMHD!n<*Ut{f7lZf4ab3cRt?gMg*~w ziLVPOx(5=x`t=q;m#^SN#3TcTGTWh(v}Fk>rVsN)%FAm~PAUjA^c~|ECokl`W8!}u zD!}?skt5CgW=OQnwXC9{u{m;H%dv$|kU@+BDZPE$fII2N4j}_nRrS zZR7r_e-(R0$5F>JE(m&4%nw_$#G-OaQgLkx&|CO_O*4c*YgfMJ+WNznAHZl%c6-@z z(fyK?*!scaR*%)a(N)dzydrGdHjf#?I~UW3)03}SFMllbxL*UTR%zK-Q|b@*Z@%@2 zy8a-9@@fzI64#TCHj)DjaS5Ft<~ou`ct+Ew|Hdm(JfRQ>xN;z5uL!ZG{MSO1<4S|$ z3;vAlO-PzLiXj$QE<%UwiU7xmgmlU;_^W|_bCeM1DaFHDBBYZ>H8j0*P;9r~x1A() z5@t|!GpCA8SH1Wguiox?QDHde;z>*+;HGC3+mQs~`?oH{vwNExRDdRipVE9b9#nt0 z`)@K};Qx^ImQis<>lS5z;2zuqB)F5p-QC^Y-CcuQ2pZfS3U_ycySuv;Ze6+ez1KZP z|D+ft9O|5L_FnUw>%#R3z$JH+$|iZNX@}75>s)M6zKPI&MbEN zbB>c3F-)L#*tmTsyt$vBfdwmugm5F9?bO{tI(l-NmZ?KDIJVj*>gmSS6_Ezhfe8uu zX3=TSq5v{7NZbCAzp+SCB#CnO7whFkoD=PAC^R{#G86>`1>IH+MlXLeU=X7LW;u~i z#^X4!gEZ>d-5Rb9WhOaV2q@9(u5&{Ym+1Py974-*@XKGC>h+zwm2ZCd*i$aNWdzp| zpTzD>pa(K*I%8m91cPl25+a69-0?ev1FRvV*>Yg7rb565Do;1~v`_ta zDb?i}9UYy|!PQMI`MNQ;e{fKSBd@h-=8tY$1cv`qixIz;XGTUM06K~b3k@e*d&N+r zN3>`GmKWdCL+112j20^hMH^=Apl8BcRjjK>l83-2#CQR|kY!3U6BEjW0=_~ByR zY9r_dH(Hf~pI;w2uSm%jn*p)p5LuPb!tUuNFOLiyr!<_coWNuTN;@(e- zzn@zcHEfr}F#|_K_=jTp6l&B)!N|7~+g)Y18%Fim@wgnGv&A#09MR1Am^nb{d z9nt$(WC0Nvr7y4k`>Gj*OAP=5^mA^qzsdoSO?Z-y)2>x&I*QG(v}|Xg8y2DSd%+#O z!NW@vM;r7I4cy8?SDZEO^2~Y4U(gM2fVpivu$ovDCg1vrr^}`i7pQlC)fEx~^`4v? z0E6|JCm6Ov&pon@-_nZDHYLhyO%;)o4V*Zg@P;y0@r)^umHcNHP{?x^a$E74RZd0k z>o89YA!=LF)EveMG+D!f(42Iv5F}2;Xwr)tTMVw=zt00GE3Ev{pEK`q;!nw}XGVM} zLsr~4dEbh3n-m&m%U0r6(qwZR6NY!SG?AOr&PZ%$djVaSoZrsp3mT0|TnO8V>*+Cn z<(&d`X zcKhs;W_QAtrf<)8M+=qO<&20wCsJTNXsgY=v5iFacyz|;UKBFgU^~NA`d3aez3tGf z7b*l(7<3^w(-;wExSX78KnvQAuN9hCkvCQ`$Fdv+OuKjC!m5(P!v>fi;nwv{j>1wZ z(l+l)HMsX9lvb3lN!$3w75lWSfsDyjAql&36%=dGsh*o(Gwxm=96ryC-9G`1B{sJo zO-$k4CjGJFIv*OEi57J=?{_thVFfxH&KR)q$z*Zh`8AGw=w ztq(!s3k38 z_q4rAIE9mDPsqjJVb@=QUt3V-p$9CuEqJ`{2;+=0xu6v6YT z;Jo;2z=1eK(3T^$g|JEW*SYsX(;24o=g$ed@qh1epjq!LXgQelSL9iKQHD)-=G`Us zHCQ~m`k(PKG1&6k7Q3aFt;T89kN-e{HlYfjD2B&ci??d?w|Fag${|ci7CzO$;#y$+ zxSWKVor+pu_Rxkur&f#SlKGhAgK&nGvh)@%5^O?_>~cxEIbqlsiV}h z!E%>*fD_#qvT*%)y$&f%BYvFRDB4*+`s?4qW5qVtb{3}VTUrp)($srrl1TEm_$kH?2^^JS0t)sWlAJ*yh~_f&3MgbVK{j5Ej2 zFyQ--v6d&+HHTB-M^n`Z{{W>xV0PD+x`pJIt~zpgU>Jix2GS%S)b6Z&&(*cgQ4~)A zGa6goiuv4pyk4>20x%P`Pbr=s5WdYdZr@MEH|wta^_T0`Lw9>xYEg??v}NK!<+y=NfaAe&_~EOpaUwG8$s;w4a+ywtN?3qRB=Z=Y=kqp zJ9m3S;+x1<&h;Q&?Ha>fH`$+{1Ox4jUz>*c>mrq45pM5|W(Q-28IVjqw}Y=rrci8l ztFSoZo5_KaadE=(*2JB@mRy}rzT~}Lx{;I%jA0cylkieaI(m*jS*3=gi-woxn%O;%5fM7;-$i3Y(9z zKmaq!o0@)4kKl9Fx*WpHRBb&Vv0w{dlw~Pzz3AlL*mutKQ&6}R+5k6R#Y-N;n$?wSvy2qe`3_MV{#$jbVz`k}hj zYRo+wUeNO%-7Aju!dsEw#HMoezW$`pSvM>5LA3G|-(UrbdBr^@o%b<39ivq+@pGZa zU4s4VgY}>Wa?b=2I&3VnuX&l;ckB~i6w{9|O%50&Z`~G2XzS%lfvs2_&(X9+M z#uK)s9oIp1_l(=-wvvWCzw0DUG-y$pWkSgo-wWB)9uT|0MrM z#l89nht7XqB#$L(?^yNQt4vYe;0smmou-lQgzoJ#m@a437z2*z|5h$#&v zQaB>rnbdf*VXKB2I9!+5e45OF%?g)&3z?-Hz7E`uh7088`{s{(DFYfWFE7nI3-XEz zt+10k9z+M>kbW0CsMmYC%2zk6$_|T(PdQzd^geG0G8sHrjDB@!`z**Opc7?l!X2@T zJFac)?7P^?X5$;I=9g=8CiiJM8?9?_dxXr`>2jFE0~9bvU~Syr<5)1m@2=8A)})$J z=YuKva-@&Md9$}~vNPJ8qze)F(MWi;w>^H?ImlnW5Fyj8MW@${u)5$ANO>?3JfR#E zSKJ=po$Zg_wBbl@W`_yA(Shi&V!3;Ll+L&nzY6T@xC939dn-E6$!{dc^F>VOi zpQ!Ioa9{R+PtnO^GcTpb!yG1* zxDo{Zu3-`~Al)=gd>%(pf3&Rg!Q>;>hq;m{0r*3_wprLDtCfI zv>L90#jSZOzV+`tw<)XNtRp3vZF?cJUrh`uYqkEU=62&iZ&3-*JXo3@LR9Ks`Bha+ zvi=DzLx6h^Q;Otd^$VQLK*LptjJX|Os(EItph6P%q635WL{A7c7Un!&u`Qo)viK3o z{j}qVP-3H*)s(Z|J`Chs=om5_C~j`t4M+Xr_!(_$$^1vWQ*WN)0?KhOW|KE!&AiLfEeoj1zNJk56hIH z{{c4|BbFZ;N1qM96dNZa5?=JQtJk}QO~!x!d%L%)fBPMXglgf*Ao?g!o5TZ;anli^ z_VC?vi_sB)g@Y3YCZZJ233k9^wSD~&7}p!#m)l^qh4|rw>t%R)nw(|2&UAT8ei}VX ziSQ~$SqsrTKH|oOLg4SeAPzoNB7GQWx5^RzZ{ZY&SSk3qog@q@v=VKyEAP!#LIk)K zBYqX-p=yoyl_+BJjy~Hty@SsVDJadQ@w^$4NBF3b=sZeus!Ps$gmoZpyM; z;yQHXdF+Fk5U*}Ux3n}CL3fE4JF1*!y12<(TF>BOH#i$!d45500S)vT$PCmhbZFE% zrr=tkdD@V$v?BEu+3pW-G$3r`1{-W-#p#ZA{yZ$`w6JC(zipnq8cQ5uT2dX)r20gW&NaJ~6RXYCww>|v;^&3}r4!6d)nI2eC`$0!x7K5>Q!@cP~gBwgk z@e8&wuT#f0E=z>kd{zTD?|G|@2^r^K))e+cux`M-0^IR!~7ML|0-Xe zm7$0aQ1CFH!CH!vr*`}aAEtksM&`0X;l8{n;OJ`C31B; zb?w2(4<6`#^JY@Rh%81!O!ob`nKIV1o^Uysao)ysx~^{suA<2%kn+;k(Ryb;U|5T* zUxMKHdr#Y`kr>V#>>Y0Hjn4P>C@PcXLu)p%36ZdjRL+26x&FMH-O@!4G(nR)LysWE zAnq|O{V=+zOt=~@*EeJZ%ueOVEtiHay(v3`VPmThG`}`y9_e* zi=_?lIOW*r!!7oq=Gh1`IFZXH-5>fF{2L8Jjl_{-2alHl3cL5q0>0Bg*>Y73&27fu zF41G?g+UQJVyTG~Eu7ExBy}Lf`6UG3+H+u$jQgQ4w~7#^ETG`%I58H-6q7NJ zK{k!%7Ii6L0trxxUu6T8>H0pzO<=L#>OKvvy<%o{>{{3?9bJBOpStDs?q7~}@81ik zH^OF*y%Csiywh!XZQC_ix!359^&P9(HFScF|=O^0mv0`h+rs6FKcr) zl@vckA>7R!bH+o!X@&z)5x5jFILq*a1<98maN_|kLg)G?Q4ybEg-?X5gng~BRKI)h zFD!1a@YllUHp%7#~DUXSjcO6FwPFMJ{g1WLll7i$lb9k~KSmf@x zF`DMpa~LQit_8vzQ+S($&KJmJ`y`opssFg77^n}esKDh4a`-mwy0C8_if6bUb?B#8 zz~|?`TsDB~;iRrHua8^)-IxxBtI2q>7I~@hRsI`NtT^|7v6dbB4+Hn<($wn_?h_K- z&9_J4*U1-hzhyN9FQvlO^nj{9+N)=M>-YsnG?x6jD`&kQV2VOuL_fq{y>WmSj2N+U zc^WX%haqwi&eLL8Z**aic(jqvBGJ7+VI>mz!)|1~6RtEZhkS2C?N~(nJFB#DpC8B9 z3xaL6Wi_>aFFCEkxmbUn)+iSbAz{J#{y;!k*MPMkxfsay1S7S*Bk{e zufsQIwvT-<6JLrT86y`q&HwC)9J_x*$FdX14%~J4fPR~1wq>HG-aay5Q-KHyXJO{r%Q#xfKpmkX#A$b~LNR;96 zvN6i^zJSVf@S9m8CQcL>NQCx%=56YB=IU~B(kLBB8#^NN^ZU8K$Mww*9;bZ~o(3+A zS&F!y^O#{h!K?xuhZ;LdQyst$XI%xD?Iq*50X*{z#lsxjTrJ|-+q13CjFJPzt7-)k z5@7(II`-o!et5zgamWdiZd6(`^kP=75HHrn_vP)DMoz-qiBt&h5pP5R?AJn*0AgJ=9i-zvV7 zjG<)^3l*Z<%C?RO^YsdoclMIl+uwdz$aaU%GW7S;R*4zuz|c)&BfW2a1<__yvLR>d zabZ4W&-d{&7&n*=Mm*>tKG;w0Oe{Y&-`_Zf?01pO?^~GYE*BOgX7!!+jp>uxV8so$u~g=x%`X1`5-^I? zRLd`nH^8)j9n=)kk09+_kYu1?zbVzFM)cK-y-5G6{?~RL)Fvu-%mJ<3Q+JrZa?yd7 ze|6!!4Pknn|K`^7V;7EiD>!@*C~##2&dhT4-LIWj^WNd--M8hIi*x2PA3cMP`;r`% z{96c_;=FM~iG_2WxtYyfy!$nw;&<@Or zaymsBj{nJ{G7#$SO*ET2!n5=^@9_`AQsP00Wd5^uI04lgp#N~TCx@*R?RZXloC->o zbijVjJt#H)QLgVeg3f5!2pMGbXXQ?D2%}_~f_Gmd6BV#taFA$ZYC%*A^QV;$_CR{H z&=zwPiyz;@XZ)TGM(T8AWCRWoQ5mr)R{=s3d#?1WEVM7Zl~qw?r7*NDjevFb5~X5K zDkPo=_ohPqXkHH7yif}EEHPZ^# za>Q3?&oBOko5ObAayasiL{*)fJk~TvmcyW} zlvpC}$QRus{8cbU*=D=S20Ejj^mhanz6Q2Gz=X1h{qL@5`f%{mt#hSni4Ui4nD5nL z(|6A3o9?NIcE(J7qfJFVjdXPiKA`wGRJnh3p}Ql!dgS6xthitAPf7M1eF9c`4PKNT zb4P!s&o}!GO=jcxF2^(9uPUGNybH+Lair}#u!bhnpn+7tg~T1luZ&FszRiKl__0f= z7LR?OjI!>@_OOx#%^OMi7*M#>@uYmszKLjTJ0*T)@A|A4jCalK2-oy!K=g^qHSJd_ zCTwsyp(k{R!>LSoM2vXBpIEPPg+Kqh`AXKJLY$EEqt~p`HbNADjzl z=+?j(46Gq9uLbW=5UzCNo_mAG?{l{lN(6LF1u;Q&%4I`3c2~^ zl@EC(FC5BPq}VN5zD;%fv^-FX|3qF!9738|C%0a1a{$P9{nl;2!~G_fP?m)0G8Yr` z$gmIrsdIv>a-4%b5Z;H5yUU+hLs80!)y&D^us1FGi)FgPu|g-!8kKhRyDWKePG!EorMeqgVeEZxdbpt9z?Y~p@f!ik! z0?+(c1kgQ@7^MKHv720edEvmNeu}qXA5sv^336`8G3} zy2?8%IR}Yz+1k#YTopDK_-pMqQIsD&oBB2b;iGNDB}DgoN0)P*n^oSYB6r-@en;=% zga|5XAm~4_6ja!PF?cN4sxmkn&i}(FIz&l9A?H9)Sy@@z_g&&(v~&Tbq0Cb5$?4=H z`mZy6p6bt~OFhLRJ#aF0<@X#Sf?HzpUgjG54(N4j%lh3m!su+gNMvTD~I&+Rip| zcxRF7v0;Fba%?Gf#<4zopv?e0y9;>ppzP8-4j}6imkTK?B-D%Eu{p&XXC2b$Ihb8?LIwyb~*c>UjTEIM*nB(yf!!0uBaHq*AqZg2%hgfKrejUw!ybfR+!T)948tbL< z&o&1=zJSNG%6CD!JNRhF!VpnS4caDW-Igo@R9T2jP?KX%<}$!%8UPfr3D&C z5@WjhzPTY>1l_hbB9~y4-F^;954iMlMC8$8AyX_eOT@9$W|)P1c&&sD0`#>-lCeCQPSc!Jj`l0 zKV>g`vcd5`E-o!C4T6s~=TSjJXh@GuLtcF~)Bn5`DgySDx2Gh$d8}rXs3kWG8#dPd zK4G^3a^y@>U7nDy(hsa5bHjR^$*z9k;oPYMYB$@Tl~ zFBYaE_VjIR)9FZF@43x1@{Z~7>S!d~-o9<;Ht_RM>cIaAYdiMfEktDB!|tVRQOi&z zWc?}pp+H~SnfvXPA%DMGhpr{^?@|Jp!Yl7)08Qr@#}d~bTj;=hb={CF6e0se)WdFE?&w$tgNiXb@dzq3wy=In zY)Z4B;Q&i}0~f^|@E#cU6j0@Bn1_Z#dBN^F4~BQrCib03^$Qqj66am{D)w0kV#4F1lo9t`MUOlG z2?#pUtvlDistiFwaWDHSh%dIpwLkbt(uuv1@XWI!z(YRvji%qSmy*v}&B@#c5L{Yc z?0$-ifX_c7F>xv;F&yQ#;r^veITJIpUJ;^GfFma-Clv#gfRRv;7djbeBCw{<+~1Bt zNlDq-7s8}LnRH@Ym)o68?(EPvT}l{Rt2ic`(XKyMI0%Ihx18udngsw@v+x%Tx=>6; z{Joz)*{r=9pDhQctuI|gft6sn43&oBSA<`9WL*Yz%aFp>7aiP(#^del9%dtt-DnG# z3ZzutmwL_pyp(GHLD6FVnMjBM>X>x1EG%fG2u5H=fRPaudMBxX8gUL=c2UVHdOzI9 zGu>u6yzk!hi@1RM{AX}a++DF_qb5JdAkWl>%^)~#;Z#R@~IBna*tD&-O5A)?|E|&K&KJQP5k0tS0Rr) z_SbeEkX?&WO@!89i9+YDfvmK6j~d--OVfz@d93X&ut72TQe_hl%)`uASg(GkxjI)+ zNsqP)BlfkswGHJsijF<`M+cp7gE1&*Xon}%J-`-CZ(7&8XeaFzk>1&AE1|b^nwUZj z=i-dDf*1M!s3iQR2|fvr!cjXaOJT2|TS=AT;1uNj{*r17?(!)tRon*f^M$5#u0cun z!|`05iCS1CX_tnswl-MDXZ_Ao`=A6ZezBAC^qA_Lm>3UfPKFMJyCCFYXNI~gXb`r8bly7uFgLg~=j+RHJU0*mDPxjl7jh)4YAvz>r(7Q zwGv-B!2TXzVwsg3Zu`Y=ovbze`snZam(TM2$~~iqdh(q9E1Q@G(-*-Cr-haKI6RDH zMA&%tieaiL6nkE(3piP74rxg*Neh>U>}#rbJQ`#e`|^r?w;6yg>heeKjHapO z@8R?E3hF|edphWB*4znL`acwwne~SeDhWlu62TwrFFP>PfA~(I=u%v=7q4^S3rv1<}!`CGPw*~3)W79$foSIb;&Ha!oNupIJ18{PJ7aF;5 z{yEh9_vi0LiFM|E+OzmEFiaZ;b@EQ zV3?14TU>K)AfRXsBJ)_0?>%1&_N{dVZ2S`7Olr_CruFXE2%99oEfGFU+&NsTXfJ zd&rdop=ra5)(+pDq7}9EQ$qhC;>1}vFBxmK;eb)as@~VZ8-vwa{{Hs&{sUdC6Bp4J zglgMc8af>&l5*1+wnaWV?H{POA9}ENab}H3Yxh$jM-^uSi}szt%bSeBHK!gtZuivh zIjO7!h==2Sy$zZmSsDGv%JkZ5w|$=18V_nIYyD6KsO8Jf7Y1xP4K!THy-3?!LulxF zdVnyrCBm1v0!}ilg3>EFMj9UsFI0xlvpmYJA|$ve2)8UA0;9Qx^)d*_!;V5&d(_>6 zU5bL~!;ZAH^|1M#GmrIzT3H#LtvR^RsC&)zL`!b4AUU*uHYP5ERd+okZP##tsEH+9d9juR{>e+R= zB92W~EfmroQy}sGB~kDhhVpNNz;DCALM8U12Hq}UQxCbPJQwC98V^1YJ*7(8dki*H zlvKOZm5xILv?<|{&}G9 zpR}(;h<0V7a$DFVqoYs%85oycgrZL7)BHX<>u@(9jE*%7p{!uDxWe;+Gf1;PkXI^i zWd91MGi6Gm_r9g9;xG?6XeCEIxX9|{coL5C_>lgfP>{vXg*%4LapRuTyp#>gxZDVB z>h^cIRk7ZZ@yv)Pn;aJLAd2TA&tLHfy^dybsOZ(n)yG~F{>B|!0NwNAd=$(I;I59& zWuqv9tr&;d{>0pFXK+Xm3st&NU>gsv9A%ReN5J##UtQ?STB0SMM~<_|k>H2vA%i8- z`=*i4x;-ek$*+hV!%d24<4tzV)n4qF2wuz129NIWAa5`<0CSY$1G{^R+V}Wi=2#Gu zR~-)=9hJpzi5ka9Ix+L>5-E9Zxf}jUL|bQlIBK9=Y2Hz5Tq9XZ15< zp!vspeNjK)$}XFZG6@{|=G?DOZ^j))qO0ZB#s-jkwq2qITDJbt1DVa27v)zVZ++vt z1;~o0Lvop?BLZe%-1Qy?0WQy=_M%Hm{ly|p3EdCSq5GI~*jeV$(Z*3u;XEO|aE6YA+f0pZkp+|sIG6)R<+zAGz zZhe9;gg9r;w=KG^Ws4Y7LPKz}2u=tVGcUPxO5bxV5=a->RmVCii}?#ap)e|)9q3t< zQhrF@BJ%m&5W-<)%z+6TO_vI)E$V4=Eq>dW#=nq-S}Yu;x;SaDvgPY)wzjnfKeFy$ zkwszD8W__;i{@b@{?W}H1W`;rLd8%o*$ZL!j!b2R;xB^fdN8rF!eWy@g{{IWpM2T9 z2#I1u(-EhEvW(vzB!r|waTwYNE<10y8e7Q?5Td06nQMLba~r7fxPLam`KQ#27Gr#b z#ZzWS(<8bW6c@EY4QkBmEc+WfYVk~To$);WjjT4!PA`M#F{sb68Bg&zJKg*w&bQ%z z#A-Ml?wEk^@qo-B>U6ycxv!o)P<<$W-w`KlN3`Y$c8#GlX%pATBf zOx}g#6sf*t>k9|V14LI?XtE>Fx6Zu#Y48WG(*Se9C!BdmXOq6i8`j|$2evc& zPN=@*w`#^`h%7vQgGn6!Ud39}LG}%?9!gfl*S{D{c4K$)i$DLZ-v5n89_3=v4T!VW zI?THE8KS)QYV2b^@_4!M+|wPYnHYWyl3ckf!4_ziqNHSx(jsgXZ-z^fs~LhMF}4WY za3)Ue2etXD1b0eq9jCwJkb12uKN^P-aRsAyOlE|K4Q59Vm%VrA;{4g`IOaGl3Ul0m zCz@unWnyTxAe-R4)4;7$`#Q9bLA?^{*Jt0yi^>-P_z2Zb#?GySL9(53I#v)eYaz`UVdZwA@;J z30JJLK`H02P}nM`RC9dGZQ#{1Pu*m$ER39f_*$S8#cOb6JrPv^IDGDo{RGvHE9YywwkA*iQsPrbB@WvK(56TLJ3A#gdxb z(s}2$beI_h&VW=Nl%7?Z7vw~$646ujgcYM63w)^|%<#m~Y=1hjNa^SX%-$!}(TOt0tJj0Z|UCF%H5^lR!ZeLLNOz8EjfHWZNkDi!S(&12&1c zUlk1w$p+~SpIYIdTo&LQ1g{_g8eY)$ z?5O+hZD|dOJqeZE4h&}b^+|8)-z|*c#1~oRdhd1_2TOX0YOaB@Ood3j-Stlz)vK`` z-hRR!TGTx*iRAp`XmbbPPMj{mF20S zz$zMtA}0Kej!2Z#V3pwryB$_vlF%ka2gdgu;pk%xB{f?OTCBLNN+&OiUqR{ zWLV$7IBtVJ17PX6h;#-&uRUL}9x1ir0=qywSsu@nnBh10fRSR`9KJIjy)*?~MB3ub7vX zUjT)&@<5Tm*sU~aINT#mlXej;q~?qfO|W8k<4Sx*Bm zv0n)+HYPM;G)2`hBzdP1@!I=@6#fLA{gD*N3VV;neoWVXe?#lx`AnPI)Cnh6 z2Th^-W2J#4NOki);H(xMcVjv99fvn)HI8ABn^C^cn6Wdka5+qGmzq)9b44D!%=DR5(;hp)5qiC^+$$OG(n8s-y`)s@mfxOm(sEG?}HZ-|6PeK zrH;LLoM(S%h)4Hr*`W`Q)L9D=M5_wvSm;(crRFKc&)AXZX%z`~RUJF5ikdBy3tV$- zf4LM*$Ju(n)NQ`+biNuWR<0gE4^v(#+%1UTb-eu0jgY${8#4)AwG@YT<-mgkbSskU0Ta^XDmT60mvq0?7~1nvY69gBn{SkX{9a1FTZw_U#v>F1x8 zSUXN;s^>~nGzmxVx-|FC9IF`*y`ObdbL&#k0>K$Iy2ERFFn{BD{{z2&)Di|O`tDuM z*aez2j`LmXz;pA7OO`@WV30A1F9_Z5Cl0C2Ar%dDWrSR4A?s88#)e)~3(dUNQ>aT*H|$XrHY9Xhh2QXjpgrK1XnvPN=| ziEwKZnpY}AMu?sEF{v9+5FC6iVHjV)sRYU#I%WT~V$e{orN}{QRSHO&(U5%}%Qq%n zBz?pp{5l6y?N)VjNsgD3$awzrkK(b{DzGiMOZ1J_eK=GE&ixSY$Ms&9G&uXptczrFn)-+| z#r|Wc6Acy)+$_8Wo(~-E+^J_PzdU(eG_X5F-kFbS>VCbc#Byjco_g1S(#!l{TyZ&$ zQ_<$b#th3RhnAOWG@5SIi0<0;LyDyh%5R1PDU9~Ku~xt4YcpdI#hZP`9`pQMt|Ydd z<$Wp8CWF&R>;u||NG#^vPgK4Fckq-|l7X9IF&{&S{vviPO%D3L7`~peQkCD8aQMNs zAL|BQkfSpn>xsy9q9^N>&Pg(Z?AUoMGq;cDPz~AFVuoQaL>{k=bUIL4otWb~2Cf>9 z!6uM=G|xVw@YgO$ID%yYF8kS&uMxnb3d!4~q?{k3J&pPs{lX7C;dt4=U?f2%HELxJ zulpyGFXW&jc92xN&p6ySP4a2SBgLaM{LqqUQjRKd0=l#=LMXY^@LPs<{H6xfp&3(X zj@yY<1D$753R%A|AszDKz|Z7LUfI#_$GM1i@yF|qCs+6Ha@WYyxQ-_R1>#fL8okU1 zJL&PaPZ%DC!bnwZKA$nOVToYxho-H1W`ADv#R(0`={hd_5_!Epcxyf_C1Kv4VU~!H z@4ZrfCZ*=l#LRdxoa|zaw1nc=4;uMkXW zEoDx~odLf$;P0hSCyF<(Punb7!k$$e_$y^8NJzD#axU(rCz zNiBXJ+aH_WC57XRSR&|!`a^~BAR~Y^A3<3%X(8=7xD~H4YOr{6z7mR8AZYjvEosZX zti^dh7xf9wmB)fJ_qp`;_TfcBmeswIad03GWuQ)avM)92-e^Z2!(p72yykYD@@gw8 zd;5|5QVb{%HMT?8_Po()e+M|%ur}*cJt)uaaO(zRwdCz6^zJAQw8V$Y+x;Q3BRG_Sx;`mye8W3QN_}pXvB>JO5gKGX zMC6{KrCh=Aw1zFOnA6`V-04hkzv0U5?|-my$`B z_tm86|J?QNCoP@S$nc+m=dj&DZob(=Igxc5R!wl&sQz(8kJr32g2Uwdtlhl3W<1CD z{UyVZcH)enH9}vhE52E{K)Qk4T$w<}cSr*y3v##l#q2@1;p@$n)q18Q!}EX*!iF9a zG#1<4i7(wzrw!HTMGCGQziHMa%Jq@du?IurJr#UflX|IJxu%cSk=(;U$!K zOkn6+vl>2c$W7*|KdR5|%h5Z(<52hVrkIp1FWT^9a0_F~EJRvydm;od)|}$}M?kMaT25 zmN?fBJoL)Ob%Y$-cZRM4k5HwtmY1IQoV9u4U@cg2TaWE~A9fJ0)_uN{g}GoBVxxi< zJbq@nBezes!(3LT^xzZ=u!DTI{MU0HR?z&OKT|1ZhdpeZZb`=l^`s%q(#!X{PjVdf z(!r59q9hLKhhFB6Tq%-{uhtVAfXf9I>La3(KNu0;Qv@e*nAKQ8>TrODBM@vFR9T;e zfkCRCJsP8b+RU{1N8A(vQdmJ#a94zIraBZJiy9*hLDRwj%7f(?_7&T68^w=p5QX5-!Z~L-;-=U3M)}2U243ZIjQS5I z2x>+wM5GbV)=b|stAWS(BPORwP+kFDa$ULnUU6e^KWac-7E5c3YCGk{DO095pHAxa z`TqQ_DVyfay66BEvkhv?mtO} zvNq)cX7m4#8=G(TjhW83udAzz&&oo{W^@rr4Nbu!dbR!`dKo1xWl*p2D}LMG#9vuF zGasnkhJ8#;eUeZOr%PC2Xvm~pNkw0wjf|`2{Nn5!pZq7{sHDvLSM_sgNlEv;?J61p z5pu$?#~c=P9+iPe4;+1&pfI?CB}WAZWHEB|j81yb+>sJ>O8TLi0G)6M9=r{La#uNx zf{f@nRM-8n*DjP>PlQJh6?x+n4^~;xRL(XhPEuh2t8`HpymVO1Y0Wm8(Ac}&SNzk& z`M?nc0M2bS%)DfCzj>FKAXL!&F@3kXD7T;c3Hi5Wlh;7-la6?%M zg{DKy?*)9T{ppThB9Gf6TUZvI_S ztxjMw8@TpWXQGJ|3eROc0%sBBdDmWe;=$oRjRb`)ElXEdeMc@M-z9jre|F=J&)!e+ z4{hlCi!Q>FhbC@(7pTwZOPWZ#q6dKG{WRSr(2UINKGP2YS5KLt;lH+IuEX^{q1O(;S zl!f5&*Fg)Pl%e1+&wb%3S-XgIA7&)UKFJ|&P{s~3^so;-lZZ5t=xu0fMH}+U08WMnVth!;V08jY>I;iV0gkO z*1#aTgdNHYkdVO6u`9L-21PXXO(67Wn}2O;jr_*~60Iu6R*bYT)zC&`{k(?uAGm=+ zQB1>|MDOiX&xZ(94ezvxS`5Pnfylpc0z`gTQC`FEh53?<}0` z<_@IsS#`e4Hz?!#8Ks6z6LC3|vo<%uYcD8c0Haqv`u6#1A0ZBG_7V)&|CO0oUmWHA zqklAX|7%ByZZJvwf7pA=u(+CTZ7{*z-QC@t;K4(%#-Rxo+#Q0`G)}M(JXrAH?(Xg$ z+}&Y1=e&8&^L^i3GuQl|pL_T2l2x^;R;^m=zH5o8AT6y3MTz8e6ZmsJ4u&uZem70BWt|F8C@^5wY2i- z6coC%#~lVCoJZ9LbdH@wk-c~gf2e1q=Fq`2uRLN%cpS6wIyQVB`fUDv?UB3~3fhKo z`671i#t5d$#4C^c=m$9M4i_z%GjYRGlTAbW{y(n*vOYTdfsWPcXdN;>DA#}3d&<6p z=C#j1iT)h)CjbsjJ&IFd8Ldh5tP~b=DG#n!DL?7IDy1$X*C@&NQYv`|?@F`Yn1XfYf zfn(&5w2!|+-BZ4O{KFme-=SGE@UYN_i(h}a#i9N4jaPyg#Xm^jXuE;K0VuQ+fs`V zR;(PI%xLf9FT?V_|6Vsi5C*IE@o#_DxML1T_zGEV!EjJR(_ozX#>RZgJ9=u(ts_$V z9?-r?MMS#BfalnMdQ*a!^NTgnJ^6^am%Qm>D*=z^cr3zX-<}|$Q9P@L74){NX58F(e?1W-LZv}JRQ+rvb)O*7MjF;NA@2=ZOdwVPzEoq+MiixE{~1#S*d&jQoXV!s z<1tvk1@X3nbgwb3w_t5wlg*F^p!OBItB5O1m;)WDS5RcN{TEalY@q5Dv2OwXh@6UI zX1W+GTnns)OZdA`%`mP?HXhQMqmRjqVogw6lP);p7jQ}Pmkw}A65j(HpSqwAX+x)) zkAS(&8|M0a6mRMK4yU&#J$Ryn%)JN*Ai=KWNIvFA6y@-tV$|8H!(T>sd+O~fD+sOe z<*q$MAZRA)!mYUp8beug8=23z{o%hTX!XV7K6ae66y(Xx{h*kuS2}};(T!j%crdhM|h~m%M5qZyNQf?2~c6CPL>aGD8!4P3-v8xkRjA9 zIY*rD3`+V`^+j8z;W9=$HMiuv$vkEXnz59S{qdHVe`jlMW&6&`oAYJhHcRh2s#Y@g zT3LTr$%@-=oO%p0;;5SwuIBnmlw(|YvR8U?=gXD%cuSRTwrG5*wgd#leFrt39%kx@ zvv?lkq7xCDoxtIx4}oj$$(zLnZl9!=Fsz-n#%k_8EUX!mcI(HPd*BqaKJVq&2sg^6 zVc2v3#3%hbw94d(?rp2zgGiEfo|SxZK3GImtmkB4jwgG^p^(2U?|xY^?+6wHrOY#; z_{w5Gj|dbG&!AClrYOy<&ZH^&IHi<*4utx9Ef;a^J4~;@R#> zF{Uq(bmXq39n8&T(?7)4L8lHwcN^0M;PlfA!e<7HjKeRgdijXCfIo8N7(g{kgnUXT z2-`%*1H)<+^Kw+1*F(UhCI@eDOc(LsNB4HVL}2G`qTlI)kW(kj zy8(q=UZR7}Nav$`_`NsbeYoje7__0q`r9cDIT+^y6ZN^OC|=+6J-l_qHWz!>Yoqa= zT7~e5hj2a}Gxub=iT2(`2gGXz8(lJ0xODlkoC6#T>KIaRVa&sI?3P!Xk&figx#np-^hC%H@={DNWWT~xcRdPSO> zjp-YI^lTn5z{;6*XQ_L@$XbM&d{V%P23Kze14Mrvzj*2>d!Y=W$o(E&0aP^Mtmj(@VfR}L_o+1Cw^)SW z5{uJGg>75&ZCn~`e?ZAuK7xKIkTwo4g*jzej*fz(4y8{s!P5JRW!6Hv0Xo` zrG#U4IK52jVe82@x}O-Hko(pmD_`IA4^BfT&Jn94h0tWEN}TzXe9b#XCsX%SG`Iw` zxJ_KU@h)?oLVS26s@)xd4f%>}_wTTkaY@iMTE^*FE|jP?{jLFBQXrFZ;)E!2Jn92}|J@sju|jvU>qs_(}7* zoc`tTJrPb7?EY$JGYtlJf@8sX`3NkI^%%Aj)Re1V&iVoRB0osumESdVM6YmcPER{{ zI4P)=@o(h(;K2F%)g(wYKw>yzutuc-y4ZNuZk+h5T1*WjNSJ=b^JSZa6!&S}kIw2;5sQkvs29 z>|#{Tvxrl>N*`T5-rFBzFJ=s9pko!h@*mS0`s3U>UvF`xLyE+Cnf`30eIy7R6NEUn zJQRH!T5S!?&4n0kW}kv{tA+xKn1^D=Inlb}uN`0mHR*EERGQ$YeZEOf84~L7fxux9 zvc8%}u2&s1T=AVL&AwfkRMjvT?(_$jj*tFYs$!hD-MnxzXb&M_&e@hM3Fm$;>OTVn z7{wXl{#!&H54M;3)meBalkW`Z;^!#EV0XY8&1b@y8f6mT(D9iLwWG@~<>S|q z90vT%=O_G^(=C~LTa&lnfou^e5)N6Q*%f-EMUBmTBv$hv2?M(n9smA%p#y2+_(qiypX1Ox5K;ub-MVMBLpjEZ zf=N&>?Ikqh1;(s^u4Qn3eq6s`dOsQ|Ev^ll|I~nP&&vMJFvPz$9I+2pUTFA*9$A%r zpo1$6b89i}Y|3cCmhkBtI#=<>E{g@=s8a z(D$LS+c)VM8*o&QX)WJP#%D z=Dcv-@K{gz^gWfXHgIqTxImZtHt83VPg5&G`U820@R$Hz9od???P!sfkCk+znD2uF zF7A!d{|!29h!rUs{ICD=dzHbZRu9XH8XD?+$+n8y%d|vB$+KFX*V_nER5Ruxh{d!G zoY?L~bG(rBvBxj!6KAff>>>yA^Ss? zU{ z-l>PF8+2Wp5`_Q(>d;R{9{^G%19sDa>Dbgt9Q7@qSt~3P(8`eT-2{9pK&MtfQ4u?S z1rfOJg{w1x76yza8hI9H`v&5?2$kbc;%Y~xo|v9qR&1lg71@d~FwZRc5ISDoO8R3b^)0|kto@!WAGGi^1o8BL1HPEbSz!XC+e__fDIEnq{cL00Ay3YDT_tUWlaOFe?8lB^;BePwh{xO0-EJ%UsbFWR=DFtEkzw{GW#`jYr$ ztv9B295O8nW=MpDO+9kuiKO)S6ay=sfUDMTV&(9<Qjdg$=a6`Cn2VbV&PD%Yyuu+aF-X9(PZT@J3QUCr(sfQM@HmEu%(N zPcwnb&s{XpUA#_Qv(jy_sdjMBr_jMAR@^)t<1bL);B?yoc88#eD*u0#ht z5`oo_AI?>F77Fb5!Ujs;Gb`xNP9hD_aOabw)G2PhpvDZ~mu0?Jj@PHBOmqmt%m$CzNEQThpjeqo%@I@yWJ8HpQ)sk}9_H@+0B#8g{XHa%DAY3) zG9ih^vI2?53OS_1FG%L(fAVL-gL;ufTz$N+l%utV zMs)uRhc$|XfLcS@$vKW#{De)ewQI=HB|t@Xk$uIKML>`mMa{fr(fs@0jr8)Jnce}d zbw`=x@KPdrnA}%)SN+XWW*IdME56O@XnBJ1oi+*1KX*N6Xi~Qxk*B|lV9 z?tg#!?-8lo0X+;}Xya{h*+1V4AKhwxbpAv9w?Uf!FXs-x_e`DfZ*L&A7yo~9?)-0l zAwMQsI#NZc?M0J+=Rb1mN$aA_|?_*I@n)N%w>h2$Mkkw3eti1k~Hx+l7UNUveBi z{_`Ouu~$I=a-f0m-Mapa{qJ(&{*F4Nv~N_9Jiz~m7vjXIQTUTu^UrfB)<0Sac?tMG z@)eE$=hOfHuYY9$DE{S*5e8tvgILuHFtEL?BCNQM=A_LLP?=)|aJ}_A|1&4PArtm}5MG%(G^twn zTjJAKzHsitjT^5SX&PwYza|jCnZi0^Lb!#Bn)<%zYl%6-QyxqPgjd0o1m~Yg27v4{ z7X2x35Gr)(2jupA#0m!R0`5qJeol)K~ zqwkj9TSo=`sV5QA|G({-EiBys6xRj1Y+Hh%{l)4sO&2?pF&~4Q*O20-&jnY|-LZWQ z>sLqw+gpF>`%kwksrTO<$|FUd7vGe>8R`4>Z)f&AW_L@(4Eb?a{jm04=5~2!8>!EN!&`R6Ps{JI%bNw|6LR> zFVgz#{x~Z)TnxHmk8@wa<^$UXM|kG47%W=(t4vM(9%JNa`_x5qz}VFc?Mt@f^yxwQ z+bca|ulux|JMkea{QyKCVExLmOnJ4Xh@XoHoE!u2{>2RK5GRPSueN8ZFK;tDpmL8W zTRZF#>M{!-cF1zX@}=6Y1-1qBj- zQQgrL+U4U^XqeqxetDR1?2Ypc1_sFUp(s^QjQ)_)ZASG4MmjLR`}hMEdUFJUdw+s$ z_Gk1Q_aaQO>iOIi*6W@UoJ;iW>nwdQ3|J*Va5&PC)7&L0&r@%LQojK17mGP{V=rJ_ zjm7y3z%X!ud@m-NX{?+dGuVwiT{7X`^~-5~7k5&_D?)^AFUa&XVRV2`o7&Q}Td z>lIk4RC7>|yRJTCi~>2c%kNZ%hN=%XE}6!`+t*rQ3*(GR^fy6h^sdU?eFb?Y`oC~7 z%{dLB;rjk>uZ%Xo-|z(!y1pcY|DC_4*ZEWX>t`P43p+jxJMS$OS8$#xzo8IJ2@(yq z+9>H&BSVmM&tyWjc1)Kxqsb-&s-$q@H)NzglaL*ncia+x{}Y*0pI1s25&`Q@nidHb zk~PsV7l=SQ2Iy>RTE8dU%sD&g=Odu^6K3W{f%SCz`lEa6ICqn?(V3+;;+_n9qpMkj zoQ?E*p!Z`>wnZeNc~4Y`uwvzEnfhFfzZcH~LrA^Zs!Df$UQXRY0J#&6zN-?`2}+5P zdoKRrU;wv}T+vo0d+qK#0WA2&+hH~fM}%odw9%9&wCAAGr45+TlWfC4M3om{oK-8# z|2C0YkP&I0?$tvJOlYd!6<6|xZ7-HAUn*Fr1&!`}DVBkog^ayZNo@H3*+^+kBXs%> z;d=r`5NDB>&*c=>FhCojMZ&*7f!x=SoTZY{!*BW>iCJm8{o$Z7IJ~zAvA6wUpW}xV zPc;7NG@Vn2xZ-(tgpcbgwO8=QS3bHwS!{L>j`Z>IRE~C^N!W%twod)E*Yi*LJ8e)0MxjJrR@d%qGqJTQ(TR}$z4w13_<4zA74=0Kefj3t%g1Q1hcVrByvbK2 zRJQ)?@MkGNdnaV3(0IVF>8`|BsX)L*i;2TNnV61v-SzAGP}}VKwSTRNgchSd(9kfG zaM!$-Du)Mut!x>Ll?fH35@1*mG`8QlOIryrDh!g^m8w=j#})w?kwj_QweR;(LSkTx zwrlaTD@tJUk?32OPTzsvR&<2bq}3WP243H}X!6~Fqd3D^2W$FF(#8sBLlt?THzER| zq;UAWYzi@kz?G6LQ(@_i0yY@VMHpMDtaQKAtcb9YSU?V7*Bsxe5C2+`IcK{+SX{;> zIfz`ejo#fYw+hg91RLC&Ie6-G5R~jq@SzP{eSIJFR@NI9Z`V7Pz$Boxo&;I(J0MdN zDRUvz@A#vGjV_9li_q_gd!qG_q1_->A*2>{hO_)I&2sF^>EdT^!fQByl5DV!3xiV< z^_WH1cGr}n@~)*c;A&iJHs_^pSP0ghZJ^i7ndd~P3^hkFqN2BqB3BtJ`Y<-KmXBIX z3O=nP+*$V1=D^FucoWmv*n?9E)8)o@iFD4(uQbxy0-XN#WIOnG4ii}@K4)z%)#pj3 zI<B>NJ!Y-0v0|~bZ}tfbCu!krGAZpg84K$f zO+VO7lphM9Oprsn#R{esC;bA1U>WJIlH2fm zknK3*nSdyeG}nZau=`2hAt|xFn4sGy*O-qu%R}_w##2P-72-Pqrud6wj-psg2QR)Z zQo48vC^&Q40=VF6qJoCJ_xwtfAeIxvVxj$)e(?T0fHGyOQDyZv(WkeT1nuul1)RkS z>7!snqeV(VZ55HD7s=ofsBBGnpIte6@QP;>P9{$of%jzpRfs;F?JSQznZ+e6}KZ4$Zd9Hn~INGYeAl2RW|b5vSfz5Hf2@)(d%&N>S5*Q`O13*+p60lNTlbAdO*ygGNr z>X?JgUS%B`iqrRP5(VqSR~-7{6r`BuQcwB1eaC!JfRTx2z^2VM$HW4==jEbQq*{>GX<{~@mt_1e>TPYkE=PUCz5thTQ; zj{Gvp}g>c+|$Y#`iTiuj|I;yak(Sf7If`*ueL1gEf@LDEEQq5d5V15#5TgIZ^pr~ zZjqNMpUcgvc&|)PNN9EDd5_ts0a&c|WEOI@Dfcsn-$#YBS*yhcfgBOg(d}zO6cq5y z%*-|yb%Sq?x$l~--nl5}T*llKOV}fzn7K;qPwzVcZ%%B7{%c;jq;Fl~7}(f4UcQsK94^AH z;(5ho9ak?gSNQg^U7gId^w?RLWUDjTe?smS+hN=u zikdc_ugnGE2hnpi9`?5#!JV5O^;zYi5Zc{)I$SN~j+8YuW++BhD8S9hs&G9-yV_p~ z`mcrt21@=0YbTGAdbUBrg}CKzn=YJ$-AebSyf9-yQMe+Vi|GVAq&f40pny%We z+x4dnGc%T7C}=-=nOpD(XdvUZp8DN>_a60Lb#8lH>73}RSvU1$@xIu+=g)eq5`WBn zwY`0Q9giRQ6i4ylu9@ts!Y_pbclC>Vky@R?*$3aYDX*7W8QORaqy-y1vbw{{V>cN( zkte_MUt^{X?7$cY0i?7Mq}+)!@hj8!uervD{;ApX3gx+)O5Qg zZoM3WRE!#K%0^sZG|3pzf$XpS0g@i+?SI%Py85v zX3k<@1s7jDd-c(pKWdSotjT=x2OxU+&j#fuiPh7^f=%=`T2dO>n}z40@X15wc_(yi zcgK$=3-*ecKaUPHZ8h(w*wBc7`VE^#MyMA`eJ$K_bIvqwcu-kf>~W^`DWB6`WqhIX zXaZZud^8nLj;$@`TZ&PAY*@-D?yuKAmuXpBD{0>eXs{G~Afl zH3_+rb6Q%3t?`~`rK&C3jJdjPEdxT=GS<#_LC|p`R1UtO{{}sZ6eEt3bi|v*?Nb7y)(5RXim2qc^@8qu~w$7U%Km*T?IYl>V zeLuyt`(zjH!5r5778-5Imu}_S9dy@}eH$GjITPWm?vHFY5LSw4^n1A(_U(7u$%Agy zBh*4yg#JItaz|Ul#n6r8;v>+!SGMp2RTaW~=OA?()nMJuY%#6vy9oyB=Wa?Rnv!E! zwH=UmlHM$A2fUoO>{W~JTHpI#+t!qQb^FQr;avRwsP$EprBQVCqoC@K9K{;dCJ(hL z_LJ_q`O}tL^hn#DoeTQfpNle!YcVBDE?X{zN*KWZ${CREO!R3TkWZ7MTEi9t>$~w*vLl0r&G3V(6~2~d`o~R2FHOV zfudC2zIo9F9RG=&G^9i#()S@(CYAm@SFAWJoQC z+NQo%aQTqhx45Gc%Mj}lEgKg%t*zltaA&e>XhqIEkhMg}94Q;*KbCKF_7v9(H^NmF zyhSDBE+1+wJdfpMIgMt=W_ATD`2~hFBl|Tqd`v-T9}>94+Kl{mMaO33flqGO0B-e$ zt``*vqe>SdQ|a2M>8dDh6Yxx(n^0Kd((++#!FdE#X&>L}WZQu-?EJ4V<4@S8b@%V` zQ1b2kgX`FDsLd{N8fFn$V;UY-z3=Mn5qEm&roSnq5Y`76wZ1aa1qt#TKlFD|)h6_P zs9GQqA-m1B?Gv-)g?;Gg&mjN7dhI~Fdv;m3s>WFpH=UE0N7l10@DNDE*qcE@_^-0 zPR79Z?x_7v;eC(7NDnL-zhyQx>VP?CpSXT&v=j#aWQor10l5dY1}w02C>qUv-WH*3 zH^WuM0%IivT09;%8Noo;YSBAvB$Kb7T=9KQBR1joOL_`_uXn2*N$4)#!mev*YGF%a z-^L%%c%lW6mvn8!+Br4sy>6gt)H47OHU(wAZgPe0=A6~kWmQba)UEoF^Y3fNea9?S zChMQ+f&WFkMS$=*QCzb^HXQ4wA_qu+o)FQB)yE4*J-i4NO5cmgCah*b9jb*^AQH~p z5sx~eslU-6^qXVO9asEuov+r_u6kN9h4@BgH37bI<}$oKE@dG1H0YKiu{O7*qv)ya z`+_mq15Vz9+w^DCdf$Dh)z^A-VnO7^&!q$n4`{0oXMDZpv)Px^IkP4|?-26>OA|Mx zp7J8piG+eb8u$cz^-mzV_qgtJC!QxGdf&Iit<(Z|QZ4H|j7c)f_Q$vQwHLEq_wUMa z8Z@6~6$A2yjI-?tWn!f6L$z=zZyjIbI$tb565m~IA`Bmwa&#v-oOg!Z-QB<-?dbB{ zleNeh@V<1HP2P?nxK7gYpLKj97!liH*wh7@!a6f!{!o_~woA2ANlX?M-i(_$H-s%i?78OSC6J{mTjNbjl?DWUlDfr;vHu0 zH#p*o$7OFXJwZKeTgom4oIe}E(Shtw7U;!^M-Le|nSpX*+I+IJ@?tsUgw{L= z<>kh{#V9dL-Ofy$&z`Nc&+;(lpvzMe2f?77B-s?Fv^xl*KL-(SZox{}?;Wlk?O$iJ zC!0r7RBrMG+y`Taz8X&_NSuY$f>F1!U3;H_V#b+Fj({4(HFZZ^>d#LwX+1HP{LwlN zwzz4+y7epF=8L&pYAVm}g6TLBKvgs9MU77NyMx(b(Wj$be22?bj$S%<{qB>0Bd zrSCocAyx$Y_;ly;a9f|(?0hnvUQ7TKap4o#1Ghiy(ZZnG zo~0HKhuvwYw;$nN2<|wCMG+(^8Uvk>bc^w=f5$*$QVS7pKVi)lz*j`;dSLeUowme) zwZkyx7RLc&Px33yhoF-pjFY8((+t+QIpR2(2q5{Ej@7_k;@UXQ!^OY?VcC>iE ztzSypsN@JGb5QM7<_vv_dC0c?9Mbhp&xUo~;%cavKa`^eFRZSCP{jZeJ9>vzYZGPZ zMoh~ThZ?n!jNi9zZ`Hdv2@`0>UsB1a-`W`baDta2kR-eT8#!t=G5-6VAZb^B`r+OB zChsz_0nGPnO9xKjqZ>Io5Z2*UK_+Ab_f->+(<;zRV-8i*8QIWuh6on8ONLU>~Hn463OF(E;{F@OryyHaET^+%eA_GvtVH5 zzUJ3{&chb1okA$Q$MPz)JAz#1VeAoB23a}>Fz3uMb)B(r@pD%=LHe1Fa(KB?{FYH? z0l!?Of%%B0ecw?j`q|X2eb(v8o0E(AkYK`=<5eW~c#<$E+47b?Q#%t67c4cWpR;i2 zwfXjObH3qv-4zoc8lmVplZ_y7iC)XqO?06KWx%e7~IclOT_=!u`MvqND5w)y(< z*712ZE272?@XUdD()izs@gjme zk%_jbK7N4?Oo62?8PY&FdDOQ>UnNCw+MgEDmJN|-=|VZV@Ix22LPoM^D-nS7gk31e zKFIPveY8^B;|5YteVpu(TEx&l=TH0@aweWc*(3=ZpfZfM=Z|l@*fR*GxZbkpKO#U6!1+8U7C2TUjOHo^@xJ-4 zg?AUi(>bBMr|f3K8g1$TL=>zdp05Y<8VCzL@paEyjEgtIM6E!>Cm88e8dDQ3d5;69 zD90opp5_eSr8R{ za2yGrEh?%?G!1sAm&w3uaaNmk1i;Z>iVRGQiwq=aVq(I<5nj^CCUq8CTbi6R2*vkX zY^D&9_UbdB;vWNnYJ}*eK#xyQ#EhuTcEVseRNz%^0Lbh?8-`k#Ph?_8OC}Y^#wNTR zyZ*L{lc((lNo5Y7!@(3xLl=&!2v0PL_?1=2ro_Hea|w>U?=XPME;C%Y6*85d_0sfv z2B)!X=^T2l0P=4^nde?F4y-$}c2p-v zvQ_CnVt?D%F~b)at1`xvo-qy5q06tbz{%o&pptNn12Brb@8J|C44%mDnH1=A;Y4Yf zdCUE%K1r}qofbQ<-%hc`sm0fE_^aa0ngmcd^nTxw#cpTgrUJtv+mN+0F$Q-kynAR* z#1HBCfmh#uesS_QL#b8E=sTe1EPsTyAgTYE5irEh^+|PFO3dFAuZpU@sD|yXHZ5 zpJ!#WbKH#^|DFun;9GY;*V)CPs);oaOFjs`hGmvK8Vp}~J%MdXWcyaJF0`V%dv6pu&!&a||56i=`lX~cH zZY)Jga&({*BTUl}$o9tdO9&kc86L<+m`F0mCUoRS$7nAe7wt}@64Ags-eo_*@mr5i zzcM0ZK?Olm*6(SlQdF888W)%@#llOKwz`b;dld%WW%5uED^gVm#eA6P|D_C#4UW}d z0HxnC$?Ckzx7Lr$BZ~Gm<8ovFK`__oM3fMu4zOrzUV%5xA+HyX*>s74S2VrNDiVGZ zgR|6Bppi%9pDE1QJLXb^>LZfet%ld#OSBWQPLxDN=s}>KHYCsEF2pJ9LahD3E#Q}r z{B0h}uH4e0x=&TIT!N8Q^WMYMoM@?{Q!}A!x}U=wibXXwNZD*Bzm(t#4%syC%SZ^T zC1_V~0_UR%-m@t(13=$_+Z|_Nc5j^l>dDU98f~_B%Yjf~{5P=P@!AwG^pL|lodF-I zzekd#g3q{m$%?s;GX2h@PNG0gWHhqRU-$?m zU;8P%4DZmqYM4_HjO|qZdJYkfaJNMR>OMif_=6D={aL&uzAgOG$fATfx~DJ`(x1 z*D2U7hukiC-93#{+y(X2mrMDzh6|o}PfAwc?o`F$Ep*q^`~*NC!<<)*CLty9dw->B zm}8ASPN`~ZAa$tgRTx*H3CU-r>$6!HjN&3Gpb1g!NzmD}2HhDMUgc0ZWL@RJ$LHYY ziiw(`C0Inu8U@gdQS>cjk6sr47GR05!}|P`Kljl=(7NKCxb89&mNg;gJqZsSc6A<4 ztsop&-4w9M#5pHqOhJ!`=?~YpQ-Md(#-gWYZ9zs6YKMib7$tXh09M`FoACO9XBMa& zvt!r$yhs%qYJo9u2s*#YT}I3A?MK|vs%XUv0@)S>U9$Wrz#Q4%a1+*y)OePc*3Ru% z92eM;QXGHup6LJnOK`~X`g*e_IWvG&C_-m*b>y z*9y`!XX<_dp>-CSaepfU&;y-ITy7rK5JiZjdm0(PcyqMm6k_w!G9!tNwed+sdxbr1 z!ddXhzUy!0V~^|GOo?LJpeB|xWmbc6`w?S`olZ(;41PF8f!7_d!1QnG-T?(1R6aU$ z&M{!?y66|JI<%#s;&8%)vxB+O+!35!IVnVv{Th>lO)C8YUE>0BtMESSt}2Ig&$sNN zu27-|H5>`ZDh3Okss6W28A9X11lQka+}Fm6dn~y25#Yo~I+K=S%HZ%XgsllOMsptD zk$!es`t3OdNFB@FdQXgW^!R=}0{U15hdXG@PwI5Qk!ymLs}w^cH@DGV(D;leJQZ26E?lbG|ShX!oEJZEis+p zL$;eKf}kEqV#OD9<3^t2%VH6)mJbKbyJU9_Jd6? zZ;jrKsiAD*ifAG>bE&(Vj)KN)@QhnPGo{Yya9;C>S{?~)5O%M$vz1V{gF9tQIo~1P z9bfq!F!RaWfH!CZ#@P?snz6LIQ{W@S3UjWyTld1CH}rXH5mQH9DG;&n15+-Bw5uc9 z>r;>;$?FcWz|=u&+qZPi>_qv+8BLzddm%&59M}%MuJ`wcSvp2$ynZC*qOUX%5dGyT zdh_zwwdQlE3}Ig!gAv2c8>F&cpSxWCjDR{4$+dnwB0VJlDZ}QyxF>D_x=YT4sjP=5 z)b?odS*de6f^zH{9*JdP9mW({w=HO*58E_myG=Md^K&F$wX564S)9~fp_y2;utP<% zqahG(P|o3UOP<7I+uBm@O&2n(OSL!P^lVuYE6Dw%-7nC!oEcPE6uW5$*RyvzluMpR zvj+f3H@5gy*G`+J{UAWu`;?F3YeoE=ydABKsOWBQ;v_1M#mrpyKJto}frgJ$Oe72i z(bLimNnMeXq6Xxx4p#aq2!oCI1MD=XV*m=~2ZNTR5X|4tLvPjB#Y`&QbzVdIRh<$=pH#NFr0bx?-En_ZN*VD3aL~Xi+jd9 zs#@sc1<;NV`8V&y*i{uOJr+N@fu}~Q+KGz7qRP3PmLBx5Da5*<9twE_hU(B0`b-IM zA50oJz>oB~h9BJjy z+3n)47bN^7&YjZA8)|#6Qd1fZ|Y(UVEN!#MRLmE&#|9F-7=r3B$1j#`2m}-lao>0+O%_~2=`)o?& z4sh667|~$rayA3nB2)$7T(Ag~UvUO-@7tD?6$xi;cMFL%@B{uFJ?k7L8H z;E?`UmGsWW73vfMa&=Bs!Rd({1lH@9u{fvn6&SIOh)Jx*53DMQ^$5zCx3&5)CDB06iCa@OEziA5aE1T&8T4Wy=Qx9C5GRv?0 zG^Kv&zJo@NRjezBW%!DbLfD<&Q-4u~gA5dObG*XasU4b6X$%l{*6X*}nnwvX21?Y6 z@dYnM?myOJ$<#(LyJ~%MbCl6zqiU{#R(3`|*q>Ud5$bl!VZd^4i$JjAZVHFD5~WH* zjJ`$Nf$}0bx)^8s65#h0NiKG7=tqXZ3heBGvV+h{p|#aJQS`xn_PxnaAynimZ|(Dr z5gnXD8J9|O{(LEh9e0kwCrVFR9`P^x4sjt!l`al=Lx-HwJE7;R@XzlZ1+?YLOg`~~ zlq^XyQO1)A<^mFVZxrbYnBds))mfUIkBkUY_n5@)&glV*qrZ$i@jg^V){yL!LHyKl zs9z(jb_D%08H^pznC#elZV|Yxk>VFTrFDMX43;|X$a&jRBQxge)@ZRU5z-%wm(yVh zGf*WD{X`u6J~$^NK*INMNtd%h`a_BDyNwd2-bH_faaHYX2Zi)EzYp`@yB_hyI;b4w zv`r~qAUinUjS!V1SHbnQ> z8k#bP*NnIJeI$?q&GU6m8=U+cyY-Ji=Fg8a9lI1JCLmmsW~>SrI`xaVPRF|3Bzbtq zuNRHe9R{iP_Dcb1%2d}c#)&S0M5ffwDQj#M4kSHc$zgFO|lmjff67KV_$eE(Q+Ow!Ew*z{*^uf&e+{0Z&K^l}Nd`e3DW@)5q= zLCp9eGbM#oA{Vj~Njs}I;7TmVcZ-vhxH{btMet*!)*ln#;EJ!~isM3ph;*vKuQRpe zy#vtZ!^1MuTONUzx{KN0(M-dNBrXa^O5_BwySxm+xvC=I3$90**H|}cc+W^>E%OI` zJTI~_3zel)*aJA4m;_D#i|%kAdS-{x-=SIsN>5;lvfdv~(Igs!2ji0?P}Dp* zXOebAgPHRbWUF*HH|wA--Do+umn1R(pV{^Q6(cd+&Y1?GjToF}A6(W-Y!sMt))N^V zJ9PrJR@#N!(MFCZ{V&ABNYECiPxUIF)6r&jn@pOS)GtAsEc@n#bS`{$7p-%(?{tIIwSzuMDLY$apLm`qvgaH_+KvD>pq z^IYYFa$T(v;qVqt9qVplOvQT_jR>I0yC>v8Zc`Q%-LRL6_ z_7P*+vYevrYViD-1JGsG5a;;HHRW+nS&2#2sS6cn?766Krm%zUI5T24h}m2{dYdf7 zOM#$Wzf2p^b+i-7xqe~+aZ}krixfFYq|kt8PPM^8zcia|a9BR;ml7)mj)hF-`kH!h z=7S-1_M_r|4~v#QU5zEZhvy5glUSsEWc+39s4ji2@@Q-ISjh_pj-$uxK|^yB?BsKj zA9YH9SzTT6yDAF!1sxpZw)GpyM~#Z3hp^SK?QLtb=u_!&bDC>YX+k&{1)_ec!x6M_$kL~v;a{de!; z#y|*18r;y5TzXt~*qkotNN}Poocp(Ic>2Y2IQPtP7SnolhyK=;+pwK{8V8&uOf4;7 zN6$cZ)nIvS2^y;h^}Pph=FCadG3m)F2UZs7XCY*<+F&;1Fgr|uqH-l)8=iaal$vBp zu#KMMr*XE^jNzyOr=NKa=U+O9ddnJSf>{zUpsx2go_Vr^pwWU;y=|yb(}N@{G7(TV zGqLbJfx?u^gWUKx7Z%EDmCwvLBB?qYs5P+gO2J_@sk^m8gsSzjs2N>eW5JhZLh#al z!}Ppt|NHn%wc#8l2n{H{>(GzFeI5SOnBz}dA#)UN$C1l5M{w&$k=h{>{*=b zYJ|V79S1wT(3C2_BvNG2pCzCwHH~>>%Ouuff-fx^HMx^BIbbEIN^Ml8!|AQHXs=6R zaV3RlbRFgPUMA3SbUt+sFTL;-3%bhcG_AgXm61gzVJ#Dci^bDTk|Gv6dtN4mP8>XS8qb|O3Fnp-2WX3PPacFm6~e~)GK&U1Jbo*RtD9Jw4#U;e!@{{@ z1Jx#zn2@?+c2{w>pC>CQFma&7#9>Y%kxfG$Oi+(#fXTze0*~X6-<-jZ|LJWEZ|c$N zmlZbEUVb@I1h|wYaoFz%qT_B%-MNG7gPS6vsqJW+bqP zY|j&T?fi>)x>t{l&>XTkBYd^(c;dO|@$#8wM7DRJcQoONgKaRX36Y96LIBwT+!~DI zWP2S+*H`luk#e~JleY&g`4ueeLa)M|5B zo0~u%{pj9!97mg6`yT(HpV6;3=VoDT?!t@bpU1PO+YrCCfE2OM<@Uhku(7`d%x!KU zI8ngaS6*a{oj`M)lQu5H+tx)~k-ICqxWeKxYmi5h!9pg7EXSrKGgXv4`<`cPY53k? zPBZ4y%D29n5UX_#9BkEKWqXUY4iDyMy=Mx`3M#EKbWhy2&;s zMh0=?$~|m)EX+YtfU+s+-i`t72T$VZQyjD*H|(%rybR>*moIy;-2(O%n&XU-migBWjh z)Z)}rXK_$g>dJ9EP*b$9AII?gi!b7En-zUaJ8bVbk0Fl9xY3vLJ3*|3G&p(sAZ&)p z_5`|e4&ygIz>nVUgR!v%?wWlo%)X>ZVVheRz(4=!C-~tHe}cE(zl~6u`0RGlpA6U_ zjv(EFBd43NIJ1IK(10#q<#ACF`6usgAud0GI&%i$6*HcF^##24;wcnE5rh+27Q9t_ zkjXK|2V+8;bK~I2(|Ca~*6CbEa6N#@atmI4^&HN!n5%Q_u22%pWWH(XYD4GAvpC#r zM`@=9t-Z(a)Tx7T8pW2(OT9ilK;Rp+@T_kM$Z9BOjNiUhWp zKUYYC+nzX&Z@qjPZM2hJDsC399)AP6TI=BO)#LE7ia&|_s3#~^16W^KChrMiJ}`%H zQua5@GCnWjZ~ynd#kFW1UOilkVxb7DuYozIgze2BmI666cIs2STN zuoBxscp(T!qZdwD8M)h>68fLkSdSB39t_?aR}*~7FN>_1j8=w;28rMTe(`tzFaGYG zVW!JUoINbcFZhM2#tOrB3I#SIerfcy;n}B~F>vWUymx&RVd_-g31e<$5gXws=9V_F z9@v3AG98)f!;k*)NBF0Ang1FZz;f}yzS0(Qb8hU)yZHNm_%YtSIH@KyRe$6_epfP@ z;o4yy5D8{a(ZN8hCn@WHhKM98gc%6ZIOzknb7@Tbh3|BB0l zYba5l9DUC!lT}n!>Lab$3KQe3u#3A&9`ZjCdE_*=wT_EF`!W8@KV3keY=_ToW{ysx z|KoS@1CIAwP?8zF$MRTymqcPII73e9#R2lwy)Y+U zrI^!oB!sfJWLXzOuCR;ejL%|Pwx}raPme^AF(vu<5%QS~Acb^ln~7#4hPqSF;Z&O$ zi}!{wGP#0ahy_(J$3QD0C;QV#0wGWcam}W)irj1mwn$FO$fXmAOFQ8lIuEpw^b050 zAD|i(av3J36e1y#w5$zB4%b6Vh3e&3wg@-{YU?6Fl*gy?c@}0wTv??dcan&oYNe9Q zj=P;U+M@uC!2-A3O=9apq-9Q|s7avA0zjY3B1)E`7Xne~z*iPYeA`R2EYfv&>Unt_ zgy~*uM>LkM>|wzROHvV$)jYXW7O7|wp^X6Y-b3iBC7CH(;dQbA;lLD2TG*@}SXtC( zb2*;1d&h>l>6o+&1X-Qmt;l7bHZ)jlaHth&awJKP+$o{`wMHh)G>KcuL;_Qxj$cXy z%w=4YTZrYfYEKW@k3&n6>8ou;a%B`t%NiW&bRf^#;`Z~0BxJZ=Ddp6jU zN;fJmwOW{Df1fP9l6K1^46xLgln>>lnAhi#j8R7&$z{V){P}5g(1MtLuIh zkvn71(GTL82mOFCB@X{0TA9IjN9 z!jm@Pc9LdevCgFXvMh)l{f!|P&PHMXNY zH($bm4hP3CgIs)@x<_DcIDifpiz}_*fmPX}=fo4lFB2Aq1~5Ffh9cuu^eB)77WGEP zh}@ME;>N+mDAH_=PH-isa3z;! z5lUQyw!K%b+Ze^n_l791@d(9Ex(eTY!^mQ_fNYjnN(@u6#D4{E zr z+_^5ZFwL`AF;Wi=@yKAf-@cq6KNm0O$>cR$cJ;V?F<*)Oibyd_EEN2s{|R0a*x_XE zuUPXz5o^h6kyJQpGYGd8VO1qcp&RZ+epdthnPSX(v0E=&3}He#kp z`B$D?L*-4{Ngl^8lbgssYHE)xe#Wm<3|2*A&+T%+$nT1AV)N|@tZi&!BM?H2<0r8p zwyBDAU4B8cB=IfRAcn~#wq90q*i8JE2P^&~ykv(sOa4P#i11iR}78Z^!cs({4 zOCEF{YC?us`taj6zqXW0h-@q)Z?D15P7l&E|}TRd`Sl@ zc?N@+-4s4oX-0M1WPrmbk5*P}CW^b7YLQ;Nhrjc6fDP*BSijAHBr!tN6ylQdxB( zzNA4svZ}U-(Cyv{m78AP_9OVifBy$KP!q@S-8F2*mXN7ozKq9_W5F+cyFe^I`0VTW z%fIkHkri{YQZS_} zD&Kxs1bdvV%*(bgM#p4z6!Ev1!1_`Oc0&q@B#W4G2*I=&P2~BJg)!C`Hgq&t)OF;) z8e&GOP=k1q+}hoWH~-+fINMS{I#=$#9R;%%JDCg;QR)!gAs2Gt+1I~=za$6!y{9^f z7aH_D`89n1Z~g**{pK_9?5V&A z&5>m+@T4MnV?(ze(TRCXY?o2%A)d=*`F@e(_)*<~1MuaR>BDiw4fI9}bcrA_QwvYq z5&XOFzkw!V@ckQd_eGu>XYu|2^nLu*AAcSC)vH*HOU~h+v@N!0`?9d&)a!qU|NJ-q z5#N3DI85xka9wo_{ZdQ6Tye0jV$Jt(PvvHj>L&v%6Ad6#=Oixa;ORbz@BaI5q06+1 zzR?YoST7uW=}r9Q_y3r=^N;ZQ6U~e>asg`=TgjZtff577oo%Gd^fB?h&zfaV%ES|+ zzXjj=<3Gp$@>l->Cron~Wld8qIq=Lk{}6xuH{Zv9INwW-nP-k{#lQLUKgD1F)t}*o zUXQYOF&V@9dI-k)gLv_D11V4mwJlHMfBMhg$6x%>x6t9_xYStj{I|b{KmGP|sM!k9 zMTD^JcHpr*mfs0soFj+Xg)o|$8(@(MFn%U{OT&0{q_d1&<|D>iAuW%6OU~r?8e)fy ze7|I1%oSiLWtbP33m%nYcmLfL1|I>i<;atGnVk`CRMJ)+rG0%Qi^<-c3Ss}n> zIQ_NAr+3)rF&5yXh#ew<IQdV93Ee&r@6sK?ao5+di92^6@40!r> zJZ(TrcNbb~?Yxd2bsZ+GERSMzdD^8JY)xxUj=2TSB8?iT9MXfvX=y%T1Kj~LUA zo{knc%`D#~u6PnlOvFMPh!#w6S+q#)B-H15I)}Tq2^jCg!1x#jr!y?B+dw4Q^+k#l zZ+uzG#IYLMW=kSklAd}4rS-kP}=W(df@j%g3F6EKUktlVvVuOX5Jl-}k zIt$Io7U-huNa!8t?CwB=$3Tp=!rvLk-CIMLn4QJSYKUZ3gS6nv)`PfWsp85?igs&8 zDH%pEl7^o+RbCrXn~)D|Ks~N3Md??S0&%=#@}t|ehQ8Sd{EgnqSW?H>#uCP9iz)hQ zMsHU8n`mu*Jp0OPc zL*Z9hjtgUKl>MF@!^~_52ODkJ-V7j|klaB3VqU8~avp#1`tx}DsV8u_y^;B$5!*|P zDlW!n7r;a5zmHDdzm^a~bJ91SF9o^W)Dk^QjJNt09p3zItV~ji$mEFBep@o>xt&oHnrfd=^(Auv?JmdegeNgFHpkpJ$?CVG zo{&i+u@gsVBg#x56Q>$vcLG>k^WgRGd<|d!`q%LXFE%lb14#3l!pCa-y*S_sBjmB^8x)e8d$~@kDZ)eMc!_Lk>j6DMKCwb>yx{zN7J-t3d{4e^xGLM zEJsn?cg)Ph2rgcog}134P6qIPh>|fDoGEBcICkO~w&sVhOfcJ77(=}6Nqp;#SMkQ1 zZ{Vy)kLAT6>N;x?ni@f@u@}CY%1sB+2^Jp?`E3}waScP0bC{f&XMB(s#O5)VXvKGw z&wUebKIy>h>WZ>Kfwr!8Mf@vAKlIc!LRVhKtviCnGw8d02O0k{G+X65;zK1^8rpEI zF^~R%6>`Y^bpq?6f|(pnul9HyrELfL$65FIQR|{_itXv!#=1_NXf2@s-YoeiSR2eU z?@W_pt)pzPK(n)mrCb;L{3`qWd-&!l6DF6})rvD!Wo#yvjb)GVT`A&Trv(O8Q!y$;;EJ&rV+EAo7uryah; zIHsay)cGvDCT%3&75Dk2V7A^#zwE}s=l}xrXREUTE&e2~esr5TaF)Kgjtuek{xn@h zBxgqGPt!bRBGK~9{Zt)0Ny)DjN9`c0+7?|DnHt6A zk4E5bZGl@JC9XOHh1SDPB*2(pTSND7_4X!?o@!(A39<&5k+`{f~P5o{yW3yADn?%Mfr zUIR(pwAv8z_@R0@JhfSAIRIh9st;r5ToF2t(s@h?h)gYVd*i z;sMc{EO0rk^fdNSXHpx~>vR?UWZqIkT|EtQ7nF7}m{Hf%46h}l>=#Tju{YGAz~m;s znp)Xhe4ifF(e7=4{Mv-s>4qsE!SGZNEr*Yzi-m^Q=R|6qNinR!6K9XZZzy1CdIB>` z8)`ZAvqxL-dB5WFt2W;k+u7WH_^buYF!6~W*ccOD*&9Q}6#YSs3!}{FL{l9LQx=p< z+Zr4`^CUWI&GeT_yRuh6DjLGlasZ)V2!{GD9B=nwl}SI4cj3v?M>r;S7DEA&t2kN@ z9!5i*8-DtoCAW#u=^%VvhtbV(cGbv6u~GV$7e*%2a*Z8L?h zvN|$1Ct}2!r24T7wI@_Agy3U$ptYi1>^6g}=@Y zjl;`Am^fNP%4xE}V=7@`Y7Dc>VHlf_;>q3y6)#2>)K>L_77t!frm}P_dS$cXCPPY1 z$dueYc=|-M+EXaIHiMaP83&IZL4)0a=C%fGFOFj=Zor|VN73xCFxdpKkq}(5DqJxr zTw&Z1SL|&^aI&WsNs{07XbDXnt+3HPBNHpAJ8%q#T0KK{a zcY8fr8|9Z6HEJKRnnVCYV>1ZE$~b)DBwBqYHJM_g9R?g4HjjlZ;P9~{XlCJMVr-g;Np{)Pn+Tn3(|OR|LI0*b4F)$FYU|+j-2a77DS&ildnF(1jcP(6 zI6IEjloe-AAA{FvL9JDTB@+0wqX{RvnpuR(kAN7-8!A5rB9kXJUkBP6^q3!=z>cXA z$BwnZZnZOBB_C_mHU!C)86?d0Xms0@P0X^#68oVu(zezdiI4#{-6mENCY*WtG@SV` z=9jjKYkuaK`%WM_Y790s$;|_cjbm28)aWF_x)ZR--tr*ZD)Qy${3Mwp^owcBJ8up-3UjDels0FUGFIz?{H!(8fC#l9k*7Ib9dt` z^Njdz^(tDU9c~BhB{7#-S3g=*fA9!;Xa{#wEsWtgtYj@{uJx$>YZ{t}ak?#H-x6#c zjLie}NUSfBUuc-)D!-0b(wk9FWtXPMv2AF?+2g&i=*ui1<4Btt(B>0t%3^jQL0ssC z=W~9o^9wiM=l7*F3pZaQ8pz#bg4iHqDI4Ci@3If8>~lrKK`VO%s$YN;A0%J&3(k%P5*EsS^*FM+F~A`)5eFQW>PlA) z-`i2w>_IlZg6Z`fdZ=5SL(AGXfCSIUrD9l~3BXEQZY@q=d@V%`B(9i~SX_$HpDLWC zm`&2B>(Sz>QN^y-Le7#Z!$!Zh@fvoE2~N5Bwna`*>q3pef(DNVE?XI%wjOu{_GPuU zm*3G&He#9JyIy`o!ENHdE^-6*pIoY*?bH+h!Pu9ZjghPwCk}U^j^n5H4r6?)RZN;J zIp+$NgJBe`4S4Rk6Y!c??o%(L#f@511{0&>m|uy&$=r6T$HAELqKz>vD?T;svo}CKi|15ZH{MY^g<~w~Xa^V*bV^5-AH>I>{STA;z8j z$Uy-e$4=v9w_oLS^~M6x)To=R)*3DH1r4m067sql zczm>Z!Gw-p*?+V$!N3OKVm|QKH^QY!V0v-}YfT&kzV{kH_k=sWn^+@J_k0N^n+1v8KHEHYSY`hbs;$$>#MmlU)XGF$=;%No0IjJ7JA}}ll-TKe&n&1VfG2nvMc_tO_FC$FJhCv(|M!^jpSdla#!tZ zMLWwcOK+|(V`)8#Y>fv`o_nIg8;dfG7Pd1vR3w?t!rvSO)-M` z`89;LvuHSU5@!xI?)jyTV=Rx^YqTZAHrKGYvWZyUgrm0VNb8+w zm0$g4Jk*h&RBwn%oF!t^Wo-i+kp#^0>)cKwOjbAZDR~7suxuyfA`VL=>=zlc$D8jz zmj50_(qJ~7BCs$w69=U1C}(3>nA?E8u@z0^%kyJnNLX6%^qFpASD4rl<#*&L%-!L+ zaRiEPJn_^Kh2IZTYuS8X^YP_(ABYGE82NAiQhy<~a_3dUH;t=qvysMaIDcJ*w?T zi7YKvx)I9ckx^ z^E$Z{0t-{PJ(s|9=bnY%BI8>Hed#y*$R0`IE;?7w6@QRx?C*{8FF8l`UG$Q%WdCK= zhSE>kWlQuaDq8UiHO}-M8QiM<C2=1MT{iAE~HpKRgc{A zUwJlK9Zwr5zmOP{_e$Z4tz=2Nm`eEz+mx%yqgeZOQ?bHxWz2*yt4qt+@EQU zT?MNi6dBh^68ZZ2TD4!$qlm}-Ym%l)eDm7MCj3sc6J0C#x!XtDMs$DVc!)3YbLmS} z@B98N7$|nG;HF5$Cn~-q?MwfpK=@U-qOgZCxrgU+9s1(_M+o!%Nf+L`e>>6veJ$1s+i}uMTtp% z#!ynCCZ?<7&jvmdOO-~Ih_4B@h;K<(WyPbt7! zvqj~-oFkYcdhg4-)R_iQekBEkW)IJ$iQOD6ec`!k+<1%{BWY7awJUkL^4Og;tYSt! zr#-UKNxXM0i{JmwDHv%Z`7sUg>;3)T6P{BUm&&JAAC@*NxT!vVK*UeenG6f7B^*0? z==1$ld~rATOWdfKm2U2~U%jzW@tcazF(F}T^d9CDO?dUi4wPhd+5SHB+LbsL>s8Mc zb5?SPe5`Pi_7eY9=gK}%(pPmo{-fHEF`+)6=V#($ z(dZT;{Oj%MdbC|0*OX&qoO!Ywt74q~E|26ZjSNrJPlW4NkC9FYE>c0v-unob1~*hci}n`$ z-Zx)Bi&L*AfJ780VjQS_?0BKQd`P=!`C4o#xG5{V)K_8){s|tcx4XVB*HpP)Oe*?T z+Y$egYs=@mHm@{8UHG?`*X4R@yec`ha%yF4Dort7j0O~=i+J~gt61Nb2ko_JIC>7> zc&44!kTxp)Qt{7o6!+oz@>BFv$B4Qu8jv%REIzI3m#U5Ae07|hA?@t5lbpTZ zFI8I=E-IoeXE1T&Q+ztSf+E}2)imI>@4kw5dnE@+8`WBCFV@+t!Xaf2S)s>v_KlNB zMF-(R!ZG-r*lHJ-q#ly^5)r?a*iyMfgnFn+-@RjY{gVC`ob1B~SH_W*$E}J^Joo!w z!|`Ujx{lae`dQ6|5B9HuQ~Q0a;wQV~!~-jFCUGMAR_w+vlwQ({WM}~&zI_FoY*$vc z_MZD1UOFZ|MB7Lol@H2w?&lP?rY3st>$2M)u^-<)$g|kznu?!@wUn*+N<+P+JF5R` zy!W3|5gF@LDutz`RUG*hwculUEdQ;E_^)7C6~p;~!VQ^=P&|_uEJ2|1}H00000NkvXXu0mjf&Oq4I literal 0 HcmV?d00001 diff --git a/docs/Screenshots/mixerprofile_servo_transition_mix.png b/docs/Screenshots/mixerprofile_servo_transition_mix.png new file mode 100644 index 0000000000000000000000000000000000000000..31e40ff54809b31c654fc03082c31fc7b87f5fd2 GIT binary patch literal 19083 zcmce-2UJtf_b(biP*6ZcEFhpLARtA0FCx8nX+flhP^3dbvjBq9r1#zl5eS`t0)q4& zqy(e}LWz_lLMRu1e!uVj-&*&syWV^E-B~LqGiRMSb7uBFd-mtE_leZgQKh9}q5%K^ zwCZZl3;+O1v-A45OH}7ao!@(t=YM2g2C7d1RYP|-&KnmT6}1%sfa=)G$2OGbZR%HQ zW?ldQUFV-4S&w_E-T6sdkkNB*LpRVXZF_GUI~#AC^K$?Il-^0Ppmp_p6JUs(;Mf zoZ$KOo%$zHt&-II58aPv&CeA>ZbM`{hQ@*EzRYx2U(d#zBb@u%efG=>0*CjV3~k^euaK2`Je^=%@yM&%34Pt>-bB+UOv zuXtH!2v5vA!lH>zE`IK0|BlBEsmWHG8s85t%dFOQp59wEZ#w{?g`rVL-ur9fywZp* zLRqtIFP#AGKRq0Ef8GP1daw+oK(bPP7C(?KpIXnuGOlrEq_m|I4m?lXRILB+7f1MW zJktc9R+~!}&5MK-aUooLZJTX}jI^_)H2oewFLvc>4Y;^4@zxMGxkp=pKWHBo+Gm@{ zIP)Jk4tl!LX8)0);-ol^GaPkC z?;jjQu}Cf6a*?gsqaGxwwz>sDnv&c1D&3+(jL!~dy^Xu|e9*c1<-{(R6}4|c4l0`!XQ+uf*$h0G-Wq`tiXM; zRv>jXWZ$^X0*_cbaZWK{6T=bva6X#>75J{47!{ifD;@s_w^2q@x+x{AFdAn+W)qL~@km#3XwN;kLM$@r61AS3kRwF@of057 z`Ci3j)s)&`^O*pIkXNSh;|KwKZmU$tg%D8c3)mqI6&(&O@7NFRg$2vXLGkPBvbF4@ z2Q_6;{pf7`kWavtP1taY8S;Dw4Pz3WAvZQ z3zum-y-Q^CZzSWj=@8K#TF7IW1|4C~m|xTnN#%9=zJEO#3rfa$p^r6T;-qQ723psXpy9YG!IXx%AN zMm^|cc2?v?_jA0DTOng!sz0|h@pElz0b=A(7@?ZEPu$`etH~Aj9pZQ+ z7@cezFzFZT5PcZ)DvOIv`~TR1+~#xTMsDKQPb`SsN7EO{@9Kp>f;`Xr1Tneg&1;kPHeq zP}62wv{>8Xo;h;#yNkljSK)#->CV-Z0rIkl1(RE#qI0|AeaPdfiaWp`lYvza*1RTf z&ocfaHJR6ME0rb9PbzTWBcC1nee1JrxoGGLH5&WTiU*%{ntIbRp`=JYa|dX0HVNPC zO(Gd>4anBLvso5-K@xLqIWUjL?P!Z!=aetxa!kbs4Yw_b3|ge+N@usK+JZOlKsoms zHip~HO(f|mSaR^pN_D4x?IRhaLf@2N>-J-PfuMu+skvbvbaXRDmyLHAD*4ZY8QuD0 zuyfOz|{+H z{!doleJ1U+;1qEIv^cmnFs0JO?t=M8a9bIvI94x$D84T2em%7K?ea{Mkh0&LtYHerUDS*&y@cVC*5U7hjRet0 zzO|?j;7=`P$xVJVWKf|_eW5UGDDmFM^a3`tgnrNm)cUgQJOXkD#@z0gz{$nPebNO$ zd+xhfNuwq*e zA7QagXT@ozR(ZQAY4v*M_33`oZdvZqlaqzPL*_(Py@+ zjmO-yiO(r8QCQnJv#M>Ce=s|oUcA{FV3Ize2H0rTG^|_0^qPSs}1xqawAuV08uTEz? zD@|Pzy$^EbeidI3@lFo*C&v2BN(clM8#t`D_=Ol6BJF(Cr(*OBez?Ixyt1fbZ&!BZ zZ$pB6eOYib)@4JSv8cMY(!7}E5GU9^&E^9nVbm>*D|!U+(Ea*I)I%$2vj+^FiTkHd zW%qu&;~f)1q~<^rLCJGx_jQUV3HDBA{>3aGmi+IPa5H8uyp3U&MiGy#3bX)Qb2 zJ6m8l<9wznoylrQsH+Y48<7`pwi50hXwz)ax|2_byX7<@?f|w6Z0xWlNyx5Wq}=*S zmMawl#%NSM9cHe&+#FFcw^1ZzV%tMB8C`tq%si!I1C}>PR^i3(&C?8;75K@?zQRfw z;_{jwH^DsRy`ZJt(b+|_ZjCw#J?X1jhZq?Zyum2{M(fJ$um&|6-)B1Hh?QF>zlvnjc6`x!)wf^J% zrbvA!5V^k;9tFuZ{$>AhsNFyG`iwDQM!EAoy*M9tC;#{%OANMFe8E^n@wF#0C@-r8 zEtjE#T-|#u<=*wo$}fzY;&@Y`n|r@CUdSzGO{WDlh0A4$EPv;_y!m#3G&K6LAh1@ugUl|j@0{d zHy66!3d2;5Cl_L6S5!B<+2#s+>xoCnXpN>l6SUN}vy~0>OL39&GXc=HiQ#QC22Ll9 zmytpyRU`Frqv=8WkF{G~wwgLv<gT)@Mi30b`nV{z0MCl!w5;wux8aF|N#YYGbqCH43$b;+X7w3u36>d65wrgd| zTGR%*B2Kf666>s>Ok&4xAop^ph8yT9Kwa6D7Im9(H^wnE=qIj~RDK7X7A!r^GmVN- z(#<-%GCUEX|LKhCN^*yA6<)4M#*Uky@BrodMaD!r8;y>XcJ6UzhSp zYw|nmw;96GQ`sfyPN@y1=-p(>5pQLVhoyGN?Zw^v`n%Bv9dVkX^BG)qhAF-+c;bS5 zvE#gG*t3pHRzWlKS1jtbh!si3PRvC247^%Wc+XSbfgWR6i!k(OZ6xeZX2e@4rb1O+IM4MJu|Js`F z`txYrNd2K5!D!N`Y%^}5y{wFT=Xx;&zGYc!rwYl>!<)4W_pI#uTZxc3wOOv=wDIF@ zwJ&R|C*fMbR!OcElEAhqzTuLAk;#I=gi6!QDVQu%$=Bto@gmj^&<4G1^eG{4O3aQ|bywr=q80D>F3n);!~|`O+p8-6V2562i2FXc1S9|(Pc~l? z;6Arhsq+Ti744G`hGB+oTlchE*RH#(=dOag?tzn&GqhS)Lwj>hw7#7&`)$;#7k9jH zq}9~V2g%rl?A3E$@T^T>pN!!e)*yg4X+u*WYCkPf9GL785n^wdypk zkyok^QKM+iFn=SdCNSHoD^+9MUyn0X&$y5^oYbK(?)S1mPE9<(R2uPkR%GwNY-%~Q z=&iK%X!3(%88ux~l)fQfEZfQ;S*U{xT5dI2xl9wM$TZhdk-z7a)Ff%q6t*LRk22Pp z)?fX>8?dS8==qJC$DmL4Mapam<3%l&zT~oCD@`wojTyhu-!@h^7$BCEvQ*qpLLxk+xzcV<@tQ*gb(B<0#p?HHXbMxG>jW3z z4_{O#!}`Z|*Rz>?&$s&FS;vjB3+~y*zG`>+8`6(kb#bu6j=?F4!2|QXe6*rj;`-ig$hI)=>#7^Che)X4;ye>*IH?p@KlzozS-m?0xN?%UtMH6DST z;f>J9Fa=L?x`U-+OkUoqeTE_p5nLrb=Z@J*62VpDsf4C;t|G`@;xbdf;o8Z|iP7vp z@~h9sE^+uieiGnZ=WUnelE8C+<9b5HM;mpGOX91&J?@RJ=iB;>QT$gOSpDz*QlP_N zMB9jFPU_vv{dzIXjYqBf0ZbdM*PRZTo_u${JDqDkELUWG5|mY=^N!c%#|`aTq+3D9 zRtV?#d;w`kEY=doNcRo)G+f4=Cp7fpnwVME z+u3hkCZ+oHcoW6|=~Zu*XO?7Pz3pUiMaNh)FCce%=4VVlQ%3&f=6b{4c(l2|xS*6# zergqk$S8rezdy+<3ApJyFc#HyGy(@M$~V-wxXnJ_)t zD_uHz#tl}g&wokd{c6~RtC4wL?sc|fX#DQb%M)zLW&8~4tqyK?*Se`n$o=<4fm#|K zXgul@#+H4%m7mF>WVWaAVQrzbz+5tQSdZ~2&z?2r4iC5Rnewv=WJV&@w?>>}$&_}8_J%P2Pz(H%^1!Wcf{$IBS1Y#S1&;NIpw~S{lvfsx-qk#wN5fQPxFVA&_ds3I0<4!Z}{G3-XiC- zj^^>V{eH6IdUANUU7XKW^#~g1LpQ*cSbhAY1lo-A!1hBLoCo>$vHa@kX`gaSJ6wXW zR|GsPIf@Ba8Mo&JJFYR>%oi#2&vwp;=Sw4aI$KBso)nGP^DC4q=7Qb`R>c)8Yz+Td*zU#_@jV?z~aW@shgoFq_Jj0>|w6oo3 z&zBt$sjqywTi)MHGu!V?wmk`fazA zeo;r?L0Vgy_vh9A`K#=5cZyGl2f7CX@?wu#By_k7;G=3Bpw{hfh@b^{?!H5`rQ?~* zF6o>3ZW;*3@o}W9qSb6jEPY#cqYyA5Xr$EKP|>)x5L9WXW0rY6BK6~DBG(h_dJEhk zD~sp!r3QV=(8=cU{IHDk710X_%jny7EU*fA^D_#_Y^if5Rjd%>s|4<>w}nV8SYg(6 zRp4UuBojRG$pdGkp*>2Kl*kN9))b_TMOz@XT8(E3*>TOqPW3FCrOWrUH{E+KOBQMo z9nt{l)%-}fSKs@0hng#tr$@bLX4#1ng?6~%4ziuPP$!Q1+|C_eq2VE5yWbCFSjmg2H`dLf;zzmB&W zAi-G+#)@?wOg5ufiGhh}sdS_iKjB z_Pp;6)pv1o`yk461GXy}TI!1OO)V3zA5G8i7sJHs+OPANXS+!Yesi%KTBA=2nm`R| z7{`eiMXm|22JWgT3qT#^X+>ut4>f1&aS1FjxrN`eQWCG0l(N@a2X;1*mpZ>kHrYke zIgl>Oi#g%0jjLcmec`SxKA#6x#=p7+T%Up>IDrlk*3v;x?pMe5Z^eP&kimoQ^q5Uq zBir!FJQ*_c_bOLvx*yqm;YgPx&FVDZK}s)^TJWyOgP1g*u4Ahv;~ra8@Qk>t_`Zdx z*TBy{Vfbr1S3N@ft1#7ULB_b)*2rSn8oMS`uvujxbpy7|9a!?!l^%4$?3jn43RN-5 zom-!<;OovoRf**0{GVeS(H*?HCx@m(o$PaZX3@7bWL6c2uo?tVUrMfO= zNEmRqD*(_QO@8YZx43@aF;k=`{_$#h{RftcCnPIB1N5d=OWmg0>-yTb7ur+HEqHgEvXW zltbfWX|9K)bQT`9#-|HDGiFUQd#B8MS+{CB7+i1x<0#EOV-sbZQ3H#_?8NvMA$G&x z@(x>T-m(&ur^=~8$OQ7i%vWAJ-L`&uVx#!LxUmce^IYQsJrB%G%zzmWy#bUn3pbX$ zJl?z#V~K3Q6?XQ5_eV{^{EhxddK3W-y1nRr&O|+{~mMj#mIC)}FdGzKt38 z&F;jfu%O^P6A851vJZaBee(NA?7?@OwNJ97t&+n=#MHsWS4eWNt;0f5WR@TJ5N=(0 zJyEgq9=$l5&iwn~(Wvg`F2a?4Z$?@xQ!mtl@$}j6uxvk_wOsDpOtN&jJobn{9m)=BC4PgK7t0>D$0$)vbQ7|nel0Q2rZul@I>+V5x=oc& zQGX`a9=fx-;RSv*p&xX#<4Il#2;~gB#|r=`Ty6;NRPEzguhh)4N#7ZDHKjEeh=-Z) z(nH06{9A9+7%<-|Ncwl(Sg^|JudEFcfi+R!6l(tSyGQfz)RXfU&* zza-QD=IXl}H*Y3GhyM+c;GgOKzl_5CM-%S;eMSXd5C3Hq*PyK@+d-RrNoyFW;kBDA zupLuinIdtnK&LYTY6w>Smoap*cL~MAs2N1Ic6*X!{HoYz8i;GT5(2tuA8vxi(SDnK zNxYjkoM?Hzr>CWrQCy@eMIa_J#`exxx-#%om4=QEp%@TdA-bkyq}=o_`JE6gOj}c+ zvv>SUlPdbNeeUr}Lm+=E^aQVwDxrVk){f42gO!6GfmSP@=k)`Fr!zdA9q-!J-I>RZ zm&CHOvu9#piXI--zB_XpGF$}()pe-A_vMdLMhx_d^F*C{?Ii-3obFE0X2|#H-fCYB zCr&j=Xb%q+Uj*~H#G;BKBb)DwPyM-P;4&{%rAXAlpA@i-sn20^a)F7m<@5A$AZ{dr zoTAM=@91PxF20-TM7L+py0T&%l*z^@12YPa-@I@X0LB@V-D}oP*ab7#CWxG z%SoCCD!mtW|7z|&HbcpYQ~Zf7;8*8PCZz^>{G1od66$;WNt<3Ak?!G*+gHL=)X~keP zmhSR#3z#+qZJ8HttS#hQ0h2I01oR4+h{~mrIPchiV#P@4; zmieYBtONkSKE|Lq#yVqBF8gHB4hbEG1~(R=mQM_?#hzK&^t4WwT-!TB)3jiG-c+8t zgw~NVi-0r=1$TrjJFU(0lTKxoYlZ73?!F()YaC038Uusj21vX9q+H1mzNt^s)W8{C zhPjLMvIlWBH8rh99MapdA;$$N0xd5gb%J%+giO(risS&t7tuF|;vMFMz9J6Sobzxz-yA}Hbu@jSej}VgZ((6! zm+_~a3#j<9b{_AUw=~jQ{Q4PVt;+_$Y#n)W_q+~PUE|*oz#3}FigOVQSCVS(Xjsdj zGstsywMO1Wq&WAsBq>IS@~&-;Ml!S}mMj?rxIZFm2XgFurbt3|XU^xmhD1;M%zak4 zoSAnCD}5o9)OMM*dUmk^=-9%u0B84KI# zDP7(xobzFEx>$}#i1N=*h$G|fN%&grMwBnAY{pv0V)(3&0;>E59=%d`KM20>oZiz`G4aYV|89+NeF z6|gVP)w0<(+?FBvs>H4GuE~q&!@FKLk3>6?o!i!$_P4HHAeIDtHS&sU@1Lq2%xZX2 z=WtcThH$+oqwhVd4sm`sCj{5%xo!1$aNF32MH82@HjSS>5%g*s(=kjdg=e@mtDhGg z`%Y7`U1OQ~01S)c{Gj;479TCbCGCzTnt>g-id^c79Pbou${&i4lbK6YO6xl~M~?R} zE8kynkg(K|z3FbncG0>!0yH0O|CuNmQ%Yc(LmDuF|icgz18G;Yl^bES1b<_1l^tB(9uc{<2J`-5~dG`u0#r4-5PD6$t3MJ8uW8f;pZ*kxk z5mnw4zR3c=!Cgo~+Um|8{ZI2c%2&F>rs}VXu)y{gu<-;~)P}kDhg)|=X%UM%wKV%V zdqW7R<*z8O+klpwV>!)^tpH9@Yu*!{%j35eurOi8UZqSf$0V3#rFmVs24z?KQhb{F zZEBcujF9-O3Q>?je*X1PFoPkIlZ^ zvgbzgu^H%im8a3WvKuI*PHC$J4xWqwtcg|OZkj;<1-Fi8z0Mi zgJVi0qg%2Ebb!t%FryjXkazA7m?P{spcm(uE_NEKXWG)WuHgohkF>x2E+Xv7fr85y zitd%|Gk>0XKH0CcW4Wd+2kV<}L(mH6h9ja+|G*INe9n5x5aQ88&RocG20iV`szf@AwWc< zdU~*Xh%xX!NH^4!j`R|K)f;}ik0cx@^^6XIg4pQ-`OhKNH>t8uK@J_CaJ)7OQS3wQ zdMqI}GYecXsM`^BTVGiB&-$Z~{-ItBupeo<+;eSm3t862=Wp!Dr5bX+bZMQ%W5&zJ z{FIW>b(a$zlCyT0#lG0Qts5(7>;J{eO6y%)T6bAnc~QRzimP3zI=Wyum;13LXajP< zaW?D$(cbuEd-i9hxnsZV43no{L|X%0dAQU76CLfUNvj7gcxE{O;1$z6WBBB(z3-(u zthg*ef^6)Hp<`d%I4eTw(j(grcOe~n~CW56tZb2!jz1enh;^qI`h#PVqI0{CPoM(S8g}^fdE6MfvE{^-~(dijQgNq_O@EFCrTm0v$f3!|DCj#qd71 zOQ+Ljt5oyRKeb;jqLmi4$%T4Vdf0}80-t84nHulDr{?LKEd>@)hz>m#_uaZ3jms&0 zC+1sqC}2Xb8UQpwpWa-)ceNFXdUL&z$MG#%;ts0 z+h8N~;25&2Y2I}Nv{#+RnV{jKL(}^S_@k{RJdfWRFt;_NMaxEB-Pj)+!n39D=f!wR zbNMpbwX#GMjFK2#L^kN$Gb@%FWa^OJvzg3HWzkmdPdyKMulrc|E~1ST#*& zXLxL=(n=~3$3Ko7R^afVF&#bCMXbGWETa492gyy&nk%VfF`Mye{POsR2@AuK(+f{W zOtC5DMY-{{k4UMq9VUtVoMx452-2~0>ATt>|KkIL5|w|^Mdl}@hsjSMB2@Pxo^=yg z<<3_2K)|Sd{*=sw*T}U6Kl<|nZ^|y^(+4fI6VC;{IEU3oo95gvK;w&I#=?N1lTp|i z-2#JcZ{`D8Y<3o_oy*(9yzao4m{kf49A z8EF-T`DU}|wpgx43u=WbOJDqt`)uL$Dncu!IR6||%rtp9Rt$c4HH}+1rQ5=hISrY6 zp~+zunlOt`=YIFNL4OkJjc;~;aPW*IE$?F~^KStGK$_P-PHc&WR++oea3NuIo(t(< zqu~AfOPB!g&;At?&l;$^T<(+UR{x)0$dZziA%-I}KWGpze?88;CNRwBGQy3o$xZza zBydF~zxHL_&h%PDZ^BJGx+1ZDr0w||M#SlHU0%m;G**PY{`o{h>E-iWA0}bhw7Y=N zaHY58=dcI<=lQ&1#dt%TrCL1-=Ffbs{##!idRYF`po zB(PB&Gx3I|=ASG)r)-y8pH16X5YEEAOhkSmgGTz90+AO!kqg}^GYp+%|NbZE@lR2d zSZ22V7d4)n>%V6e^!|JG>i@F(N16MP7}2}Zfj^+(N7#|Fg#DDDO8_Toi7K)|=78G@ zN(KKN)?bDEU!(j_ZhbqU?zP|$B_Nk$v5`u|eZ>Yq8|_KubVR;7UceSo$s&K&M1Y$Y zjlCgv=jq7LpKv|)$De$qzX4qgo1f?lx_wCzMb$w@1sM7C%90{od`~bmTt$*XBxrKK zjP`R?(~cA^saH4gFGBSzR^l1zH(bkCo;g@%#Yg+kGUApAH(QpZK`>7AU^~f3Da^lMso&E>6ZU=9R(uNSsxVC2_UT1p5O*;Jk z^<53WJ!^XH+O_$KWO!rab7|i#J#~G3*qtnjD??$Zbb5VbtA37qw=qkND(41b-7;x0 zT3?()mm<2L8XJyyJErWVHUl9)V=DvI-104g9t8dT1Dz ziZTjnne43g--rBq7fLx&>Y$U73=@fXE4;3gw0Kg}Cf9LwfqAIxl zFjS>heUY0x>X&R)YT5gqv#QUw^IPMW0#4k*(ECz~COtEh8ivicB)CnFI`@-Q-d=Q) zQ3?nD*3?9dwU;>g7AL1uR7>74W%7de))ILpHR~;@)Ay%5`O>m}7M+NE4f-{rM9?kxjIU)>gtb-N$RIo4&ZemuXU}j}r42XvCrI=m7OEO& zAN-c<^H-CZ(Ty3>i=JQe2)60pljAxOXb9=ojh)8a0P-AkAK@ z2rDwM0?RpYCR8k_%2c>2m(DMP>?qAuWZs2iNK#`boe_blV$1^Fu5UNx(MittDxAF( zcNMTh;`i@zi&%hUZI=hONBxW(_i_z4n`gP6*9We2M$YquEB~7Bsp<)?LXZXvN#k=< zCT#qIE_uFGhAEny9Q z$?}ubwq$#~0lwnUr8)ncE+M3hqxRePz5wHYf*%C9sx53D&)WZSmsr@3q9=b;+xmE5 zIe6N39auh)K0HkcTpHvv`mu1PdCj!&5xY+fd-k+<-xs^@L+!lBD32&Lb>lAjn~>Kt zE@5Xsd1->yLZ4PO$U3ycUSWF7hB~_7v+-Q7gjf?*M??O&4n+e3qm8uwC$hKmzYXQ zuI%AhOskL|ikgt+Rkj-^V=^tlEo=_iCqR-o+B@OXr%#!E=g#R;g@5b*kn~V%hI`wz z1(VaXkZ^J{*R$3>=(k9Qk_fQ9?1TFOjocAJNgG9EB8o%3@rxRSNrvkQqG+vN8OP;X z3Wfd`(!*LgVqYbxvmhT_=_%!Gl3q<;X%8rtZ47`+9-Oo>Sl1!iyR}9NPEFNJF8I4L z@9GS)EVblMyFM`S^(>3@)!}7eDvLq#$A=S>QLaAZarbd2MtQL-JjAvz$Y!K;;@OZ^ z81il|`>U7H9cwcApZeKGNSAZQvVpveM>v5rAMeo}cXVNb@3oSiEk8tytt@Kx3lrye z?ByXD(GrJY1^_0;OX1)R-O$%x-du9mMKEQ`W0^ZN8=|J>$IJpR(hHLMld+>MfdMm* z{Zc{zQ{{Z2P)M7`8(w4L5hXY)LCjcdD&L~@XDKL`)-T66^(@h^c=8T?eRe0{$H@xO z?7G9SaM_{xhN)R<+iw&1ENTtbB^k*Im(`b(<;KQ5_f8pO2edlW&S{&(rs*|F;@C@z z#he^0A+ywsAKI?rue^Zg3B%4?Zdw9hi0(&>!!f(6FE*&0r|b#U+m5M4JE5|;$lVXtaG&f5Cs zF3nB^A!)a_+H;Tts0~V#zc_;IXF{bNF4SWAg+EWE*TCzky zjfXzL6z7Hla_;^2xAvA8Pct{PxJz#a7)BS5U2ca^zKgnO&ec!@e3HDEYEkD@Y|-ln zsUmj*W@c9aLSL-NoE5HRgn-%zI%!)uxx4O-~Pj(4)NNbG#>a?V?=D5U%`XmQk;quuU&9N${TXHH>v>OuOJV zjzJatvD4i5MeO03{WqY@m!?RQt$~soZq_-tA$a-DrmK^q_;=?X?0VfZVc*GM0{NGw zr5HnrkZ^9XlUVUq;nurOxf#kZD<>YBSROPqhr@4@D|Ly= zer{WHszBf{BxW3}k#d)0s!-|=NDAl5s2QLFAMZIEo->uXH&12DAD1{*Ec_w^gpU8J z60Dr(uT?5FZr`Zxp^kG%l`;&^B;>L@Rk*`D2$@4Hdv6OY#F2qbog)L0)>dL8*x8ta zb3$^*ssy+4RJug;@Y#KL7X4}Ew?+=9NwfT=wXCn)J{s@--c1^!tvybP2vSUj1J&{@eN+ZItBO$YY!cSQi&GNyqP0~qV^t$7ZP-$NN zlUHx*f*n<}6vsEGH4(vq(Vy?~1v|G1uO4jO+d36*@qF85bL-+?`^Irc%vg!Y z`rHp0iX$_2hgg2iPHj6=mu;GsF0s;TkeDK%pi^uE&9OD zF~GUp1Mf%pJvuJgXS^w-9Z^hgQrP_HtY&vCJS$yr1SyGXe9|c*cYkQ0qTIjh0^_Qy z5q#`5lVdWowC~4mqOQ?XX6dQpTfAYbclF+@hfUa?t9>PpKduVc@(%4 z#50^zD6n%<^)z92M$%b$HKMO=t?;QsK))8L{;7PWB$a~Q*yN1g@FdSkr&d_TD!V~@ z{$~uTVlEB(dhc{wDD32+@nYFo*=GtLYj>r~+>al7H#`Zoji84PJI^!+wJ@-_!A#&l znBoZuT9z*5ja@m0xw4Ueb>2Srva_oGc-j2_@v;Y*nyrB4wM)VaUt{ z{o({tEkYQaLbuw|?~N1IQ_t!!Mw~IgB!8HdQ7mV%mfCX>xxuQ*zAXHLm+Ost-pMhg z&P_LM7=L{|jF7a2>y)=p#jKZ9#g_na)1M`T3=9c7KG`IK%{|PKip5_j<)o5Xk#c8= zvJRU&Z;S57Z$I!^3Byj!%AbSba@Phqra+HXp*964yN1_Ho0QLCBlWvjVLL=i+k}4e z$mP%G`c@>6QF)ddMWt_F*%Xxj-&mpo;7>5u`aOyx^UUP0|LBFY56 z7a{b2hEH!Oo*b%O2BlQAUJIxG?1agclw7uU2Gi}t^^O{Oe~g}tVUad>1-|PKKKoB6 z1usxSk$(Gt851@5K{bZe*vu?VoDvodQ<#lXb+x~K zwbIMO@-JHUfmu*hJi!+KVLCD^Jd31ezBu06mN`e{c@R1DZ#=vLGih3}u-zaHnm9N| z&R`-K4*Fd?ECo7G+F$wjw$cPVaNskza`y!Qz}MR(RW+Kc0QRb4iigN!ghTgqZ5 z3JPs&d?4gtIks-Cc~fMIOJ09(t|`iCVLpwn;Uf6I;J-gGa>)Dq)(=bX@#;iVT=^g1 zP(x-X^zMER_^jNRhwss^;tslNBmbaK9`ed$cQ&f0adod>g^~df5ARNeu0_jS$<5Or z0%)@xiuj+S%S#Vz{`q=F;eUdG{|o4LM(+Omc}A}9!M|AQe{=l!|L3@L#gE`ZwP9EJ zVtN9m;xZ>wJ5J zx8J>B{+HND2Qa@t?&Ak}qTU+^_*-zllQ92a2rQ2Klo0h;u6)5#^x=zK(Vq=&(9bh~ z&5w!C$t$(rov>~ZZQ5^=iyRO_HY1L)4t7=bTWgR4qkYD;dpKPDp~zS z-gH(H@(1pp&ugNG>8|}ec%l5kvE7jrbn&|2xufu+=puOBuKiZ`_rGA+i7E5R^Np`F zQmME@Bio(5%YO#~{Ey{20_l1Nwlw&t((S)do13kOk~!H9{r9hqZar*k7 zPlJ||pQi|r48V>>{@fw;T$^&pgsbopl?Gz*;f?j$gCGcd%kzvuCh3Ogu@LKdC8d|H zcc%tO7~sh(cTkeTO6Fxl5#kRW?cT_-iYdIFqcCiJ-vxc<@p`^GNA%&d1?G8EuX6Xk z>>$XVwSxuC;2!5;(mr%Od(m|e><9k37KpS7{t$0t(;TGsX6+!>7g%!$yK-R^V^|CN%V)GWC-pA=SoYl`Zg4j2Z>lr(`Zl`c8 z$Xdb3!m)+;d(C>oA<@u1V*5T+%j(mEy3>AgM_FI_6PLjJqv@UA9(vHObkk91q-SkO zQDN$BSy2u}*)5Hej{#4V&N5N6=eZ?+N^bSXGtFj=Sq?~9x=Jwt1!vgDcc`wOb82Fc z!#Xr%uTi{K)%0Xz={X*3o1Jn4Oj0ik$p}2zJ0pOr*+noltj$R1J9eeQ*3Ls7>yg|32F8icl2X7vtWAIKP5&1mJ4rmP6YNXVlN` z-YAQepDV+;h|i|^W(T8rpPESvA578@cosmwt~pncwMUmvRAXwHBDP&g$a-ZBdQbtv z*P*koKdDYy7b;Z`*TPBV!mA`5l6ML*jy|8{W~-)~kO$aru0^sW(N(l9_DOC@HZv2f zwNf^{?R*u(2@|b}PWVgW0=$pMm@Np{*B@WjDnXpTDcj6sa?nZ&7;NjZPWdHcoRGDm z$=i#}1+7+L*tyQuwpN7@OM^m>S}C=(wc6u;euffjU0ilN(aOh$tELVM1_8^*%r<+|8$5E_s=1yuSf*9hO%W%QM#Gx7v+i=0njh>2 z2idxp?jXx!QNT&XsSMB*5x00jutK6$_p;c{Qf-_+ENfErtd$)&#R=UH)QDY=1@9q{ zwyH=-P!vi>d&G~FCh#5Vib-T00$U^RS%#2a!B5wS51zLZ3)v$$HgjsPf}0NG z28a)~g{)^V-zF|P%Xy_+-^z37HdD@O)e@}bE5G};1$5{7qvszyy;$E0SC6fn@H)IEx~#`K`=BLcqq8nyNy6GNQB0^5ZF*v3bady4uG^y;d%& zeV4ScFXmgcu%q)qDUz;AMaw-0C?J_pLrmE5RvJb z5Hm^43`4eM-M2C5=7P96R!b4rOV4&j759&nD}r`dPo~P3*R&Z#+!YXg!e>S5^pzuQ zUY()=POWbBaK1WO=!2x>R|W!)A<7iD+=%DyQ+UA@{DE) zEQZf_pSa51!{bn+n?|<^g13uWGYgJ1x13mH>rLHp6(3Wq79=g>`^GP_d5=~HBk?7% zblkHUw?=k5Ax~->X6U!dE_&@1{_^yx88^%qeb}nTw)04j@I?`V>9lo_y@pK*)S8V^ z%aVSUu^nj~Qp?vuzfvwEX5i%_*l5*Avmb?E?=piL+Xq10wJlggadpe@Xf4yXwHh{p zkI8G}YCk1$8bqg>ZgP9n&*elhhFKm449Ikj@Z zfmI*q->8y}L!y2kjBCj<$f>a`*&?}(S&o-9(J2{~bQm9)^_P7k5@sSRfkH}C5p|t~ zH(sUt2QWMP`&A$Pw3--=?SjGB{KjW#s{Mrplzl>^HdVwzO?LjveWfUx3MA3Nqlxgy zQnon&qssc-ZHK+-*1l}P2Sp`V|}03({Ur0&7mm&Dst8P9j)>6#vtvc*;tW*Dq(|LCA3dw z3j*rg+Is7NS9h>h2L3QUL$|3d z1O%0Iw+0)Tp{20UTU3{9!&7DLgJqztb_xz39t_^9acoZ^JX1+UK3}aX;t^_}jNisy z<%gZN6)`TnKvLGRL>Y{&&qEx{=})+y7{Nn=)!dCpng3WWIw>d5l1r=hZWCWF-VBJ< z#e>WW!yiu5`MVvLfwfi#KOft^57R06B36D|y*B9ib{4tPQ}TG zCr(JwC|c7ztW?OU0~N&AYdWsoKM{gQXQyQ^J$ska-0Jm(O&K%qnpn(^tR4k+x!;w` zf874Wm<5^d6ZE`n{zve$0I{Feue5T4(%=Mj{q)MG$m7>Ru4#MqYa6RedeNFPC+L1D zKXG}t{kDqwRDtJ3Qi$C`ps(ZP%H=&)!371-V4SbutjD9}TtcQG8&5v$h$EE^5l}1U z6FK;gYYkF&D>)r4nhAJl&O#MKV7)&R{0uuPY4X6wXqHZMyQOP=O~=6;SCu|DNh@V8 zfXUR$%NOXH^gP#esBDCGv=*GX3p+&g515qC> zS*~oC_BLpbskP+rvzEZM*~%vR(E7SXJdYC~zFYahYeA}XJGo>f?{7^thhP^!zNy?W zBV|g@wZ#6nR?ajg4Fihfy0)`%i_TaxYX{Y~o5zw8>($~Ymdd=XXJ=Lq(&|){q4O%> z(X^vl8z)YRIz_9FBD#TPUKIsPry>}Hj-DsWyTAu0$m1p>n$7vW+EOtCPNJgc52UJKGZ zdf2Nl#H$6!nKl*>429J~#i;mN+A+P=FIlZ1*Uzu(hKR`Ld~)w*=avWb>L-$l?zL() zc18&`ioI-Bxa;1?*g7xkgE28wx85}UOxfd!)>>Y`D=dxW0j?-_N1CsWlKf_BGDUjX z6&~aVSG;WG`^4}Zy|oIJ;|wLQk0e~Bpz-ol>U>Le&h`8lXrXtI+1$`dqjT4hM9`M* zjx9M^j;~R9N3`-v!jgcz94wWMu}{D>M#w6xu~X->NE+Mm5I1mfiri6b$dTk??F-78 z5?=+$D$`uNg$KrF`7He%r**{rp?8LOFv`V6vNQ$Ak0ZV9izhFR8iZ4fNWO-qvbFO^ z8L7ZMYK3AGhQk zviJk(xh!cjVKRD-z8v>6zr29nch40$OJ%jj^6EJ^Fg1gv>V{w65-MHhDjT`C^yUv% z=$0j4U(~+se3LO;mOh?p_P?6$;Fz#)KE#ce=n2cDmfMIhN=D;DwE} z@jH;OJPV+Rd0G|Lo`-P zRgS&J76Uj<44uJ~d7@SZ1w#vz+w-tt*EqMM;GbsC>XZOo(8CUSbH70-cj%SR$?Q_m z+;XhLfr3BoUgyFqC9OnV5xLo&e_RMoeFFGkVI2~hkufSrSfxW845C5l@%BSwz=rS& z!6S-nrkyMr%Rpn3PJ@C~zmJS`?YQpurinXxm#$G4eE$Z#z6ut3^WU_*%j?npBLN^hX|!-`!)S31LC`+g251D9 zmdJpiaBPRC)dsG8zIZEMsoRIjJ41QH?Xo=}CoI0!q@ZY{IwU8-2$8IL69`-`_lGr% zjimg<$}`ol=J|HM4e7(!qjCb^%)kbs(^Rw#INMJ=qj6T4Lx~yL@}w0ANcE_G`lMA)k7=0$^Y;N<3B%X2&*+areR#OW_B$c PxtDJMJk*yCL)`rbwE`xr literal 0 HcmV?d00001 diff --git a/docs/VTOL.md b/docs/VTOL.md new file mode 100644 index 0000000000..64afb333d1 --- /dev/null +++ b/docs/VTOL.md @@ -0,0 +1,236 @@ +# Welcome to INAV VTOL + +Thank you for trying the INAV VTOL. Read every line in this tutorial. Your patience can save both time and potential repair costs for the model. + +## Who Should Use This Tutorial? + +This tutorial is designed for individuals who +- have prior experience with **both INAV multi-rotor and INAV fixed-wing configurations/operations.** +- know how to create a custom mixer for their model. +- know basic physics of vtol operation + +## Firmware Status + +The firmware is in a flyable state, but it hasn't undergone extensive testing yet. This means there may be potential issues that have not yet been discovered. + +## Future Changes + +Please be aware that both the setup procedure and firmware may change in response to user feedback and testing results. +## Your Feedback Matters + +We highly value your feedback as it plays a crucial role in the development and refinement of INAV VTOL capabilities. Please share your experiences, suggestions, and any issues you encounter during testing. Your insights are invaluable in making INAV VTOL better for everyone. + +# VTOL Configuration Steps + +### The VTOL functionality is achieved by switching/transitioning between two configurations stored in the FC. VTOL specific configurations are Mixer Profiles with associated PID profiles. One profile set is for fixed-wing(FW) mode, One is for multi-copter(MC) mode. Configuration/Settings other than Mixer/PID profiles are shared among two modes +![Alt text](Screenshots/mixerprofile_flow.png) + +0. **Find a DIFF ALL file for your model and start from there if possible** + - Be aware that `MIXER PROFILE 2` RC mode setting introduced by diff file can get your stuck in a mixer_profile. remove or change channel to proceed +1. **Setup Profile 1:** + - Configure it as a normal fixed-wing/multi-copter. + +2. **Setup Profile 2:** + - Configure it as a normal multi-copter/fixed-wing. + +3. **Mode Tab Settings:** + - Set up switching in the mode tab. + +4. *(Recommended)* **Transition Mixing (Multi-Rotor Profile):** + - Configure transition mixing to gain airspeed in the multi-rotor profile. + +5. *(Optional)* **Automated Switching (RTH):** + - Optionally, set up automated switching in case of failsafe. + +# STEP0: Load parameter preset/templates +Find a working diff file if you can and start from there. If not, select keep current settings and apply following parameter in cli but read description about which one to apply. + +``` +set small_angle = 180 +set gyro_main_lpf_hz = 80 +set dynamic_gyro_notch_min_hz = 50 +set dynamic_gyro_notch_mode = 3D +set motor_pwm_protocol = DSHOT300 #Try dshot first and see if it works +set airmode_type = STICK_CENTER_ONCE + + +set nav_disarm_on_landing = OFF #band-aid for false landing detection in NAV landing of multi-copter +set nav_rth_allow_landing = FS_ONLY +set nav_wp_max_safe_distance = 500 +set nav_fw_control_smoothness = 2 +set nav_fw_launch_max_altitude = 5000 + +set servo_pwm_rate = 160 #If model using servo for stabilization in MC mode and servo can tolerate it +set servo_lpf_hz = 30 #If model using servo for stabilization in MC mode + + +## profile 1 as airplane and profile 2 as multi rotor +mixer_profile 1 + +set platform_type = AIRPLANE +set model_preview_type = 26 +set motorstop_on_low = ON +set mixer_pid_profile_linking = ON + +mixer_profile 2 + +set platform_type = TRICOPTER +set model_preview_type = 1 +set mixer_pid_profile_linking = ON + +profile 1 #pid profile +set dterm_lpf_hz = 10 +set d_boost_min = 1.000 +set d_boost_max = 1.000 +set fw_level_pitch_trim = 5.000 +set roll_rate = 18 +set pitch_rate = 9 +set yaw_rate = 3 +set fw_turn_assist_pitch_gain = 0.4 +set max_angle_inclination_rll = 450 +set fw_ff_pitch = 80 +set fw_ff_roll = 50 +set fw_p_pitch = 15 +set fw_p_roll = 15 + +profile 2 +set dterm_lpf_hz = 60 +set dterm_lpf_type = PT3 +set d_boost_min = 0.800 +set d_boost_max = 1.200 +set d_boost_gyro_delta_lpf_hz = 60 +set antigravity_gain = 2.000 +set antigravity_accelerator = 5.000 +set smith_predictor_delay = 1.500 +set tpa_rate = 20 +set tpa_breakpoint = 1200 +set tpa_on_yaw = ON #If model using control surface/tilt mechanism for stabilization in MC mode +set roll_rate = 18 +set pitch_rate = 18 +set yaw_rate = 9 +set mc_iterm_relax = RPY + +save +``` + +# STEP1&2: Configuring as a Normal fixed-wing/Multi-Copter in two profiles separately + +1. **Select the fisrt Mixer Profile and PID Profile:** + - In the CLI, switch to the mixer_profile and pid_profile you wish to set first. You can also switch mixer_profile/pid_profile through gui if with aforementioned presets loaded. + ``` + mixer_profile 1 #in this example, we set profile 1 first + set mixer_pid_profile_linking = ON # Let the mixer_profile handle the pid_profile switch on this mixer_profile + set platform_type = AIRPLANE + save + ``` + +2. **Configure the fixed-wing/Multi-Copter:** + - Configure your fixed-wing/Multi-Copter as you normally would, or you can copy and paste default settings to expedite the process. + - Dshot esc protocol availability might be limited depends on outputs and fc board you are using. change the motor wiring or use oneshot/multishot esc protocol and calibrate throttle range. + - You can use throttle = -1 as a placeholder for the motor you wish to stop if the motor isn't the last motor + - Consider conducting a test flight to ensure that everything operates as expected. And tune the settings, trim the servos. + +![Alt text](Screenshots/mixerprofile_fw_mixer.png) + +3. **Switch to Another Mixer Profile with PID Profile:** + - In the CLI, switch to another mixer_profile along with the appropriate pid_profile. You can also switch mixer_profile/pid_profile through gui if with aforementioned presets loaded. + ``` + mixer_profile 2 + set mixer_pid_profile_linking = ON + set platform_type = MULTIROTOR/TRICOPTER + save + ``` + +4. **Configure the Multi-Copter/fixed-wing:** + - Set up your multi-copter/fixed-wing as usual, this time for mixer_profile 2 and pid_profile 2. + - Utilize the 'MAX' input in the servo mixer to tilt the motors without altering the servo midpoint. + - At this stage, focus on configuring profile-specific settings. You can streamline this process by copying and pasting the default PID settings. + - you can set -1 in motor mixer throttle as a place holder: disable that motor but will load following motor rules + - compass is required to enable navigation modes for multi-rotor profile. + - Consider conducting a test flight to ensure that everything operates as expected. And tune the settings. + - It is advisable to have a certain degree of control surface (elevon / elevator) mapping for stabilization even in multi-copter mode. This helps improve control authority when airspeed is high. It might be unable to recover from a dive without them. + +![Alt text](Screenshots/mixerprofile_mc_mixer.png) + +5. **Tailsitters:planned for INAV 7.1** + - Configure the fixed-wing mode/profile sets normally. Use MultiCopter platform type for tail_sitting flying mode/profile sets. + - The baseline board aliment is FW mode(ROLL axis is the trust axis). So set `tailsitter_orientation_offset = ON ` in the tail_sitting MC mode. + - Configure mixer ROLL/YAW mixing according to tail_sitting orientation in the tail_sitting MC mode. YAW axis is the trust axis. + - Conduct a bench test and see the orientation of the model changes in inav-configurator setup tab + +# STEP3: Mode Tab Settings: +### We recommend using an 3-pos switch on you radio to activate these modes, So pilot can jump in or bell out at any moment. +### Here is a example, in the bottom of inav-configurator Modes tab: +![Alt text](Screenshots/mixer_profile.png) +| 1000~1300 | 1300~1700 | 1700~2000 | +| :-- | :-- | :-- | +| Profile1(FW) with transition off | Profile2(MC) with transition on | Profile2(MC) with transition off | + +- Profile file switching becomes available after completing the runtime sensor calibration(15-30s after booting). And It is **not available** when a navigation mode or position hold is active. + +- By default, `mixer_profile 1` is used. `mixer_profile 2` is used when the `MIXER PROFILE 2` mode is activate. Once configured successfully, you will notice that the profiles and model preview changes accordingly when you refresh the relevant INAV Configurator tabs. + +- Use the `MIXER TRANSITION` mode to gain airspeed in MC profile, set `MIXER TRANSITION` accordingly. + +Conduct a bench test on the model (without props attached). The model can now switch between fixed-wing and multi-copter modes while armed. Furthermore, it is capable of mid-air switching, resulting in an immediate stall upon entering fixed-wing profile + +# STEP4: Transition Mixing (Multi-Rotor Profile)(Recommended) +### Transition Mixing is typically useful in multi-copter profile to gain airspeed in prior to entering the fixed-wing profile. When the `MIXER TRANSITION` mode is activated, the associated motor or servo will move according to your configured Transition Mixing. + +Please note that transition input is disabled when a navigation mode is activated. The use of Transition Mixing is necessary to enable additional features such as VTOL RTH with out stalling. +## Servo 'Transition Mixing': Tilting rotor configuration. +Add new servo mixer rules, and select 'Mixer Transition' in input. Set the weight/rate according to your desired angle. This will allow tilting the motor for tilting rotor model. + +![Alt text](Screenshots/mixerprofile_servo_transition_mix.png) + +## Motor 'Transition Mixing': Dedicated forward motor configuration +In motor mixer set: +- -2.0 < throttle < -1.0: The motor will spin regardless of the radio's throttle position at a speed of `abs(throttle) - 1` multiplied by throttle range only when Mixer Transition is activated. + +![Alt text](Screenshots/mixerprofile_4puls1_mix.png) + +## TailSitter 'Transition Mixing': +No additional settings needed, 45deg off set will be added to target pitch angle for angle mode in the firmware. + +### With aforementioned settings, your model should be able to enter fixed-wing profile without stalling. + +# Automated Switching (RTH) (Optional): +### This is one of the least tested features. This feature is primarily designed for Return to Home (RTH) in the event of a failsafe. +When configured correctly, the model will use the Fixed-Wing (FW) mode to efficiently return home and then transition to Multi-Copter (MC) mode for easier landing. + +To enable this feature, type following command in cli + +1. In your MC mode mixer profile (e.g., mixer_profile 2), set `mixer_automated_switch` to `ON`. leave it to `OFF` if burning remaining battery capacity on the way home is acceptable. +``` +mixer_profile 2or1 +set mixer_automated_switch= ON +``` + +2. Set `mixer_switch_trans_timer` ds in cli in the MC mode mixer profile to specify the time required for your model to gain sufficient airspeed before transitioning to FW mode. +``` +mixer_profile 2or1 +set mixer_switch_trans_timer = 30 # 3s, 3000ms +``` +3. In your FW mode mixer profile (e.g., mixer_profile 1), also set `mixer_automated_switch` to `ON`. leave it to `OFF` if automated landing in fixed-wing is acceptable. +``` +mixer_profile 1or2 +set mixer_automated_switch = ON +``` +4. Save your settings. type `save` in cli. + +If you set `mixer_automated_switch` to `OFF` for all mixer profiles (the default setting), the model will not perform automated transitions. You can always enable navigation modes after performing a manual transition. + + +# Notes and Experiences +## General +- VTOL model operating in multi-copter (MC) mode may encounter challenges in windy conditions. Please exercise caution when testing in such conditions. +- Make sure you can recover from a complete stall before trying the mid air transition +- It will be much safer if you can understand every line in diff all, read your diff all before maiden + +## Tilting-rotor +- In some tilting motor models, you may experience roll/yaw coupled oscillations when `MIXER TRANSITION` is activated. To address this issue, you can try the following: + 1. Use prop blade meets at top/rear prop direction for tilting motors to balance the effects of torque and P-factor. + 2. In addition to 1. Add a little yaw mixing(about 0.2) in tilt motors. +- There will be a time window that tilting motors is providing up lift but rear motor isn't. Result in a sudden pitch raise on the entering of the mode. Use the max speed or faster speed in tiling servo to reduce the time window. OR lower the throttle on the entering of the FW mode to mitigate the effect. +## Dedicated forward motor +- Easiest way to setup a vtol. and efficiency can be improved by using different motor/prop for hover and forward flight \ No newline at end of file From c2577e477733ceb602859a9f35baa24925cc9365 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 31 Oct 2023 10:34:49 +0100 Subject: [PATCH 174/175] Put getConfigMixerProfile as the last byte in message --- src/main/fc/fc_msp.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index f504ffb059..fddcde00eb 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -462,9 +462,9 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, packSensorStatus()); sbufWriteU16(dst, averageSystemLoadPercent); sbufWriteU8(dst, (getConfigBatteryProfile() << 4) | getConfigProfile()); - sbufWriteU8(dst, getConfigMixerProfile()); sbufWriteU32(dst, armingFlags); sbufWriteData(dst, &mspBoxModeFlags, sizeof(mspBoxModeFlags)); + sbufWriteU8(dst, getConfigMixerProfile()); } break; From fac64cecbbe768bfdaab09046d6b13e2bf0dd297 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Tue, 31 Oct 2023 21:41:16 +0000 Subject: [PATCH 175/175] Update navigation.c --- src/main/navigation/navigation.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index cb12579b83..c991531f32 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -4055,7 +4055,8 @@ bool navigationPositionEstimateIsHealthy(void) navArmingBlocker_e navigationIsBlockingArming(bool *usedBypass) { - const bool navBoxModesEnabled = IS_RC_MODE_ACTIVE(BOXNAVRTH) || IS_RC_MODE_ACTIVE(BOXNAVWP) || IS_RC_MODE_ACTIVE(BOXNAVPOSHOLD) || (STATE(FIXED_WING_LEGACY) && IS_RC_MODE_ACTIVE(BOXNAVALTHOLD)) || (STATE(FIXED_WING_LEGACY) && (IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD) || IS_RC_MODE_ACTIVE(BOXNAVCRUISE))); + const bool navBoxModesEnabled = IS_RC_MODE_ACTIVE(BOXNAVRTH) || IS_RC_MODE_ACTIVE(BOXNAVWP) || IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD) || + IS_RC_MODE_ACTIVE(BOXNAVCRUISE) || IS_RC_MODE_ACTIVE(BOXNAVPOSHOLD) || (STATE(FIXED_WING_LEGACY) && IS_RC_MODE_ACTIVE(BOXNAVALTHOLD)); if (usedBypass) { *usedBypass = false;