From 0b247d9bfc18e092480dd2d3405f17585ebc86c7 Mon Sep 17 00:00:00 2001 From: shota Date: Sun, 6 Nov 2022 02:28:52 +0900 Subject: [PATCH 001/122] mixer profile switching by cli --- src/main/cms/cms_menu_mixer_servo.c | 1 + src/main/config/parameter_group_ids.h | 2 +- src/main/fc/cli.c | 29 ++++++++++++++++++ src/main/fc/config.c | 30 +++++++++++++++++++ src/main/fc/config.h | 5 ++++ src/main/fc/fc_msp.c | 5 ++++ src/main/fc/settings.c | 2 ++ src/main/fc/settings.h | 7 +++-- src/main/fc/settings.yaml | 5 ++-- src/main/flight/mixer.c | 35 +++++++++++++++++----- src/main/flight/mixer.h | 19 +++++++++--- src/test/unit/flight_mixer_unittest.cc.txt | 2 +- 12 files changed, 123 insertions(+), 19 deletions(-) diff --git a/src/main/cms/cms_menu_mixer_servo.c b/src/main/cms/cms_menu_mixer_servo.c index 92d18ab3a0..7c876d7150 100644 --- a/src/main/cms/cms_menu_mixer_servo.c +++ b/src/main/cms/cms_menu_mixer_servo.c @@ -40,6 +40,7 @@ #include "fc/runtime_config.h" #include "fc/settings.h" +#include "fc/config.h" static uint8_t currentMotorMixerIndex = 0; static uint8_t tmpcurrentMotorMixerIndex = 1; diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index 46293524b1..754b7dbada 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -36,7 +36,7 @@ //#define PG_TRANSPONDER_CONFIG 17 #define PG_SYSTEM_CONFIG 18 #define PG_FEATURE_CONFIG 19 -#define PG_MIXER_CONFIG 20 +#define PG_MIXER_PROFILE 20 #define PG_SERVO_MIXER 21 #define PG_IMU_CONFIG 22 //#define PG_PROFILE_SELECTION 23 diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 6dd129b5c3..b6450593a8 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3049,6 +3049,33 @@ static void cliDumpBatteryProfile(uint8_t profileIndex, uint8_t dumpMask) dumpAllValues(BATTERY_CONFIG_VALUE, dumpMask); } +static void cliMixerProfile(char *cmdline) +{ + // CLI profile index is 1-based + if (isEmpty(cmdline)) { + cliPrintLinef("mixer_profile %d", getConfigMixerProfile() + 1); + return; + } else { + const int i = fastA2I(cmdline) - 1; + if (i >= 0 && i < MAX_PROFILE_COUNT) { + setConfigMixerProfileAndWriteEEPROM(i); + cliMixerProfile(""); + } + } +} + +static void cliDumpMixerProfile(uint8_t profileIndex, uint8_t dumpMask) +{ + if (profileIndex >= MAX_MIXER_PROFILE_COUNT) { + // Faulty values + return; + } + setConfigMixerProfile(profileIndex); + cliPrintHashLine("mixer_profile"); + cliPrintLinef("mixer_profile %d\r\n", getConfigMixerProfile() + 1); + dumpAllValues(MIXER_CONFIG_VALUE, dumpMask); +} + #ifdef USE_CLI_BATCH static void cliPrintCommandBatchWarning(const char *warning) { @@ -3861,6 +3888,8 @@ const clicmd_t cmdTable[] = { "[]", cliProfile), CLI_COMMAND_DEF("battery_profile", "change battery profile", "[]", cliBatteryProfile), + CLI_COMMAND_DEF("mixer_profile", "change mixer profile", + "[]", cliMixerProfile), CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource), CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange), #if defined(USE_SAFE_HOME) diff --git a/src/main/fc/config.c b/src/main/fc/config.c index b8f665598d..1a7ced8515 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -107,6 +107,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, PG_RESET_TEMPLATE(systemConfig_t, systemConfig, .current_profile_index = 0, .current_battery_profile_index = 0, + .current_mixer_profile_index = 0, .debug_mode = SETTING_DEBUG_MODE_DEFAULT, #ifdef USE_DEV_TOOLS .groundTestMode = SETTING_GROUND_TEST_MODE_DEFAULT, // disables motors, set heading trusted for FW (for dev use) @@ -417,6 +418,35 @@ void setConfigBatteryProfileAndWriteEEPROM(uint8_t profileIndex) beeperConfirmationBeeps(profileIndex + 1); } +uint8_t getConfigMixerProfile(void) +{ + return systemConfig()->current_mixer_profile_index; +} + +bool setConfigMixerProfile(uint8_t profileIndex) +{ + bool ret = true; // return true if current_mixer_profile_index has changed + if (systemConfig()->current_mixer_profile_index == profileIndex) { + ret = false; + } + if (profileIndex >= MAX_MIXER_PROFILE_COUNT) {// sanity check + profileIndex = 0; + } + systemConfigMutable()->current_mixer_profile_index = profileIndex; + // setMixerProfile(profileIndex); + return ret; +} + +void setConfigMixerProfileAndWriteEEPROM(uint8_t profileIndex) +{ + if (setConfigMixerProfile(profileIndex)) { + // profile has changed, so ensure current values saved before new profile is loaded + writeEEPROM(); + readEEPROM(); + } + beeperConfirmationBeeps(profileIndex + 1); +} + void setGyroCalibrationAndWriteEEPROM(int16_t getGyroZero[XYZ_AXIS_COUNT]) { gyroConfigMutable()->gyro_zero_cal[X] = getGyroZero[X]; gyroConfigMutable()->gyro_zero_cal[Y] = getGyroZero[Y]; diff --git a/src/main/fc/config.h b/src/main/fc/config.h index 57dcbe3726..ab5a6fff72 100644 --- a/src/main/fc/config.h +++ b/src/main/fc/config.h @@ -69,6 +69,7 @@ typedef enum { typedef struct systemConfig_s { uint8_t current_profile_index; uint8_t current_battery_profile_index; + uint8_t current_mixer_profile_index; uint8_t debug_mode; #ifdef USE_DEV_TOOLS bool groundTestMode; // Disables motor ouput, sets heading trusted on FW (for dev use) @@ -135,6 +136,10 @@ uint8_t getConfigBatteryProfile(void); bool setConfigBatteryProfile(uint8_t profileIndex); void setConfigBatteryProfileAndWriteEEPROM(uint8_t profileIndex); +uint8_t getConfigMixerProfile(void); +bool setConfigMixerProfile(uint8_t profileIndex); +void setConfigMixerProfileAndWriteEEPROM(uint8_t profileIndex); + void setGyroCalibrationAndWriteEEPROM(int16_t getGyroZero[XYZ_AXIS_COUNT]); void setGravityCalibrationAndWriteEEPROM(float getGravity); diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 524fc6319b..56c716ade1 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -3126,7 +3126,12 @@ static bool mspSettingInfoCommand(sbuf_t *dst, sbuf_t *src) sbufWriteU8(dst, getConfigBatteryProfile()); sbufWriteU8(dst, MAX_BATTERY_PROFILE_COUNT); break; + case MIXER_CONFIG_VALUE: + sbufWriteU8(dst, getConfigMixerProfile()); + sbufWriteU8(dst, MAX_MIXER_PROFILE_COUNT); + break; } + // If the setting uses a table, send each possible string (null terminated) if (SETTING_MODE(setting) == MODE_LOOKUP) { diff --git a/src/main/fc/settings.c b/src/main/fc/settings.c index 8dc17edc63..200921bf86 100644 --- a/src/main/fc/settings.c +++ b/src/main/fc/settings.c @@ -239,6 +239,8 @@ static uint16_t getValueOffset(const setting_t *value) return value->offset + sizeof(controlRateConfig_t) * getConfigProfile(); case BATTERY_CONFIG_VALUE: return value->offset + sizeof(batteryProfile_t) * getConfigBatteryProfile(); + case MIXER_CONFIG_VALUE: + return value->offset + sizeof(batteryProfile_t) * getConfigBatteryProfile(); } return 0; } diff --git a/src/main/fc/settings.h b/src/main/fc/settings.h index b14289ba27..16c47d766b 100644 --- a/src/main/fc/settings.h +++ b/src/main/fc/settings.h @@ -15,7 +15,7 @@ typedef struct lookupTableEntry_s { #define SETTING_TYPE_OFFSET 0 #define SETTING_SECTION_OFFSET 4 -#define SETTING_MODE_OFFSET 6 +#define SETTING_MODE_OFFSET 7 typedef enum { // value type, bits 0-3 @@ -29,15 +29,16 @@ typedef enum { } setting_type_e; typedef enum { - // value section, bits 4-5 + // value section, bits 4-6 MASTER_VALUE = (0 << SETTING_SECTION_OFFSET), PROFILE_VALUE = (1 << SETTING_SECTION_OFFSET), CONTROL_RATE_VALUE = (2 << SETTING_SECTION_OFFSET), // 0x20 BATTERY_CONFIG_VALUE = (3 << SETTING_SECTION_OFFSET), + MIXER_CONFIG_VALUE = (4 << SETTING_SECTION_OFFSET), } setting_section_e; typedef enum { - // value mode, bits 6-7 + // value mode, bits 7 MODE_DIRECT = (0 << SETTING_MODE_OFFSET), MODE_LOOKUP = (1 << SETTING_MODE_OFFSET), // 0x40 } setting_mode_e; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 0af6fe63e7..c96ab3db47 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -206,6 +206,7 @@ constants: MAX_CONTROL_RATE_PROFILE_COUNT: 3 MAX_BATTERY_PROFILE_COUNT: 3 + MAX_MIXER_PROFILE_COUNT: 2 groups: @@ -1145,8 +1146,8 @@ groups: field: powerLimits.burstPowerFalldownTime max: 3000 - - name: PG_MIXER_CONFIG - type: mixerConfig_t + - name: PG_MIXER_PROFILE + type: mixerProfile_t members: - name: motor_direction_inverted description: "Use if you need to inverse yaw motor direction." diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index ee4cf4ef54..fb9934a37b 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -33,6 +33,7 @@ FILE_COMPILE_FOR_SPEED #include "config/feature.h" #include "config/parameter_group.h" #include "config/parameter_group_ids.h" +#include "config/config_reset.h" #include "drivers/pwm_output.h" #include "drivers/pwm_mapping.h" @@ -82,16 +83,34 @@ PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig, .deadband_high = SETTING_3D_DEADBAND_HIGH_DEFAULT, .neutral = SETTING_3D_NEUTRAL_DEFAULT ); +PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1); -PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 5); +void pgResetFn_mixerProfiles(mixerProfile_t *instance) +{ + for (int i = 0; i < MAX_MIXER_PROFILE_COUNT; i++) { + RESET_CONFIG(mixerProfile_t, &instance[i], + .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT, + .platformType = SETTING_PLATFORM_TYPE_DEFAULT, + .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, + .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only + .outputMode = SETTING_OUTPUT_MODE_DEFAULT, + ); + motorMixer_t tmp_mixer = {.throttle=0,.roll=0,.pitch=0,.yaw=0}; + for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) { + instance->MotorMixer[j] = tmp_mixer; + } + } +} -PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, - .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT, - .platformType = SETTING_PLATFORM_TYPE_DEFAULT, - .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, - .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only - .outputMode = SETTING_OUTPUT_MODE_DEFAULT, -); +// PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_PROFILE, 5); + +// PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, +// .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT, +// .platformType = SETTING_PLATFORM_TYPE_DEFAULT, +// .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, +// .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only +// .outputMode = SETTING_OUTPUT_MODE_DEFAULT, +// ); PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 9); diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index cfb8fb9a60..fa560af504 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -19,12 +19,17 @@ #include "config/parameter_group.h" +#ifndef MAX_MIXER_PROFILE_COUNT +#define MAX_MIXER_PROFILE_COUNT 2 +#endif + #if defined(TARGET_MOTOR_COUNT) #define MAX_SUPPORTED_MOTORS TARGET_MOTOR_COUNT #else #define MAX_SUPPORTED_MOTORS 12 #endif + // Digital protocol has fixed values #define DSHOT_DISARM_COMMAND 0 #define DSHOT_MIN_THROTTLE 48 @@ -64,15 +69,21 @@ typedef struct motorMixer_s { PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer); -typedef struct mixerConfig_s { +typedef struct mixerProfile_s { int8_t motorDirectionInverted; uint8_t platformType; bool hasFlaps; int16_t appliedMixerPreset; uint8_t outputMode; -} mixerConfig_t; + motorMixer_t MotorMixer[MAX_SUPPORTED_MOTORS]; +} mixerProfile_t; -PG_DECLARE(mixerConfig_t, mixerConfig); +PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); +#define mixerConfig() mixerProfiles(systemConfig()->current_mixer_profile_index) +#define mixerConfigMutable() ((mixerProfile_t *)mixerConfig()) +#define primaryMotorMixer(_index) (&((mixerConfig()->MotorMixer)[_index])) +#define primaryMotorMixerMutable(_index) ((motorMixer_t *)primaryMotorMixer(_index)) +extern motorMixer_t primaryMotorMixer_CopyArray[12]; typedef struct reversibleMotorsConfig_s { uint16_t deadband_low; // min 3d value @@ -130,4 +141,4 @@ void stopMotors(void); void stopPwmAllMotors(void); void loadPrimaryMotorMixer(void); -bool areMotorsRunning(void); +bool areMotorsRunning(void); \ No newline at end of file diff --git a/src/test/unit/flight_mixer_unittest.cc.txt b/src/test/unit/flight_mixer_unittest.cc.txt index 6b33b6c50c..c0915b3cc2 100644 --- a/src/test/unit/flight_mixer_unittest.cc.txt +++ b/src/test/unit/flight_mixer_unittest.cc.txt @@ -144,7 +144,7 @@ TEST_F(ChannelForwardingTest, TestForwardAuxChannelsToServosWithLessRemainingSer class BasicMixerIntegrationTest : public ::testing::Test { protected: - mixerConfig_t mixerConfig; + mixerProfile_t mixerConfig; rxConfig_t rxConfig; escAndServoConfig_t escAndServoConfig; servoParam_t servoConf[MAX_SUPPORTED_SERVOS]; From fcf9ca14dea85f68c13ab06734f9a87db8784637 Mon Sep 17 00:00:00 2001 From: shota Date: Sun, 6 Nov 2022 16:40:16 +0900 Subject: [PATCH 002/122] add mixer profile switching by logic --- src/main/fc/cli.c | 2 +- src/main/fc/settings.c | 2 +- src/main/programming/logic_condition.c | 30 ++++++++++++++++++++++++++ src/main/programming/logic_condition.h | 4 +++- 4 files changed, 35 insertions(+), 3 deletions(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index b6450593a8..d32cf9f610 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3057,7 +3057,7 @@ static void cliMixerProfile(char *cmdline) return; } else { const int i = fastA2I(cmdline) - 1; - if (i >= 0 && i < MAX_PROFILE_COUNT) { + if (i >= 0 && i < MAX_MIXER_PROFILE_COUNT) { setConfigMixerProfileAndWriteEEPROM(i); cliMixerProfile(""); } diff --git a/src/main/fc/settings.c b/src/main/fc/settings.c index 200921bf86..8ea69b82f0 100644 --- a/src/main/fc/settings.c +++ b/src/main/fc/settings.c @@ -240,7 +240,7 @@ static uint16_t getValueOffset(const setting_t *value) case BATTERY_CONFIG_VALUE: return value->offset + sizeof(batteryProfile_t) * getConfigBatteryProfile(); case MIXER_CONFIG_VALUE: - return value->offset + sizeof(batteryProfile_t) * getConfigBatteryProfile(); + return value->offset + sizeof(mixerProfile_t) * getConfigMixerProfile(); } return 0; } diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 990e9c1510..08cb452b64 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -50,6 +50,10 @@ #include "io/osd_common.h" #include "sensors/diagnostics.h" +#include "flight/mixer.h" +#include "flight/servos.h" +#include "drivers/pwm_mapping.h" + #include "navigation/navigation.h" #include "navigation/navigation_private.h" @@ -361,6 +365,28 @@ static int logicConditionCompute( } break; + case LOGIC_CONDITION_SET_MIXER_PROFILE: + operandA--; + if ( getConfigMixerProfile() != operandA && (operandA >= 0 && operandA < MAX_MIXER_PROFILE_COUNT)) { + bool mixerprofileChanged = false; + if (setConfigMixerProfile(operandA)) { + stopMotors(); + stopPwmAllMotors(); + servosInit(); + mixerUpdateStateFlags(); + mixerInit(); + pwmMotorAndServoInit(); + if (!STATE(ALTITUDE_CONTROL)) { + featureClear(FEATURE_AIRMODE); + } + mixerprofileChanged = true; + } + return mixerprofileChanged; + } else { + return false; + } + break; + case LOGIC_CONDITION_LOITER_OVERRIDE: logicConditionValuesByType[LOGIC_CONDITION_LOITER_OVERRIDE] = constrain(operandA, 0, 100000); LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS); @@ -610,6 +636,10 @@ static int logicConditionGetFlightOperandValue(int operand) { case LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_PROFILE: // int return getConfigProfile() + 1; break; + + case LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE: // int + return getConfigMixerProfile() + 1; + break; case LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS: return getLoiterRadius(navConfig()->fw.loiter_radius); diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 0025602984..2b18be4fa8 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -76,7 +76,8 @@ typedef enum { LOGIC_CONDITION_MAX = 44, LOGIC_CONDITION_FLIGHT_AXIS_ANGLE_OVERRIDE = 45, LOGIC_CONDITION_FLIGHT_AXIS_RATE_OVERRIDE = 46, - LOGIC_CONDITION_LAST = 47, + LOGIC_CONDITION_SET_MIXER_PROFILE = 47, + LOGIC_CONDITION_LAST = 48, } logicOperation_e; typedef enum logicOperandType_s { @@ -132,6 +133,7 @@ typedef enum { LOGIC_CONDITION_OPERAND_FLIGHT_AGL_STATUS, //0,1,2 // 38 LOGIC_CONDITION_OPERAND_FLIGHT_AGL, //0,1,2 // 39 LOGIC_CONDITION_OPERAND_FLIGHT_RANGEFINDER_RAW, //int // 40 + LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE, //int // 41 } logicFlightOperands_e; typedef enum { From 88e923122eb1d53bdbe577d417edc59940749f52 Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 7 Nov 2022 20:22:42 +0900 Subject: [PATCH 003/122] in progress of output_profile dev --- src/main/CMakeLists.txt | 2 ++ src/main/drivers/pwm_mapping.c | 9 +------- src/main/drivers/pwm_mapping.h | 9 ++++++++ src/main/drivers/pwm_output.c | 4 ++++ src/main/drivers/pwm_output.h | 1 + src/main/fc/settings.h | 20 +++++++++------- src/main/flight/mixer.c | 3 +++ src/main/flight/output_profile.c | 39 ++++++++++++++++++++++++++++++++ src/main/flight/output_profile.h | 4 ++++ 9 files changed, 75 insertions(+), 16 deletions(-) create mode 100644 src/main/flight/output_profile.c create mode 100644 src/main/flight/output_profile.h diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 9f78997cad..9598676f75 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -310,6 +310,8 @@ main_sources(COMMON_SRC flight/rate_dynamics.h flight/mixer.c flight/mixer.h + flight/output_profile.c + flight/output_profile.h flight/pid.c flight/pid.h flight/pid_autotune.c diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 1d3ab1b584..b67fcf2f90 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -47,13 +47,6 @@ enum { MAP_TO_SERVO_OUTPUT, }; -typedef struct { - int maxTimMotorCount; - int maxTimServoCount; - const timerHardware_t * timMotors[MAX_PWM_OUTPUT_PORTS]; - const timerHardware_t * timServos[MAX_PWM_OUTPUT_PORTS]; -} timMotorServoHardware_t; - static pwmInitError_e pwmInitError = PWM_INIT_ERROR_NONE; static const char * pwmInitErrorMsg[] = { @@ -388,7 +381,7 @@ bool pwmMotorAndServoInit(void) // Build temporary timer mappings for motor and servo pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); - + resetAllocatedOutputPortCount(); // At this point we have built tables of timers suitable for motor and servo mappings // Now we can actually initialize them according to motor/servo count from mixer pwmInitMotors(&timOutputs); diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 14c3f9293b..0b38d098bd 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -18,6 +18,7 @@ #pragma once #include "drivers/io_types.h" +#include "drivers/timer.h" #include "flight/mixer.h" #include "flight/servos.h" @@ -61,6 +62,13 @@ typedef enum { PWM_INIT_ERROR_TIMER_INIT_FAILED, } pwmInitError_e; +typedef struct { + int maxTimMotorCount; + int maxTimServoCount; + const timerHardware_t * timMotors[MAX_PWM_OUTPUT_PORTS]; + const timerHardware_t * timServos[MAX_PWM_OUTPUT_PORTS]; +} timMotorServoHardware_t; + typedef struct rangefinderIOConfig_s { ioTag_t triggerTag; ioTag_t echoTag; @@ -71,6 +79,7 @@ typedef struct { bool isDSHOT; } motorProtocolProperties_t; +void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos) bool pwmMotorAndServoInit(void); const motorProtocolProperties_t * getMotorProtocolProperties(motorPwmProtocolTypes_e proto); pwmInitError_e getPwmInitError(void); diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 658c3f5cb5..7b4891bf85 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -113,6 +113,10 @@ static uint8_t commandsBuff[DHSOT_COMMAND_QUEUE_SIZE]; static currentExecutingCommand_t currentExecutingCommand; #endif +void resetAllocatedOutputPortCount(void){ + allocatedOutputPortCount = 0; +} + static void pwmOutConfigTimer(pwmOutputPort_t * p, TCH_t * tch, uint32_t hz, uint16_t period, uint16_t value) { p->tch = tch; diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index b3c0fa6be0..d2ef60690f 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -34,6 +34,7 @@ void pwmRequestMotorTelemetry(int motorIndex); ioTag_t pwmGetMotorPinTag(int motorIndex); +void resetAllocatedOutputPortCount(void); void pwmWriteMotor(uint8_t index, uint16_t value); void pwmShutdownPulsesForAllMotors(uint8_t motorCount); void pwmCompleteMotorUpdate(void); diff --git a/src/main/fc/settings.h b/src/main/fc/settings.h index 16c47d766b..ae7da85317 100644 --- a/src/main/fc/settings.h +++ b/src/main/fc/settings.h @@ -14,11 +14,11 @@ typedef struct lookupTableEntry_s { } lookupTableEntry_t; #define SETTING_TYPE_OFFSET 0 -#define SETTING_SECTION_OFFSET 4 -#define SETTING_MODE_OFFSET 7 +#define SETTING_SECTION_OFFSET 3 +#define SETTING_MODE_OFFSET 6 typedef enum { - // value type, bits 0-3 + // value type, bits 0-2 VAR_UINT8 = (0 << SETTING_TYPE_OFFSET), VAR_INT8 = (1 << SETTING_TYPE_OFFSET), VAR_UINT16 = (2 << SETTING_TYPE_OFFSET), @@ -29,22 +29,26 @@ typedef enum { } setting_type_e; typedef enum { - // value section, bits 4-6 + // value section, bits 3-5 MASTER_VALUE = (0 << SETTING_SECTION_OFFSET), PROFILE_VALUE = (1 << SETTING_SECTION_OFFSET), - CONTROL_RATE_VALUE = (2 << SETTING_SECTION_OFFSET), // 0x20 + CONTROL_RATE_VALUE = (2 << SETTING_SECTION_OFFSET), BATTERY_CONFIG_VALUE = (3 << SETTING_SECTION_OFFSET), MIXER_CONFIG_VALUE = (4 << SETTING_SECTION_OFFSET), } setting_section_e; typedef enum { - // value mode, bits 7 + // value mode, bits 6-7 MODE_DIRECT = (0 << SETTING_MODE_OFFSET), MODE_LOOKUP = (1 << SETTING_MODE_OFFSET), // 0x40 } setting_mode_e; -#define SETTING_TYPE_MASK (0x0F) -#define SETTING_SECTION_MASK (0x30) +// #define SETTING_TYPE_MASK (0x0F) +// #define SETTING_SECTION_MASK (0x30) +// #define SETTING_MODE_MASK (0xC0) + +#define SETTING_TYPE_MASK (0x07) +#define SETTING_SECTION_MASK (0x38) #define SETTING_MODE_MASK (0xC0) typedef struct settingMinMaxConfig_s { diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index fb9934a37b..a174b513eb 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -615,6 +615,9 @@ void FAST_CODE mixTable() if (currentMotorStatus != MOTOR_RUNNING) { motor[i] = motorValueWhenStopped; } + if (currentMixer[i].throttle <= -1.0f) { + motor[i] = motorZeroCommand; + } #ifdef USE_DEV_TOOLS if (systemConfig()->groundTestMode) { motor[i] = motorZeroCommand; diff --git a/src/main/flight/output_profile.c b/src/main/flight/output_profile.c new file mode 100644 index 0000000000..2a65264a62 --- /dev/null +++ b/src/main/flight/output_profile.c @@ -0,0 +1,39 @@ +#include +#include +#include + +#include "drivers/pwm_output.h" +#include "drivers/pwm_mapping.h" +#include "drivers/time.h" +#include "flight/mixer.h" +// #include "flight/pid.h" +#include "flight/servos.h" + + +bool MixerProfileHotSwitch(void) +{ + //store current output for check + timMotorServoHardware_t old_timOutputs; + pwmBuildTimerOutputList(&old_timOutputs, isMixerUsingServos()); + + servosInit(); + mixerUpdateStateFlags(); + mixerInit(); + + timMotorServoHardware_t timOutputs; + pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); + bool motor_output_type_not_changed = old_timOutputs.maxTimMotorCount == timOutputs.maxTimMotorCount; + bool servo_output_type_not_changed = old_timOutputs.maxTimServoCount == timOutputs.maxTimServoCount; + for (int i; i++; i Date: Mon, 7 Nov 2022 23:29:43 +0900 Subject: [PATCH 004/122] add mixer_profile.h --- src/main/CMakeLists.txt | 4 +- src/main/cms/cms_menu_mixer_servo.c | 1 + src/main/drivers/pwm_mapping.c | 10 +- src/main/drivers/pwm_mapping.h | 5 +- src/main/fc/cli.c | 16 ++- src/main/fc/fc_core.c | 1 + src/main/fc/fc_msp.c | 1 + src/main/fc/fc_msp_box.c | 1 + src/main/fc/settings.yaml | 12 ++- src/main/flight/mixer.c | 37 ++++--- src/main/flight/mixer.h | 32 +++--- src/main/flight/mixer_profile.c | 109 +++++++++++++++++++++ src/main/flight/mixer_profile.h | 26 +++++ src/main/flight/output_profile.c | 39 -------- src/main/flight/output_profile.h | 4 - src/main/flight/pid.c | 1 + src/main/flight/servos.c | 4 + src/main/navigation/navigation.c | 2 +- src/main/programming/logic_condition.c | 12 +-- src/main/telemetry/mavlink.c | 2 +- src/test/unit/flight_mixer_unittest.cc.txt | 2 +- 21 files changed, 219 insertions(+), 102 deletions(-) create mode 100644 src/main/flight/mixer_profile.c create mode 100644 src/main/flight/mixer_profile.h delete mode 100644 src/main/flight/output_profile.c delete mode 100644 src/main/flight/output_profile.h diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 9598676f75..eb9460f409 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -310,8 +310,6 @@ main_sources(COMMON_SRC flight/rate_dynamics.h flight/mixer.c flight/mixer.h - flight/output_profile.c - flight/output_profile.h flight/pid.c flight/pid.h flight/pid_autotune.c @@ -321,6 +319,8 @@ main_sources(COMMON_SRC flight/rth_estimator.h flight/servos.c flight/servos.h + flight/mixer_profile.c + flight/mixer_profile.h flight/wind_estimator.c flight/wind_estimator.h flight/gyroanalyse.c diff --git a/src/main/cms/cms_menu_mixer_servo.c b/src/main/cms/cms_menu_mixer_servo.c index 7c876d7150..e23229e7ac 100644 --- a/src/main/cms/cms_menu_mixer_servo.c +++ b/src/main/cms/cms_menu_mixer_servo.c @@ -31,6 +31,7 @@ #include "build/version.h" +#include "flight/mixer_profile.h" #include "flight/mixer.h" #include "flight/servos.h" diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index b67fcf2f90..bbd1c29828 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -381,7 +381,6 @@ bool pwmMotorAndServoInit(void) // Build temporary timer mappings for motor and servo pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); - resetAllocatedOutputPortCount(); // At this point we have built tables of timers suitable for motor and servo mappings // Now we can actually initialize them according to motor/servo count from mixer pwmInitMotors(&timOutputs); @@ -389,3 +388,12 @@ bool pwmMotorAndServoInit(void) return (pwmInitError == PWM_INIT_ERROR_NONE); } + +bool pwmMotorAndServoHotInit(timMotorServoHardware_t* timOutputs) +{ + resetAllocatedOutputPortCount(); + pwmInitMotors(timOutputs); + pwmInitServos(timOutputs); + + return (pwmInitError == PWM_INIT_ERROR_NONE); +} \ No newline at end of file diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 0b38d098bd..3de4431470 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -19,7 +19,7 @@ #include "drivers/io_types.h" #include "drivers/timer.h" -#include "flight/mixer.h" +#include "flight/mixer_profile.h" #include "flight/servos.h" #if defined(TARGET_MOTOR_COUNT) @@ -79,8 +79,9 @@ typedef struct { bool isDSHOT; } motorProtocolProperties_t; -void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos) +void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos); bool pwmMotorAndServoInit(void); +bool pwmMotorAndServoHotInit(timMotorServoHardware_t* timOutputs); const motorProtocolProperties_t * getMotorProtocolProperties(motorPwmProtocolTypes_e proto); pwmInitError_e getPwmInitError(void); const char * getPwmInitErrorMessage(void); diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index d32cf9f610..3a3af83304 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -81,7 +81,8 @@ bool cliMode = false; #include "flight/failsafe.h" #include "flight/imu.h" -#include "flight/mixer.h" +// #include "flight/mixer.h" +#include "flight/mixer_profile.h" #include "flight/pid.h" #include "flight/servos.h" @@ -282,7 +283,8 @@ typedef enum { DUMP_MASTER = (1 << 0), DUMP_PROFILE = (1 << 1), DUMP_BATTERY_PROFILE = (1 << 2), - DUMP_RATES = (1 << 3), + // DUMP_RATES = (1 << 3), + DUMP_MIXER_PROFILE = (1 << 3), DUMP_ALL = (1 << 4), DO_DIFF = (1 << 5), SHOW_DEFAULTS = (1 << 6), @@ -3567,6 +3569,8 @@ static void printConfig(const char *cmdline, bool doDiff) dumpMask = DUMP_PROFILE; // only } else if ((options = checkCommand(cmdline, "battery_profile"))) { dumpMask = DUMP_BATTERY_PROFILE; // only + } else if ((options = checkCommand(cmdline, "mixer_profile"))) { + dumpMask = DUMP_MIXER_PROFILE; // only } else if ((options = checkCommand(cmdline, "all"))) { dumpMask = DUMP_ALL; // all profiles and rates } else { @@ -3712,6 +3716,9 @@ static void printConfig(const char *cmdline, bool doDiff) for (int ii = 0; ii < MAX_BATTERY_PROFILE_COUNT; ++ii) { cliDumpBatteryProfile(ii, dumpMask); } + for (int ii = 0; ii < MAX_MIXER_PROFILE_COUNT; ++ii) { + cliDumpMixerProfile(ii, dumpMask); + } setConfigProfile(currentProfileIndexSave); setConfigBatteryProfile(currentBatteryProfileIndexSave); @@ -3726,6 +3733,7 @@ static void printConfig(const char *cmdline, bool doDiff) // dump just the current profiles cliDumpProfile(getConfigProfile(), dumpMask); cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask); + cliDumpMixerProfile(getConfigMixerProfile(), dumpMask); } } @@ -3737,6 +3745,10 @@ static void printConfig(const char *cmdline, bool doDiff) cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask); } + if (dumpMask & DUMP_MIXER_PROFILE) { + cliDumpMixerProfile(getConfigMixerProfile(), dumpMask); + } + if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) { cliPrintHashLine("save configuration\r\nsave"); } diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index b79e97c396..4253c995a3 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -82,6 +82,7 @@ FILE_COMPILE_FOR_SPEED #include "telemetry/telemetry.h" +#include "flight/mixer_profile.h" #include "flight/mixer.h" #include "flight/servos.h" #include "flight/pid.h" diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 56c716ade1..587651b21d 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -73,6 +73,7 @@ #include "flight/failsafe.h" #include "flight/imu.h" +#include "flight/mixer_profile.h" #include "flight/mixer.h" #include "flight/pid.h" #include "flight/servos.h" diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index aeb1463164..112c850987 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -30,6 +30,7 @@ #include "fc/fc_msp_box.h" #include "fc/runtime_config.h" #include "flight/mixer.h" +#include "flight/mixer_profile.h" #include "io/osd.h" diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index c96ab3db47..6c94747e04 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1148,33 +1148,35 @@ groups: - name: PG_MIXER_PROFILE type: mixerProfile_t + headers: ["flight/mixer.h","flight/mixer_profile.h"] + value_type: MIXER_CONFIG_VALUE members: - name: motor_direction_inverted description: "Use if you need to inverse yaw motor direction." default_value: OFF - field: motorDirectionInverted + field: mixer_config.motorDirectionInverted type: bool - name: platform_type description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented" default_value: "MULTIROTOR" - field: platformType + field: mixer_config.platformType type: uint8_t table: platform_type - name: has_flaps description: "Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot" default_value: OFF - field: hasFlaps + field: mixer_config.hasFlaps type: bool - name: model_preview_type description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons." default_value: -1 - field: appliedMixerPreset + field: mixer_config.appliedMixerPreset min: -1 max: INT16_MAX - name: output_mode description: "Output function assignment mode. AUTO assigns outputs according to the default mapping, SERVOS assigns all outputs to servos, MOTORS assigns all outputs to motors" default_value: "AUTO" - field: outputMode + field: mixer_config.outputMode table: output_mode - name: PG_REVERSIBLE_MOTORS_CONFIG diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index a174b513eb..37011845bc 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -83,24 +83,24 @@ PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig, .deadband_high = SETTING_3D_DEADBAND_HIGH_DEFAULT, .neutral = SETTING_3D_NEUTRAL_DEFAULT ); -PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1); +// PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1); -void pgResetFn_mixerProfiles(mixerProfile_t *instance) -{ - for (int i = 0; i < MAX_MIXER_PROFILE_COUNT; i++) { - RESET_CONFIG(mixerProfile_t, &instance[i], - .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT, - .platformType = SETTING_PLATFORM_TYPE_DEFAULT, - .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, - .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only - .outputMode = SETTING_OUTPUT_MODE_DEFAULT, - ); - motorMixer_t tmp_mixer = {.throttle=0,.roll=0,.pitch=0,.yaw=0}; - for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) { - instance->MotorMixer[j] = tmp_mixer; - } - } -} +// void pgResetFn_mixerProfiles(mixerProfile_t *instance) +// { +// for (int i = 0; i < MAX_MIXER_PROFILE_COUNT; i++) { +// RESET_CONFIG(mixerProfile_t, &instance[i], +// .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT, +// .platformType = SETTING_PLATFORM_TYPE_DEFAULT, +// .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, +// .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only +// .outputMode = SETTING_OUTPUT_MODE_DEFAULT, +// ); +// motorMixer_t tmp_mixer = {.throttle=0,.roll=0,.pitch=0,.yaw=0}; +// for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) { +// instance->MotorMixer[j] = tmp_mixer; +// } +// } +// } // PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_PROFILE, 5); @@ -122,8 +122,6 @@ PG_RESET_TEMPLATE(motorConfig_t, motorConfig, .motorPoleCount = SETTING_MOTOR_POLES_DEFAULT, // Most brushless motors that we use are 14 poles ); -PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTOR_MIXER, 0); - #define CRASH_OVER_AFTER_CRASH_FLIP_STICK_MIN 0.15f int getThrottleIdleValue(void) @@ -438,7 +436,6 @@ void FAST_CODE writeMotors(void) // We don't define USE_DSHOT motorValue = motor[i]; #endif - pwmWriteMotor(i, motorValue); } } diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index fa560af504..3e62463407 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -19,10 +19,6 @@ #include "config/parameter_group.h" -#ifndef MAX_MIXER_PROFILE_COUNT -#define MAX_MIXER_PROFILE_COUNT 2 -#endif - #if defined(TARGET_MOTOR_COUNT) #define MAX_SUPPORTED_MOTORS TARGET_MOTOR_COUNT #else @@ -67,23 +63,31 @@ typedef struct motorMixer_s { float yaw; } motorMixer_t; -PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer); +// PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer); -typedef struct mixerProfile_s { +typedef struct mixerConfig_s { int8_t motorDirectionInverted; uint8_t platformType; bool hasFlaps; int16_t appliedMixerPreset; uint8_t outputMode; - motorMixer_t MotorMixer[MAX_SUPPORTED_MOTORS]; -} mixerProfile_t; +} mixerConfig_t; -PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); -#define mixerConfig() mixerProfiles(systemConfig()->current_mixer_profile_index) -#define mixerConfigMutable() ((mixerProfile_t *)mixerConfig()) -#define primaryMotorMixer(_index) (&((mixerConfig()->MotorMixer)[_index])) -#define primaryMotorMixerMutable(_index) ((motorMixer_t *)primaryMotorMixer(_index)) -extern motorMixer_t primaryMotorMixer_CopyArray[12]; +// typedef struct mixerProfile_s { +// int8_t motorDirectionInverted; +// uint8_t platformType; +// bool hasFlaps; +// int16_t appliedMixerPreset; +// uint8_t outputMode; +// motorMixer_t MotorMixer[MAX_SUPPORTED_MOTORS]; +// } mixerProfile_t; + +// PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); +// #define mixerConfig() mixerProfiles(systemConfig()->current_mixer_profile_index) +// #define mixerConfigMutable() ((mixerProfile_t *)mixerConfig()) +// #define primaryMotorMixer(_index) (&((mixerConfig()->MotorMixer)[_index])) +// #define primaryMotorMixerMutable(_index) ((motorMixer_t *)primaryMotorMixer(_index)) +// extern motorMixer_t primaryMotorMixer_CopyArray[12]; typedef struct reversibleMotorsConfig_s { uint16_t deadband_low; // min 3d value diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c new file mode 100644 index 0000000000..fab3cbe3e0 --- /dev/null +++ b/src/main/flight/mixer_profile.c @@ -0,0 +1,109 @@ +#include +#include +#include + +#include "config/feature.h" +#include "config/parameter_group.h" +#include "config/parameter_group_ids.h" +#include "config/config_reset.h" + +#include "drivers/pwm_output.h" +#include "drivers/pwm_mapping.h" +#include "drivers/time.h" +#include "flight/mixer.h" +// #include "flight/pid.h" +#include "flight/servos.h" + +#include "fc/config.h" +#include "fc/runtime_config.h" +#include "fc/settings.h" + +#include "common/log.h" + +PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1); + +void pgResetFn_mixerProfiles(mixerProfile_t *instance) +{ + for (int i = 0; i < MAX_MIXER_PROFILE_COUNT; i++) { + RESET_CONFIG(mixerProfile_t, &instance[i], + .mixer_config = { + .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT, + .platformType = SETTING_PLATFORM_TYPE_DEFAULT, + .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, + .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only + .outputMode = SETTING_OUTPUT_MODE_DEFAULT, + } + ); + motorMixer_t tmp_mixer = {.throttle=0,.roll=0,.pitch=0,.yaw=0}; + for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) { + instance->MotorMixers[j] = tmp_mixer; + } + } +} + +PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTOR_MIXER, 0); + +int min_ab(int a,int b) +{ + return a > b ? b : a; +} + +bool OutputProfileHotSwitch(int profile_index) +{ + // does not work with timerHardwareOverride + LOG_INFO(PWM, "OutputProfileHotSwitch"); + + LOG_INFO(PWM, "stop all motors"); + stopMotors(); + // LOG_INFO(PWM, "stop all pwm motors"); + // stopPwmAllMotors(); + + //store current output for check + LOG_INFO(PWM, "get old_timOutputs"); + // delay(1000); // give time to print + timMotorServoHardware_t old_timOutputs; + LOG_INFO(PWM, "get pwmBuildTimerOutputList"); + // delay(1000); // give time to print + pwmBuildTimerOutputList(&old_timOutputs, isMixerUsingServos()); + // delay(1000); // give time to print + if (!setConfigMixerProfile(profile_index)){ + return false; + } + // delay(1000); // give time to print + LOG_INFO(PWM, "servosInit"); + // delay(1000); // give time to print + servosInit(); + LOG_INFO(PWM, "mixerUpdateStateFlags"); + // delay(1000); // give time to print + mixerUpdateStateFlags(); + LOG_INFO(PWM, "mixerInit"); + // delay(1000); // give time to print + mixerInit(); + + LOG_INFO(PWM, "get timOutputs"); + // delay(1000); // give time to print + timMotorServoHardware_t timOutputs; + pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); + LOG_INFO(PWM, "check changes"); + // delay(1000); // give time to print, stuck here + bool motor_output_type_not_changed = old_timOutputs.maxTimMotorCount == timOutputs.maxTimMotorCount; + bool servo_output_type_not_changed = old_timOutputs.maxTimServoCount == timOutputs.maxTimServoCount; + for (int i; i < min_ab(old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); i++) + { + motor_output_type_not_changed &= old_timOutputs.timMotors[i]->tag==timOutputs.timMotors[i]->tag; + } + for (int i; i < min_ab(old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); i++) + { + servo_output_type_not_changed &= old_timOutputs.timServos[i]->tag==timOutputs.timServos[i]->tag; + } + if(!motor_output_type_not_changed || !servo_output_type_not_changed){ + LOG_INFO(PWM, "pwmMotorAndServoHotInit"); + // delay(1000); // give time to print + pwmMotorAndServoHotInit(&timOutputs); + } + if (!STATE(ALTITUDE_CONTROL)) { + featureClear(FEATURE_AIRMODE); + } + return true; +} + diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h new file mode 100644 index 0000000000..b192e20170 --- /dev/null +++ b/src/main/flight/mixer_profile.h @@ -0,0 +1,26 @@ +#pragma once + +#include "config/parameter_group.h" + +#include "flight/mixer.h" +#include "flight/servos.h" + +#ifndef MAX_MIXER_PROFILE_COUNT +#define MAX_MIXER_PROFILE_COUNT 2 +#endif + +typedef struct mixerProfile_s { + mixerConfig_t mixer_config; + motorMixer_t MotorMixers[MAX_SUPPORTED_MOTORS]; + servoMixer_t ServoMixers[MAX_SERVO_RULES]; +} mixerProfile_t; + +PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); + +#define mixerConfig() (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->mixer_config)) +#define mixerConfigMutable() ((mixerConfig_t *) mixerConfig()) +#define primaryMotorMixer(_index) (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->MotorMixers)[_index]) +#define primaryMotorMixerMutable(_index) ((motorMixer_t *)primaryMotorMixer(_index)) +extern motorMixer_t primaryMotorMixer_CopyArray[12]; + +bool OutputProfileHotSwitch(int profile_index); diff --git a/src/main/flight/output_profile.c b/src/main/flight/output_profile.c deleted file mode 100644 index 2a65264a62..0000000000 --- a/src/main/flight/output_profile.c +++ /dev/null @@ -1,39 +0,0 @@ -#include -#include -#include - -#include "drivers/pwm_output.h" -#include "drivers/pwm_mapping.h" -#include "drivers/time.h" -#include "flight/mixer.h" -// #include "flight/pid.h" -#include "flight/servos.h" - - -bool MixerProfileHotSwitch(void) -{ - //store current output for check - timMotorServoHardware_t old_timOutputs; - pwmBuildTimerOutputList(&old_timOutputs, isMixerUsingServos()); - - servosInit(); - mixerUpdateStateFlags(); - mixerInit(); - - timMotorServoHardware_t timOutputs; - pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); - bool motor_output_type_not_changed = old_timOutputs.maxTimMotorCount == timOutputs.maxTimMotorCount; - bool servo_output_type_not_changed = old_timOutputs.maxTimServoCount == timOutputs.maxTimServoCount; - for (int i; i++; i = 0 && operandA < MAX_MIXER_PROFILE_COUNT)) { bool mixerprofileChanged = false; - if (setConfigMixerProfile(operandA)) { - stopMotors(); - stopPwmAllMotors(); - servosInit(); - mixerUpdateStateFlags(); - mixerInit(); - pwmMotorAndServoInit(); - if (!STATE(ALTITUDE_CONTROL)) { - featureClear(FEATURE_AIRMODE); - } + if (OutputProfileHotSwitch(operandA)) { mixerprofileChanged = true; } return mixerprofileChanged; diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 07df75bcc0..e180d64723 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -54,7 +54,7 @@ #include "flight/failsafe.h" #include "flight/imu.h" -#include "flight/mixer.h" +#include "flight/mixer_profile.h" #include "flight/pid.h" #include "flight/servos.h" diff --git a/src/test/unit/flight_mixer_unittest.cc.txt b/src/test/unit/flight_mixer_unittest.cc.txt index c0915b3cc2..6b33b6c50c 100644 --- a/src/test/unit/flight_mixer_unittest.cc.txt +++ b/src/test/unit/flight_mixer_unittest.cc.txt @@ -144,7 +144,7 @@ TEST_F(ChannelForwardingTest, TestForwardAuxChannelsToServosWithLessRemainingSer class BasicMixerIntegrationTest : public ::testing::Test { protected: - mixerProfile_t mixerConfig; + mixerConfig_t mixerConfig; rxConfig_t rxConfig; escAndServoConfig_t escAndServoConfig; servoParam_t servoConf[MAX_SUPPORTED_SERVOS]; From 23968a64d238b77d076b4397e871931625c3539e Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 9 Nov 2022 03:02:06 +0900 Subject: [PATCH 005/122] in development --- src/main/drivers/pwm_mapping.c | 6 ++ src/main/fc/cli.c | 13 +++- src/main/flight/mixer.h | 1 + src/main/flight/mixer_profile.c | 75 +++++++++++------------- src/main/flight/mixer_profile.h | 1 - src/main/target/MATEKF405/CMakeLists.txt | 1 + src/main/target/MATEKF405/target.c | 16 +++++ src/main/target/MATEKF405/target.h | 4 ++ 8 files changed, 73 insertions(+), 44 deletions(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index bbd1c29828..7360a8f01d 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -220,10 +220,12 @@ static void timerHardwareOverride(timerHardware_t * timer) { void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos) { + LOG_INFO(PWM, "pwmBuildTimerOutputList"); timOutputs->maxTimMotorCount = 0; timOutputs->maxTimServoCount = 0; uint8_t motorCount = getMotorCount(); + LOG_INFO(PWM, "motorCount %d", motorCount); uint8_t motorIdx = 0; for (int idx = 0; idx < timerHardwareCount; idx++) { @@ -257,6 +259,10 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU else if (timHw->usageFlags & TIM_USE_MC_MOTOR) { type = MAP_TO_MOTOR_OUTPUT; } + else if (timHw->usageFlags & TIM_USE_MC_SERVO){ + type = MAP_TO_SERVO_OUTPUT; + } + } else { // Fixed wing or HELI (one/two motors and a lot of servos if (timHw->usageFlags & TIM_USE_FW_SERVO) { diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 3a3af83304..ebcf4448bf 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3076,6 +3076,13 @@ static void cliDumpMixerProfile(uint8_t profileIndex, uint8_t dumpMask) cliPrintHashLine("mixer_profile"); cliPrintLinef("mixer_profile %d\r\n", getConfigMixerProfile() + 1); dumpAllValues(MIXER_CONFIG_VALUE, dumpMask); + cliPrintHashLine("mixer"); + cliPrintHashLine("dumpMask"); + char buf0[FTOA_BUFFER_SIZE]; + itoa(dumpMask,buf0,2); + cliPrintHashLine(buf0); + cliDumpPrintLinef(dumpMask, primaryMotorMixer(0)->throttle == 0.0f, "\r\nmmix reset\r\n"); + printMotorMix(dumpMask, primaryMotorMixer(0), NULL); } #ifdef USE_CLI_BATCH @@ -3619,10 +3626,10 @@ static void printConfig(const char *cmdline, bool doDiff) cliPrintHashLine("resources"); //printResource(dumpMask, &defaultConfig); - cliPrintHashLine("mixer"); - cliDumpPrintLinef(dumpMask, primaryMotorMixer_CopyArray[0].throttle == 0.0f, "\r\nmmix reset\r\n"); + // cliPrintHashLine("mixer"); + // cliDumpPrintLinef(dumpMask, primaryMotorMixer_CopyArray[0].throttle == 0.0f, "\r\nmmix reset\r\n"); - printMotorMix(dumpMask, primaryMotorMixer_CopyArray, primaryMotorMixer(0)); + // printMotorMix(dumpMask, primaryMotorMixer_CopyArray, primaryMotorMixer(0)); // print custom servo mixer if exists cliPrintHashLine("servo mixer"); diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 3e62463407..07d1ab248b 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -142,6 +142,7 @@ void processServoAutotrim(const float dT); void processServoAutotrimMode(void); void processContinuousServoAutotrim(const float dT); void stopMotors(void); +void stopAndDisableMotors(void); void stopPwmAllMotors(void); void loadPrimaryMotorMixer(void); diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index fab3cbe3e0..561b7d6bb7 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -41,7 +41,7 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) } } -PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTOR_MIXER, 0); +// PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTOR_MIXER, 0); int min_ab(int a,int b) { @@ -50,60 +50,55 @@ int min_ab(int a,int b) bool OutputProfileHotSwitch(int profile_index) { +#ifdef ENABLE_MIXER_PROFILE_HOTSWAP // does not work with timerHardwareOverride LOG_INFO(PWM, "OutputProfileHotSwitch"); - LOG_INFO(PWM, "stop all motors"); - stopMotors(); - // LOG_INFO(PWM, "stop all pwm motors"); - // stopPwmAllMotors(); - //store current output for check - LOG_INFO(PWM, "get old_timOutputs"); - // delay(1000); // give time to print + uint8_t old_platform_type=mixerConfig()->platformType; timMotorServoHardware_t old_timOutputs; - LOG_INFO(PWM, "get pwmBuildTimerOutputList"); - // delay(1000); // give time to print pwmBuildTimerOutputList(&old_timOutputs, isMixerUsingServos()); - // delay(1000); // give time to print if (!setConfigMixerProfile(profile_index)){ return false; } - // delay(1000); // give time to print - LOG_INFO(PWM, "servosInit"); - // delay(1000); // give time to print + stopMotors(); + // delay(3000); //check motor stop servosInit(); - LOG_INFO(PWM, "mixerUpdateStateFlags"); - // delay(1000); // give time to print mixerUpdateStateFlags(); - LOG_INFO(PWM, "mixerInit"); - // delay(1000); // give time to print mixerInit(); - LOG_INFO(PWM, "get timOutputs"); - // delay(1000); // give time to print - timMotorServoHardware_t timOutputs; - pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); - LOG_INFO(PWM, "check changes"); - // delay(1000); // give time to print, stuck here - bool motor_output_type_not_changed = old_timOutputs.maxTimMotorCount == timOutputs.maxTimMotorCount; - bool servo_output_type_not_changed = old_timOutputs.maxTimServoCount == timOutputs.maxTimServoCount; - for (int i; i < min_ab(old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); i++) + // timMotorServoHardware_t timOutputs; + // pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); + // bool motor_output_type_not_changed = old_timOutputs.maxTimMotorCount == timOutputs.maxTimMotorCount; + // bool servo_output_type_not_changed = old_timOutputs.maxTimServoCount == timOutputs.maxTimServoCount; + // LOG_INFO(PWM, "motor_output_type_not_changed:%d,%d,%d",motor_output_type_not_changed,old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); + // for (int i; i < min_ab(old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); i++) + // { + // LOG_INFO(PWM, "motor_output_type_not_changed:%d,%d",i,motor_output_type_not_changed); + // motor_output_type_not_changed &= old_timOutputs.timMotors[i]->tag==timOutputs.timMotors[i]->tag; + // } + // LOG_INFO(PWM, "motor_output_type_not_changed:%d",motor_output_type_not_changed); + + // LOG_INFO(PWM, "servo_output_type_not_changed:%d,%d,%d",servo_output_type_not_changed,old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); + // for (int i; i < min_ab(old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); i++) + // { + // LOG_INFO(PWM, "servo_output_type_not_changed:%d,%d",i,servo_output_type_not_changed); + // servo_output_type_not_changed &= old_timOutputs.timServos[i]->tag==timOutputs.timServos[i]->tag; + // } + // LOG_INFO(PWM, "servo_output_type_not_changed:%d",servo_output_type_not_changed); + + // if(!motor_output_type_not_changed || !servo_output_type_not_changed){ + // LOG_INFO(PWM, "pwmMotorAndServoHotInit"); + // pwmMotorAndServoHotInit(&timOutputs); + // } + if(old_platform_type!=mixerConfig()->platformType) { - motor_output_type_not_changed &= old_timOutputs.timMotors[i]->tag==timOutputs.timMotors[i]->tag; - } - for (int i; i < min_ab(old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); i++) - { - servo_output_type_not_changed &= old_timOutputs.timServos[i]->tag==timOutputs.timServos[i]->tag; - } - if(!motor_output_type_not_changed || !servo_output_type_not_changed){ - LOG_INFO(PWM, "pwmMotorAndServoHotInit"); - // delay(1000); // give time to print - pwmMotorAndServoHotInit(&timOutputs); - } - if (!STATE(ALTITUDE_CONTROL)) { - featureClear(FEATURE_AIRMODE); + } return true; +#else + profile_index=0; //prevent compilier warning: parameter 'profile_index' set but not used + return (bool) profile_index; +#endif } diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index b192e20170..9d59e65f1f 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -21,6 +21,5 @@ PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); #define mixerConfigMutable() ((mixerConfig_t *) mixerConfig()) #define primaryMotorMixer(_index) (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->MotorMixers)[_index]) #define primaryMotorMixerMutable(_index) ((motorMixer_t *)primaryMotorMixer(_index)) -extern motorMixer_t primaryMotorMixer_CopyArray[12]; bool OutputProfileHotSwitch(int profile_index); diff --git a/src/main/target/MATEKF405/CMakeLists.txt b/src/main/target/MATEKF405/CMakeLists.txt index c4f839c1c1..36d193a945 100644 --- a/src/main/target/MATEKF405/CMakeLists.txt +++ b/src/main/target/MATEKF405/CMakeLists.txt @@ -1,3 +1,4 @@ target_stm32f405xg(MATEKF405) target_stm32f405xg(MATEKF405_SERVOS6) target_stm32f405xg(MATEKF405OSD) +target_stm32f405xg(MATEKF405VTOL) diff --git a/src/main/target/MATEKF405/target.c b/src/main/target/MATEKF405/target.c index 40ebf626e5..34387de6c8 100644 --- a/src/main/target/MATEKF405/target.c +++ b/src/main/target/MATEKF405/target.c @@ -23,6 +23,21 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM +#ifdef MATEKF405VTOL + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 UP(2,1) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S3 UP(2,1) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 UP(2,1) + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED , 0, 0), // S5 UP(1,7) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 UP(2,5) + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,7)!S5 UP(2,6) + + DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2 + + DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // TX4 UP(1,6) D(1,2)!S1 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // RX4 UP(1,6) D(1,4) +#else #ifdef MATEKF405_SERVOS6 DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 @@ -46,6 +61,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // TX4 UP(1,6) D(1,2)!S1 DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // RX4 UP(1,6) D(1,4) +#endif }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index fa2af63384..e664fa40b1 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -195,3 +195,7 @@ #define USE_ESC_SENSOR #define MAX_PWM_OUTPUT_PORTS 6 + +#ifdef MATEKF405VTOL +#define ENABLE_MIXER_PROFILE_HOTSWAP +#endif \ No newline at end of file From 97318e4f84c45048dd8620177e08856bb3340022 Mon Sep 17 00:00:00 2001 From: shota Date: Fri, 11 Nov 2022 04:47:32 +0900 Subject: [PATCH 006/122] add sannity check in hot mixprofile switching, and fix cli --- src/main/drivers/pwm_mapping.c | 14 +-- src/main/drivers/pwm_mapping.h | 2 +- src/main/fc/cli.c | 10 +- src/main/flight/mixer_profile.c | 126 ++++++++++++++++--------- src/main/flight/mixer_profile.h | 5 + src/main/navigation/navigation.c | 7 ++ src/main/navigation/navigation.h | 1 + src/main/programming/logic_condition.c | 5 +- src/main/target/MATEKF405/target.h | 2 +- 9 files changed, 107 insertions(+), 65 deletions(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 7360a8f01d..744e9fa2dd 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -395,11 +395,11 @@ bool pwmMotorAndServoInit(void) return (pwmInitError == PWM_INIT_ERROR_NONE); } -bool pwmMotorAndServoHotInit(timMotorServoHardware_t* timOutputs) -{ - resetAllocatedOutputPortCount(); - pwmInitMotors(timOutputs); - pwmInitServos(timOutputs); +// bool pwmMotorAndServoHotInit(timMotorServoHardware_t* timOutputs) +// { +// resetAllocatedOutputPortCount(); +// pwmInitMotors(timOutputs); +// pwmInitServos(timOutputs); - return (pwmInitError == PWM_INIT_ERROR_NONE); -} \ No newline at end of file +// return (pwmInitError == PWM_INIT_ERROR_NONE); +// } \ No newline at end of file diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 3de4431470..8563d2fd95 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -81,7 +81,7 @@ typedef struct { void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos); bool pwmMotorAndServoInit(void); -bool pwmMotorAndServoHotInit(timMotorServoHardware_t* timOutputs); +// bool pwmMotorAndServoHotInit(timMotorServoHardware_t* timOutputs); const motorProtocolProperties_t * getMotorProtocolProperties(motorPwmProtocolTypes_e proto); pwmInitError_e getPwmInitError(void); const char * getPwmInitErrorMessage(void); diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index ebcf4448bf..a135e91e2a 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -1040,7 +1040,7 @@ static void cliAdjustmentRange(char *cmdline) } static void printMotorMix(uint8_t dumpMask, const motorMixer_t *primaryMotorMixer, const motorMixer_t *defaultprimaryMotorMixer) -{ +{ const char *format = "mmix %d %s %s %s %s"; char buf0[FTOA_BUFFER_SIZE]; char buf1[FTOA_BUFFER_SIZE]; @@ -3077,12 +3077,8 @@ static void cliDumpMixerProfile(uint8_t profileIndex, uint8_t dumpMask) cliPrintLinef("mixer_profile %d\r\n", getConfigMixerProfile() + 1); dumpAllValues(MIXER_CONFIG_VALUE, dumpMask); cliPrintHashLine("mixer"); - cliPrintHashLine("dumpMask"); - char buf0[FTOA_BUFFER_SIZE]; - itoa(dumpMask,buf0,2); - cliPrintHashLine(buf0); - cliDumpPrintLinef(dumpMask, primaryMotorMixer(0)->throttle == 0.0f, "\r\nmmix reset\r\n"); - printMotorMix(dumpMask, primaryMotorMixer(0), NULL); + cliDumpPrintLinef(dumpMask, primaryMotorMixer_CopyArray()[0].throttle == 0.0f, "\r\nmmix reset\r\n"); + printMotorMix(dumpMask, primaryMotorMixer_CopyArray(), primaryMotorMixer(0)); } #ifdef USE_CLI_BATCH diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 561b7d6bb7..f424715421 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -11,7 +11,8 @@ #include "drivers/pwm_mapping.h" #include "drivers/time.h" #include "flight/mixer.h" -// #include "flight/pid.h" +#include "common/axis.h" +#include "flight/pid.h" #include "flight/servos.h" #include "fc/config.h" @@ -20,6 +21,8 @@ #include "common/log.h" +#include "navigation/navigation.h" + PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1); void pgResetFn_mixerProfiles(mixerProfile_t *instance) @@ -43,62 +46,95 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) // PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTOR_MIXER, 0); +bool OutputProfileHotSwitch(int profile_index) +{ + // does not work with timerHardwareOverride + LOG_INFO(PWM, "OutputProfileHotSwitch"); + + //do not allow switching between multi rotor and non multi rotor +#ifdef ENABLE_MCFW_MIXER_PROFILE_HOTSWAP + bool MCFW_hotswap_unavailable = false; +#else + bool MCFW_hotswap_unavailable = true; +#endif + uint8_t old_platform_type = mixerConfig()->platformType; + uint8_t new_platform_type = mixerConfigByIndex(profile_index)->platformType; + bool old_platform_type_mc = old_platform_type == PLATFORM_MULTIROTOR || old_platform_type == PLATFORM_TRICOPTER; + bool new_platform_type_mc = new_platform_type == PLATFORM_MULTIROTOR || new_platform_type == PLATFORM_TRICOPTER; + bool is_mcfw_switching = old_platform_type_mc ^ new_platform_type_mc; + if (MCFW_hotswap_unavailable && is_mcfw_switching) + { + LOG_INFO(PWM, "MCFW_hotswap_unavailable"); + return false; + } + + //do not allow switching in navigation mode + if (ARMING_FLAG(ARMED) && navigationInAnyMode()){ + LOG_INFO(PWM, "navModesEnabled"); + return false; + } + + if (!setConfigMixerProfile(profile_index)){ + LOG_INFO(PWM, "failed to set config"); + return false; + } + // stopMotors(); + writeAllMotors(feature(FEATURE_REVERSIBLE_MOTORS) ? reversibleMotorsConfig()->neutral : motorConfig()->mincommand);//stop motors + servosInit(); + mixerUpdateStateFlags(); + mixerInit(); + + if(old_platform_type!=mixerConfig()->platformType) + { + pidInit(); + pidInitFilters(); + schedulePidGainsUpdate(); + navigationInit(); + } + return true; +} + int min_ab(int a,int b) { return a > b ? b : a; } -bool OutputProfileHotSwitch(int profile_index) -{ -#ifdef ENABLE_MIXER_PROFILE_HOTSWAP - // does not work with timerHardwareOverride - LOG_INFO(PWM, "OutputProfileHotSwitch"); - - //store current output for check - uint8_t old_platform_type=mixerConfig()->platformType; +void checkOutputMapping(int profile_index) +{ timMotorServoHardware_t old_timOutputs; pwmBuildTimerOutputList(&old_timOutputs, isMixerUsingServos()); - if (!setConfigMixerProfile(profile_index)){ - return false; - } stopMotors(); - // delay(3000); //check motor stop + delay(1000); //check motor stop + if (!setConfigMixerProfile(profile_index)){ + LOG_INFO(PWM, "failed to set config"); + return; + } servosInit(); mixerUpdateStateFlags(); mixerInit(); - - // timMotorServoHardware_t timOutputs; - // pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); - // bool motor_output_type_not_changed = old_timOutputs.maxTimMotorCount == timOutputs.maxTimMotorCount; - // bool servo_output_type_not_changed = old_timOutputs.maxTimServoCount == timOutputs.maxTimServoCount; - // LOG_INFO(PWM, "motor_output_type_not_changed:%d,%d,%d",motor_output_type_not_changed,old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); - // for (int i; i < min_ab(old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); i++) - // { - // LOG_INFO(PWM, "motor_output_type_not_changed:%d,%d",i,motor_output_type_not_changed); - // motor_output_type_not_changed &= old_timOutputs.timMotors[i]->tag==timOutputs.timMotors[i]->tag; - // } - // LOG_INFO(PWM, "motor_output_type_not_changed:%d",motor_output_type_not_changed); - - // LOG_INFO(PWM, "servo_output_type_not_changed:%d,%d,%d",servo_output_type_not_changed,old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); - // for (int i; i < min_ab(old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); i++) - // { - // LOG_INFO(PWM, "servo_output_type_not_changed:%d,%d",i,servo_output_type_not_changed); - // servo_output_type_not_changed &= old_timOutputs.timServos[i]->tag==timOutputs.timServos[i]->tag; - // } - // LOG_INFO(PWM, "servo_output_type_not_changed:%d",servo_output_type_not_changed); - - // if(!motor_output_type_not_changed || !servo_output_type_not_changed){ - // LOG_INFO(PWM, "pwmMotorAndServoHotInit"); - // pwmMotorAndServoHotInit(&timOutputs); - // } - if(old_platform_type!=mixerConfig()->platformType) + timMotorServoHardware_t timOutputs; + pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); + bool motor_output_type_not_changed = old_timOutputs.maxTimMotorCount == timOutputs.maxTimMotorCount; + bool servo_output_type_not_changed = old_timOutputs.maxTimServoCount == timOutputs.maxTimServoCount; + LOG_INFO(PWM, "maxTimMotorCount:%d,%d",old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); + for (int i; i < min_ab(old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); i++) { - + LOG_INFO(PWM, "motor_output_type_not_changed:%d,%d",i,motor_output_type_not_changed); + motor_output_type_not_changed &= old_timOutputs.timMotors[i]->tag==timOutputs.timMotors[i]->tag; + } + LOG_INFO(PWM, "motor_output_type_not_changed:%d",motor_output_type_not_changed); + + LOG_INFO(PWM, "maxTimServoCount:%d,%d",old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); + for (int i; i < min_ab(old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); i++) + { + LOG_INFO(PWM, "servo_output_type_not_changed:%d,%d",i,servo_output_type_not_changed); + servo_output_type_not_changed &= old_timOutputs.timServos[i]->tag==timOutputs.timServos[i]->tag; + } + LOG_INFO(PWM, "servo_output_type_not_changed:%d",servo_output_type_not_changed); + + if(!motor_output_type_not_changed || !servo_output_type_not_changed){ + LOG_INFO(PWM, "pwm output mapping has changed"); } - return true; -#else - profile_index=0; //prevent compilier warning: parameter 'profile_index' set but not used - return (bool) profile_index; -#endif } + diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index 9d59e65f1f..249cccf193 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -22,4 +22,9 @@ PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); #define primaryMotorMixer(_index) (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->MotorMixers)[_index]) #define primaryMotorMixerMutable(_index) ((motorMixer_t *)primaryMotorMixer(_index)) +static inline const mixerProfile_t* mixerProfiles_CopyArray_macro(int _index) { return &mixerProfiles_CopyArray[_index]; } +#define primaryMotorMixer_CopyArray() (mixerProfiles_CopyArray_macro(systemConfig()->current_mixer_profile_index)->MotorMixers) + +#define mixerConfigByIndex(index) (&(mixerProfiles(index)->mixer_config)) + bool OutputProfileHotSwitch(int profile_index); diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index c6c5d6cd51..08c6676686 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -4263,6 +4263,13 @@ bool navigationIsExecutingAnEmergencyLanding(void) return navGetCurrentStateFlags() & NAV_CTL_EMERG; } + +bool navigationInAnyMode(void) +{ + navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); + return !(stateFlags ==0); +} + bool navigationInAutomaticThrottleMode(void) { navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 339da15392..13f9f58bc9 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -582,6 +582,7 @@ void abortForcedEmergLanding(void); emergLandState_e getStateOfForcedEmergLanding(void); /* Getter functions which return data about the state of the navigation system */ +bool navigationInAnyMode(void); bool navigationInAutomaticThrottleMode(void); bool navigationIsControllingThrottle(void); bool isFixedWingAutoThrottleManuallyIncreased(void); diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index cd0a728b14..6a49290050 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -369,10 +369,7 @@ static int logicConditionCompute( case LOGIC_CONDITION_SET_MIXER_PROFILE: operandA--; if ( getConfigMixerProfile() != operandA && (operandA >= 0 && operandA < MAX_MIXER_PROFILE_COUNT)) { - bool mixerprofileChanged = false; - if (OutputProfileHotSwitch(operandA)) { - mixerprofileChanged = true; - } + bool mixerprofileChanged = OutputProfileHotSwitch(operandA); return mixerprofileChanged; } else { return false; diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index e664fa40b1..f0f1c8bc87 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -197,5 +197,5 @@ #define MAX_PWM_OUTPUT_PORTS 6 #ifdef MATEKF405VTOL -#define ENABLE_MIXER_PROFILE_HOTSWAP +#define ENABLE_MCFW_MIXER_PROFILE_HOTSWAP #endif \ No newline at end of file From 80a3dee407178b29404941dbb2fa7c6cb08af4ff Mon Sep 17 00:00:00 2001 From: shota Date: Fri, 11 Nov 2022 18:26:39 +0900 Subject: [PATCH 007/122] added servo to mixer --- src/main/fc/cli.c | 11 +++++++---- src/main/flight/mixer_profile.c | 23 +++++++++++++++++++---- src/main/flight/mixer_profile.h | 8 ++++++-- src/main/flight/servos.c | 30 +++++++++++++++--------------- 4 files changed, 47 insertions(+), 25 deletions(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index a135e91e2a..778889c11a 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3079,6 +3079,9 @@ static void cliDumpMixerProfile(uint8_t profileIndex, uint8_t dumpMask) cliPrintHashLine("mixer"); cliDumpPrintLinef(dumpMask, primaryMotorMixer_CopyArray()[0].throttle == 0.0f, "\r\nmmix reset\r\n"); printMotorMix(dumpMask, primaryMotorMixer_CopyArray(), primaryMotorMixer(0)); + cliPrintHashLine("servo mixer"); + cliDumpPrintLinef(dumpMask, customServoMixers_CopyArray()[0].rate == 0, "smix reset\r\n"); + printServoMix(dumpMask, customServoMixers_CopyArray(), customServoMixers(0)); } #ifdef USE_CLI_BATCH @@ -3619,7 +3622,7 @@ static void printConfig(const char *cmdline, bool doDiff) #endif } - cliPrintHashLine("resources"); + // cliPrintHashLine("resources"); //printResource(dumpMask, &defaultConfig); // cliPrintHashLine("mixer"); @@ -3628,9 +3631,9 @@ static void printConfig(const char *cmdline, bool doDiff) // printMotorMix(dumpMask, primaryMotorMixer_CopyArray, primaryMotorMixer(0)); // print custom servo mixer if exists - cliPrintHashLine("servo mixer"); - cliDumpPrintLinef(dumpMask, customServoMixers_CopyArray[0].rate == 0, "smix reset\r\n"); - printServoMix(dumpMask, customServoMixers_CopyArray, customServoMixers(0)); + // cliPrintHashLine("servo mixer"); + // cliDumpPrintLinef(dumpMask, customServoMixers_CopyArray[0].rate == 0, "smix reset\r\n"); + // printServoMix(dumpMask, customServoMixers_CopyArray, customServoMixers(0)); // print servo parameters cliPrintHashLine("servo"); diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index f424715421..204d54a2b4 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -37,9 +37,24 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) .outputMode = SETTING_OUTPUT_MODE_DEFAULT, } ); - motorMixer_t tmp_mixer = {.throttle=0,.roll=0,.pitch=0,.yaw=0}; for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) { - instance->MotorMixers[j] = tmp_mixer; + RESET_CONFIG(motorMixer_t, &instance[i].MotorMixers[j], + .throttle=0, + .roll=0, + .pitch=0, + .yaw=0 + ); + } + for (int j = 0; j < MAX_SERVO_RULES; j++) { + RESET_CONFIG(servoMixer_t, &instance[i].ServoMixers[j], + .targetChannel = 0, + .inputSource = 0, + .rate = 0, + .speed = 0 +#ifdef USE_PROGRAMMING_FRAMEWORK + ,.conditionId = -1 +#endif + ); } } } @@ -79,7 +94,7 @@ bool OutputProfileHotSwitch(int profile_index) return false; } // stopMotors(); - writeAllMotors(feature(FEATURE_REVERSIBLE_MOTORS) ? reversibleMotorsConfig()->neutral : motorConfig()->mincommand);//stop motors + writeAllMotors(feature(FEATURE_REVERSIBLE_MOTORS) ? reversibleMotorsConfig()->neutral : motorConfig()->mincommand);//stop motors with out delay servosInit(); mixerUpdateStateFlags(); mixerInit(); @@ -99,7 +114,7 @@ int min_ab(int a,int b) return a > b ? b : a; } -void checkOutputMapping(int profile_index) +void checkOutputMapping(int profile_index)//debug purpose { timMotorServoHardware_t old_timOutputs; pwmBuildTimerOutputList(&old_timOutputs, isMixerUsingServos()); diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index 249cccf193..97d5296abd 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -19,11 +19,15 @@ PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); #define mixerConfig() (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->mixer_config)) #define mixerConfigMutable() ((mixerConfig_t *) mixerConfig()) + #define primaryMotorMixer(_index) (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->MotorMixers)[_index]) #define primaryMotorMixerMutable(_index) ((motorMixer_t *)primaryMotorMixer(_index)) +#define customServoMixers(_index) (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->ServoMixers)[_index]) +#define customServoMixersMutable(_index) ((servoMixer_t *)customServoMixers(_index)) -static inline const mixerProfile_t* mixerProfiles_CopyArray_macro(int _index) { return &mixerProfiles_CopyArray[_index]; } -#define primaryMotorMixer_CopyArray() (mixerProfiles_CopyArray_macro(systemConfig()->current_mixer_profile_index)->MotorMixers) +static inline const mixerProfile_t* mixerProfiles_CopyArray_by_index(int _index) { return &mixerProfiles_CopyArray[_index]; } +#define primaryMotorMixer_CopyArray() (mixerProfiles_CopyArray_by_index(systemConfig()->current_mixer_profile_index)->MotorMixers) +#define customServoMixers_CopyArray() (mixerProfiles_CopyArray_by_index(systemConfig()->current_mixer_profile_index)->ServoMixers) #define mixerConfigByIndex(index) (&(mixerProfiles(index)->mixer_config)) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index fed5519ef9..93ebeb9991 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -70,22 +70,22 @@ PG_RESET_TEMPLATE(servoConfig_t, servoConfig, .servo_autotrim_rotation_limit = SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT_DEFAULT ); -PG_REGISTER_ARRAY_WITH_RESET_FN(servoMixer_t, MAX_SERVO_RULES, customServoMixers, PG_SERVO_MIXER, 1); +// PG_REGISTER_ARRAY_WITH_RESET_FN(servoMixer_t, MAX_SERVO_RULES, customServoMixers, PG_SERVO_MIXER, 1); -void pgResetFn_customServoMixers(servoMixer_t *instance) -{ - for (int i = 0; i < MAX_SERVO_RULES; i++) { - RESET_CONFIG(servoMixer_t, &instance[i], - .targetChannel = 0, - .inputSource = 0, - .rate = 0, - .speed = 0 -#ifdef USE_PROGRAMMING_FRAMEWORK - ,.conditionId = -1 -#endif - ); - } -} +// void pgResetFn_customServoMixers(servoMixer_t *instance) +// { +// for (int i = 0; i < MAX_SERVO_RULES; i++) { +// RESET_CONFIG(servoMixer_t, &instance[i], +// .targetChannel = 0, +// .inputSource = 0, +// .rate = 0, +// .speed = 0 +// #ifdef USE_PROGRAMMING_FRAMEWORK +// ,.conditionId = -1 +// #endif +// ); +// } +// } PG_REGISTER_ARRAY_WITH_RESET_FN(servoParam_t, MAX_SUPPORTED_SERVOS, servoParams, PG_SERVO_PARAMS, 3); From cbbef197210c05dbcd775f9adc8612b5b0277c7e Mon Sep 17 00:00:00 2001 From: shota Date: Sun, 13 Nov 2022 23:02:35 +0900 Subject: [PATCH 008/122] mixer_profile draft pr --- src/main/config/parameter_group_ids.h | 2 +- src/main/fc/cli.c | 13 +++++++++---- src/main/fc/config.c | 1 + src/main/flight/mixer_profile.c | 7 ++++--- src/main/flight/mixer_profile.h | 2 ++ src/main/flight/servos.c | 16 ++++++++++++++++ src/main/flight/servos.h | 1 + src/main/target/MATEKF405/target.c | 2 +- src/main/target/MATEKF405/target.h | 2 +- src/main/target/MATEKF405TE/CMakeLists.txt | 1 + src/main/target/MATEKF405TE/target.c | 14 +++++++++++++- src/main/target/MATEKF405TE/target.h | 3 +++ 12 files changed, 53 insertions(+), 11 deletions(-) diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index 754b7dbada..384fa79ba4 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -37,7 +37,7 @@ #define PG_SYSTEM_CONFIG 18 #define PG_FEATURE_CONFIG 19 #define PG_MIXER_PROFILE 20 -#define PG_SERVO_MIXER 21 +// #define PG_SERVO_MIXER 21 #define PG_IMU_CONFIG 22 //#define PG_PROFILE_SELECTION 23 #define PG_RX_CONFIG 24 diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 778889c11a..34932c58c3 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -1864,7 +1864,8 @@ static void cliServoMix(char *cmdline) printServoMix(DUMP_MASTER, customServoMixers(0), NULL); } else if (sl_strncasecmp(cmdline, "reset", 5) == 0) { // erase custom mixer - pgResetCopy(customServoMixersMutable(0), PG_SERVO_MIXER); + // pgResetCopy(customServoMixersMutable(0), PG_SERVO_MIXER); + Reset_servoMixers(customServoMixersMutable(0)); } else { enum {RULE = 0, TARGET, INPUT, RATE, SPEED, CONDITION, ARGS_COUNT}; char *ptr = strtok_r(cmdline, " ", &saveptr); @@ -3589,12 +3590,14 @@ static void printConfig(const char *cmdline, bool doDiff) const int currentProfileIndexSave = getConfigProfile(); const int currentBatteryProfileIndexSave = getConfigBatteryProfile(); + const int currentMixerProfileIndexSave = getConfigMixerProfile(); backupConfigs(); // reset all configs to defaults to do differencing resetConfigs(); // restore the profile indices, since they should not be reset for proper comparison setConfigProfile(currentProfileIndexSave); setConfigBatteryProfile(currentBatteryProfileIndexSave); + setConfigMixerProfile(currentMixerProfileIndexSave); if (checkCommand(options, "showdefaults")) { dumpMask = dumpMask | SHOW_DEFAULTS; // add default values as comments for changed values @@ -3622,8 +3625,8 @@ static void printConfig(const char *cmdline, bool doDiff) #endif } - // cliPrintHashLine("resources"); - //printResource(dumpMask, &defaultConfig); + cliPrintHashLine("resources"); + // printResource(dumpMask, &defaultConfig); // cliPrintHashLine("mixer"); // cliDumpPrintLinef(dumpMask, primaryMotorMixer_CopyArray[0].throttle == 0.0f, "\r\nmmix reset\r\n"); @@ -3716,6 +3719,7 @@ static void printConfig(const char *cmdline, bool doDiff) // dump all profiles const int currentProfileIndexSave = getConfigProfile(); const int currentBatteryProfileIndexSave = getConfigBatteryProfile(); + const int currentMixerProfileIndexSave = getConfigMixerProfile(); for (int ii = 0; ii < MAX_PROFILE_COUNT; ++ii) { cliDumpProfile(ii, dumpMask); } @@ -3727,10 +3731,11 @@ static void printConfig(const char *cmdline, bool doDiff) } setConfigProfile(currentProfileIndexSave); setConfigBatteryProfile(currentBatteryProfileIndexSave); + setConfigMixerProfile(currentMixerProfileIndexSave); cliPrintHashLine("restore original profile selection"); cliPrintLinef("profile %d", currentProfileIndexSave + 1); - cliPrintLinef("battery_profile %d", currentBatteryProfileIndexSave + 1); + cliPrintLinef("mixer_profile %d", currentMixerProfileIndexSave + 1); #ifdef USE_CLI_BATCH batchModeEnabled = false; diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 1a7ced8515..e0f21442db 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -321,6 +321,7 @@ void readEEPROM(void) setConfigProfile(getConfigProfile()); setConfigBatteryProfile(getConfigBatteryProfile()); + setConfigMixerProfile(getConfigMixerProfile()); validateAndFixConfig(); activateConfig(); diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 204d54a2b4..04974eb22d 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -62,12 +62,12 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) // PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTOR_MIXER, 0); bool OutputProfileHotSwitch(int profile_index) -{ +{ // does not work with timerHardwareOverride LOG_INFO(PWM, "OutputProfileHotSwitch"); //do not allow switching between multi rotor and non multi rotor -#ifdef ENABLE_MCFW_MIXER_PROFILE_HOTSWAP +#ifdef ENABLE_MIXER_PROFILE_MCFW_HOTSWAP bool MCFW_hotswap_unavailable = false; #else bool MCFW_hotswap_unavailable = true; @@ -88,6 +88,7 @@ bool OutputProfileHotSwitch(int profile_index) LOG_INFO(PWM, "navModesEnabled"); return false; } + //TODO add check of each motor/servo is mapped before and after the switch if (!setConfigMixerProfile(profile_index)){ LOG_INFO(PWM, "failed to set config"); @@ -104,7 +105,7 @@ bool OutputProfileHotSwitch(int profile_index) pidInit(); pidInitFilters(); schedulePidGainsUpdate(); - navigationInit(); + // navigationInit(); //may need to initilize FW_HEADING_USE_YAW on rover or boat } return true; } diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index 97d5296abd..4eee2a0415 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -30,5 +30,7 @@ static inline const mixerProfile_t* mixerProfiles_CopyArray_by_index(int _index) #define customServoMixers_CopyArray() (mixerProfiles_CopyArray_by_index(systemConfig()->current_mixer_profile_index)->ServoMixers) #define mixerConfigByIndex(index) (&(mixerProfiles(index)->mixer_config)) +#define mixerMotorMixersByIndex(index) (&(mixerProfiles(index)->MotorMixers)) +#define mixerServoMixersByIndex(index) (&(mixerProfiles(index)->ServoMixers)) bool OutputProfileHotSwitch(int profile_index); diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 93ebeb9991..674a7ab355 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -87,6 +87,22 @@ PG_RESET_TEMPLATE(servoConfig_t, servoConfig, // } // } +void Reset_servoMixers(servoMixer_t *instance) +{ + for (int i = 0; i < MAX_SERVO_RULES; i++) + { + RESET_CONFIG(servoMixer_t, &instance[i], + .targetChannel = 0, + .inputSource = 0, + .rate = 0, + .speed = 0 +#ifdef USE_PROGRAMMING_FRAMEWORK + ,.conditionId = -1 +#endif + ); + } +} + PG_REGISTER_ARRAY_WITH_RESET_FN(servoParam_t, MAX_SUPPORTED_SERVOS, servoParams, PG_SERVO_PARAMS, 3); void pgResetFn_servoParams(servoParam_t *instance) diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index 841415ea23..cf303db6a4 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -151,6 +151,7 @@ typedef struct servoMetadata_s { extern int16_t servo[MAX_SUPPORTED_SERVOS]; +void Reset_servoMixers(servoMixer_t* instance); bool isServoOutputEnabled(void); void setServoOutputEnabled(bool flag); bool isMixerUsingServos(void); diff --git a/src/main/target/MATEKF405/target.c b/src/main/target/MATEKF405/target.c index 34387de6c8..3f4d761834 100644 --- a/src/main/target/MATEKF405/target.c +++ b/src/main/target/MATEKF405/target.c @@ -23,7 +23,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM -#ifdef MATEKF405VTOL +#ifdef MATEKF405VTOL//development purpose, TODO: remove it in the release DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 UP(2,1) DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S3 UP(2,1) diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index f0f1c8bc87..e9aff02df4 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -197,5 +197,5 @@ #define MAX_PWM_OUTPUT_PORTS 6 #ifdef MATEKF405VTOL -#define ENABLE_MCFW_MIXER_PROFILE_HOTSWAP +#define ENABLE_MIXER_PROFILE_MCFW_HOTSWAP #endif \ No newline at end of file diff --git a/src/main/target/MATEKF405TE/CMakeLists.txt b/src/main/target/MATEKF405TE/CMakeLists.txt index ce0150c7d3..d8fc13c77b 100644 --- a/src/main/target/MATEKF405TE/CMakeLists.txt +++ b/src/main/target/MATEKF405TE/CMakeLists.txt @@ -1,2 +1,3 @@ target_stm32f405xg(MATEKF405TE) target_stm32f405xg(MATEKF405TE_SD) +target_stm32f405xg(MATEKF405TE_SD_VTOL) diff --git a/src/main/target/MATEKF405TE/target.c b/src/main/target/MATEKF405TE/target.c index 70561e001f..54e485b3c9 100644 --- a/src/main/target/MATEKF405TE/target.c +++ b/src/main/target/MATEKF405TE/target.c @@ -25,6 +25,18 @@ #include "drivers/timer_def_stm32f4xx.h" timerHardware_t timerHardware[] = { +#ifdef MATEKF405TE_SD_VTOL +//using d-shot on motors seems to have problems on s3,maybe dma related,maybe my board problem + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2,7,7) UP217 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(2,2,0) UP217 + DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 D(2,6,0) UP256 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S4 D(2,1,6) UP256 + + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 D(1,7,3) UP173 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,1,3) UP173 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,6,3) UP173 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8 D(1,5,3) UP173 +#else DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2,7,7) UP217 DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(2,2,0) UP217 DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 D(2,6,0) UP256 @@ -34,7 +46,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,1,3) UP173 DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,6,3) UP173 DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 D(1,5,3) UP173 - +#endif DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 DMA NONE DEF_TIM(TIM13, CH1, PA6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 DMA NONE DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11 D(1,0,2) diff --git a/src/main/target/MATEKF405TE/target.h b/src/main/target/MATEKF405TE/target.h index 93ab3345de..e51a6d9a20 100644 --- a/src/main/target/MATEKF405TE/target.h +++ b/src/main/target/MATEKF405TE/target.h @@ -180,3 +180,6 @@ #define USE_DSHOT #define USE_ESC_SENSOR +#ifdef MATEKF405TE_SD_VTOL +#define ENABLE_MIXER_PROFILE_MCFW_HOTSWAP +#endif \ No newline at end of file From 67390e12edbbdcf4912cf49a2267b4096d983c08 Mon Sep 17 00:00:00 2001 From: "haoxiang.qiu" Date: Mon, 14 Nov 2022 18:43:16 +0900 Subject: [PATCH 009/122] mixprofile development --- src/main/drivers/pwm_mapping.c | 19 ++-- src/main/drivers/pwm_mapping.h | 10 -- src/main/drivers/pwm_output.c | 4 - src/main/drivers/pwm_output.h | 1 - src/main/fc/cli.c | 33 ++----- src/main/fc/fc_msp.c | 1 - src/main/flight/mixer.c | 29 +----- src/main/flight/mixer.h | 22 +---- src/main/flight/mixer_profile.c | 131 +++++++++++++++++-------- src/main/programming/logic_condition.c | 6 +- src/main/target/MATEKF405TE/target.c | 2 +- src/main/target/MATEKF405TE/target.h | 11 ++- 12 files changed, 116 insertions(+), 153 deletions(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 744e9fa2dd..3707c716d1 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -47,6 +47,13 @@ enum { MAP_TO_SERVO_OUTPUT, }; +typedef struct { + int maxTimMotorCount; + int maxTimServoCount; + const timerHardware_t * timMotors[MAX_PWM_OUTPUT_PORTS]; + const timerHardware_t * timServos[MAX_PWM_OUTPUT_PORTS]; +} timMotorServoHardware_t; + static pwmInitError_e pwmInitError = PWM_INIT_ERROR_NONE; static const char * pwmInitErrorMsg[] = { @@ -220,12 +227,10 @@ static void timerHardwareOverride(timerHardware_t * timer) { void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos) { - LOG_INFO(PWM, "pwmBuildTimerOutputList"); timOutputs->maxTimMotorCount = 0; timOutputs->maxTimServoCount = 0; uint8_t motorCount = getMotorCount(); - LOG_INFO(PWM, "motorCount %d", motorCount); uint8_t motorIdx = 0; for (int idx = 0; idx < timerHardwareCount; idx++) { @@ -387,6 +392,7 @@ bool pwmMotorAndServoInit(void) // Build temporary timer mappings for motor and servo pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); + // At this point we have built tables of timers suitable for motor and servo mappings // Now we can actually initialize them according to motor/servo count from mixer pwmInitMotors(&timOutputs); @@ -394,12 +400,3 @@ bool pwmMotorAndServoInit(void) return (pwmInitError == PWM_INIT_ERROR_NONE); } - -// bool pwmMotorAndServoHotInit(timMotorServoHardware_t* timOutputs) -// { -// resetAllocatedOutputPortCount(); -// pwmInitMotors(timOutputs); -// pwmInitServos(timOutputs); - -// return (pwmInitError == PWM_INIT_ERROR_NONE); -// } \ No newline at end of file diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 8563d2fd95..4f46f14f9f 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -18,7 +18,6 @@ #pragma once #include "drivers/io_types.h" -#include "drivers/timer.h" #include "flight/mixer_profile.h" #include "flight/servos.h" @@ -62,13 +61,6 @@ typedef enum { PWM_INIT_ERROR_TIMER_INIT_FAILED, } pwmInitError_e; -typedef struct { - int maxTimMotorCount; - int maxTimServoCount; - const timerHardware_t * timMotors[MAX_PWM_OUTPUT_PORTS]; - const timerHardware_t * timServos[MAX_PWM_OUTPUT_PORTS]; -} timMotorServoHardware_t; - typedef struct rangefinderIOConfig_s { ioTag_t triggerTag; ioTag_t echoTag; @@ -79,9 +71,7 @@ typedef struct { bool isDSHOT; } motorProtocolProperties_t; -void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos); bool pwmMotorAndServoInit(void); -// bool pwmMotorAndServoHotInit(timMotorServoHardware_t* timOutputs); const motorProtocolProperties_t * getMotorProtocolProperties(motorPwmProtocolTypes_e proto); pwmInitError_e getPwmInitError(void); const char * getPwmInitErrorMessage(void); diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 7b4891bf85..658c3f5cb5 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -113,10 +113,6 @@ static uint8_t commandsBuff[DHSOT_COMMAND_QUEUE_SIZE]; static currentExecutingCommand_t currentExecutingCommand; #endif -void resetAllocatedOutputPortCount(void){ - allocatedOutputPortCount = 0; -} - static void pwmOutConfigTimer(pwmOutputPort_t * p, TCH_t * tch, uint32_t hz, uint16_t period, uint16_t value) { p->tch = tch; diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index d2ef60690f..b3c0fa6be0 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -34,7 +34,6 @@ void pwmRequestMotorTelemetry(int motorIndex); ioTag_t pwmGetMotorPinTag(int motorIndex); -void resetAllocatedOutputPortCount(void); void pwmWriteMotor(uint8_t index, uint16_t value); void pwmShutdownPulsesForAllMotors(uint8_t motorCount); void pwmCompleteMotorUpdate(void); diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 34932c58c3..025e98d00f 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -81,7 +81,6 @@ bool cliMode = false; #include "flight/failsafe.h" #include "flight/imu.h" -// #include "flight/mixer.h" #include "flight/mixer_profile.h" #include "flight/pid.h" #include "flight/servos.h" @@ -283,7 +282,6 @@ typedef enum { DUMP_MASTER = (1 << 0), DUMP_PROFILE = (1 << 1), DUMP_BATTERY_PROFILE = (1 << 2), - // DUMP_RATES = (1 << 3), DUMP_MIXER_PROFILE = (1 << 3), DUMP_ALL = (1 << 4), DO_DIFF = (1 << 5), @@ -1864,7 +1862,6 @@ static void cliServoMix(char *cmdline) printServoMix(DUMP_MASTER, customServoMixers(0), NULL); } else if (sl_strncasecmp(cmdline, "reset", 5) == 0) { // erase custom mixer - // pgResetCopy(customServoMixersMutable(0), PG_SERVO_MIXER); Reset_servoMixers(customServoMixersMutable(0)); } else { enum {RULE = 0, TARGET, INPUT, RATE, SPEED, CONDITION, ARGS_COUNT}; @@ -3626,17 +3623,6 @@ static void printConfig(const char *cmdline, bool doDiff) } cliPrintHashLine("resources"); - // printResource(dumpMask, &defaultConfig); - - // cliPrintHashLine("mixer"); - // cliDumpPrintLinef(dumpMask, primaryMotorMixer_CopyArray[0].throttle == 0.0f, "\r\nmmix reset\r\n"); - - // printMotorMix(dumpMask, primaryMotorMixer_CopyArray, primaryMotorMixer(0)); - - // print custom servo mixer if exists - // cliPrintHashLine("servo mixer"); - // cliDumpPrintLinef(dumpMask, customServoMixers_CopyArray[0].rate == 0, "smix reset\r\n"); - // printServoMix(dumpMask, customServoMixers_CopyArray, customServoMixers(0)); // print servo parameters cliPrintHashLine("servo"); @@ -3720,34 +3706,39 @@ static void printConfig(const char *cmdline, bool doDiff) const int currentProfileIndexSave = getConfigProfile(); const int currentBatteryProfileIndexSave = getConfigBatteryProfile(); const int currentMixerProfileIndexSave = getConfigMixerProfile(); + for (int ii = 0; ii < MAX_MIXER_PROFILE_COUNT; ++ii) { + cliDumpMixerProfile(ii, dumpMask); + } for (int ii = 0; ii < MAX_PROFILE_COUNT; ++ii) { cliDumpProfile(ii, dumpMask); } for (int ii = 0; ii < MAX_BATTERY_PROFILE_COUNT; ++ii) { cliDumpBatteryProfile(ii, dumpMask); } - for (int ii = 0; ii < MAX_MIXER_PROFILE_COUNT; ++ii) { - cliDumpMixerProfile(ii, dumpMask); - } setConfigProfile(currentProfileIndexSave); setConfigBatteryProfile(currentBatteryProfileIndexSave); setConfigMixerProfile(currentMixerProfileIndexSave); cliPrintHashLine("restore original profile selection"); - cliPrintLinef("profile %d", currentProfileIndexSave + 1); cliPrintLinef("mixer_profile %d", currentMixerProfileIndexSave + 1); + cliPrintLinef("profile %d", currentProfileIndexSave + 1); + cliPrintLinef("battery_profile %d", currentBatteryProfileIndexSave + 1); #ifdef USE_CLI_BATCH batchModeEnabled = false; #endif } else { // dump just the current profiles + cliDumpMixerProfile(getConfigMixerProfile(), dumpMask); cliDumpProfile(getConfigProfile(), dumpMask); cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask); - cliDumpMixerProfile(getConfigMixerProfile(), dumpMask); } } + if (dumpMask & DUMP_MIXER_PROFILE) { + cliDumpMixerProfile(getConfigMixerProfile(), dumpMask); + } + if (dumpMask & DUMP_PROFILE) { cliDumpProfile(getConfigProfile(), dumpMask); } @@ -3756,10 +3747,6 @@ static void printConfig(const char *cmdline, bool doDiff) cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask); } - if (dumpMask & DUMP_MIXER_PROFILE) { - cliDumpMixerProfile(getConfigMixerProfile(), dumpMask); - } - if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) { cliPrintHashLine("save configuration\r\nsave"); } diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 587651b21d..66737d4379 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -3132,7 +3132,6 @@ static bool mspSettingInfoCommand(sbuf_t *dst, sbuf_t *src) sbufWriteU8(dst, MAX_MIXER_PROFILE_COUNT); break; } - // If the setting uses a table, send each possible string (null terminated) if (SETTING_MODE(setting) == MODE_LOOKUP) { diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 37011845bc..21e2a75545 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -83,34 +83,6 @@ PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig, .deadband_high = SETTING_3D_DEADBAND_HIGH_DEFAULT, .neutral = SETTING_3D_NEUTRAL_DEFAULT ); -// PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1); - -// void pgResetFn_mixerProfiles(mixerProfile_t *instance) -// { -// for (int i = 0; i < MAX_MIXER_PROFILE_COUNT; i++) { -// RESET_CONFIG(mixerProfile_t, &instance[i], -// .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT, -// .platformType = SETTING_PLATFORM_TYPE_DEFAULT, -// .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, -// .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only -// .outputMode = SETTING_OUTPUT_MODE_DEFAULT, -// ); -// motorMixer_t tmp_mixer = {.throttle=0,.roll=0,.pitch=0,.yaw=0}; -// for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) { -// instance->MotorMixer[j] = tmp_mixer; -// } -// } -// } - -// PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_PROFILE, 5); - -// PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, -// .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT, -// .platformType = SETTING_PLATFORM_TYPE_DEFAULT, -// .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, -// .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only -// .outputMode = SETTING_OUTPUT_MODE_DEFAULT, -// ); PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 9); @@ -436,6 +408,7 @@ void FAST_CODE writeMotors(void) // We don't define USE_DSHOT motorValue = motor[i]; #endif + pwmWriteMotor(i, motorValue); } } diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 07d1ab248b..5813e6a73e 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -25,7 +25,6 @@ #define MAX_SUPPORTED_MOTORS 12 #endif - // Digital protocol has fixed values #define DSHOT_DISARM_COMMAND 0 #define DSHOT_MIN_THROTTLE 48 @@ -63,8 +62,6 @@ typedef struct motorMixer_s { float yaw; } motorMixer_t; -// PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer); - typedef struct mixerConfig_s { int8_t motorDirectionInverted; uint8_t platformType; @@ -73,22 +70,6 @@ typedef struct mixerConfig_s { uint8_t outputMode; } mixerConfig_t; -// typedef struct mixerProfile_s { -// int8_t motorDirectionInverted; -// uint8_t platformType; -// bool hasFlaps; -// int16_t appliedMixerPreset; -// uint8_t outputMode; -// motorMixer_t MotorMixer[MAX_SUPPORTED_MOTORS]; -// } mixerProfile_t; - -// PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); -// #define mixerConfig() mixerProfiles(systemConfig()->current_mixer_profile_index) -// #define mixerConfigMutable() ((mixerProfile_t *)mixerConfig()) -// #define primaryMotorMixer(_index) (&((mixerConfig()->MotorMixer)[_index])) -// #define primaryMotorMixerMutable(_index) ((motorMixer_t *)primaryMotorMixer(_index)) -// extern motorMixer_t primaryMotorMixer_CopyArray[12]; - typedef struct reversibleMotorsConfig_s { uint16_t deadband_low; // min 3d value uint16_t deadband_high; // max 3d value @@ -142,8 +123,7 @@ void processServoAutotrim(const float dT); void processServoAutotrimMode(void); void processContinuousServoAutotrim(const float dT); void stopMotors(void); -void stopAndDisableMotors(void); void stopPwmAllMotors(void); void loadPrimaryMotorMixer(void); -bool areMotorsRunning(void); \ No newline at end of file +bool areMotorsRunning(void); diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 04974eb22d..cf41074e15 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -59,13 +59,54 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) } } -// PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTOR_MIXER, 0); +static int computeMotorCountByMixerProfileIndex(int index) +{ + int motorCount = 0; + for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) { + // check if done + if (mixerMotorMixersByIndex(index)[i]->throttle == 0.0f) { + break; + } + motorCount++; + } + return motorCount; +} + +static int computeServoCountByMixerProfileIndex(int index) +{ + int servoRuleCount = 0; + int minServoIndex = 255; + int maxServoIndex = 0; + for (int i = 0; i < MAX_SERVO_RULES; i++) { + // check if done + if (mixerServoMixersByIndex(index)[i]->rate == 0) + break; + + if (mixerServoMixersByIndex(index)[i]->targetChannel < minServoIndex) { + minServoIndex = mixerServoMixersByIndex(index)[i]->targetChannel; + } + + if (mixerServoMixersByIndex(index)[i]->targetChannel > maxServoIndex) { + maxServoIndex = mixerServoMixersByIndex(index)[i]->targetChannel; + } + servoRuleCount++; + } + if (servoRuleCount) { + return 1 + maxServoIndex - minServoIndex; + } + else { + return 0; + } +} bool OutputProfileHotSwitch(int profile_index) { // does not work with timerHardwareOverride LOG_INFO(PWM, "OutputProfileHotSwitch"); - + if (profile_index >= MAX_MIXER_PROFILE_COUNT) {// sanity check + LOG_INFO(PWM, "invalid profile index"); + return false; + } //do not allow switching between multi rotor and non multi rotor #ifdef ENABLE_MIXER_PROFILE_MCFW_HOTSWAP bool MCFW_hotswap_unavailable = false; @@ -88,8 +129,12 @@ bool OutputProfileHotSwitch(int profile_index) LOG_INFO(PWM, "navModesEnabled"); return false; } - //TODO add check of each motor/servo is mapped before and after the switch - + //do not allow switching if motor or servos counts has changed + if ((getMotorCount() != computeMotorCountByMixerProfileIndex(profile_index)) || (getServoCount() != computeServoCountByMixerProfileIndex(profile_index))) + { + LOG_INFO(PWM, "motor/servo count will change"); + return false; + } if (!setConfigMixerProfile(profile_index)){ LOG_INFO(PWM, "failed to set config"); return false; @@ -110,47 +155,47 @@ bool OutputProfileHotSwitch(int profile_index) return true; } -int min_ab(int a,int b) -{ - return a > b ? b : a; -} +// static int min_ab(int a,int b) +// { +// return a > b ? b : a; +// } -void checkOutputMapping(int profile_index)//debug purpose -{ - timMotorServoHardware_t old_timOutputs; - pwmBuildTimerOutputList(&old_timOutputs, isMixerUsingServos()); - stopMotors(); - delay(1000); //check motor stop - if (!setConfigMixerProfile(profile_index)){ - LOG_INFO(PWM, "failed to set config"); - return; - } - servosInit(); - mixerUpdateStateFlags(); - mixerInit(); - timMotorServoHardware_t timOutputs; - pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); - bool motor_output_type_not_changed = old_timOutputs.maxTimMotorCount == timOutputs.maxTimMotorCount; - bool servo_output_type_not_changed = old_timOutputs.maxTimServoCount == timOutputs.maxTimServoCount; - LOG_INFO(PWM, "maxTimMotorCount:%d,%d",old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); - for (int i; i < min_ab(old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); i++) - { - LOG_INFO(PWM, "motor_output_type_not_changed:%d,%d",i,motor_output_type_not_changed); - motor_output_type_not_changed &= old_timOutputs.timMotors[i]->tag==timOutputs.timMotors[i]->tag; - } - LOG_INFO(PWM, "motor_output_type_not_changed:%d",motor_output_type_not_changed); +// void checkOutputMapping(int profile_index)//debug purpose +// { +// timMotorServoHardware_t old_timOutputs; +// pwmBuildTimerOutputList(&old_timOutputs, isMixerUsingServos()); +// stopMotors(); +// delay(1000); //check motor stop +// if (!setConfigMixerProfile(profile_index)){ +// LOG_INFO(PWM, "failed to set config"); +// return; +// } +// servosInit(); +// mixerUpdateStateFlags(); +// mixerInit(); +// timMotorServoHardware_t timOutputs; +// pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); +// bool motor_output_type_not_changed = old_timOutputs.maxTimMotorCount == timOutputs.maxTimMotorCount; +// bool servo_output_type_not_changed = old_timOutputs.maxTimServoCount == timOutputs.maxTimServoCount; +// LOG_INFO(PWM, "maxTimMotorCount:%d,%d",old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); +// for (int i; i < min_ab(old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); i++) +// { +// LOG_INFO(PWM, "motor_output_type_not_changed:%d,%d",i,motor_output_type_not_changed); +// motor_output_type_not_changed &= old_timOutputs.timMotors[i]->tag==timOutputs.timMotors[i]->tag; +// } +// LOG_INFO(PWM, "motor_output_type_not_changed:%d",motor_output_type_not_changed); - LOG_INFO(PWM, "maxTimServoCount:%d,%d",old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); - for (int i; i < min_ab(old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); i++) - { - LOG_INFO(PWM, "servo_output_type_not_changed:%d,%d",i,servo_output_type_not_changed); - servo_output_type_not_changed &= old_timOutputs.timServos[i]->tag==timOutputs.timServos[i]->tag; - } - LOG_INFO(PWM, "servo_output_type_not_changed:%d",servo_output_type_not_changed); +// LOG_INFO(PWM, "maxTimServoCount:%d,%d",old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); +// for (int i; i < min_ab(old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); i++) +// { +// LOG_INFO(PWM, "servo_output_type_not_changed:%d,%d",i,servo_output_type_not_changed); +// servo_output_type_not_changed &= old_timOutputs.timServos[i]->tag==timOutputs.timServos[i]->tag; +// } +// LOG_INFO(PWM, "servo_output_type_not_changed:%d",servo_output_type_not_changed); - if(!motor_output_type_not_changed || !servo_output_type_not_changed){ - LOG_INFO(PWM, "pwm output mapping has changed"); - } -} +// if(!motor_output_type_not_changed || !servo_output_type_not_changed){ +// LOG_INFO(PWM, "pwm output mapping has changed"); +// } +// } diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 6a49290050..054031e203 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -46,15 +46,11 @@ #include "sensors/rangefinder.h" #include "flight/imu.h" #include "flight/pid.h" +#include "flight/mixer_profile.h" #include "drivers/io_port_expander.h" #include "io/osd_common.h" #include "sensors/diagnostics.h" -#include "flight/mixer_profile.h" -#include "flight/mixer.h" -#include "flight/servos.h" -#include "drivers/pwm_mapping.h" - #include "navigation/navigation.h" #include "navigation/navigation_private.h" diff --git a/src/main/target/MATEKF405TE/target.c b/src/main/target/MATEKF405TE/target.c index 54e485b3c9..ba89313a94 100644 --- a/src/main/target/MATEKF405TE/target.c +++ b/src/main/target/MATEKF405TE/target.c @@ -26,7 +26,7 @@ timerHardware_t timerHardware[] = { #ifdef MATEKF405TE_SD_VTOL -//using d-shot on motors seems to have problems on s3,maybe dma related,maybe my board problem +//With INAV firmware, DSHOT can not work on S3, S5,S7 because of DMA clash, pls use ONESHOT or MULTISHOT and calibrate ESC PWM range.<-copied from matek website DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2,7,7) UP217 DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(2,2,0) UP217 DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 D(2,6,0) UP256 diff --git a/src/main/target/MATEKF405TE/target.h b/src/main/target/MATEKF405TE/target.h index e51a6d9a20..f8edb3d2ba 100644 --- a/src/main/target/MATEKF405TE/target.h +++ b/src/main/target/MATEKF405TE/target.h @@ -18,6 +18,11 @@ #pragma once #define USE_TARGET_CONFIG +#ifdef MATEKF405TE_SD_VTOL +#define ENABLE_MIXER_PROFILE_MCFW_HOTSWAP +#define MATEKF405TE_SD +#endif + #if defined(MATEKF405TE_SD) # define TARGET_BOARD_IDENTIFIER "MF4T" # define USBD_PRODUCT_STRING "MatekF405TE_SD" @@ -178,8 +183,4 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_DSHOT -#define USE_ESC_SENSOR - -#ifdef MATEKF405TE_SD_VTOL -#define ENABLE_MIXER_PROFILE_MCFW_HOTSWAP -#endif \ No newline at end of file +#define USE_ESC_SENSOR \ No newline at end of file From 6d861fdf3b603b8999541b4320a7aff2ab4344b5 Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 16 Nov 2022 00:59:31 +0900 Subject: [PATCH 010/122] mixer profile dev --- src/main/flight/mixer_profile.c | 45 ++++++++++++++++++++++----------- 1 file changed, 30 insertions(+), 15 deletions(-) diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index cf41074e15..98b07c9522 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -62,9 +62,10 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) static int computeMotorCountByMixerProfileIndex(int index) { int motorCount = 0; + const motorMixer_t* temp_motormixers=mixerMotorMixersByIndex(index)[0]; for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) { // check if done - if (mixerMotorMixersByIndex(index)[i]->throttle == 0.0f) { + if (temp_motormixers[i].throttle == 0.0f) { break; } motorCount++; @@ -77,18 +78,24 @@ static int computeServoCountByMixerProfileIndex(int index) int servoRuleCount = 0; int minServoIndex = 255; int maxServoIndex = 0; + + const servoMixer_t* temp_servomixers=mixerServoMixersByIndex(index)[0]; for (int i = 0; i < MAX_SERVO_RULES; i++) { - // check if done - if (mixerServoMixersByIndex(index)[i]->rate == 0) + // mixerServoMixersByIndex(index)[i]->targetChannel will occour problem after i=1 + // LOG_INFO(PWM, "i:%d, targetChannel:%d, inputSource:%d, rate:%d",i,mixerServoMixersByIndex(index)[i]->targetChannel,mixerServoMixersByIndex(index)[i]->inputSource,mixerServoMixersByIndex(index)[i]->rate); + // LOG_INFO(PWM, "i:%d, targetChannel:%d, inputSource:%d, rate:%d",i,mixerProfiles_SystemArray[index].ServoMixers[i].targetChannel,mixerProfiles_SystemArray[index].ServoMixers[i].inputSource,mixerProfiles_SystemArray[index].ServoMixers[i].rate); + // LOG_INFO(PWM, "i:%d, targetChannel:%d, inputSource:%d, rate:%d",i,temp_servomixers[i].targetChannel,temp_servomixers[i].inputSource,temp_servomixers[i].rate); + if (temp_servomixers[i].rate == 0) break; - if (mixerServoMixersByIndex(index)[i]->targetChannel < minServoIndex) { - minServoIndex = mixerServoMixersByIndex(index)[i]->targetChannel; + if (temp_servomixers[i].targetChannel < minServoIndex) { + minServoIndex = temp_servomixers[i].targetChannel; } - if (mixerServoMixersByIndex(index)[i]->targetChannel > maxServoIndex) { - maxServoIndex = mixerServoMixersByIndex(index)[i]->targetChannel; + if (temp_servomixers[i].targetChannel > maxServoIndex) { + maxServoIndex = temp_servomixers[i].targetChannel; } + // LOG_INFO(PWM, "i:%d, minServoIndex:%d, maxServoIndex:%d",i,minServoIndex,maxServoIndex); servoRuleCount++; } if (servoRuleCount) { @@ -103,8 +110,13 @@ bool OutputProfileHotSwitch(int profile_index) { // does not work with timerHardwareOverride LOG_INFO(PWM, "OutputProfileHotSwitch"); - if (profile_index >= MAX_MIXER_PROFILE_COUNT) {// sanity check - LOG_INFO(PWM, "invalid profile index"); + if (profile_index < 0 || profile_index >= MAX_MIXER_PROFILE_COUNT) + { // sanity check + LOG_INFO(PWM, "invalid mixer profile index"); + return false; + } + if (getConfigMixerProfile() == profile_index) + { return false; } //do not allow switching between multi rotor and non multi rotor @@ -120,33 +132,36 @@ bool OutputProfileHotSwitch(int profile_index) bool is_mcfw_switching = old_platform_type_mc ^ new_platform_type_mc; if (MCFW_hotswap_unavailable && is_mcfw_switching) { - LOG_INFO(PWM, "MCFW_hotswap_unavailable"); + LOG_INFO(PWM, "mixer MCFW_hotswap_unavailable"); return false; } //do not allow switching in navigation mode if (ARMING_FLAG(ARMED) && navigationInAnyMode()){ - LOG_INFO(PWM, "navModesEnabled"); + LOG_INFO(PWM, "mixer switch navModesEnabled"); return false; } //do not allow switching if motor or servos counts has changed if ((getMotorCount() != computeMotorCountByMixerProfileIndex(profile_index)) || (getServoCount() != computeServoCountByMixerProfileIndex(profile_index))) { - LOG_INFO(PWM, "motor/servo count will change"); + LOG_INFO(PWM, "mixer switch motor/servo count will change"); + // LOG_INFO(PWM, "old motor/servo count:%d,%d",getMotorCount(),getServoCount()); + // LOG_INFO(PWM, "new motor/servo count:%d,%d",computeMotorCountByMixerProfileIndex(profile_index),computeServoCountByMixerProfileIndex(profile_index)); return false; } if (!setConfigMixerProfile(profile_index)){ - LOG_INFO(PWM, "failed to set config"); + LOG_INFO(PWM, "mixer switch failed to set config"); return false; } // stopMotors(); - writeAllMotors(feature(FEATURE_REVERSIBLE_MOTORS) ? reversibleMotorsConfig()->neutral : motorConfig()->mincommand);//stop motors with out delay + writeAllMotors(feature(FEATURE_REVERSIBLE_MOTORS) ? reversibleMotorsConfig()->neutral : motorConfig()->mincommand);//stop motors without delay servosInit(); mixerUpdateStateFlags(); mixerInit(); if(old_platform_type!=mixerConfig()->platformType) - { + { + LOG_INFO(PWM, "mixer switch pidInit"); pidInit(); pidInitFilters(); schedulePidGainsUpdate(); From 0e94190eb18294aeff852e192f825ee11a424652 Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 16 Nov 2022 13:10:28 +0900 Subject: [PATCH 011/122] updates in mixer_profile --- src/main/flight/mixer_profile.c | 47 ++++++++++++++++++++++++++------- 1 file changed, 37 insertions(+), 10 deletions(-) diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 98b07c9522..efbd945ad4 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -15,14 +15,16 @@ #include "flight/pid.h" #include "flight/servos.h" +#include "fc/fc_core.h" #include "fc/config.h" #include "fc/runtime_config.h" #include "fc/settings.h" -#include "common/log.h" - +#include "programming/logic_condition.h" #include "navigation/navigation.h" +#include "common/log.h" + PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1); void pgResetFn_mixerProfiles(mixerProfile_t *instance) @@ -106,6 +108,29 @@ static int computeServoCountByMixerProfileIndex(int index) } } +//pid init will be done by the following pid profile change +static bool CheckIfPidInitNeededInSwitch(void) +{ + static bool ret = true; + if (!ret) + { + return false; + } + for (uint8_t i = 0; i < MAX_LOGIC_CONDITIONS; i++) + { + const int activatorValue = logicConditionGetValue(logicConditions(i)->activatorId); + const logicOperand_t *operandA = &(logicConditions(i)->operandA); + if (logicConditions(i)->enabled && activatorValue && logicConditions(i)->operation == LOGIC_CONDITION_SET_PROFILE && + operandA->type == LOGIC_CONDITION_OPERAND_TYPE_FLIGHT && operandA->value == LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE && + logicConditions(i)->flags == 0) + { + ret = false; + return false; + } + } + return true; +} + bool OutputProfileHotSwitch(int profile_index) { // does not work with timerHardwareOverride @@ -119,6 +144,14 @@ bool OutputProfileHotSwitch(int profile_index) { return false; } + if (areSensorsCalibrating()) {//it seems like switching before sensors calibration complete will cause pid stops to respond, especially in D + return false; + } + //do not allow switching in navigation mode + if (ARMING_FLAG(ARMED) && navigationInAnyMode()){ + LOG_INFO(PWM, "mixer switch failed, navModesEnabled"); + return false; + } //do not allow switching between multi rotor and non multi rotor #ifdef ENABLE_MIXER_PROFILE_MCFW_HOTSWAP bool MCFW_hotswap_unavailable = false; @@ -135,16 +168,10 @@ bool OutputProfileHotSwitch(int profile_index) LOG_INFO(PWM, "mixer MCFW_hotswap_unavailable"); return false; } - - //do not allow switching in navigation mode - if (ARMING_FLAG(ARMED) && navigationInAnyMode()){ - LOG_INFO(PWM, "mixer switch navModesEnabled"); - return false; - } //do not allow switching if motor or servos counts has changed if ((getMotorCount() != computeMotorCountByMixerProfileIndex(profile_index)) || (getServoCount() != computeServoCountByMixerProfileIndex(profile_index))) { - LOG_INFO(PWM, "mixer switch motor/servo count will change"); + LOG_INFO(PWM, "mixer switch failed, motor/servo count will change"); // LOG_INFO(PWM, "old motor/servo count:%d,%d",getMotorCount(),getServoCount()); // LOG_INFO(PWM, "new motor/servo count:%d,%d",computeMotorCountByMixerProfileIndex(profile_index),computeServoCountByMixerProfileIndex(profile_index)); return false; @@ -159,7 +186,7 @@ bool OutputProfileHotSwitch(int profile_index) mixerUpdateStateFlags(); mixerInit(); - if(old_platform_type!=mixerConfig()->platformType) + if(old_platform_type!=mixerConfig()->platformType && CheckIfPidInitNeededInSwitch()) { LOG_INFO(PWM, "mixer switch pidInit"); pidInit(); From e0db9ae4c920530d405822f186f3b90f6aaddd2b Mon Sep 17 00:00:00 2001 From: shota Date: Thu, 17 Nov 2022 00:20:15 +0900 Subject: [PATCH 012/122] navigation init on mixer profile --- src/main/flight/mixer_profile.c | 18 +++++++++++------- src/main/navigation/navigation.c | 24 ++++++++++++++---------- src/main/navigation/navigation.h | 1 + src/main/programming/logic_condition.c | 1 + 4 files changed, 27 insertions(+), 17 deletions(-) diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index efbd945ad4..8ca8cca882 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -186,13 +186,17 @@ bool OutputProfileHotSwitch(int profile_index) mixerUpdateStateFlags(); mixerInit(); - if(old_platform_type!=mixerConfig()->platformType && CheckIfPidInitNeededInSwitch()) - { - LOG_INFO(PWM, "mixer switch pidInit"); - pidInit(); - pidInitFilters(); - schedulePidGainsUpdate(); - // navigationInit(); //may need to initilize FW_HEADING_USE_YAW on rover or boat + if(old_platform_type!=mixerConfig()->platformType) + { + navigationYawControlInit(); + if (CheckIfPidInitNeededInSwitch()) + { + LOG_INFO(PWM, "mixer switch pidInit"); + pidInit(); + pidInitFilters(); + schedulePidGainsUpdate(); + navigationUsePIDs(); + } } return true; } diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 08c6676686..c802cbe180 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -4108,6 +4108,18 @@ void navigationUsePIDs(void) ); } +void navigationYawControlInit(void){ + if ( + mixerConfig()->platformType == PLATFORM_BOAT || + mixerConfig()->platformType == PLATFORM_ROVER || + navConfig()->fw.useFwNavYawControl + ) { + ENABLE_STATE(FW_HEADING_USE_YAW); + } else { + DISABLE_STATE(FW_HEADING_USE_YAW); + } +} + void navigationInit(void) { /* Initial state */ @@ -4141,16 +4153,8 @@ void navigationInit(void) /* Use system config */ navigationUsePIDs(); - - if ( - mixerConfig()->platformType == PLATFORM_BOAT || - mixerConfig()->platformType == PLATFORM_ROVER || - navConfig()->fw.useFwNavYawControl - ) { - ENABLE_STATE(FW_HEADING_USE_YAW); - } else { - DISABLE_STATE(FW_HEADING_USE_YAW); - } + navigationYawControlInit(); + #if defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) /* configure WP missions at boot */ #ifdef USE_MULTI_MISSION diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 13f9f58bc9..b2872822e2 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -472,6 +472,7 @@ typedef struct { } navSystemStatus_t; void navigationUsePIDs(void); +void navigationYawControlInit(void); void navigationInit(void); /* Position estimator update functions */ diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 054031e203..b0a7b83ecb 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -354,6 +354,7 @@ static int logicConditionCompute( pidInit(); pidInitFilters(); schedulePidGainsUpdate(); + navigationUsePIDs(); profileChanged = true; } return profileChanged; From 8b72ffa3e2598072da4c7b503f5ceb8d63a2df27 Mon Sep 17 00:00:00 2001 From: shota Date: Tue, 22 Nov 2022 02:33:05 +0900 Subject: [PATCH 013/122] move motor stop feature to mixer config --- src/main/fc/config.h | 2 +- src/main/fc/fc_core.c | 4 ++-- src/main/fc/rc_controls.c | 3 ++- src/main/fc/settings.yaml | 5 +++++ src/main/flight/mixer.c | 8 ++++++-- src/main/flight/mixer.h | 2 ++ src/main/sensors/battery.c | 2 +- src/main/target/ALIENFLIGHTF4/target.h | 2 +- src/main/target/ALIENFLIGHTNGF7/target.h | 2 +- src/main/telemetry/frsky_d.c | 2 +- 10 files changed, 22 insertions(+), 10 deletions(-) diff --git a/src/main/fc/config.h b/src/main/fc/config.h index ab5a6fff72..5b8fe8fdfd 100644 --- a/src/main/fc/config.h +++ b/src/main/fc/config.h @@ -36,7 +36,7 @@ typedef enum { FEATURE_VBAT = 1 << 1, FEATURE_TX_PROF_SEL = 1 << 2, // Profile selection by TX stick command FEATURE_BAT_PROFILE_AUTOSWITCH = 1 << 3, - FEATURE_MOTOR_STOP = 1 << 4, + FEATURE_UNUSED_12 = 1 << 4, FEATURE_UNUSED_1 = 1 << 5, // was FEATURE_SERVO_TILT was FEATURE_DYNAMIC_FILTERS FEATURE_SOFTSERIAL = 1 << 6, FEATURE_GPS = 1 << 7, diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 4253c995a3..a63d5aeac1 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -634,7 +634,7 @@ void processRx(timeUs_t currentTimeUs) const throttleStatus_e throttleStatus = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC); // When armed and motors aren't spinning, do beeps periodically - if (ARMING_FLAG(ARMED) && feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING_LEGACY)) { + if (ARMING_FLAG(ARMED) && ifMotorstopFeatureEnabled() && !STATE(FIXED_WING_LEGACY)) { static bool armedBeeperOn = false; if (throttleStatus == THROTTLE_LOW) { @@ -762,7 +762,7 @@ void processRx(timeUs_t currentTimeUs) else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER) { if (throttleStatus == THROTTLE_LOW) { if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { - if ((rollPitchStatus == CENTERED) || (feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING_LEGACY))) { + if ((rollPitchStatus == CENTERED) || (ifMotorstopFeatureEnabled() && !STATE(FIXED_WING_LEGACY))) { ENABLE_STATE(ANTI_WINDUP); } else { diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index 8ccc9c63de..97a85ccc07 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -49,6 +49,7 @@ #include "flight/pid.h" #include "flight/failsafe.h" +#include "flight/mixer.h" #include "io/gps.h" #include "io/beeper.h" @@ -209,7 +210,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus) bool armingSwitchIsActive = IS_RC_MODE_ACTIVE(BOXARM); emergencyArmingUpdate(armingSwitchIsActive); - if (STATE(AIRPLANE) && feature(FEATURE_MOTOR_STOP) && armingConfig()->fixed_wing_auto_arm) { + if (STATE(AIRPLANE) && ifMotorstopFeatureEnabled() && armingConfig()->fixed_wing_auto_arm) { // Auto arm on throttle when using fixedwing and motorstop if (throttleStatus != THROTTLE_LOW) { tryArm(); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 6c94747e04..0dfc1fdde1 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1178,6 +1178,11 @@ groups: default_value: "AUTO" field: mixer_config.outputMode table: output_mode + - name: motorstop_feature + description: "If enabled, motor will stop when throttle is low" + default_value: OFF + field: mixer_config.motorstopFeature + type: bool - name: PG_REVERSIBLE_MOTORS_CONFIG type: reversibleMotorsConfig_t diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 21e2a75545..82786044d0 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -117,6 +117,10 @@ static void computeMotorCount(void) } } +bool ifMotorstopFeatureEnabled(void){ + return mixerConfig()->motorstopFeature; +} + uint8_t getMotorCount(void) { return motorCount; } @@ -212,7 +216,7 @@ void mixerResetDisarmedMotors(void) reversibleMotorsThrottleState = MOTOR_DIRECTION_FORWARD; - if (feature(FEATURE_MOTOR_STOP)) { + if (ifMotorstopFeatureEnabled()) { motorValueWhenStopped = motorZeroCommand; } else { motorValueWhenStopped = getThrottleIdleValue(); @@ -444,7 +448,7 @@ static int getReversibleMotorsThrottleDeadband(void) directionValue = reversibleMotorsConfig()->deadband_high; } - return feature(FEATURE_MOTOR_STOP) ? reversibleMotorsConfig()->neutral : directionValue; + return ifMotorstopFeatureEnabled() ? reversibleMotorsConfig()->neutral : directionValue; } void FAST_CODE mixTable() diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 5813e6a73e..eacbc69311 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -68,6 +68,7 @@ typedef struct mixerConfig_s { bool hasFlaps; int16_t appliedMixerPreset; uint8_t outputMode; + bool motorstopFeature; } mixerConfig_t; typedef struct reversibleMotorsConfig_s { @@ -106,6 +107,7 @@ extern int16_t motor[MAX_SUPPORTED_MOTORS]; extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS]; extern int mixerThrottleCommand; +bool ifMotorstopFeatureEnabled(void); int getThrottleIdleValue(void); int16_t getThrottlePercent(void); uint8_t getMotorCount(void); diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index adeb9ad3f0..b3222518cb 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -558,7 +558,7 @@ void currentMeterUpdate(timeUs_t timeDelta) if (allNav || autoNav) { // account for motors running in Nav modes with throttle low + motor stop throttleOffset = (int32_t)rcCommand[THROTTLE] - 1000; } else { - throttleOffset = ((throttleStatus == THROTTLE_LOW) && feature(FEATURE_MOTOR_STOP)) ? 0 : (int32_t)rcCommand[THROTTLE] - 1000; + throttleOffset = ((throttleStatus == THROTTLE_LOW) && ifMotorstopFeatureEnabled()) ? 0 : (int32_t)rcCommand[THROTTLE] - 1000; } int32_t throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50); amperage += throttleFactor * batteryMetersConfig()->current.scale / 1000; diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index 09a2757642..5527b45a1d 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -152,7 +152,7 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_MOTOR_STOP | FEATURE_BLACKBOX) +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) #define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define SERIALRX_UART SERIAL_PORT_USART2 #define RX_CHANNELS_TAER diff --git a/src/main/target/ALIENFLIGHTNGF7/target.h b/src/main/target/ALIENFLIGHTNGF7/target.h index 59ad543c3b..5971f3d848 100644 --- a/src/main/target/ALIENFLIGHTNGF7/target.h +++ b/src/main/target/ALIENFLIGHTNGF7/target.h @@ -165,7 +165,7 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_MOTOR_STOP | FEATURE_BLACKBOX) +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) #define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define SERIALRX_UART SERIAL_PORT_USART2 #define RX_CHANNELS_TAER diff --git a/src/main/telemetry/frsky_d.c b/src/main/telemetry/frsky_d.c index 0bc65d3457..83a87375f0 100644 --- a/src/main/telemetry/frsky_d.c +++ b/src/main/telemetry/frsky_d.c @@ -197,7 +197,7 @@ static void sendThrottleOrBatterySizeAsRpm(void) if (ARMING_FLAG(ARMED)) { const throttleStatus_e throttleStatus = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC); uint16_t throttleForRPM = rcCommand[THROTTLE] / BLADE_NUMBER_DIVIDER; - if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP)) + if (throttleStatus == THROTTLE_LOW && ifMotorstopFeatureEnabled()) throttleForRPM = 0; serialize16(throttleForRPM); } else { From 91ee7cc45bda2a5138e2960fb45522fac1781a80 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 15 Apr 2023 22:09:15 +0100 Subject: [PATCH 014/122] 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 203bb2a47150bf7525c341f7be7fb6151af75cb4 Mon Sep 17 00:00:00 2001 From: shota Date: Fri, 30 Jun 2023 04:01:01 +0900 Subject: [PATCH 015/122] mixer and pid profile linking --- src/main/fc/config.c | 5 ++ src/main/fc/config.h | 2 +- src/main/fc/settings.yaml | 7 ++- src/main/flight/mixer.c | 9 ++- src/main/flight/mixer.h | 10 +--- src/main/flight/mixer_profile.c | 78 +++++++++++++------------- src/main/flight/mixer_profile.h | 9 +++ src/main/flight/servos.h | 2 +- src/main/navigation/navigation.c | 14 ++++- src/main/navigation/navigation.h | 2 +- src/main/programming/logic_condition.c | 12 +--- src/main/programming/logic_condition.h | 1 + src/main/target/MATEKF405TE/target.h | 3 +- src/main/target/common.h | 2 +- 14 files changed, 87 insertions(+), 69 deletions(-) diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 689ecc5bd3..8822e20254 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -332,6 +332,9 @@ void readEEPROM(void) setConfigProfile(getConfigProfile()); setConfigBatteryProfile(getConfigBatteryProfile()); setConfigMixerProfile(getConfigMixerProfile()); + if(mixerConfig()->PIDProfileLinking){ + setConfigProfile(getConfigMixerProfile()); + } validateAndFixConfig(); activateConfig(); @@ -494,8 +497,10 @@ void setConfigMixerProfileAndWriteEEPROM(uint8_t profileIndex) { if (setConfigMixerProfile(profileIndex)) { // profile has changed, so ensure current values saved before new profile is loaded + suspendRxSignal(); writeEEPROM(); readEEPROM(); + resumeRxSignal(); } beeperConfirmationBeeps(profileIndex + 1); } diff --git a/src/main/fc/config.h b/src/main/fc/config.h index 003cb9fc98..bafa5c0cbe 100644 --- a/src/main/fc/config.h +++ b/src/main/fc/config.h @@ -36,7 +36,7 @@ typedef enum { FEATURE_VBAT = 1 << 1, FEATURE_TX_PROF_SEL = 1 << 2, // Profile selection by TX stick command FEATURE_BAT_PROFILE_AUTOSWITCH = 1 << 3, - FEATURE_UNUSED_12 = 1 << 4, + FEATURE_UNUSED_12 = 1 << 4, //was FEATURE_MOTOR_STOP FEATURE_UNUSED_1 = 1 << 5, // was FEATURE_SERVO_TILT was FEATURE_DYNAMIC_FILTERS FEATURE_SOFTSERIAL = 1 << 6, FEATURE_GPS = 1 << 7, diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index fca009364c..9becd26770 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1134,7 +1134,7 @@ groups: - name: PG_MIXER_PROFILE type: mixerProfile_t - headers: ["flight/mixer.h","flight/mixer_profile.h"] + headers: ["flight/mixer_profile.h"] value_type: MIXER_CONFIG_VALUE members: - name: motor_direction_inverted @@ -1169,6 +1169,11 @@ groups: default_value: OFF field: mixer_config.motorstopFeature type: bool + - name: mixer_pid_profile_linking + description: "If enabled, pid profile index will follow mixer profile index" + default_value: OFF + field: mixer_config.PIDProfileLinking + type: bool - name: PG_REVERSIBLE_MOTORS_CONFIG type: reversibleMotorsConfig_t diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index b8fafec71a..a0f62c6dc3 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -426,10 +426,15 @@ void writeAllMotors(int16_t mc) writeMotors(); } -void stopMotors(void) + +void stopMotorsNoDelay(void) { writeAllMotors(feature(FEATURE_REVERSIBLE_MOTORS) ? reversibleMotorsConfig()->neutral : motorConfig()->mincommand); - +} +void stopMotors(void) +{ + stopMotorsNoDelay(); + delay(50); // give the timers and ESCs a chance to react. } diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index bbf06696d9..871332447e 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -62,15 +62,6 @@ typedef struct motorMixer_s { float yaw; } motorMixer_t; -typedef struct mixerConfig_s { - int8_t motorDirectionInverted; - uint8_t platformType; - bool hasFlaps; - int16_t appliedMixerPreset; - uint8_t outputMode; - bool motorstopFeature; -} mixerConfig_t; - typedef struct reversibleMotorsConfig_s { uint16_t deadband_low; // min 3d value uint16_t deadband_high; // max 3d value @@ -125,6 +116,7 @@ void processServoAutotrim(const float dT); void processServoAutotrimMode(void); void processContinuousServoAutotrim(const float dT); void stopMotors(void); +void stopMotorsNoDelay(void); void stopPwmAllMotors(void); void loadPrimaryMotorMixer(void); diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 8ca8cca882..c8e2c596c8 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -37,6 +37,8 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only .outputMode = SETTING_OUTPUT_MODE_DEFAULT, + .motorstopFeature = SETTING_MOTORSTOP_FEATURE_DEFAULT, + .PIDProfileLinking = SETTING_OUTPUT_MODE_DEFAULT } ); for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) { @@ -108,29 +110,17 @@ static int computeServoCountByMixerProfileIndex(int index) } } -//pid init will be done by the following pid profile change -static bool CheckIfPidInitNeededInSwitch(void) +void SwitchPidProfileByMixerProfile() { - static bool ret = true; - if (!ret) - { - return false; - } - for (uint8_t i = 0; i < MAX_LOGIC_CONDITIONS; i++) - { - const int activatorValue = logicConditionGetValue(logicConditions(i)->activatorId); - const logicOperand_t *operandA = &(logicConditions(i)->operandA); - if (logicConditions(i)->enabled && activatorValue && logicConditions(i)->operation == LOGIC_CONDITION_SET_PROFILE && - operandA->type == LOGIC_CONDITION_OPERAND_TYPE_FLIGHT && operandA->value == LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE && - logicConditions(i)->flags == 0) - { - ret = false; - return false; - } - } - return true; + LOG_INFO(PWM, "mixer switch pidInit"); + setConfigProfile(getConfigMixerProfile()); + pidInit(); + pidInitFilters(); + schedulePidGainsUpdate(); + navigationUsePIDs(); //set navigation pid gains } +//switch mixerprofile without reboot bool OutputProfileHotSwitch(int profile_index) { // does not work with timerHardwareOverride @@ -144,7 +134,7 @@ bool OutputProfileHotSwitch(int profile_index) { return false; } - if (areSensorsCalibrating()) {//it seems like switching before sensors calibration complete will cause pid stops to respond, especially in D + if (areSensorsCalibrating()) {//it seems like switching before sensors calibration complete will cause pid stops to respond, especially in D,TODO return false; } //do not allow switching in navigation mode @@ -154,16 +144,16 @@ bool OutputProfileHotSwitch(int profile_index) } //do not allow switching between multi rotor and non multi rotor #ifdef ENABLE_MIXER_PROFILE_MCFW_HOTSWAP - bool MCFW_hotswap_unavailable = false; + bool MCFW_hotswap_available = true; #else - bool MCFW_hotswap_unavailable = true; + bool MCFW_hotswap_available = false; #endif uint8_t old_platform_type = mixerConfig()->platformType; uint8_t new_platform_type = mixerConfigByIndex(profile_index)->platformType; bool old_platform_type_mc = old_platform_type == PLATFORM_MULTIROTOR || old_platform_type == PLATFORM_TRICOPTER; bool new_platform_type_mc = new_platform_type == PLATFORM_MULTIROTOR || new_platform_type == PLATFORM_TRICOPTER; bool is_mcfw_switching = old_platform_type_mc ^ new_platform_type_mc; - if (MCFW_hotswap_unavailable && is_mcfw_switching) + if ((!MCFW_hotswap_available) && is_mcfw_switching) { LOG_INFO(PWM, "mixer MCFW_hotswap_unavailable"); return false; @@ -171,7 +161,7 @@ bool OutputProfileHotSwitch(int profile_index) //do not allow switching if motor or servos counts has changed if ((getMotorCount() != computeMotorCountByMixerProfileIndex(profile_index)) || (getServoCount() != computeServoCountByMixerProfileIndex(profile_index))) { - LOG_INFO(PWM, "mixer switch failed, motor/servo count will change"); + LOG_INFO(PWM, "mixer switch failed, because of motor/servo count will change"); // LOG_INFO(PWM, "old motor/servo count:%d,%d",getMotorCount(),getServoCount()); // LOG_INFO(PWM, "new motor/servo count:%d,%d",computeMotorCountByMixerProfileIndex(profile_index),computeServoCountByMixerProfileIndex(profile_index)); return false; @@ -180,23 +170,14 @@ bool OutputProfileHotSwitch(int profile_index) LOG_INFO(PWM, "mixer switch failed to set config"); return false; } - // stopMotors(); - writeAllMotors(feature(FEATURE_REVERSIBLE_MOTORS) ? reversibleMotorsConfig()->neutral : motorConfig()->mincommand);//stop motors without delay + stopMotorsNoDelay(); servosInit(); mixerUpdateStateFlags(); mixerInit(); - if(old_platform_type!=mixerConfig()->platformType) + if(mixerConfig()->PIDProfileLinking) { - navigationYawControlInit(); - if (CheckIfPidInitNeededInSwitch()) - { - LOG_INFO(PWM, "mixer switch pidInit"); - pidInit(); - pidInitFilters(); - schedulePidGainsUpdate(); - navigationUsePIDs(); - } + SwitchPidProfileByMixerProfile(); } return true; } @@ -244,4 +225,25 @@ bool OutputProfileHotSwitch(int profile_index) // } // } - +//check if a pid profile switch followed on a mixer profile switch +// static bool CheckIfPidInitNeededInSwitch(void) +// { +// static bool ret = true; +// if (!ret) +// { +// return false; +// } +// for (uint8_t i = 0; i < MAX_LOGIC_CONDITIONS; i++) +// { +// const int activatorValue = logicConditionGetValue(logicConditions(i)->activatorId); +// const logicOperand_t *operandA = &(logicConditions(i)->operandA); +// if (logicConditions(i)->enabled && activatorValue && logicConditions(i)->operation == LOGIC_CONDITION_SET_PROFILE && +// operandA->type == LOGIC_CONDITION_OPERAND_TYPE_FLIGHT && operandA->value == LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE && +// logicConditions(i)->flags == 0) +// { +// ret = false; +// return false; +// } +// } +// return true; +// } \ No newline at end of file diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index 4eee2a0415..7da2c073d9 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -9,6 +9,15 @@ #define MAX_MIXER_PROFILE_COUNT 2 #endif +typedef struct mixerConfig_s { + int8_t motorDirectionInverted; + uint8_t platformType; + bool hasFlaps; + int16_t appliedMixerPreset; + uint8_t outputMode; + bool motorstopFeature; + bool PIDProfileLinking; +} mixerConfig_t; typedef struct mixerProfile_s { mixerConfig_t mixer_config; motorMixer_t MotorMixers[MAX_SUPPORTED_MOTORS]; diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index cf303db6a4..c8dbd06d1e 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -62,7 +62,7 @@ typedef enum { INPUT_GVAR_5 = 35, INPUT_GVAR_6 = 36, INPUT_GVAR_7 = 37, - + INPUT_MC2FW_TRANSITION = 38, INPUT_SOURCE_COUNT } inputSource_e; diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index c340076adc..ca548ba4e8 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -4177,7 +4177,7 @@ void navigationUsePIDs(void) ); } -void navigationYawControlInit(void){ +void navigationInitYawControl(void){ if ( mixerConfig()->platformType == PLATFORM_BOAT || mixerConfig()->platformType == PLATFORM_ROVER || @@ -4222,8 +4222,16 @@ void navigationInit(void) /* Use system config */ navigationUsePIDs(); - navigationYawControlInit(); - + + if ( + mixerConfig()->platformType == PLATFORM_BOAT || + mixerConfig()->platformType == PLATFORM_ROVER || + navConfig()->fw.useFwNavYawControl + ) { + ENABLE_STATE(FW_HEADING_USE_YAW); + } else { + DISABLE_STATE(FW_HEADING_USE_YAW); + } #if defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) /* configure WP missions at boot */ #ifdef USE_MULTI_MISSION diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 4e419dd14c..57d7f49c8e 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -479,7 +479,7 @@ typedef struct { } navSystemStatus_t; void navigationUsePIDs(void); -void navigationYawControlInit(void); +void navigationInitYawControl(void); void navigationInit(void); /* Position estimator update functions */ diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index f639dc49c1..cdb3bc7d7e 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -425,7 +425,7 @@ static int logicConditionCompute( pidInit(); pidInitFilters(); schedulePidGainsUpdate(); - navigationUsePIDs(); + navigationUsePIDs(); //set navigation pid gains profileChanged = true; } return profileChanged; @@ -434,16 +434,6 @@ static int logicConditionCompute( } break; - case LOGIC_CONDITION_SET_MIXER_PROFILE: - operandA--; - if ( getConfigMixerProfile() != operandA && (operandA >= 0 && operandA < MAX_MIXER_PROFILE_COUNT)) { - bool mixerprofileChanged = OutputProfileHotSwitch(operandA); - return mixerprofileChanged; - } else { - return false; - } - break; - case LOGIC_CONDITION_LOITER_OVERRIDE: logicConditionValuesByType[LOGIC_CONDITION_LOITER_OVERRIDE] = constrain(operandA, 0, 100000); LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS); diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 779dbb1b98..446532fb29 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -135,6 +135,7 @@ 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 // TBD } logicFlightOperands_e; typedef enum { diff --git a/src/main/target/MATEKF405TE/target.h b/src/main/target/MATEKF405TE/target.h index f8edb3d2ba..73b38e0721 100644 --- a/src/main/target/MATEKF405TE/target.h +++ b/src/main/target/MATEKF405TE/target.h @@ -183,4 +183,5 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_DSHOT -#define USE_ESC_SENSOR \ No newline at end of file +#define USE_ESC_SENSOR + diff --git a/src/main/target/common.h b/src/main/target/common.h index 4a60523548..70916fdbd3 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -187,5 +187,5 @@ #define USE_SERIALRX_SUMD #define USE_TELEMETRY_HOTT #define USE_HOTT_TEXTMODE - +#define MAX_MIXER_PROFILE_COUNT 1 #endif From 2fb9601dd6335e76a6fa0e564c699668f0230dce Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 1 Jul 2023 03:29:10 +0900 Subject: [PATCH 016/122] mixprofile transition support --- src/main/drivers/pwm_mapping.c | 6 +-- src/main/fc/config.c | 3 -- src/main/fc/fc_core.c | 2 +- src/main/fc/fc_init.c | 4 +- src/main/fc/fc_msp_box.c | 2 + src/main/fc/rc_modes.h | 2 + src/main/flight/mixer.c | 35 +++++++++------ src/main/flight/mixer_profile.c | 61 ++++++++++++++++---------- src/main/flight/mixer_profile.h | 3 ++ src/main/flight/pid.c | 6 +-- src/main/flight/servos.c | 6 ++- src/main/flight/servos.h | 2 +- src/main/navigation/navigation.c | 10 ++--- src/main/programming/logic_condition.c | 2 +- 14 files changed, 86 insertions(+), 58 deletions(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 9bf037242f..653404a4e2 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -201,7 +201,7 @@ static bool checkPwmTimerConflicts(const timerHardware_t *timHw) } static void timerHardwareOverride(timerHardware_t * timer) { - if (mixerConfig()->outputMode == OUTPUT_MODE_SERVOS) { + if (currentMixerConfig.outputMode == OUTPUT_MODE_SERVOS) { //Motors are rewritten as servos if (timer->usageFlags & TIM_USE_MC_MOTOR) { @@ -213,7 +213,7 @@ static void timerHardwareOverride(timerHardware_t * timer) { timer->usageFlags = timer->usageFlags | TIM_USE_FW_SERVO; } - } else if (mixerConfig()->outputMode == OUTPUT_MODE_MOTORS) { + } else if (currentMixerConfig.outputMode == OUTPUT_MODE_MOTORS) { // Servos are rewritten as motors if (timer->usageFlags & TIM_USE_MC_SERVO) { @@ -250,7 +250,7 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU } // Determine if timer belongs to motor/servo - if (mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER) { + if (currentMixerConfig.platformType == PLATFORM_MULTIROTOR || currentMixerConfig.platformType == PLATFORM_TRICOPTER) { // Multicopter // Make sure first motorCount outputs get assigned to motor diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 8822e20254..27ed9eddd0 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -332,9 +332,6 @@ void readEEPROM(void) setConfigProfile(getConfigProfile()); setConfigBatteryProfile(getConfigBatteryProfile()); setConfigMixerProfile(getConfigMixerProfile()); - if(mixerConfig()->PIDProfileLinking){ - setConfigProfile(getConfigMixerProfile()); - } validateAndFixConfig(); activateConfig(); diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 2c0f8ce463..b5bb2fc322 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -784,7 +784,7 @@ void processRx(timeUs_t currentTimeUs) } } //--------------------------------------------------------- - if (mixerConfig()->platformType == PLATFORM_AIRPLANE) { + if (currentMixerConfig.platformType == PLATFORM_AIRPLANE) { DISABLE_FLIGHT_MODE(HEADFREE_MODE); } diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 7c36b49f0b..a5b270a518 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -303,9 +303,7 @@ void init(void) // Initialize servo and motor mixers // This needs to be called early to set up platform type correctly and count required motors & servos - servosInit(); - mixerUpdateStateFlags(); - mixerInit(); + mixerConfigInit(); // Some sanity checking if (motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) { diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index 1fa7a71239..8caa76b923 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -99,6 +99,8 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = { { .boxId = BOXSOARING, .boxName = "SOARING", .permanentId = 56 }, { .boxId = BOXCHANGEMISSION, .boxName = "MISSION CHANGE", .permanentId = 59 }, { .boxId = BOXBEEPERMUTE, .boxName = "BEEPER MUTE", .permanentId = 60 }, + { .boxId = BOXMIXERPROFILE, .boxName = "MIXER RPROFILE 2", .permanentId = 61 }, + { .boxId = BOXMIXERTRANSITION, .boxName = "MIXER TRANSITION", .permanentId = 62 }, { .boxId = CHECKBOX_ITEM_COUNT, .boxName = NULL, .permanentId = 0xFF } }; diff --git a/src/main/fc/rc_modes.h b/src/main/fc/rc_modes.h index 93b17e6e2f..43de336b98 100644 --- a/src/main/fc/rc_modes.h +++ b/src/main/fc/rc_modes.h @@ -78,6 +78,8 @@ typedef enum { BOXUSER4 = 49, BOXCHANGEMISSION = 50, BOXBEEPERMUTE = 51, + BOXMIXERPROFILE = 52, + BOXMIXERTRANSITION = 53, CHECKBOX_ITEM_COUNT } boxId_e; diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index a0f62c6dc3..6a97ab4e17 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -116,7 +116,7 @@ static void computeMotorCount(void) } bool ifMotorstopFeatureEnabled(void){ - return mixerConfig()->motorstopFeature; + return currentMixerConfig.motorstopFeature; } uint8_t getMotorCount(void) { @@ -142,31 +142,31 @@ void mixerUpdateStateFlags(void) DISABLE_STATE(AIRPLANE); DISABLE_STATE(MOVE_FORWARD_ONLY); - if (mixerConfig()->platformType == PLATFORM_AIRPLANE) { + if (currentMixerConfig.platformType == PLATFORM_AIRPLANE) { ENABLE_STATE(FIXED_WING_LEGACY); ENABLE_STATE(AIRPLANE); ENABLE_STATE(ALTITUDE_CONTROL); ENABLE_STATE(MOVE_FORWARD_ONLY); - } if (mixerConfig()->platformType == PLATFORM_ROVER) { + } if (currentMixerConfig.platformType == PLATFORM_ROVER) { ENABLE_STATE(ROVER); ENABLE_STATE(FIXED_WING_LEGACY); ENABLE_STATE(MOVE_FORWARD_ONLY); - } if (mixerConfig()->platformType == PLATFORM_BOAT) { + } if (currentMixerConfig.platformType == PLATFORM_BOAT) { ENABLE_STATE(BOAT); ENABLE_STATE(FIXED_WING_LEGACY); ENABLE_STATE(MOVE_FORWARD_ONLY); - } else if (mixerConfig()->platformType == PLATFORM_MULTIROTOR) { + } else if (currentMixerConfig.platformType == PLATFORM_MULTIROTOR) { ENABLE_STATE(MULTIROTOR); ENABLE_STATE(ALTITUDE_CONTROL); - } else if (mixerConfig()->platformType == PLATFORM_TRICOPTER) { + } else if (currentMixerConfig.platformType == PLATFORM_TRICOPTER) { ENABLE_STATE(MULTIROTOR); ENABLE_STATE(ALTITUDE_CONTROL); - } else if (mixerConfig()->platformType == PLATFORM_HELICOPTER) { + } else if (currentMixerConfig.platformType == PLATFORM_HELICOPTER) { ENABLE_STATE(MULTIROTOR); ENABLE_STATE(ALTITUDE_CONTROL); } - if (mixerConfig()->hasFlaps) { + if (currentMixerConfig.hasFlaps) { ENABLE_STATE(FLAPERON_AVAILABLE); } else { DISABLE_STATE(FLAPERON_AVAILABLE); @@ -192,7 +192,7 @@ void mixerInit(void) mixerResetDisarmedMotors(); - if (mixerConfig()->motorDirectionInverted) { + if (currentMixerConfig.motorDirectionInverted) { motorYawMultiplier = -1; } else { motorYawMultiplier = 1; @@ -272,7 +272,7 @@ static void applyTurtleModeToMotors(void) { float signPitch = rcCommand[PITCH] < 0 ? 1 : -1; float signRoll = rcCommand[ROLL] < 0 ? 1 : -1; - float signYaw = (float)((rcCommand[YAW] < 0 ? 1 : -1) * (mixerConfig()->motorDirectionInverted ? 1 : -1)); + float signYaw = (float)((rcCommand[YAW] < 0 ? 1 : -1) * (currentMixerConfig.motorDirectionInverted ? 1 : -1)); float stickDeflectionLength = calc_length_pythagorean_2D(stickDeflectionPitchAbs, stickDeflectionRollAbs); float stickDeflectionExpoLength = calc_length_pythagorean_2D(stickDeflectionPitchExpo, stickDeflectionRollExpo); @@ -434,7 +434,7 @@ void stopMotorsNoDelay(void) void stopMotors(void) { stopMotorsNoDelay(); - + delay(50); // give the timers and ESCs a chance to react. } @@ -592,14 +592,21 @@ void FAST_CODE mixTable(void) } else { motor[i] = constrain(motor[i], throttleRangeMin, throttleRangeMax); } + + //stop motors + if (currentMixer[i].throttle <= 0.0f) { + motor[i] = motorZeroCommand; + } + //spin stopped motors only in mixer transition mode + if (IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION) && currentMixer[i].throttle <= -1.05f && currentMixer[i].throttle >= -2.0f && (!feature(FEATURE_REVERSIBLE_MOTORS))) { + motor[i] = -currentMixer[i].throttle * 1000; + motor[i] = constrain(motor[i], throttleRangeMin, throttleRangeMax); + } // Motor stop handling if (currentMotorStatus != MOTOR_RUNNING) { motor[i] = motorValueWhenStopped; } - if (currentMixer[i].throttle <= -1.0f) { - motor[i] = motorZeroCommand; - } #ifdef USE_DEV_TOOLS if (systemConfig()->groundTestMode) { motor[i] = motorZeroCommand; diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index c8e2c596c8..f5f6179d85 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -19,12 +19,16 @@ #include "fc/config.h" #include "fc/runtime_config.h" #include "fc/settings.h" +#include "fc/rc_modes.h" #include "programming/logic_condition.h" #include "navigation/navigation.h" #include "common/log.h" +mixerConfig_t currentMixerConfig; +int currentMixerProfileIndex; + PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1); void pgResetFn_mixerProfiles(mixerProfile_t *instance) @@ -63,6 +67,26 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) } } +void loadMixerConfig(void) { + currentMixerProfileIndex=getConfigMixerProfile(); + currentMixerConfig=*mixerConfig(); +} + +void mixerConfigInit(void){ + loadMixerConfig(); + servosInit(); + mixerUpdateStateFlags(); + mixerInit(); + if(currentMixerConfig.PIDProfileLinking){ + LOG_INFO(PWM, "mixer switch pidInit"); + setConfigProfile(getConfigMixerProfile()); + pidInit(); + pidInitFilters(); + schedulePidGainsUpdate(); + navigationUsePIDs(); //set navigation pid gains + } +} + static int computeMotorCountByMixerProfileIndex(int index) { int motorCount = 0; @@ -110,27 +134,22 @@ static int computeServoCountByMixerProfileIndex(int index) } } -void SwitchPidProfileByMixerProfile() -{ - LOG_INFO(PWM, "mixer switch pidInit"); - setConfigProfile(getConfigMixerProfile()); - pidInit(); - pidInitFilters(); - schedulePidGainsUpdate(); - navigationUsePIDs(); //set navigation pid gains -} - //switch mixerprofile without reboot bool OutputProfileHotSwitch(int profile_index) { - // does not work with timerHardwareOverride + static bool allow_hot_switch = true; + // does not work with timerHardwareOverride,need to set mixerConfig()->outputMode == OUTPUT_MODE_AUTO LOG_INFO(PWM, "OutputProfileHotSwitch"); + if (!allow_hot_switch) + { + return false; + } if (profile_index < 0 || profile_index >= MAX_MIXER_PROFILE_COUNT) { // sanity check LOG_INFO(PWM, "invalid mixer profile index"); return false; } - if (getConfigMixerProfile() == profile_index) + if (currentMixerProfileIndex == profile_index) { return false; } @@ -138,17 +157,18 @@ bool OutputProfileHotSwitch(int profile_index) return false; } //do not allow switching in navigation mode - if (ARMING_FLAG(ARMED) && navigationInAnyMode()){ + if (ARMING_FLAG(ARMED) && (navigationInAnyMode() || isUsingNavigationModes())){ LOG_INFO(PWM, "mixer switch failed, navModesEnabled"); return false; } - //do not allow switching between multi rotor and non multi rotor + //pwm mapping map outputs based on platformtype, check if mapping remain unchanged after the switch + //do not allow switching between multi rotor and non multi rotor if sannity check fails #ifdef ENABLE_MIXER_PROFILE_MCFW_HOTSWAP bool MCFW_hotswap_available = true; #else bool MCFW_hotswap_available = false; #endif - uint8_t old_platform_type = mixerConfig()->platformType; + uint8_t old_platform_type = currentMixerConfig.platformType; uint8_t new_platform_type = mixerConfigByIndex(profile_index)->platformType; bool old_platform_type_mc = old_platform_type == PLATFORM_MULTIROTOR || old_platform_type == PLATFORM_TRICOPTER; bool new_platform_type_mc = new_platform_type == PLATFORM_MULTIROTOR || new_platform_type == PLATFORM_TRICOPTER; @@ -156,14 +176,17 @@ bool OutputProfileHotSwitch(int profile_index) if ((!MCFW_hotswap_available) && is_mcfw_switching) { LOG_INFO(PWM, "mixer MCFW_hotswap_unavailable"); + allow_hot_switch = false; return false; } //do not allow switching if motor or servos counts has changed if ((getMotorCount() != computeMotorCountByMixerProfileIndex(profile_index)) || (getServoCount() != computeServoCountByMixerProfileIndex(profile_index))) { + LOG_INFO(PWM, "mixer switch failed, because of motor/servo count will change"); // LOG_INFO(PWM, "old motor/servo count:%d,%d",getMotorCount(),getServoCount()); // LOG_INFO(PWM, "new motor/servo count:%d,%d",computeMotorCountByMixerProfileIndex(profile_index),computeServoCountByMixerProfileIndex(profile_index)); + allow_hot_switch = false; return false; } if (!setConfigMixerProfile(profile_index)){ @@ -171,14 +194,8 @@ bool OutputProfileHotSwitch(int profile_index) return false; } stopMotorsNoDelay(); - servosInit(); - mixerUpdateStateFlags(); - mixerInit(); + mixerConfigInit(); - if(mixerConfig()->PIDProfileLinking) - { - SwitchPidProfileByMixerProfile(); - } return true; } diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index 7da2c073d9..4e9d44b353 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -26,6 +26,8 @@ typedef struct mixerProfile_s { PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); +extern mixerConfig_t currentMixerConfig; +extern int currentMixerProfileIndex; #define mixerConfig() (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->mixer_config)) #define mixerConfigMutable() ((mixerConfig_t *) mixerConfig()) @@ -43,3 +45,4 @@ static inline const mixerProfile_t* mixerProfiles_CopyArray_by_index(int _index) #define mixerServoMixersByIndex(index) (&(mixerProfiles(index)->ServoMixers)) bool OutputProfileHotSwitch(int profile_index); +void mixerConfigInit(void); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 82819d4de3..eb9abb4b55 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -1215,9 +1215,9 @@ void pidInit(void) if (pidProfile()->pidControllerType == PID_TYPE_AUTO) { if ( - mixerConfig()->platformType == PLATFORM_AIRPLANE || - mixerConfig()->platformType == PLATFORM_BOAT || - mixerConfig()->platformType == PLATFORM_ROVER + currentMixerConfig.platformType == PLATFORM_AIRPLANE || + currentMixerConfig.platformType == PLATFORM_BOAT || + currentMixerConfig.platformType == PLATFORM_ROVER ) { usedPidControllerType = PID_TYPE_PIFF; } else { diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 6a16e54be0..f46619753a 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -251,7 +251,7 @@ void writeServos(void) /* * in case of tricopters, there might me a need to zero servo output when unarmed */ - if (mixerConfig()->platformType == PLATFORM_TRICOPTER && !ARMING_FLAG(ARMED) && !servoConfig()->tri_unarmed_servo) { + if (currentMixerConfig.platformType == PLATFORM_TRICOPTER && !ARMING_FLAG(ARMED) && !servoConfig()->tri_unarmed_servo) { zeroServoValue = true; } @@ -281,7 +281,7 @@ void servoMixer(float dT) // Reverse yaw servo when inverted in 3D mode only for multirotor and tricopter if (feature(FEATURE_REVERSIBLE_MOTORS) && (rxGetChannelValue(THROTTLE) < PWM_RANGE_MIDDLE) && - (mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER)) { + (currentMixerConfig.platformType == PLATFORM_MULTIROTOR || currentMixerConfig.platformType == PLATFORM_TRICOPTER)) { input[INPUT_STABILIZED_YAW] *= -1; } } @@ -317,6 +317,8 @@ void servoMixer(float dT) input[INPUT_STABILIZED_THROTTLE] = mixerThrottleCommand - 1000 - 500; // Since it derives from rcCommand or mincommand and must be [-500:+500] + input[BOXMIXERTRANSITION] = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION) * 500; //fixed value + // center the RC input value around the RC middle value // by subtracting the RC middle value from the RC input value, we get: // data - middle = input diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index c8dbd06d1e..1dd6591221 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -62,7 +62,7 @@ typedef enum { INPUT_GVAR_5 = 35, INPUT_GVAR_6 = 36, INPUT_GVAR_7 = 37, - INPUT_MC2FW_TRANSITION = 38, + INPUT_MIXER_TRANSITION = 38, INPUT_SOURCE_COUNT } inputSource_e; diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index ca548ba4e8..436c3c3796 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -4179,8 +4179,8 @@ void navigationUsePIDs(void) void navigationInitYawControl(void){ if ( - mixerConfig()->platformType == PLATFORM_BOAT || - mixerConfig()->platformType == PLATFORM_ROVER || + currentMixerConfig.platformType == PLATFORM_BOAT || + currentMixerConfig.platformType == PLATFORM_ROVER || navConfig()->fw.useFwNavYawControl ) { ENABLE_STATE(FW_HEADING_USE_YAW); @@ -4224,8 +4224,8 @@ void navigationInit(void) navigationUsePIDs(); if ( - mixerConfig()->platformType == PLATFORM_BOAT || - mixerConfig()->platformType == PLATFORM_ROVER || + currentMixerConfig.platformType == PLATFORM_BOAT || + currentMixerConfig.platformType == PLATFORM_ROVER || navConfig()->fw.useFwNavYawControl ) { ENABLE_STATE(FW_HEADING_USE_YAW); @@ -4352,7 +4352,7 @@ bool navigationIsExecutingAnEmergencyLanding(void) bool navigationInAnyMode(void) { navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); - return !(stateFlags ==0); + return !(stateFlags == 0); } bool navigationInAutomaticThrottleMode(void) diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index cdb3bc7d7e..6a08871508 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -773,7 +773,7 @@ static int logicConditionGetFlightOperandValue(int operand) { break; case LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE: // int - return getConfigMixerProfile() + 1; + return currentMixerProfileIndex + 1; break; case LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS: From 1839a458d2f849fe0f06451a50435e87d02641c6 Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 1 Jul 2023 13:01:37 +0900 Subject: [PATCH 017/122] add mode to swtich mixer profile --- src/main/fc/fc_msp_box.c | 10 +++++++++- src/main/flight/mixer_profile.c | 25 ++++++++++++++----------- src/main/flight/mixer_profile.h | 3 ++- src/main/programming/programming_task.c | 2 ++ 4 files changed, 27 insertions(+), 13 deletions(-) diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index 8caa76b923..c6ad2cfc0e 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -349,6 +349,11 @@ void initActiveBoxIds(void) ADD_ACTIVE_BOX(BOXTURTLE); } #endif + +#if (MAX_MIXER_PROFILE_COUNT > 1) + ADD_ACTIVE_BOX(BOXMIXERPROFILE); + ADD_ACTIVE_BOX(BOXMIXERTRANSITION); +#endif } #define IS_ENABLED(mask) ((mask) == 0 ? 0 : 1) @@ -415,7 +420,10 @@ void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags) #ifdef USE_MULTI_MISSION CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCHANGEMISSION)), BOXCHANGEMISSION); #endif - +#if (MAX_MIXER_PROFILE_COUNT > 1) + CHECK_ACTIVE_BOX(IS_ENABLED(currentMixerProfileIndex)); + CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION))); +#endif memset(mspBoxModeFlags, 0, sizeof(boxBitmask_t)); for (uint32_t i = 0; i < activeBoxIdCount; i++) { if (activeBoxes[activeBoxIds[i]]) { diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index f5f6179d85..d92761f766 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -67,13 +67,9 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) } } -void loadMixerConfig(void) { +void mixerConfigInit(void){ currentMixerProfileIndex=getConfigMixerProfile(); currentMixerConfig=*mixerConfig(); -} - -void mixerConfigInit(void){ - loadMixerConfig(); servosInit(); mixerUpdateStateFlags(); mixerInit(); @@ -134,25 +130,32 @@ static int computeServoCountByMixerProfileIndex(int index) } } + +void outputProfileUpdateTask(timeUs_t currentTimeUs) { + UNUSED(currentTimeUs); + outputProfileHotSwitch((int) IS_RC_MODE_ACTIVE(BOXMIXERPROFILE)); + +} + //switch mixerprofile without reboot -bool OutputProfileHotSwitch(int profile_index) +bool outputProfileHotSwitch(int profile_index) { static bool allow_hot_switch = true; // does not work with timerHardwareOverride,need to set mixerConfig()->outputMode == OUTPUT_MODE_AUTO - LOG_INFO(PWM, "OutputProfileHotSwitch"); + // LOG_INFO(PWM, "OutputProfileHotSwitch"); if (!allow_hot_switch) { return false; } + if (currentMixerProfileIndex == profile_index) + { + return false; + } if (profile_index < 0 || profile_index >= MAX_MIXER_PROFILE_COUNT) { // sanity check LOG_INFO(PWM, "invalid mixer profile index"); return false; } - if (currentMixerProfileIndex == profile_index) - { - return false; - } if (areSensorsCalibrating()) {//it seems like switching before sensors calibration complete will cause pid stops to respond, especially in D,TODO return false; } diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index 4e9d44b353..4302c60b40 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -44,5 +44,6 @@ static inline const mixerProfile_t* mixerProfiles_CopyArray_by_index(int _index) #define mixerMotorMixersByIndex(index) (&(mixerProfiles(index)->MotorMixers)) #define mixerServoMixersByIndex(index) (&(mixerProfiles(index)->ServoMixers)) -bool OutputProfileHotSwitch(int profile_index); +bool outputProfileHotSwitch(int profile_index); void mixerConfigInit(void); +void outputProfileUpdateTask(timeUs_t currentTimeUs); \ No newline at end of file diff --git a/src/main/programming/programming_task.c b/src/main/programming/programming_task.c index 69f1e92944..e5b6642d24 100644 --- a/src/main/programming/programming_task.c +++ b/src/main/programming/programming_task.c @@ -26,8 +26,10 @@ #include "programming/logic_condition.h" #include "programming/pid.h" +#include "flight/mixer_profile.h" void programmingFrameworkUpdateTask(timeUs_t currentTimeUs) { programmingPidUpdateTask(currentTimeUs); + outputProfileUpdateTask(currentTimeUs); logicConditionUpdateTask(currentTimeUs); } \ No newline at end of file From ab8bab92c4e41660d958a341a9fb9cdaeb53131b Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Thu, 20 Jul 2023 13:40:59 +0100 Subject: [PATCH 018/122] Fix for #9182 --- src/main/io/osd.c | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 63312af46c..e515ad3c51 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2120,37 +2120,38 @@ static bool osdDrawSingleElement(uint8_t item) 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, "---"); + buff[3] = SYM_BLANK; + buff[4] = '\0'; + strcpy(buff, "---"); } else if (distanceMeters == -2) { // Wind is too strong to come back with cruise throttle - buff[1] = buff[2] = buff[3] = SYM_WIND_HORIZONTAL; + buff[0] = buff[1] = buff[2] = SYM_WIND_HORIZONTAL; switch ((osd_unit_e)osdConfig()->units){ case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - buff[4] = SYM_DIST_MI; + buff[3] = SYM_DIST_MI; break; case OSD_UNIT_METRIC_MPH: FALLTHROUGH; case OSD_UNIT_METRIC: - buff[4] = SYM_DIST_KM; + buff[3] = SYM_DIST_KM; break; case OSD_UNIT_GA: - buff[4] = SYM_DIST_NM; + buff[3] = SYM_DIST_NM; break; } - buff[5] = '\0'; + buff[4] = '\0'; TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); } else { - osdFormatDistanceSymbol(buff + 1, distanceMeters * 100, 0); + osdFormatDistanceSymbol(buff, distanceMeters * 100, 0); if (distanceMeters == 0) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); } + elemPosX++; break; case OSD_FLYMODE: From 618664810cd5a665256f2c40f085339893be2204 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Fri, 21 Jul 2023 13:56:59 +0100 Subject: [PATCH 019/122] Updated logic in RTH dist calc - Changed FIXED_WING_LEGACY to AIRPLANE to remove legacy code - Inverted arming check. As the RTH distance should be calculated if armed, not if disarmed. --- src/main/flight/rth_estimator.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/flight/rth_estimator.c b/src/main/flight/rth_estimator.c index eed9adbae3..0ad5746305 100644 --- a/src/main/flight/rth_estimator.c +++ b/src/main/flight/rth_estimator.c @@ -209,8 +209,8 @@ float calculateRemainingFlightTimeBeforeRTH(bool takeWindIntoAccount) { // returns meters float calculateRemainingDistanceBeforeRTH(bool takeWindIntoAccount) { - // Fixed wing only for now - if (!(STATE(FIXED_WING_LEGACY) || ARMING_FLAG(ARMED))) { + // Fixed wing only for now, and must be armed + if (!(STATE(AIRPLANE) || !ARMING_FLAG(ARMED))) { return -1; } From 545af919c555a2005e4a456c4b666cb31f4130ab Mon Sep 17 00:00:00 2001 From: MrD-RC Date: Fri, 21 Jul 2023 19:27:40 +0100 Subject: [PATCH 020/122] Reverted change, but made code more readable --- src/main/flight/rth_estimator.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/rth_estimator.c b/src/main/flight/rth_estimator.c index 0ad5746305..708c71bd1c 100644 --- a/src/main/flight/rth_estimator.c +++ b/src/main/flight/rth_estimator.c @@ -210,7 +210,7 @@ float calculateRemainingFlightTimeBeforeRTH(bool takeWindIntoAccount) { float calculateRemainingDistanceBeforeRTH(bool takeWindIntoAccount) { // Fixed wing only for now, and must be armed - if (!(STATE(AIRPLANE) || !ARMING_FLAG(ARMED))) { + if (!STATE(AIRPLANE) || !ARMING_FLAG(ARMED)) { return -1; } From fe30a8a8ce1883b532607e6ca977190b5e39828e Mon Sep 17 00:00:00 2001 From: shota Date: Sun, 23 Jul 2023 00:24:27 +0900 Subject: [PATCH 021/122] refactoring --- src/main/fc/fc_init.c | 1 + src/main/fc/fc_msp_box.c | 4 +- src/main/fc/settings.yaml | 5 +- src/main/flight/mixer.c | 4 +- src/main/flight/mixer_profile.c | 157 +++++++++++-------------------- src/main/flight/mixer_profile.h | 4 +- src/main/flight/servos.c | 2 +- src/main/navigation/navigation.h | 1 - src/main/target/common.h | 1 + 9 files changed, 65 insertions(+), 114 deletions(-) diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index d04defd3e9..f64edd4d02 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -304,6 +304,7 @@ void init(void) // Initialize servo and motor mixers // This needs to be called early to set up platform type correctly and count required motors & servos mixerConfigInit(); + checkMixerProfileHotSwitchAvalibility(); // Some sanity checking if (motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) { diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index c6ad2cfc0e..98c0e87890 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -421,8 +421,8 @@ void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags) CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCHANGEMISSION)), BOXCHANGEMISSION); #endif #if (MAX_MIXER_PROFILE_COUNT > 1) - CHECK_ACTIVE_BOX(IS_ENABLED(currentMixerProfileIndex)); - CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION))); + CHECK_ACTIVE_BOX(IS_ENABLED(currentMixerProfileIndex), BOXMIXERPROFILE); + CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION)), BOXMIXERTRANSITION); #endif memset(mspBoxModeFlags, 0, sizeof(boxBitmask_t)); for (uint32_t i = 0; i < activeBoxIdCount; i++) { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 9becd26770..9064ef63ad 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -203,7 +203,6 @@ constants: MAX_CONTROL_RATE_PROFILE_COUNT: 3 MAX_BATTERY_PROFILE_COUNT: 3 - MAX_MIXER_PROFILE_COUNT: 2 groups: @@ -1164,10 +1163,10 @@ groups: default_value: "AUTO" field: mixer_config.outputMode table: output_mode - - name: motorstop_feature + - name: motorstop_on_low description: "If enabled, motor will stop when throttle is low" default_value: OFF - field: mixer_config.motorstopFeature + field: mixer_config.motorstopOnLow type: bool - name: mixer_pid_profile_linking description: "If enabled, pid profile index will follow mixer profile index" diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 6a97ab4e17..b77e39c0b8 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -116,7 +116,7 @@ static void computeMotorCount(void) } bool ifMotorstopFeatureEnabled(void){ - return currentMixerConfig.motorstopFeature; + return currentMixerConfig.motorstopOnLow; } uint8_t getMotorCount(void) { @@ -598,7 +598,7 @@ void FAST_CODE mixTable(void) motor[i] = motorZeroCommand; } //spin stopped motors only in mixer transition mode - if (IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION) && currentMixer[i].throttle <= -1.05f && currentMixer[i].throttle >= -2.0f && (!feature(FEATURE_REVERSIBLE_MOTORS))) { + if (isInMixerTransition && currentMixer[i].throttle <= -1.05f && currentMixer[i].throttle >= -2.0f && (!feature(FEATURE_REVERSIBLE_MOTORS))) { motor[i] = -currentMixer[i].throttle * 1000; motor[i] = constrain(motor[i], throttleRangeMin, throttleRangeMax); } diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index d92761f766..c6864094cc 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -28,6 +28,7 @@ mixerConfig_t currentMixerConfig; int currentMixerProfileIndex; +bool isInMixerTransition; PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1); @@ -41,8 +42,8 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only .outputMode = SETTING_OUTPUT_MODE_DEFAULT, - .motorstopFeature = SETTING_MOTORSTOP_FEATURE_DEFAULT, - .PIDProfileLinking = SETTING_OUTPUT_MODE_DEFAULT + .motorstopOnLow = SETTING_MOTORSTOP_ON_LOW_DEFAULT, + .PIDProfileLinking = SETTING_MIXER_PID_PROFILE_LINKING_DEFAULT } ); for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) { @@ -105,10 +106,6 @@ static int computeServoCountByMixerProfileIndex(int index) const servoMixer_t* temp_servomixers=mixerServoMixersByIndex(index)[0]; for (int i = 0; i < MAX_SERVO_RULES; i++) { - // mixerServoMixersByIndex(index)[i]->targetChannel will occour problem after i=1 - // LOG_INFO(PWM, "i:%d, targetChannel:%d, inputSource:%d, rate:%d",i,mixerServoMixersByIndex(index)[i]->targetChannel,mixerServoMixersByIndex(index)[i]->inputSource,mixerServoMixersByIndex(index)[i]->rate); - // LOG_INFO(PWM, "i:%d, targetChannel:%d, inputSource:%d, rate:%d",i,mixerProfiles_SystemArray[index].ServoMixers[i].targetChannel,mixerProfiles_SystemArray[index].ServoMixers[i].inputSource,mixerProfiles_SystemArray[index].ServoMixers[i].rate); - // LOG_INFO(PWM, "i:%d, targetChannel:%d, inputSource:%d, rate:%d",i,temp_servomixers[i].targetChannel,temp_servomixers[i].inputSource,temp_servomixers[i].rate); if (temp_servomixers[i].rate == 0) break; @@ -130,9 +127,51 @@ static int computeServoCountByMixerProfileIndex(int index) } } +bool checkMixerProfileHotSwitchAvalibility(void) +{ + static int allow_hot_switch = -1; + //pwm mapping maps outputs based on platformtype, check if mapping remain unchanged after the switch + //do not allow switching between multi rotor and non multi rotor if sannity check fails + if (MAX_MIXER_PROFILE_COUNT!=2) + { + return false; + } + if (allow_hot_switch == 0) + { + return false; + } + if (allow_hot_switch == 1) + { + return true; + } +#ifdef ENABLE_MIXER_PROFILE_MCFW_HOTSWAP + bool MCFW_hotswap_available = true; +#else + bool MCFW_hotswap_available = false; +#endif + uint8_t platform_type0 = mixerConfigByIndex(0)->platformType; + uint8_t platform_type1 = mixerConfigByIndex(1)->platformType; + bool platform_type_mc0 = (platform_type0 == PLATFORM_MULTIROTOR) || (platform_type0 == PLATFORM_TRICOPTER); + bool platform_type_mc1 = (platform_type1 == PLATFORM_MULTIROTOR) || (platform_type1 == PLATFORM_TRICOPTER); + bool is_mcfw_switching = platform_type_mc0 ^ platform_type_mc1; + if ((!MCFW_hotswap_available) && is_mcfw_switching) + { + allow_hot_switch = 0; + return false; + } + //do not allow switching if motor or servos counts are different + if ((computeMotorCountByMixerProfileIndex(0) != computeMotorCountByMixerProfileIndex(1)) || (computeServoCountByMixerProfileIndex(0) != computeServoCountByMixerProfileIndex(1))) + { + allow_hot_switch = 0; + return false; + } + allow_hot_switch = 1; + return true; +} void outputProfileUpdateTask(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); + isInMixerTransition = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION); outputProfileHotSwitch((int) IS_RC_MODE_ACTIVE(BOXMIXERPROFILE)); } @@ -153,117 +192,27 @@ bool outputProfileHotSwitch(int profile_index) } if (profile_index < 0 || profile_index >= MAX_MIXER_PROFILE_COUNT) { // sanity check - LOG_INFO(PWM, "invalid mixer profile index"); + // LOG_INFO(PWM, "invalid mixer profile index"); return false; } if (areSensorsCalibrating()) {//it seems like switching before sensors calibration complete will cause pid stops to respond, especially in D,TODO return false; } - //do not allow switching in navigation mode - if (ARMING_FLAG(ARMED) && (navigationInAnyMode() || isUsingNavigationModes())){ - LOG_INFO(PWM, "mixer switch failed, navModesEnabled"); + // do not allow switching when user activated navigation mode + 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))); + if (ARMING_FLAG(ARMED) && navBoxModesEnabled){ + // LOG_INFO(PWM, "mixer switch failed, navModesEnabled"); return false; } - //pwm mapping map outputs based on platformtype, check if mapping remain unchanged after the switch - //do not allow switching between multi rotor and non multi rotor if sannity check fails -#ifdef ENABLE_MIXER_PROFILE_MCFW_HOTSWAP - bool MCFW_hotswap_available = true; -#else - bool MCFW_hotswap_available = false; -#endif - uint8_t old_platform_type = currentMixerConfig.platformType; - uint8_t new_platform_type = mixerConfigByIndex(profile_index)->platformType; - bool old_platform_type_mc = old_platform_type == PLATFORM_MULTIROTOR || old_platform_type == PLATFORM_TRICOPTER; - bool new_platform_type_mc = new_platform_type == PLATFORM_MULTIROTOR || new_platform_type == PLATFORM_TRICOPTER; - bool is_mcfw_switching = old_platform_type_mc ^ new_platform_type_mc; - if ((!MCFW_hotswap_available) && is_mcfw_switching) - { - LOG_INFO(PWM, "mixer MCFW_hotswap_unavailable"); - allow_hot_switch = false; - return false; - } - //do not allow switching if motor or servos counts has changed - if ((getMotorCount() != computeMotorCountByMixerProfileIndex(profile_index)) || (getServoCount() != computeServoCountByMixerProfileIndex(profile_index))) - { - - LOG_INFO(PWM, "mixer switch failed, because of motor/servo count will change"); - // LOG_INFO(PWM, "old motor/servo count:%d,%d",getMotorCount(),getServoCount()); - // LOG_INFO(PWM, "new motor/servo count:%d,%d",computeMotorCountByMixerProfileIndex(profile_index),computeServoCountByMixerProfileIndex(profile_index)); - allow_hot_switch = false; + if (!checkMixerProfileHotSwitchAvalibility()){ + // LOG_INFO(PWM, "mixer switch failed, checkMixerProfileHotSwitchAvalibility"); return false; } if (!setConfigMixerProfile(profile_index)){ - LOG_INFO(PWM, "mixer switch failed to set config"); + // LOG_INFO(PWM, "mixer switch failed to set config"); return false; } stopMotorsNoDelay(); mixerConfigInit(); - return true; } - -// static int min_ab(int a,int b) -// { -// return a > b ? b : a; -// } - -// void checkOutputMapping(int profile_index)//debug purpose -// { -// timMotorServoHardware_t old_timOutputs; -// pwmBuildTimerOutputList(&old_timOutputs, isMixerUsingServos()); -// stopMotors(); -// delay(1000); //check motor stop -// if (!setConfigMixerProfile(profile_index)){ -// LOG_INFO(PWM, "failed to set config"); -// return; -// } -// servosInit(); -// mixerUpdateStateFlags(); -// mixerInit(); -// timMotorServoHardware_t timOutputs; -// pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos()); -// bool motor_output_type_not_changed = old_timOutputs.maxTimMotorCount == timOutputs.maxTimMotorCount; -// bool servo_output_type_not_changed = old_timOutputs.maxTimServoCount == timOutputs.maxTimServoCount; -// LOG_INFO(PWM, "maxTimMotorCount:%d,%d",old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); -// for (int i; i < min_ab(old_timOutputs.maxTimMotorCount,timOutputs.maxTimMotorCount); i++) -// { -// LOG_INFO(PWM, "motor_output_type_not_changed:%d,%d",i,motor_output_type_not_changed); -// motor_output_type_not_changed &= old_timOutputs.timMotors[i]->tag==timOutputs.timMotors[i]->tag; -// } -// LOG_INFO(PWM, "motor_output_type_not_changed:%d",motor_output_type_not_changed); - -// LOG_INFO(PWM, "maxTimServoCount:%d,%d",old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); -// for (int i; i < min_ab(old_timOutputs.maxTimServoCount,timOutputs.maxTimServoCount); i++) -// { -// LOG_INFO(PWM, "servo_output_type_not_changed:%d,%d",i,servo_output_type_not_changed); -// servo_output_type_not_changed &= old_timOutputs.timServos[i]->tag==timOutputs.timServos[i]->tag; -// } -// LOG_INFO(PWM, "servo_output_type_not_changed:%d",servo_output_type_not_changed); - -// if(!motor_output_type_not_changed || !servo_output_type_not_changed){ -// LOG_INFO(PWM, "pwm output mapping has changed"); -// } -// } - -//check if a pid profile switch followed on a mixer profile switch -// static bool CheckIfPidInitNeededInSwitch(void) -// { -// static bool ret = true; -// if (!ret) -// { -// return false; -// } -// for (uint8_t i = 0; i < MAX_LOGIC_CONDITIONS; i++) -// { -// const int activatorValue = logicConditionGetValue(logicConditions(i)->activatorId); -// const logicOperand_t *operandA = &(logicConditions(i)->operandA); -// if (logicConditions(i)->enabled && activatorValue && logicConditions(i)->operation == LOGIC_CONDITION_SET_PROFILE && -// operandA->type == LOGIC_CONDITION_OPERAND_TYPE_FLIGHT && operandA->value == LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE && -// logicConditions(i)->flags == 0) -// { -// ret = false; -// return false; -// } -// } -// return true; -// } \ No newline at end of file diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index 4302c60b40..25d4e79362 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -15,7 +15,7 @@ typedef struct mixerConfig_s { bool hasFlaps; int16_t appliedMixerPreset; uint8_t outputMode; - bool motorstopFeature; + bool motorstopOnLow; bool PIDProfileLinking; } mixerConfig_t; typedef struct mixerProfile_s { @@ -28,6 +28,7 @@ PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); extern mixerConfig_t currentMixerConfig; extern int currentMixerProfileIndex; +extern bool isInMixerTransition; #define mixerConfig() (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->mixer_config)) #define mixerConfigMutable() ((mixerConfig_t *) mixerConfig()) @@ -45,5 +46,6 @@ static inline const mixerProfile_t* mixerProfiles_CopyArray_by_index(int _index) #define mixerServoMixersByIndex(index) (&(mixerProfiles(index)->ServoMixers)) bool outputProfileHotSwitch(int profile_index); +bool checkMixerProfileHotSwitchAvalibility(void); void mixerConfigInit(void); void outputProfileUpdateTask(timeUs_t currentTimeUs); \ No newline at end of file diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index f46619753a..c08ee293ee 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -317,7 +317,7 @@ void servoMixer(float dT) input[INPUT_STABILIZED_THROTTLE] = mixerThrottleCommand - 1000 - 500; // Since it derives from rcCommand or mincommand and must be [-500:+500] - input[BOXMIXERTRANSITION] = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION) * 500; //fixed value + input[INPUT_MIXER_TRANSITION] = isInMixerTransition * 500; //fixed value // center the RC input value around the RC middle value // by subtracting the RC middle value from the RC input value, we get: diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 57d7f49c8e..b6ff19f711 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -590,7 +590,6 @@ void abortForcedEmergLanding(void); emergLandState_e getStateOfForcedEmergLanding(void); /* Getter functions which return data about the state of the navigation system */ -bool navigationInAnyMode(void); bool navigationInAutomaticThrottleMode(void); bool navigationIsControllingThrottle(void); bool isFixedWingAutoThrottleManuallyIncreased(void); diff --git a/src/main/target/common.h b/src/main/target/common.h index 70916fdbd3..b56c242675 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -187,5 +187,6 @@ #define USE_SERIALRX_SUMD #define USE_TELEMETRY_HOTT #define USE_HOTT_TEXTMODE +#else #define MAX_MIXER_PROFILE_COUNT 1 #endif From fb73715e342df29d007ea2e11f876c34fd45357e Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 24 Jul 2023 12:05:37 +0900 Subject: [PATCH 022/122] minor fix --- src/main/flight/servos.c | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index c08ee293ee..45d32bf7ff 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -131,7 +131,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]; +static rateLimitFilter_t servoSpeedLimitFilter[MAX_SERVO_RULES*MAX_MIXER_PROFILE_COUNT]; STATIC_FASTRAM pt1Filter_t rotRateFilter; STATIC_FASTRAM pt1Filter_t targetRateFilter; @@ -377,7 +377,7 @@ void servoMixer(float dT) * 10 = 100us/s -> full sweep (from 1000 to 2000) is performed in 10s * 100 = 1000us/s -> full sweep in 1s */ - int16_t inputLimited = (int16_t) rateLimitFilterApply4(&servoSpeedLimitFilter[i], input[from], currentServoMixer[i].speed * 10, dT); + int16_t inputLimited = (int16_t) rateLimitFilterApply4(&servoSpeedLimitFilter[i+MAX_SERVO_RULES*currentMixerProfileIndex], input[from], currentServoMixer[i].speed * 10, dT); servo[target] += ((int32_t)inputLimited * currentServoMixer[i].rate) / 100; } @@ -615,6 +615,10 @@ void processServoAutotrim(const float dT) { return; } #endif + if(!STATE(AIRPLANE)) + { + return; + } if (feature(FEATURE_FW_AUTOTRIM)) { processContinuousServoAutotrim(dT); } else { From e0abc47c1031769eda82c60c68ce10082d624adf Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 24 Jul 2023 18:45:56 +0900 Subject: [PATCH 023/122] minor fix --- src/main/target/MATEKF405TE/target.c | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/target/MATEKF405TE/target.c b/src/main/target/MATEKF405TE/target.c index ba89313a94..f39e03e6c3 100644 --- a/src/main/target/MATEKF405TE/target.c +++ b/src/main/target/MATEKF405TE/target.c @@ -36,6 +36,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,1,3) UP173 DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,6,3) UP173 DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8 D(1,5,3) UP173 + + DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_MC_MOTOR, 0, 0), // S9 DMA NONE + DEF_TIM(TIM13, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_MC_MOTOR, 0, 0), // S10 DMA NONE + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11 D(1,0,2) #else DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2,7,7) UP217 DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(2,2,0) UP217 @@ -46,10 +50,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,1,3) UP173 DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,6,3) UP173 DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 D(1,5,3) UP173 -#endif DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 DMA NONE DEF_TIM(TIM13, CH1, PA6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 DMA NONE DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11 D(1,0,2) +#endif DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), // 2812LED D(1,2,5) DEF_TIM(TIM11, CH1, PB9, TIM_USE_BEEPER, 0, 0), // BEEPER PWM From d220dcb4794341413ef76494f1f86afecfc1a14d Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 24 Jul 2023 19:31:45 +0900 Subject: [PATCH 024/122] mend --- src/main/target/MATEKF405TE/target.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/MATEKF405TE/target.c b/src/main/target/MATEKF405TE/target.c index f39e03e6c3..90afefba4b 100644 --- a/src/main/target/MATEKF405TE/target.c +++ b/src/main/target/MATEKF405TE/target.c @@ -37,8 +37,8 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,6,3) UP173 DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8 D(1,5,3) UP173 - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_MC_MOTOR, 0, 0), // S9 DMA NONE - DEF_TIM(TIM13, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_MC_MOTOR, 0, 0), // S10 DMA NONE + DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S9 DMA NONE + DEF_TIM(TIM13, CH1, PA6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 DMA NONE DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11 D(1,0,2) #else DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2,7,7) UP217 From 18cefccd308a16a783464fdbe200f27fde46bc91 Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 24 Jul 2023 19:32:36 +0900 Subject: [PATCH 025/122] mend --- src/main/target/MATEKF405TE/target.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/MATEKF405TE/target.c b/src/main/target/MATEKF405TE/target.c index 90afefba4b..bee9ebee56 100644 --- a/src/main/target/MATEKF405TE/target.c +++ b/src/main/target/MATEKF405TE/target.c @@ -37,9 +37,9 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,6,3) UP173 DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8 D(1,5,3) UP173 - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S9 DMA NONE + DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 DMA NONE DEF_TIM(TIM13, CH1, PA6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 DMA NONE - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11 D(1,0,2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S11 D(1,0,2) #else DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2,7,7) UP217 DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(2,2,0) UP217 From 4d8136176f44978b64029b9fd6f56dcb4faf95b8 Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 24 Jul 2023 23:22:59 +0900 Subject: [PATCH 026/122] mixer profile switching servo speed support --- src/main/flight/mixer_profile.c | 55 ++++++++++++++++---------------- src/main/flight/servos.c | 56 ++++++++++++++++++++------------- 2 files changed, 62 insertions(+), 49 deletions(-) diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index c6864094cc..d0585a023f 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -61,7 +61,7 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) .rate = 0, .speed = 0 #ifdef USE_PROGRAMMING_FRAMEWORK - ,.conditionId = -1 + ,.conditionId = -1, #endif ); } @@ -98,34 +98,34 @@ static int computeMotorCountByMixerProfileIndex(int index) return motorCount; } -static int computeServoCountByMixerProfileIndex(int index) -{ - int servoRuleCount = 0; - int minServoIndex = 255; - int maxServoIndex = 0; +// static int computeServoCountByMixerProfileIndex(int index) +// { +// int servoRuleCount = 0; +// int minServoIndex = 255; +// int maxServoIndex = 0; - const servoMixer_t* temp_servomixers=mixerServoMixersByIndex(index)[0]; - for (int i = 0; i < MAX_SERVO_RULES; i++) { - if (temp_servomixers[i].rate == 0) - break; +// const servoMixer_t* temp_servomixers=mixerServoMixersByIndex(index)[0]; +// for (int i = 0; i < MAX_SERVO_RULES; i++) { +// if (temp_servomixers[i].rate == 0) +// break; - if (temp_servomixers[i].targetChannel < minServoIndex) { - minServoIndex = temp_servomixers[i].targetChannel; - } +// if (temp_servomixers[i].targetChannel < minServoIndex) { +// minServoIndex = temp_servomixers[i].targetChannel; +// } - if (temp_servomixers[i].targetChannel > maxServoIndex) { - maxServoIndex = temp_servomixers[i].targetChannel; - } - // LOG_INFO(PWM, "i:%d, minServoIndex:%d, maxServoIndex:%d",i,minServoIndex,maxServoIndex); - servoRuleCount++; - } - if (servoRuleCount) { - return 1 + maxServoIndex - minServoIndex; - } - else { - return 0; - } -} +// if (temp_servomixers[i].targetChannel > maxServoIndex) { +// maxServoIndex = temp_servomixers[i].targetChannel; +// } +// // LOG_INFO(PWM, "i:%d, minServoIndex:%d, maxServoIndex:%d",i,minServoIndex,maxServoIndex); +// servoRuleCount++; +// } +// if (servoRuleCount) { +// return 1 + maxServoIndex - minServoIndex; +// } +// else { +// return 0; +// } +// } bool checkMixerProfileHotSwitchAvalibility(void) { @@ -160,7 +160,8 @@ bool checkMixerProfileHotSwitchAvalibility(void) return false; } //do not allow switching if motor or servos counts are different - if ((computeMotorCountByMixerProfileIndex(0) != computeMotorCountByMixerProfileIndex(1)) || (computeServoCountByMixerProfileIndex(0) != computeServoCountByMixerProfileIndex(1))) + // if ((computeMotorCountByMixerProfileIndex(0) != computeMotorCountByMixerProfileIndex(1)) || (computeServoCountByMixerProfileIndex(0) != computeServoCountByMixerProfileIndex(1))) + if ((computeMotorCountByMixerProfileIndex(0) != computeMotorCountByMixerProfileIndex(1))) { allow_hot_switch = 0; return false; diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 45d32bf7ff..4b421d4118 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -120,7 +120,8 @@ void pgResetFn_servoParams(servoParam_t *instance) int16_t servo[MAX_SUPPORTED_SERVOS]; static uint8_t servoRuleCount = 0; -static servoMixer_t currentServoMixer[MAX_SERVO_RULES]; +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 servoOutputEnabled; static bool mixerUsesServos; @@ -192,28 +193,31 @@ int getServoCount(void) void loadCustomServoMixer(void) { - // reset settings servoRuleCount = 0; minServoIndex = 255; maxServoIndex = 0; memset(currentServoMixer, 0, sizeof(currentServoMixer)); - // load custom mixer into currentServoMixer - for (int i = 0; i < MAX_SERVO_RULES; i++) { - // check if done - if (customServoMixers(i)->rate == 0) - break; + 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 (customServoMixers(i)->targetChannel < minServoIndex) { - minServoIndex = customServoMixers(i)->targetChannel; + 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++; } - - if (customServoMixers(i)->targetChannel > maxServoIndex) { - maxServoIndex = customServoMixers(i)->targetChannel; - } - - memcpy(¤tServoMixer[i], customServoMixers(i), sizeof(servoMixer_t)); - servoRuleCount++; } } @@ -357,19 +361,22 @@ void servoMixer(float dT) // mix servos according to rules for (int i = 0; i < servoRuleCount; i++) { + const uint8_t target = currentServoMixer[i].targetChannel; + const uint8_t from = currentServoMixer[i].inputSource; + + int16_t inputRaw = input[from]; /* * Check if conditions for a rule are met, not all conditions apply all the time */ #ifdef USE_PROGRAMMING_FRAMEWORK if (!logicConditionGetValue(currentServoMixer[i].conditionId)) { - continue; + inputRaw = 0; } #endif - - const uint8_t target = currentServoMixer[i].targetChannel; - const uint8_t from = currentServoMixer[i].inputSource; - + if (!currentServoMixerActivative[i]) { + inputRaw = 0; + } /* * Apply mixer speed limit. 1 [one] speed unit is defined as 10us/s: * 0 = no limiting @@ -377,7 +384,7 @@ void servoMixer(float dT) * 10 = 100us/s -> full sweep (from 1000 to 2000) is performed in 10s * 100 = 1000us/s -> full sweep in 1s */ - int16_t inputLimited = (int16_t) rateLimitFilterApply4(&servoSpeedLimitFilter[i+MAX_SERVO_RULES*currentMixerProfileIndex], input[from], currentServoMixer[i].speed * 10, dT); + int16_t inputLimited = (int16_t) rateLimitFilterApply4(&servoSpeedLimitFilter[i], inputRaw, currentServoMixer[i].speed * 10, dT); servo[target] += ((int32_t)inputLimited * currentServoMixer[i].rate) / 100; } @@ -452,6 +459,8 @@ 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; if (source == axis) { @@ -473,6 +482,7 @@ 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) { @@ -485,6 +495,7 @@ 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) { @@ -518,6 +529,7 @@ 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 3cf482cb59416f3a04154394e986b4e229b4a672 Mon Sep 17 00:00:00 2001 From: shota Date: Tue, 25 Jul 2023 10:08:21 +0900 Subject: [PATCH 027/122] fix include for target config.c --- docs/Settings.md | 20 ++++++++++++++++++++ src/main/target/FF_F35_LIGHTNING/config.c | 2 +- src/main/target/MATEKF405SE/config.c | 2 +- 3 files changed, 22 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index dda075cee6..cce1b16006 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -2542,6 +2542,16 @@ This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly --- +### mixer_pid_profile_linking + +If enabled, pid profile index will follow mixer profile index + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + ### mode_range_logic_operator Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode. @@ -2602,6 +2612,16 @@ Output frequency (in Hz) for motor pins. Applies only to brushed motors. --- +### motorstop_on_low + +If enabled, motor will stop when throttle is low + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + ### msp_override_channels Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode. diff --git a/src/main/target/FF_F35_LIGHTNING/config.c b/src/main/target/FF_F35_LIGHTNING/config.c index d0825a06fe..cec7b4f8b4 100644 --- a/src/main/target/FF_F35_LIGHTNING/config.c +++ b/src/main/target/FF_F35_LIGHTNING/config.c @@ -19,7 +19,7 @@ #include #include "config/config_master.h" -#include "flight/mixer.h" +#include "flight/mixer_profile.h" #include "rx/rx.h" #include "io/serial.h" #include "telemetry/telemetry.h" diff --git a/src/main/target/MATEKF405SE/config.c b/src/main/target/MATEKF405SE/config.c index f82e5fa109..8cd618e3cf 100644 --- a/src/main/target/MATEKF405SE/config.c +++ b/src/main/target/MATEKF405SE/config.c @@ -21,7 +21,7 @@ #include "config/config_master.h" #include "config/feature.h" -#include "flight/mixer.h" +#include "flight/mixer_profile.h" #include "io/serial.h" From ec9ee9df8289bf461705f8fdf315833b662fe531 Mon Sep 17 00:00:00 2001 From: shota Date: Tue, 25 Jul 2023 14:30:20 +0900 Subject: [PATCH 028/122] update documents --- docs/MixerProfile.md | 140 +++++++++++++++++++++++++++ docs/Screenshots/mixer_profile.png | Bin 0 -> 24263 bytes src/main/drivers/timer.h | 2 + src/main/fc/fc_msp_box.c | 2 +- src/main/flight/mixer.c | 13 ++- src/main/flight/mixer_profile.c | 36 +++---- src/main/target/MATEKF405TE/target.c | 22 ++--- 7 files changed, 184 insertions(+), 31 deletions(-) create mode 100644 docs/MixerProfile.md create mode 100644 docs/Screenshots/mixer_profile.png diff --git a/docs/MixerProfile.md b/docs/MixerProfile.md new file mode 100644 index 0000000000..3681fcc05c --- /dev/null +++ b/docs/MixerProfile.md @@ -0,0 +1,140 @@ +# MixerProfile +A MixerProfile is a set of motor mixer,servomixer,platform type configuration settings. + +Currently Two profiles are supported expect f411 and f722. The default profile is profile `1`. + +Switching between profiles requires reboot to take affect by default. But When the conditions are met, It allows inflight profile switching to allow things like vtol build. + +# Setup for vtol +- Need to keep motor/servo pwm mapping consistent among profiles +- FW and MC have different way to map the pwm mapping, we need to change `timerHardware`` for to make it have same mapping. +- A vtol specific fc target is required. There might more official vtol fc target in the future +- Set mixer_profile, pid_profile separately, and set RC mode to switch them +## FC target +To keep motor/servo pwm mapping consistent and enable hot switching. Here is MATEKF405TE_SD board (folder name `MATEKF405TE`) used for vtol as a example. + +The target name for vtol build is MATEKF405TE_SD_VTOL, target folder name is MATEKF405TE. +when it is done, build your target and flash it to your fc,. + +### CMakeLists.txt +```c +target_stm32f405xg(MATEKF405TE) +target_stm32f405xg(MATEKF405TE_SD) +target_stm32f405xg(MATEKF405TE_SD_VTOL) //new target added +``` +### target.c +It is **important** to map all the serial output to `TIM_USE_VTOL_MOTOR` or `TIM_USE_VTOL_SERVO` to ensure same mapping among MC mapping and FW mapping. +```c +timerHardware_t timerHardware[] = { +#ifdef MATEKF405TE_SD_VTOL // Vtol target specific mapping start from there + DEF_TIM(TIM8, CH4, PC9, TIM_USE_VTOL_MOTOR, 0, 0), // S1 for motor + DEF_TIM(TIM8, CH3, PC8, TIM_USE_VTOL_MOTOR, 0, 0), // S2 for motor + DEF_TIM(TIM1, CH3N, PB15, TIM_USE_VTOL_MOTOR, 0, 0), // S3 for motor + DEF_TIM(TIM1, CH1, PA8, TIM_USE_VTOL_MOTOR, 0, 1), // S4 for motor + + DEF_TIM(TIM2, CH4, PB11, TIM_USE_VTOL_SERVO, 0, 0), // S5 for servo + DEF_TIM(TIM2, CH3, PB10, TIM_USE_VTOL_SERVO, 0, 0), // S6 for servo + DEF_TIM(TIM2, CH2, PB3, TIM_USE_VTOL_SERVO, 0, 0), // S7 for servo + DEF_TIM(TIM2, CH1, PA15, TIM_USE_VTOL_SERVO, 0, 0), // S8 for servo + + DEF_TIM(TIM12, CH1, PB14, TIM_USE_VTOL_SERVO, 0, 0), // S9 for servo + DEF_TIM(TIM13, CH1, PA6, TIM_USE_VTOL_SERVO, 0, 0), // S10 for servo + DEF_TIM(TIM4, CH1, PB6, TIM_USE_VTOL_MOTOR, 0, 0), // S11 for motor +#else // Vtol target specific mapping end there + //Non votl target start from here + .........omitted +#endif + DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), // 2812LED D(1,2,5) + DEF_TIM(TIM11, CH1, PB9, TIM_USE_BEEPER, 0, 0), // BEEPER PWM + + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), //RX2 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 softserial1_Tx +}; +``` +### target.h + +Then define `ENABLE_MIXER_PROFILE_MCFW_HOTSWAP` to enable mixer_profile hot switching once you have set the pwm mapping +```c +#ifdef MATEKF405TE_SD_VTOL +#define ENABLE_MIXER_PROFILE_MCFW_HOTSWAP //Enable hot swap +#define MATEKF405TE_SD //Define the original target name keep its original configuration such as USBD_PRODUCT_STRING +#endif +``` + +## Configuration +### Profile switch +Setup the FW mode and MC mode separately in two different mixer profile, + +I will use FW mode as mixer_profile 1, and MC as mixer_profile 2 as example. +At current state, inav-configurator do not support mixer_profile, some of the settings have to be done in cli + +`set mixer_pid_profile_linking = ON` to enable pid_profile auto handling. It will change the pid_profile index according to mixer_profile index on fc boot and mixer_profile hot switching(recommended) +``` +mixer_profile 1 #switch to mixer_profile by cli + +set platform_type = AIRPLANE +set model_preview_type = 26 +set motorstop_on_low = ON # motor stop feature have been moved to here +set mixer_pid_profile_linking = ON # enable pid_profile auto handling(recommended). +save +``` +Then finish the airplane setting on mixer_profile 1 + +``` +mixer_profile 2 + +set platform_type = TRICOPTER +set model_preview_type = 1 +set mixer_pid_profile_linking = ON # also enable pid_profile auto handling +save +``` +Then finish the multirotor setting on mixer_profile 2. + +You can use `MAX` servo input to set a fixed input for the tilting servo. speed setting for `MAX` input is available in cli. + +It is recommended to have some amount of control surface (elevon/elevator) mapped for stabilization even in MC mode to get improved authority when airspeed is high. + +**Double check all settings in cli by `diff all` command**, make sure you have correct settings. And see 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 +Normally 'transition input' will be useful in MC mode to gain airspeed. +Servo mixer and motor mixer can accept transition mode as input. +It will move accordingly when transition mode is activated. + +The use of Transition mode is recommended to enable further features/developments like failsafe support. Map motor to servo output, or servo with logic condition is not recommended +#### servo +38 is the input source for transition input, use this to tilt motor to gain airspeed. + +example:Add servo 1 output by +45 in speed of 150 when transition mode is activate for tilted motor setup +``` +# rule no; servo index; input source; rate; speed; activate logic function number +smix 6 1 38 45 150 -1 +``` + +#### motor +the default mmix throttle value is 0.0, It will not show in diff command when throttle value is 0.0(unused), which motor will stop. +- 0.0fM6}k72;) zA5YML*BV*&K;Z46$2-}#530tgc7ZRCZ6uT>9z3W`!n!s?1-@gr%ISGLc!1k?|Mzgf zrPT7l17kyZDG5y<7Y`S$*H zcB?x1BSjNS<_?Xo4rlBG`^AWz%0XI=ELWr*M3vE4!;F~3(V@@iObMQ0EDXBW-Rub4 zz%1Pbb}Ug<#xH}~ohMkCY__qv5tm~wFn`9fnNZ`az4GcDx|DGo^4DN;0{p)vh7}Hn zkE`umF}N|&|4RZ{7JZ5T`2l{)(*kgA^gkl^l(|U(b4yjLM0^L|7w7qPA*3HKMj2QKWpHRrk>zB@bb@vyVb)ZBW}M2 z@sW+4ojrN!DJh8(VQ6L-$Lr@loXfst6$IYyz5nUqjk1vuHOOT(@wx1)9OeNEF%fi& zfkf$d?>=&G=`PDdzn5149nK+Y_nJqa!xQ!_NPiA=cTyuZ?kZ|5TO9XuLt%C2tGd+z z1``vtza~NDB_XSfwDdxR($j^xh=7dy-xIug)Xy?dn7mPthx}cb6w0^>Wjna&Y zZWf1b<|D$lMlQQFz^H&1dis=s$58=W#DiB?SDm>7a7ElBZD583e-e?N zi3@uj)DXHw$}hrKlMwBc{LWObU%x(pH#&&BuAqJ^!Rz(i$=!)>oa$p{_;x>41bWaA zQzs`ja|;VD*R^iYgS68`oiBq{%^4b6S`o#?j0{XnOH0DWe7r+ zfwJyx&YeDUUeZndZbM};#m;UAg8q&QPXQVe9X;q~6)N$%@8{2-Ohw6EXZLCs#0N&D zdT_D_Nq>Jpv%kIcD2afOFz0KYh7MpGev4Y5=4LY4L@K*B3VfJuN^wcab7A47EI^N4 zoZz)I148@bv@^g$`j)CLuF^ZfTbC^D@|^oR^&*|_ekL3yK&Qc+wP+?|%^L-`eFz$F zrO7P+#oD4=`Nd1Gj4er4MwOi3z$FZE*P)=5DUxtQzP zhh;V}YsQpc8}M`dl<~~WJ}|>q0#Y0bp3+KGnlrDg_0snCc1aywF;PAyrV=)Jpy^a^ zlc39@)yMhOLAlK%)Z9egs#G6xW@XyzH=okHIu`IK;Jo}}b^*U&u;iOrkEq;wIZhr+ z8y_ztA&*kP{gJB-{xWYNfUH`xfnJOo$2*_B)Gfwvk#P zIvjBd@}$T0NqqcfHg3e}!P+rnjpICVH@+I^X7=XDaYG}GIPb2~ZjA`GOy6@g==N<+ zF{2~0j9?;AJHp;U^zg_s-G!P#dP^3*x3lF_RDmid2cBcHUb|Y48C2dzZ_v+Q{@{ta zyAgR(b2dWvz#76_k<{d{8e01GxplfFD z>v;Gf^7H4!BSm>g!mOWR3ULyZg9Hu^&4Gwo3=>Gl+< zI>@XKO(~PJC(HfB)kr~6QC&~ZE+aFOOzSs2!P7o0LZ4R21Sr%no=ULJDbMADy|MoY zYiczs?1AUq?M<_lGXCd^rUqR&>grI_Qt*`Q2q~a6JBxm@6`!aqoR#_t;@a8nR1c50 z^z6XRg{>EI=5$8zNINTGLWI9#>ZYp+y-V`aBV@-FB&;=AVlfrn2Cfu{TxHx}ljP<{ zP@>DCB%JAXu5)6_;Px36TGV>zkgurHglEe_3QE5aAsj0QvUV)jLF%xoZ+7h~p2D$05h4)k7( zu8(2u&68Q`Egzm@m0?I=2^0NoX=C15C7B2(ehbE!F2as0=)_l43A3>Y(Cwx&?apY{ zX1sJdV#OaXl~LIpqC#VACg5{yx`d;-@aP?JOZ4Ln+;gSU9vv}Wr|DAla{&}E>~U!n zZo293nhJ}^8#j*Bh=;GRh)GDye@0U9=zsO7=ZzT>uDg>t`wVOge|T9SoLso6UR*!l z;7ku0$ z#(`5(*OTV50XsE^8h`qbuRH;kj!E$GNJ1}3P?Q+|`AWpH($BB0f9!qTMv`R_weG$1jlQwqQJ1bxtfxx3aB8!IV(bi)+0P0`Xy!t^ zca!ds;>5wR;6jPz`kc}%wP5HSb7J3E>S9J0x6{)gQ4daQnYs096CTsy-7wCU{wtMi zJoDWU8Gqjrq2PQC7dDqbL6OZmp@5*q8+M1A5`+CC$1oK_ZZ6!&T5c~o*kFj zuqnst{;?pXJKgt8S*3vUQ{_Nd6(;+uJqd@{k&vxszCC?b@wIr$kYZ%r>dq0j(MWq& zAG8Ln?PYJrL~qn@`eT~3xa!Yl$WL4Ys5i^q!OIbOE+B8AfRNY4|UTzF-^Z~lguMhqAbDO9NiLeu__iTu`z)Sp68OK^J6N({Cdcno<4TXwQNyL0&1v4Xq&SZ|{$Z$69adau0{JM%DU zy7=_4`K*A;XaB@ZHyJ;nu1>$*cTm1rFF!RqHDq-wp|_f;dxiH?`*FpIQ*0{<8 zM^#jD8SHWcnqC8JWfBq^JOl+5M@v8A_dw|%(jyr^`BjAV3)N^47MfMtE%_z(IB5Is ze#BNfIAL3@K;dD;)ff<1z5DatkUw@v%?6aDF;KF3g%9ukso$=lNxK*$EF8i|n9s`L z+~%j&eoZ*~N4epQNIdu#j?WPJnSK&_rQJ>izYgo{dWgUE#^R1*&gFVcT5}5l1N|g1 ztb4-b>2HJlKhigoX%oK~{98pQe6`g77Qwv!7(ueI`9iT)g1+}UI%4(pKFW#xB@a*S zYLzC9ycUYQnsgceT#H5*G`;0lNGTL`F{Xgi_tzU> zT9Ik5(eb*i1mWj3>PG5e#KJ5!Q1&#RrUHx9){A*tuxz90+=@Hv4gH|#as{<0-T2}{ z((GD`>PU`1*!KlP|8tu+*aY_b$J>d0J}!-azjEwnQ*TyKuOQV(HXqmkv5JH4<$XH``Vq$ z`u^88Zch?Z5q(qRLze)r$0Lf8$Zn&%KR7P+55+*4T5;zCJ6*$bY$#a89N%g9h zqK07W8C))vu4w`Rn+gNV`C4#?>d+Y*#9m=BqBvO@3SY;kr9JN^%=j?kf&L6#dERS~ z!rK}dJ3$tWYH`VdXn{Kve*O@8eXi4NVL^O;A>WQ_NgXczf_UYqs}XzRKos5u> zBzBL;o!9MKI%YhY{YTE zlG`_rmHC$~NnadEF&Lip6K{%HRjLeDrUF}>)MH^ZjK&{wZt8=W%U~l17BO+%sN94% z_U1$)yq>x`BrlPaaf$;a>l>P1*516xLta0*^=u}GA5aL3p-Sd>do~X&>+N3nX%7Sy z^dni|3U1FuP(IeIeF_oaeZ&7wRfF1iK_kHl=cjTRCWj^d0U&KT|WBg^a+aL`OKK z3z2d6{68` zj3If2p_?$k>F~0W#GF&fYM>b3)M4h&%F;10;b2{4JtU$o?Jbw4@gX2^yPUU-_j1md zYawxDF9m0Bv8{kNYP8$i3m@&FBQZT~1XgG|cW2 z&2=0^GCfOMIK@RYQ-)Ixlr%J*#3_TVTE1sGx;$MecX?Lj4bqB2oH@*`wcM<1cR5+z zdCX3)oU9xrE_*Jujnl-%w0N)hmPnqA=Qb?0@%!)_09)|A#ISN9>W+*#ZtP@RxTpPT zq`rQw#TU*hWpU`fjntl=ncl1noVlnNN9JwB`Z+diA2~hVD-)g9SPH+HZNNilZ`=vb zJFenYwU*JK;;_A}c90oT#}lipSC$BUqkR|gS7%=;TFCv&Db?5QAao9w{*@D}Hf&P?iP<-~ zBD3B?hH+0dxL|z9zKIW{w}Zr#+)^sq0b=2FP^7mJ!Plu@Q)kUeiig8E8E}DIgNV z`x>3GtyL902e#j>4@KClArZ#WDdP+rVq;#6LFXf$wl}_OvtE!d5@DRdw*eJ~Ep?Us zMmF+ofyi^S-#@;N&kt#6XoT(U*#kNFbH?J4EPMPISC}(tyD0%FX;ec)!+H8d)!Xfv z{6cNfPaih|XMQ%PK0sWnt~XjzqM_u+|Z!HLJM$h*s18ThE=o@4i1+rqO(* zrZhP^j(~t*k>>4unw8=ayuG!&pdz>ecGmaD0wV4uEJ>g1&&IJ#zSnxV)MPQ9BRH-r zyML6_t3;J8u+O<1^!gyK+3PN@c_nuZi)VQ*5*^EGH1CBf$nz-?*{4$o^!h6&4ls_~!3N85+)>g;ej?qyin^F(DWi9P*EaP3ff`%RwN{0JE zp$C!ZT&H;s$57?mrqKN?0#=jXPIhyt=%$&@^?Nide|rJ?ke6;uH>=V6aPxhk9FIV+ zCE`ae`^_r)KhGc`ygqQ${j4+tZ)Rk}F7~062qUAWTxqQ_7!YP!lqm*Gva(s_M4i@5 z2%r$1I|+{MZt4xh9`lIiIOl$gsdqp|`)&gU*4R*a`zpZV^)P~Amn4e%!JAPtnbG`8)iMO`xpZS~v z!16vd3&TG(rzX#)f{lWL#H>d%@!eFpog5v(kvNo`X1$MXhKKrS3DPGg-?h!;M$6fd znREW$EN4EjpLmd_)Zs1?Dn+=Gx%FDWiVm%`Vqnx=?;@{L9|V{~GzXzW=6v`I%?)}+ z7<8lr`0qstI5)f@j{)Wr%9=ri7@YwYscNxtfQ_@S{w}wQ z3s!*2%k9f=Bxbe?yZ@3~N(*rvP~a976}9~6MNhxn|1?a3)?_SgxvcC}JQ-I3+siW? zwINX`A?!zFpY^5n1)!(%j`L>6`T&)qLw9K)(0RmF8yTZWL@Leq;vRnDxd&fwk}$ZH zKIm&`SePVpN_=$XwovfV~uGHS7dI7*%tQGj`p0DHzROKcoCqjgw84zLs{2KVMZ zY_t-p9S0AOdLyMD!)D{$M>{NG(uh@bixr1QN}Y9?lx+2`^YI=uCOD^mp~M4m!d2>q zL<{#uQ4GMta+b$9uP^OmF_f13$F7yVFVQ|T3V4!s4iLTG|BYHe2_l5eB?&@E%_VF@Z7E95Q{8plFX!xqQ{lK>pb)7&GUav*c-tqc@>Dm0 zNYe%!hZtRtarfWob@q4QPR|X!-KG2oECrIo$DyzfKOV>QgvtSVVYW@|(M}eE66Wcq znsJPXnsCVdn%H+g0!$0Md&T~9oy{W&La8fCzUrRXb(g%hOho3~n?3@;%u@fuH(}gp z{<=c|R4+*WsQ(4b?3AK{>~^~)&Ns;yhllm6{NF43D^%yba`*4f4XDnjJ9I>dW+dg- zOgUzN+qKc6ctv}Y?a59w$2?6n;q+c)lemenk!n}?uMyunh3M$;XD?vi z?iNAVzP_i&^8*7b`Nh`>{j=@;x}NjGd3Q}m>n#)QeI4ryZ3GCT>?o_H9E@qhuxp)+ zHIU0#{oGFL5^diiflXe2y#p%A(&_dlNOrEEc_GUTgHIJ$J@-PNP2fFQt=vM7CoDD} zoA|xWyuxTXn%PF6Fdbvn7n8pk;$Lvl5#=^l4;Mh1+k~z&OUMtug(5SwbUXZr^KP}N z@~%(yr{_;WYccsjp$m8hrz_V?Fp4%z?>mpC8ykro03^Q`xqF9v)yRf2V6g(5nYXnW zqKe2q_JXmFDtJQJE>%HIA4h^ugngX%ohvT7PE#^6qAr`f9O+2qwwdSFSNb!aEj4Kw zPWp^?_=vpT=qO~i$q%#3C+@u+yiV}BIdQQtPUNK`Oj6I782B{D*Q+vtn*Fb05x#1S z@a~REPs4~p&357W=rRm%74m1KxM!&FQa#>=)+Ej?&IGbIQx3nd>esC^k87G)$s@j4 z(Ne4dL4z#N;ev(9_!?n#VdIa3KReVQ8#8J*hj+%!f-^k3?c=W8iv7HOETl z8sGc%cQ1fz?aByT4_K>gtnqLfYpZozey>EEVLE|jIm}-L`NVVNdLF-!`A&1=a8bzl zVV<8Sm$l7&eJdU9$jM2v_hkUJuN8;0l@ zS;+T#E@2P!&X?$~Ba_|+eMREeBWwM4mO#tZhJ>9n51WWBUP=|p5ua&`*RjszXE%81)m z4shaOnskwR>jdBhBgcIla>GWkBphZdYE5>=a~-;dYa0^2H8tSLoBRkO$^ohF0AD$5 z#Xqi0icJeT72dLNb5D`)8R|ARTTH@Wr;+BvKfXn)F5)*mY(j0qXj0aV%a7LENjJYP zs&7jUzzW4HX`a37V}2Cla{Xw6z2)JlPf}a^WwVnn^Y+~~nv3`H1;)jS=v3|2xbI-w zwLSE5_q|ASxBMt-HfiXE#TVM}wf}8@2A^uP!EW~tdb|o05*xSFsA-n<_u_L6184tT z6#bSTGf(1uK*MrtxAfQAyf*+2v$SRn#C&&y)4k5_<%(2POZ)GSQc?_$rIj|S%E~as zZ{bO96QYPOAkb`>Rcn2V@FVB0f)%=Z7A}=N-tSF4}B<7YOa$h3vsXJvvAG z@uRD?OWMEI)4i>m_3nMIn=s^?B;PA7DneBiyJSGarJ7HdYP-GK$0y$EI9dWZE!Di= zeJA`AlJ2eq8_VKGKiwXa1j?$n=S^MfKnH~(36xQ%6XLW6AjcjQJdqC#4Lr!B7&aJ9 z(1n>&*6aRT;j5|q+i=M!-1TwcBdPcAd5nWDt&kp>0__(Yafj*tg)#|s1GK@{ZaF|U z>Q#^wd^+Y5M7Vl6?w$PUQ+RLhTaoj53!j}_?}LdVhpHCHEi^V3Qv?ns1Y9O>v1)!| zwo4~@NuFQXX;q^0^<0q6?_ZM|R+5CNOZfpOF`}b^$X+ZCsepiX(Qym&o2xThXJ<%_ zSs$mvEUUjz;BgQ7`87}nLSC$0yL$ZjtzKc&HY?UShS=nxNfkM7tM8b%_eMCoa z?wF2da-G+Ni{CDtKKi&o3q@ii(2CR8oAINymd#0xrb~2&!K)V??=&=or}<%rYi-q!7jb*eIWSzVn-G<8 zP-NJK90qt3zIKCHb=mLOZma(DO$8Sed?pJ!lI(=j!9_aU^7ZA_or@|#@HaaFnqwH8?Ug68qxOS9kJ|Qgc8MHUFnWjciG^5B9I87=Vq#+E8|+d=lf)m<2L4IuxO-h| zWMbmdm2olbrm_>znRJB5v@M&wI<@9DLOTtN!^^>+ORzQgF38ZWpV-M0r>P@c+`C%} z8YOmj?a}7EBL=<+K}IgnKB6}0ITyunVNBj}=@Q3YBd?%L(Ivg4u>o5|t}b79*1Be^ z)f_(kO?GfJ8dII^FPs?|G4=9?*Aq~%yw9l)X$v9>29^ebI(btOahlhb(H;56tIJA- zdDBDd+N7Q&v>&@HICTTas=6*y80iVT9py7}a^lzfqLzfY>*pAsF|)ISj(i8gaw|77 zZ7s?vUZdmg;7|)q-(rJ4VQue--?aoLwcTA$+<~P@jizU>66XonpFi@jaGo;Ajs zdXzlWfyLh3otKfCYQeOb>H15E6MtYfsJ*pYM`dUA^}>KVtYv3$KL|o@Ghg}SGMB!m zokhlC2J+TsbbTST$y>Si69b?i-{dMzVh0%eAR!Q+b zLu(E`88`<@^5>mHj|BzfI7<&~KSBRt>*&}J%vxVpci`sC4+=VT z^oQqVgrVWoRmT^Vlq}^BF?5CV=e_ixT|=b|L!udYWtaDNA|=0Au*`Qdt;ca;p}0fv zD@+31#8kD(6v zCLKRLj}eA}X@f54jDv4H+gg4@TRhoB5gnFjt3%^ZDWSGV58t~6oi)B51w&z zJYCsL9I=>8B*rjUOxblG!4@F&S2}Kizd0e*JXxa_@u|suvD12-wwW`I8M7QPW@GHP zTjaFLLhvbpGAX9IA_BSCYO{}iVLr|p@6o8wvf6-+SO$|g`DO<1Tj=gjYxKLYLJD@q zO#GAYM(J67Idq3vX$Y(IKQQa5WHjXLW(MkWDU5n3OhPtWkwGDf0R|Ttj{WH0=gig@ zn9ps88}1^?yY%DO3^i+fnaEj!VSP$_@Ti`H5fN>&csC)FvD&^%5wVNSr|cJnf&hFK zPb0dRwPE#0lTmnxs;vh^x=)WrUEvZvz}ZAvBJZ;~qdY4PdoV(Z!1EBPb;f(|h`NMe z2;hq8Z5=epz(m^;_J%cZ9JEO58xj2$*sSe28UwGyadg@;RgYpAeK~x3Kz2}lanl^w zoD01$A~!iH;B3OfYD&u@wH1E6)Wr~hS{8TxLQi1)hW+EF+-{D)$*z1Z70fe5SnS)I zzr5uSue9422ZY|E&GlLoDEMMLp%EB7pl?8}FWnyMHkR}_)sqq4KkK0MtA%?K+gYfO zW#zzc#2IABSIfeZT`qPq_}t6GnDL@D6w$nSb8&l;(KU~#0iZ2}>y$G8!c+^a-5d@u zu0VnOBp$@i4_+wuRCugHAV%W?_BHTI_tCCnA{!`6kQ|NkW#5Qb&Fy`Bd=lA2>2O}u zw6RC6YWm_X=DhtwQ5&iGPpa}d7L&LabH-6Si(>pAw%tFGCiVWtwh>{bEUZ}n?4D1O z6ooKTgxO{`JuKwh8=X)aBpL46&V5q>)vG-%6L!nD*+_hZsd~g|0ZD$jQKTnKedzeC=afCqgG=7@Be*P%;pr@Qh0FX>Wr?SI^PDv7f;00CoUUY7 z01MA7zu6)*k=&jyo0n|uwcr4I1C{k;XyCeF!V&+?#^v+(SGy%kn~t#~+8#>Xo~UgU zuS3ok9jX_G#BSNidcv4=S}+{+tu6GC+>(yW7LeylyF%H4D~?KwMxpMBU`vaYyR5i` z5t=@Wq@(WMyU+W|U#vzU8>A-PIJf!m_2XxE6L@9=XINZxkgRDOjGz6bRh}{dkF&ko zYplqFpI*3Pq8VP}Z_SVyH*)Ft1Z0&Pr9^v1x|HKeE-ALgRT_|KDrfVJ(cpoq9|NX+ zQX?$B@38W!FJq6M;}#Tn=wRZok2ahh1GSE?e&iG-S5e(!bZ^dNUY8Px&??S#gAC3Tr#KB?O{ zlzj6;{IF59{JP$66m1Re7g6HZblO#hcHVSrVb6U~EH>*#*!#jU2oFlyPePtPmx-@2 zX!DFr!@EmIr)sOI*=IEvtSx6ZSgLh!(7~mraa4MA@|EbCl7ta{(T%OG*|ZuY4Djfj ztA(-h^F~a0%;U2Y6=%DgR&A;RZtN`$#jsY;dLz*zTtp&ig^jFEJ8w8a4GpX9lzJJa zK@f!ss$lAE(2kd|)-|NMhV_;Y>Tl<7&;kR%N6EJzJdR9H6PaiTu|c|-RNI{cvjOei%LGrKo^dJT~hdJzL9lI6ZuAGZ+cGb^L|o7uYfm?Tuy&=?pUkt{c;5ucKuO3kK^!AoOE_g zdWGBu*vplCYRkVH}Ya zoK)A*0hqp0MQ33qiPhEG$5+fBSCtnUo{h_j@X9(2-Qb7yRV!5WN%E__*_kPQ;lNW& zd~gansV6Qto?<2&Tm5c&s`AX3c}t%5C=HC6Td6*VW2(1)ik?!bBAB%NY*a-1ifZS* z2e;WOOn*K442>|mm{Qb$F*CapZOIs$bAB>xDXWJySYR3P)Hkfb(LX!sky&YS6 zXt6x1rL->`A>*mEtG)qS0wrzPZBfE#C;>{sD0p6M+jw8>AT&S_WBFMXwC%MW!;rtR z(>eJvC9H>V-#d@NgZ6a<5(ic2-f-!i%i`Kcy|>|$x%V+9wk#Akp5@Z0g<4?zZ3sxR z2JpjpNt86=&|semxM2|sQh|ZmW}`oxz#yuAg|{|oS9|%d0Ht7jqwh^9V78$0KeXzV zjL)aBxNp~ks&2NY$Vu`>>nW8pc%kO%b>i-;B$c6P`&`P74K^wS`=_PQ0Vgt5xz z%R>~P26d*N*F+xZ@~Nwq3~!yCwI!6i%DkfetV`Wve>Dd=xn-fZf^2p@qgOg6GM{ld z0#AA;K3k73ciU05F&j8itZ^L@`6S-;L>0$4^o5G|+{PT~rVdVA&HHgN)|N}VoU81T znlF8lR~Ic!W)a-8&J?hKAdGFn7R{=q-d-1rGd99@!qNc3^c!;w?EvktPuwJ?@W8mm zRF9tRe}Q4T@IWC~P9Wt*R@b9j4F4EE5+{uTQI+)-8Yt%0rj~OM{F{e-qwY=MZ8oFj z1t26|Bd>R(m%^81{*{(rCDkZEi8XzX*JPs(W~~&~d4A;9lc%J z>3`?)^jcuAw0~2lF-ZRh!0}(VmU^4~pHBSu$k6xT_CJCl@xN?F?H(SwN96yKl&4?+ z8yxJjp+08oYl|jshRK$>lgV7Vf8A~HV^-EKwxmSicMDPifKj~-~?-B^9NJ$*vXm% zYFTzA$#-^s`3Ixk2J^mpHOy|QVvB4|K600mdZ|Y3CW85$odAD#RqX0_;g=x+Z!F=? zqY;j-_YgnXe_(K*4SN;+G5JcttV2a>L6{YF(pI$G-M3abDXCT<6ztslF`2k*W;2mD zlU}j85Ad!youRt^IrArp!E*+!1Gzb_z)Q5;FD|CCe-XP==LsW5RF#w(P+02Og?ve3 zSj*yo+6+2UuJx&3RsFY=BP!()Puw_()+i&)wbK!SQjg;(K%rn`=H6 z98M8nB`OwhaSWPe>MY`L1Ih<31fy3otVz{5D{~{HDL+gTT{=Iz{iS&7PDHcC$8qRX zBHN+T#RGDJh%^|N@|bkBgpxneWL5QPNVL=KL@aB1zfvf1=i^! zb{$5=(cyd^IoW=1fU*AZ21;gLO-MOGaj^y99E0%th^;9L4|n&)kMEThxqJ~@875cC z$CrEFF>M#4JWx^3r^S#a^PSFjA{TaS!#TcL3t7#`gAf6>VvKBW8i-30!-kExT zt{$?z5|7mp=NMqID(2M@VHfv)8N^ACdrQHWt~2`;Dx?Ns0wMUSs=oKPnP{$k??v-D zVE&mYz@7E-8^!gG1G4j{vX2Lnj&*s}woBN1R1GRhhw+kmAdGhIIbu{P zz(w=5JG#{K&hMyJjW`#_BkmRUO8tj~=+9bPX^7=x$Ov8Td}Wns9EIlN-4nVHq;*YK>f%oO*WhR$}3|LD+>66oZ%|k*)CD-B{5yK3io~)^@z4(HW zQKqLT`mv?To3WwNl#t>ujitRR?vT8fiZ|?T8K2V&_6d4-G2RWgxMydAh|*qR3nS#M|{1JCJ?tmuZ?;Ob#fC5N_IyHgje ze=mbb?&EHx4JWQPwN?<|ISa&lS04HA+3ERMo;=_o$}r#kD#a?qLfpbOy94mVX^9hZ zq)bnD&})0I^18%WP}Qw?FPfOp!Zs^u&o6wGXlw(cKBEy$Hx+#S8P?Irl_~7?z%+0L z;H~%B+2Hg!wZNlY-iu9P8o8tOKj&Ut1PS8-Iokt%qhzPb>NDT7S-xe>P^P2Sano3KS@03Qtx0S zFs|5KoMus4?3dymcImGpXQopph40pNj{HJ~vYAMQpFNov!A(zJAB`cr2L1lnY17(& zC05#-|3)>H_sVkvcZ{a}#0?|;;Ov1NireZaU30**;O0bSsOTRF!7>O=-|{Bmx}a{1 zx4A}5_Z4jaMDaL|qwqKktFFe>l+gIHluQw`qjGUjB{?_k(Wg)AO#6wZHjB@${kBa< z|lP4H!XE*2SBi9O={aBaO;%yZ47gO~TcxU}St)*QtuzpTUpybYm!_o<^ zf5oA-p)OZXkVhL<1-*a1a)Xe#wzLTxIC98kcUHVOh8k>^z__Oq3M3w;n0 z&|5cU11zb}jvYw=otCbt^U>1h0Yy zv4?TB%`P)m*z@@I(K!b`doSsQRep@2^dRKw&az?v_dm;9wl>gTw>wwa2hEdxb9KWz1 z6^7t=(>T@V#8o3f5)Px}#P7iI7cI>MPpf5QZM-V^2Lld@uqJi{NRx%7ygxfiB$_rS zJ}av>y4s;z80k=x5L5Gh-`@(f>QUXJk;H$_|3!!nUne&`l4|bg64r}ZQM1j<@M2@% zW^3(8Ckb55RP;w6B!h}JA-q&ulb@%sbtp>?NBQNM?&<=j^*h1>(`q9{ZoZ>R2?<4P z>qO-Nt19G01jD}>=O6X{*Nk)3x&O*Ie^}J=itV0po~jni^sVzu-ej7?=u%0gu4L&n zM~9d=?U-%cZG3Zu=Im#hUtwG8NmlMm3Q*nqd|~M>#+EMMI>O#I4I>!|UxEJyQR$Os zZ8HWKE9cyR#4z?n}S6lP*OqW08*GZNe$=o_Qq+C)@UlHY}Y&Po7UR_xQt`suZC zIOgt^b>?;C=>MbaOj1|#T}Y9EV&%I?oAcQ|5u(O}ANWvs5cx`_o%D9{!)AL+#FR$f z=RzNIC$97i9u$<1Zqm+}?jH%cxLF>4uVi~!di>=J$NOKI_*%h?Q6ZiN|+1Oo1HZ)t!mgrO7o)2~QXubj|*pMicLHxL@7 z@A+326#Aq^EE&hDao%t$_9EOC%+G7;;f6AwI+YI|4QUQ~Pw9^Lo)m@;i$p3=nHMAL<=LNugFihWxsxx342c4d7m{$;h5bQC3t zN_`0>MdtSUJR)hlK7M@wp&q0)o3=3)O9C!oFw-w?8=_RJX?iq*@L!9GaVJRR64-B` z(+yA&Vppi|lvQ{=J{B!q#ykIGK6LRz%xE_zp21S%;$oHE_h$G3oo+Iu_$GX~kxjYM^do|-sS<{TK&~~-NV!XSrvgZ|A*NS-8vLZER{sv{`sBpI6lnn480Ly;pXV+dY^L&tW(# zWB(#a&?}C19JI|T1~00^u+QR4USQU;jR~mf$0b++Cp{M*sY*T*c~n@ zN7_g1t6aKi_WkE(d~3GW)Z35scuy*i+y?dTlDf*kg$BcLFKL#&rxB4?GL9@;-nFx< zR|nP(lr#Fl*)C3nV_IY99eV+*I@(%M{D|3ST~)+ZGqXGTQ>*{*+6{6$VnG|j=SM?G zTv&y(jFSbSm)_B;&wSXMmg%b2|6{hgffm~5|2J%Ph^M#=e#$ebQMXSI13Npeot@nw zTfR}mXt}s-rQgdJ{m2RrgsV;_7N4e`UW^vHugTm?G3=GAOYRZuc1Qf({KX{a+qvN- zgXer@#HW$c5mH9e^YcEVufy03q`}leR4v zc;rDxdIk*JbNT#miOXi3%BG_53?XaAn5dlNndvM}elBg;b|-Ckq;ib<8RpOz7F{Q1 zZM45^YZA+EH&C+Rg)sIj?x*&gorL`-btnPOnF9PMK%6zxxc9FQqI8fb`&9wIBbBEmnlH&ZIDL7!tUbcZPz$IBq|=$ z{$?t0thsH|W-)ljI8Wo&H*hZR?UE`lFYiLcs+QC@6AMx63=$x2iGDR+%RxVxl;w;V z8*6Xt2p3-7R8eW}>>My^#!B;t0*4yE02CEZPtWr)RSOG?L+wa<`VdaAsi@gooK9RS zfttR+B51YDm)4?kM4EdP9~B>4#4;kS)l&n9LcgFL(d=L#3*3?c>f=D@VnpOby>l)K zD=>i1H+)JijVmiFTTJiMQNe34#K#Z2&(#!whf5TDRt-iyQ@ESV^@jqFM_|hNhx3k> za?g4H0O@5Kc~wJ{Qe|3d=G-af_vg2TO8PPYKDEFm>D&;;Ton2rAS4b#gkH1n^EO!A zmE}2J31or+0+4ue3)R$H z=@?-QJ5hP)*3OOv@GpD>kA@htZC@l#CZ|~__tq~nwUJ&XQutotU#$3JsZZ6#3@=_R zFpXI55hG&UO>&z*A46C(9Ewj!t_1Ljir*uY0Qht~xx@geWgew? z>ZRPrIS<_sEc~wX?GAXz#an#TY;GRT z0&MnNxTu*`px5!5#Ql-^!^f9Wd92z014W)dKVTmPK;H;(eS(FP1`59!i5LCD!;ciIV*G#AoOwLd`@hG}X;Ds#Wh|94iKr}-oRYm0LPd3yCA%q- zj4d-9+lg%1l9X*|S6PRQ!Jx4X(Wr#MFc@Z%!3;6RnDP5e%Q@%%9`|wYANSrr?)U%i zcb4z>`+2-S@Avch(u}h|ed<17_jrbR;o?!(H}%DFEG*5;6_rVVTuzzK&_3^>sq$_oU4K5Jey+KP&mm-TveTVFhtW-!-kjOw zkvqS1HM0RUX~#=W39r)D4(Ryryn6JkC=5{QD(y349)f4JVQ2n$n^0cMGI(~|-i+EH zoyGzkQ0r1wkCdYP-15KAy>xtQeYSh+P-%Ee?z-Bqki29FB`9UT2ZcXi8#cAmT8wKY z3qIsw!JAv=`3@Bx$xg>jfBWr*)A0oCIlqTXzA}JrzseI|XgP97g)ozT0sAXkot}4w zE;u7NdG1`=KXLa#$d`XW@=yJSPP|OCDmpuu3ZU?m zl&tjM1CLMnlJO#{fJUEjABH=x-EwN&_0de_+AXAQOt-zWd(J$ld2MjbIa<1js*lo~ z)hxXc3rvkQ=e|xStoEU%Bm?I@BlsWw6E5CltMIS<00n;~n0u())d`tMDAWl#tWt>< zUM*4>D3kW0WRh%>(BLJhv!+MlI~6aSLZsyhBWRYN0$s7z-1Q+g`8b=Z_8oU0H+(q# zGOy^&nS0$Ah=IJDn}jZbT+mD~Lb1m*P2nT{(~a5Tqo}j}-{wdbtCc?6=jQ06 znAFrdBTE456^A5ZK9`~NSAD5Xf%zeEp-mO2y)(5(#5%A#kmuDR+)@pK4>jAfv@58} zD7JDhNk7pOz`$6>TcS^DiK%~uR+Hpc4q8a3ngDg>iAzp^sXQ{QOnR3!s>QChM#7rp zcS0RfKQD#wOXircL&az%o;3f(7Sg&V>!>?-V{jZ;Vc8!G2lV;HNAsyF>!p;n32VZIqHM1re zZs;~ty~$7G%CVOxsIB;&-bafH};US}l-KZEi%4^bq1=ey25*|KGpoztz&^F6cnF{ zT;6~d75v)g%JGK5i5cCR!#mVr`;7A_jm2P5l) z^>s42+MbAQ;rx9`x83WzH98w#Cf8yn>I`s~miKusTZltaldL`ANcz^Wb6YQMhQ_QM z=O}t`;2e_m?F@;quW)@a6rGo(YWAwCjd8F*I0C*|{@f-}ivrgYNa$8|ckSAiT1ed5 z{G`*Qxy1y@iEE|XT!R%7-@ppbp6y{*7pio7gRH8vFdv6l{DQ1I7%($cUKuV%Q{Ai= z7lN<1>tA}Xvrxup9i@KVd@SpRR7mjZN{`*I)wHr{)&aGMb+`^eEr}H<>rSm2Sgn6{ z5ISK&)4Uqbc^Uq;MA~kyLnLe#rtKOQXn2o5VxJW8?qaH&yi|PzY^G#MUa*K}_v&uQ zl8q9oLk%RfUSC88+)K{F*9&^5{sDjAQJ;M9>I&(2rMjo#&jSZe@NGRjo@sroF1rfC zhlYk2TUzcuw2;VurHELI*o1%}a>`_kBq~ViEla07Q3_m{bxt8cdq&(yFXth&%=@DB7m5F>hU^WBrdemBxVB@SE1CLS}|Ncbl7p{V8t1cJN}x(PnN`6P^O1!WqW#hKq$;^un%CI zo(|5nmL@!;N6;oABw=75vIv$0FmPe=xg6 zc2J!o^k7qs1WUA|v-o+Y33Qd7LtRm>pGVK`-oIZI>?MMk7$OVc^yK_geU5?2{Ay`w z>EN*h6|iJpJ)Lj3OPd;|Wo58%p5e4>XsMJ>de{E6;7zQua+MKx91@zzTa1x)jt8=1 zXfCmNd12~3g_7jf6zc|_$;Io-Bhg|^uBN8uBAdV+rGI+=*sc~?93GZ4OZ3uL4q>7^ zLoq!wGeg6=^SOZ}0+_Nf-9#f-su=5)DvWR($PS|jeUk2!T4?4Ej+z497TuX=Ah%Xz zv){8nviR;}%?UmWCzX0l>xtX5;O%};ZvYtL1oiAtVC*8F`%(r8C>POh@Xzp)@2mqr zsyDQxNyZat1m0`|wKw!F>MP!PZS`|1g&G$|Gad^KOCEDl=&KN2`}XrWO{WhCHU0 z-k(_C=r651zs>;^< zh-I(ZfB~Gpq72MANwpL&Sv7=|1AZxU1_u&~%Bic#zF|#P$L926YUi|N6k)SRiqry> zapOihUD;KexuoFyLe=IsJci<|MW5u>(#A2ozIXMm4!mbB=WbC8yy{|Py0%y!|Jr(F zUx>-n&bV!rAT^u%l zw0ULYT<8vc1UFhYV7v|C15-BR%u-WTOK^{hOGdHxS&Xfj@w|87cOv?xDRDR>KkC81 znCiFd=2oUTaX;%v2PuA&8G<`mwK-I683g1P?5;JtqWNeYc2J=2hKf?Z9qYgQ41&*l zID&U*+&;%tEzu+f(KvQ9h654Q=6HSl0Vx^Jp*D*oiZv~08+|Y_8B0;01YCk<*pgqU zr^n*JIwi0fSu~gpE~~h(6XJ92f-(K|DE^^w+(16zUI1YQ+=8lEe@^}?Hy`)uQR2Ww zs)R%1WdKHG&0^rhfho6(KOL$@5!TC+=K}%)n3r}!QXDrZkC6vbZDp6B^H@?#*;XecPfLI8uCx9^xr=U*=bC7 zYyaGXoa=LNCVq&4u%@#hMOlB5@V#Fy1TRlLwVSI2h0E$eG9D5~Ja+Qrt?;CG`wMcT zva@&ah__2I7|f#PYks;BHckwRGHhLv-nQ^i$GT87b|C*bhMe0Wwy z#^uz&TFipC=U^fSzw_5Cx5F>185j%+PAhZw;@Kuyyq{p?Z4_;C`Jkiv;?NI?!6nIl z+ik5BSN>Syd`NktU1R*Knl`Hc33{g6W`-&mxv`3>EvVHpRQL}l{9NN>uVjh8!D^h* zZ5ZaQFlId_tR)WQ0<+jeBk9j!n#uInl2kCaIlGs;@-4pk= z`zbGGjs((fjKiLf6ZAk-fZi!m(5Naf1*9cwx!GO#FCR_~*4rxWlhc-mxY%#vR0ehR zim_U9?YA+mR@&5iZJ()4P#>5(xY|oB>wQshi)xo-+LhC=xO+9r)NamMWq-vhHg2Zg zW#kU&BHK3NPg$%}R5i2Gv0NJZ#5pd;vw&Rj`!hbwk>7Li+UO(jrnTE~1EC(jry6bc zaG_%wU6Z=GS5tP87;FMG&W`|n%bjPyzkGU6l7c}V9O}2Aleb{&>|`}RxrQ6-$5z)J zwQQ6tMU)HtH`vwVA~R_TL7_iX1q-QOQ$fx7gZrq}fd%1iUFsh`KRQO-p1LK%S9#Gn zjBTnHa@pz=;Dud@u8}RX#ObE#@z&WlOLt^rs>AJY#hv(Lg9>E9-ci-FPUEolM*kU9 z+D@~R3<~e0kX$WIq_7p%>xx9T#N7ZOAWVp5x1x(bY>Q_-lu$eU0I)aFQrPpf6z>S7 z%p$D>7}goSrwg6t;n%(0neEZ%fUKA(PjIsDcU(v_lgH%DA0qTggZnj0)(g{$jyEhe*Yn;XpQ7Y{V=$dQ?V)^pLxz8P>qOuHKaa|keNTGk@&OVXX!k}8i00H%VtD$0h5|7=BJWZ@nk`}rGWO$0wM*! z!4oU>c&ANOVpR|aud)kfKk)2JKgpT1@QDn^(~_A=n9qAeZ!T<}l3PShd3|>c{${hu zDl?f6;IY|nJ+_G8PLnX3)Z?;Vxw-^f(Rh{(!GewGh~>$}qd8;cJv$+OPK1)!(+}zZ z0go(CjqF$$xj{5>v*is}Ji1tUHG}_7RCywTH%J{2d$k+8W{l&ms%L|ATrDp@6ngZ~ z6W2GF?~hEQ(7d(_h{o)D{h7UjPH~4fnd~-X4ap;4TP_`W|3R*zW`8CplI~6`C$h*i zy)sq<{SU~M?G>1%7FoaORnM^Nr1aDb7&@xdWu$Iw^vv<=nlHW45>Ntt7wnpSD|DS< zZq(1RktQLBV{LsprR81dS8bKt(W8Seo8B$nnQ@J95@O)J58 z86HKD*_7Ty;Vc=q!{cndJ0n_D9VjRrbSeGh{puYuq6EBGEF$~q`~g}2KORiC__V9O zd*)SBU4A9IWN=3t4TI^CkO>!Ctd&f}jCc z^w(ts$L5zHK*jYHC7#+N;8k>}v5y#2Y{_@5{hutkH>QZ0kND(KI20yOXi|dCJpf*Z zPhDy(4Bu%MuYl`otQXkFuz7 zKvcKn5jkp(IPnIMOw7EQpJRWI=O%S}N!_KM5;0-CKeJ4$m>w)1z+KV9=JNQnkyIp9 zo#TmdP)|<{d%1V@-jLoB*;9F2LdK8*hXOaU$(d>kVq8d!m(Y^$h7H~n!_Kr0^z>&2 zVb8Q+r}wXn@Xz6TCJ)pur>!S#hIM&%jlPJ@@$0@ZF|1KhXOmRrvIeod9PCNCb9hJh zFN+}#-2PwAElo-#(PxFGlX&UfxhJWdlkPF3-sg0YvLY5Yy3M8_mxvJekXH>4Tx<9L zk9*g7mXT9XA`xwtd|aeJ`#!uo&fz_h|1?C~c`4GxbyQt@L)d4x2+%K^b6Hd0j6qz!X0 z^W#L6ys+Gyq0fw_5PpJolU_$VC34qZ$;NCLbk@(Jrx#bFL-w>6ELE5OdUD*A)x3;W zX{W@U9*r>m=Fi6G09j@p9Ri$ny>+@GO%hdWX(uCW5gSq}&H@MQ8c<}KXt6{w4piP- z-*)m%y`%*(D_HYkbMI&o%907MxgfM;s%oBBEFHWJ9@#SR$eNumY~Q%hm=uZ2p9+~< zVc(I6PfQ4CZCsnf1GRp|V))Fh#6(T64@x{b0q?S@vUJJ)!p~E5BOt-&)(fV=ILF;8tQ{sI8wJ zl#g0J7xA81Rk*dns;di$g0RW`=EKH>^C)*Kg4 zvDUi}(bPx{Ngti_ab{Kbbm1ztE=qra+RKkY7);~KLMG^gFz;RdAOURpwFHiu_ zt3IC_A*62YFYdVedS01{Q^#52{?gZ1SIW|)cCiy z;&(RxTkOV<{q_GP1^+hDoF{y&A({|*x0BN_F-`s;381ucOfVc+=Mp=9#> zuii;KXoOrvAZ!vr1k1N0O&rqm@#8-e)6IVtM9v?8R`2+%y8y!Hf3h&OGATLk8uc%c CTD3m_ literal 0 HcmV?d00001 diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index 5272c804b8..ec6b7a672f 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -111,6 +111,8 @@ typedef enum { TIM_USE_MC_CHNFW = (1 << 4), // Deprecated and not used after removal of CHANNEL_FORWARDING feature TIM_USE_FW_MOTOR = (1 << 5), TIM_USE_FW_SERVO = (1 << 6), + TIM_USE_VTOL_SERVO = (TIM_USE_FW_SERVO | TIM_USE_MC_SERVO), + TIM_USE_VTOL_MOTOR = (TIM_USE_FW_MOTOR | TIM_USE_MC_MOTOR), TIM_USE_LED = (1 << 24), TIM_USE_BEEPER = (1 << 25), } timerUsageFlag_e; diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index 98c0e87890..0cb6c22f83 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -99,7 +99,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = { { .boxId = BOXSOARING, .boxName = "SOARING", .permanentId = 56 }, { .boxId = BOXCHANGEMISSION, .boxName = "MISSION CHANGE", .permanentId = 59 }, { .boxId = BOXBEEPERMUTE, .boxName = "BEEPER MUTE", .permanentId = 60 }, - { .boxId = BOXMIXERPROFILE, .boxName = "MIXER RPROFILE 2", .permanentId = 61 }, + { .boxId = BOXMIXERPROFILE, .boxName = "MIXER PROFILE 2", .permanentId = 61 }, { .boxId = BOXMIXERTRANSITION, .boxName = "MIXER TRANSITION", .permanentId = 62 }, { .boxId = CHECKBOX_ITEM_COUNT, .boxName = NULL, .permanentId = 0xFF } }; diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index b77e39c0b8..ea46891440 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -105,14 +105,25 @@ int getThrottleIdleValue(void) static void computeMotorCount(void) { + static bool firstRun = true; + if (!firstRun) { + return; + } motorCount = 0; for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) { + bool isMotorUsed = false; + for(int j = 0; j< MAX_MIXER_PROFILE_COUNT; j++){ + if (mixerMotorMixersByIndex(j)[i]->throttle != 0.0f) { + isMotorUsed = true; + } + } // check if done - if (primaryMotorMixer(i)->throttle == 0.0f) { + if (!isMotorUsed) { break; } motorCount++; } + firstRun = false; } bool ifMotorstopFeatureEnabled(void){ diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index d0585a023f..926cab96a9 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -84,19 +84,19 @@ void mixerConfigInit(void){ } } -static int computeMotorCountByMixerProfileIndex(int index) -{ - int motorCount = 0; - const motorMixer_t* temp_motormixers=mixerMotorMixersByIndex(index)[0]; - for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) { - // check if done - if (temp_motormixers[i].throttle == 0.0f) { - break; - } - motorCount++; - } - return motorCount; -} +// static int computeMotorCountByMixerProfileIndex(int index) +// { +// int motorCount = 0; +// const motorMixer_t* temp_motormixers=mixerMotorMixersByIndex(index)[0]; +// for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) { +// // check if done +// if (temp_motormixers[i].throttle == 0.0f) { +// break; +// } +// motorCount++; +// } +// return motorCount; +// } // static int computeServoCountByMixerProfileIndex(int index) // { @@ -159,13 +159,13 @@ bool checkMixerProfileHotSwitchAvalibility(void) allow_hot_switch = 0; return false; } + //not necessary when map motor/servos of all mixer profiles on the first boot //do not allow switching if motor or servos counts are different // if ((computeMotorCountByMixerProfileIndex(0) != computeMotorCountByMixerProfileIndex(1)) || (computeServoCountByMixerProfileIndex(0) != computeServoCountByMixerProfileIndex(1))) - if ((computeMotorCountByMixerProfileIndex(0) != computeMotorCountByMixerProfileIndex(1))) - { - allow_hot_switch = 0; - return false; - } + // { + // allow_hot_switch = 0; + // return false; + // } allow_hot_switch = 1; return true; } diff --git a/src/main/target/MATEKF405TE/target.c b/src/main/target/MATEKF405TE/target.c index bee9ebee56..03c7d98807 100644 --- a/src/main/target/MATEKF405TE/target.c +++ b/src/main/target/MATEKF405TE/target.c @@ -27,19 +27,19 @@ timerHardware_t timerHardware[] = { #ifdef MATEKF405TE_SD_VTOL //With INAV firmware, DSHOT can not work on S3, S5,S7 because of DMA clash, pls use ONESHOT or MULTISHOT and calibrate ESC PWM range.<-copied from matek website - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2,7,7) UP217 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(2,2,0) UP217 - DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 D(2,6,0) UP256 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S4 D(2,1,6) UP256 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_VTOL_MOTOR, 0, 0), // S1 D(2,7,7) UP217 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_VTOL_MOTOR, 0, 0), // S2 D(2,2,0) UP217 + DEF_TIM(TIM1, CH3N, PB15, TIM_USE_VTOL_MOTOR, 0, 0), // S3 D(2,6,0) UP256 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_VTOL_MOTOR, 0, 1), // S4 D(2,1,6) UP256 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 D(1,7,3) UP173 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,1,3) UP173 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,6,3) UP173 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8 D(1,5,3) UP173 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_VTOL_SERVO, 0, 0), // S5 D(1,7,3) UP173 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_VTOL_SERVO, 0, 0), // S6 D(1,1,3) UP173 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_VTOL_SERVO, 0, 0), // S7 D(1,6,3) UP173 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_VTOL_SERVO, 0, 0), // S8 D(1,5,3) UP173 - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 DMA NONE - DEF_TIM(TIM13, CH1, PA6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 DMA NONE - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S11 D(1,0,2) + DEF_TIM(TIM12, CH1, PB14, TIM_USE_VTOL_SERVO, 0, 0), // S9 DMA NONE + DEF_TIM(TIM13, CH1, PA6, TIM_USE_VTOL_SERVO, 0, 0), // S10 DMA NONE + DEF_TIM(TIM4, CH1, PB6, TIM_USE_VTOL_MOTOR, 0, 0), // S11 D(1,0,2) #else DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2,7,7) UP217 DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(2,2,0) UP217 From a10d6cab5895f1e40841e879a4a2d34ad78a2b8f Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Tue, 25 Jul 2023 13:07:38 +0100 Subject: [PATCH 029/122] [mixer-profile] [doc] add some clarifications --- docs/MixerProfile.md | 162 ++++++++++++++++++++++++++++--------------- 1 file changed, 108 insertions(+), 54 deletions(-) diff --git a/docs/MixerProfile.md b/docs/MixerProfile.md index 3681fcc05c..08fcae804c 100644 --- a/docs/MixerProfile.md +++ b/docs/MixerProfile.md @@ -1,32 +1,51 @@ # MixerProfile -A MixerProfile is a set of motor mixer,servomixer,platform type configuration settings. -Currently Two profiles are supported expect f411 and f722. The default profile is profile `1`. +A MixerProfile is a set of motor mixer, servo-mixer and platform type configuration settings to enable VTOL transitions. -Switching between profiles requires reboot to take affect by default. But When the conditions are met, It allows inflight profile switching to allow things like vtol build. +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. + +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. + +Please note that this is an emerging / experimental capability that will require some effort by the pilot to implement. + +## Setup for VTOL + +- 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 change the source code `timerHardware` table to allow a consistent enumeration and thus mapping between MR and FW modes. +- For this reason, a **VTOL specific FC target is required**. This means that the pilot must build a custom target. In future there may be official VTOL FC targets. +- 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. -# Setup for vtol -- Need to keep motor/servo pwm mapping consistent among profiles -- FW and MC have different way to map the pwm mapping, we need to change `timerHardware`` for to make it have same mapping. -- A vtol specific fc target is required. There might more official vtol fc target in the future -- Set mixer_profile, pid_profile separately, and set RC mode to switch them ## FC target -To keep motor/servo pwm mapping consistent and enable hot switching. Here is MATEKF405TE_SD board (folder name `MATEKF405TE`) used for vtol as a example. -The target name for vtol build is MATEKF405TE_SD_VTOL, target folder name is MATEKF405TE. -when it is done, build your target and flash it to your fc,. +In order to keep motor and servo PWM mapping consistent and enable hot switching, the steps below are required. + +The following sections use a MATEKF405TE\_SD board (folder name `MATEKF405TE`) configured for VTOL as a example. + +The target name for VTOL build is `MATEKF405TE_SD_VTOL`, the standard target folder name is `MATEKF405TE`. + +### CMakeLists.text modifications + +#### Adding the VTOL target + +Add the VTOL target definition to `CMakeLists.txt`, i.e. the third line below. -### CMakeLists.txt ```c target_stm32f405xg(MATEKF405TE) target_stm32f405xg(MATEKF405TE_SD) target_stm32f405xg(MATEKF405TE_SD_VTOL) //new target added ``` -### target.c -It is **important** to map all the serial output to `TIM_USE_VTOL_MOTOR` or `TIM_USE_VTOL_SERVO` to ensure same mapping among MC mapping and FW mapping. +### target.c modifications + +Two new enumerations are available to define the motors and servos used for VTOL. + +It is **important** to map all the PWM outputs to `TIM_USE_VTOL_MOTOR` or `TIM_USE_VTOL_SERVO` to ensure consistency between the MR mapping and FW mapping. + +For example, add the new section, encapsulated below by the `#ifdef MATEKF405TE_SD_VTOL` ... `else` section : + ```c timerHardware_t timerHardware[] = { -#ifdef MATEKF405TE_SD_VTOL // Vtol target specific mapping start from there +#ifdef MATEKF405TE_SD_VTOL + // VTOL target specific mapping start from there DEF_TIM(TIM8, CH4, PC9, TIM_USE_VTOL_MOTOR, 0, 0), // S1 for motor DEF_TIM(TIM8, CH3, PC8, TIM_USE_VTOL_MOTOR, 0, 0), // S2 for motor DEF_TIM(TIM1, CH3N, PB15, TIM_USE_VTOL_MOTOR, 0, 0), // S3 for motor @@ -36,24 +55,29 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH3, PB10, TIM_USE_VTOL_SERVO, 0, 0), // S6 for servo DEF_TIM(TIM2, CH2, PB3, TIM_USE_VTOL_SERVO, 0, 0), // S7 for servo DEF_TIM(TIM2, CH1, PA15, TIM_USE_VTOL_SERVO, 0, 0), // S8 for servo - + DEF_TIM(TIM12, CH1, PB14, TIM_USE_VTOL_SERVO, 0, 0), // S9 for servo DEF_TIM(TIM13, CH1, PA6, TIM_USE_VTOL_SERVO, 0, 0), // S10 for servo DEF_TIM(TIM4, CH1, PB6, TIM_USE_VTOL_MOTOR, 0, 0), // S11 for motor -#else // Vtol target specific mapping end there - //Non votl target start from here - .........omitted + // VTOL target specific mapping ends here +#else + // Non VOTL target start from here + // .........omitted for brevity #endif DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), // 2812LED D(1,2,5) DEF_TIM(TIM11, CH1, PB9, TIM_USE_BEEPER, 0, 0), // BEEPER PWM - + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), //RX2 DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 softserial1_Tx }; ``` -### target.h -Then define `ENABLE_MIXER_PROFILE_MCFW_HOTSWAP` to enable mixer_profile hot switching once you have set the pwm mapping +Note that using the VTOL enumerations does not affect the normal INAV requirement on the use of discrete timers for motors and servos. + +### target.h modification + +In `target.h`, define `ENABLE_MIXER_PROFILE_MCFW_HOTSWAP` to enable `mixer_profile` hot switching once you have set the `timer.c` PWM mapping: + ```c #ifdef MATEKF405TE_SD_VTOL #define ENABLE_MIXER_PROFILE_MCFW_HOTSWAP //Enable hot swap @@ -61,80 +85,110 @@ Then define `ENABLE_MIXER_PROFILE_MCFW_HOTSWAP` to enable mixer_profile hot swit #endif ``` +Once the target is built, it can be flashed to the FC. + ## Configuration -### Profile switch -Setup the FW mode and MC mode separately in two different mixer profile, -I will use FW mode as mixer_profile 1, and MC as mixer_profile 2 as example. -At current state, inav-configurator do not support mixer_profile, some of the settings have to be done in cli +### 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 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: -`set mixer_pid_profile_linking = ON` to enable pid_profile auto handling. It will change the pid_profile index according to mixer_profile index on fc boot and mixer_profile hot switching(recommended) ``` -mixer_profile 1 #switch to mixer_profile by cli +#switch to mixer_profile by cli +mixer_profile 1 set platform_type = AIRPLANE set model_preview_type = 26 -set motorstop_on_low = ON # motor stop feature have been moved to here -set mixer_pid_profile_linking = ON # enable pid_profile auto handling(recommended). +# 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 airplane setting on mixer_profile 1 +Then finish the aeroplane setting on mixer_profile 1 ``` mixer_profile 2 set platform_type = TRICOPTER set model_preview_type = 1 -set mixer_pid_profile_linking = ON # also enable pid_profile auto handling +# also enable pid_profile auto handling +set mixer_pid_profile_linking = ON save ``` -Then finish the multirotor setting on mixer_profile 2. +Then finish the multi-rotor setting on `mixer_profile` 2. -You can use `MAX` servo input to set a fixed input for the tilting servo. speed setting for `MAX` input is available in cli. +Note that default profile is profile `1`. -It is recommended to have some amount of control surface (elevon/elevator) mapped for stabilization even in MC mode to get improved authority when airspeed is high. +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. -**Double check all settings in cli by `diff all` command**, make sure you have correct settings. And see what will change with mixer_profile. For example servo output min/max range will not change. But `smix` and `mmix` will change. +It is recommended to have some amount of control surface (elevon / elevator) mapped for stabilisation 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 -Normally 'transition input' will be useful in MC mode to gain airspeed. -Servo mixer and motor mixer can accept transition mode as input. -It will move accordingly when transition mode is activated. -The use of Transition mode is recommended to enable further features/developments like failsafe support. Map motor to servo output, or servo with logic condition is not recommended -#### servo -38 is the input source for transition input, use this to tilt motor to gain airspeed. +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. + +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 + +38 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: -example:Add servo 1 output by +45 in speed of 150 when transition mode is activate for tilted motor setup ``` # rule no; servo index; input source; rate; speed; activate logic function number smix 6 1 38 45 150 -1 ``` -#### motor -the default mmix throttle value is 0.0, It will not show in diff command when throttle value is 0.0(unused), which motor will stop. +#### 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. + - 0.0 Date: Wed, 26 Jul 2023 00:03:49 +0900 Subject: [PATCH 030/122] move ENABLE_STATE(FW_HEADING_USE_YAW) from navigation.c to mixer.c --- src/main/flight/mixer.c | 9 +++++++++ src/main/navigation/navigation.c | 21 --------------------- src/main/navigation/navigation.h | 1 - 3 files changed, 9 insertions(+), 22 deletions(-) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index ea46891440..1f144dc60c 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -182,6 +182,15 @@ void mixerUpdateStateFlags(void) } else { DISABLE_STATE(FLAPERON_AVAILABLE); } + if ( + currentMixerConfig.platformType == PLATFORM_BOAT || + currentMixerConfig.platformType == PLATFORM_ROVER || + navConfig()->fw.useFwNavYawControl + ) { + ENABLE_STATE(FW_HEADING_USE_YAW); + } else { + DISABLE_STATE(FW_HEADING_USE_YAW); + } } void nullMotorRateLimiting(const float dT) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 436c3c3796..780122e724 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -4177,18 +4177,6 @@ void navigationUsePIDs(void) ); } -void navigationInitYawControl(void){ - if ( - currentMixerConfig.platformType == PLATFORM_BOAT || - currentMixerConfig.platformType == PLATFORM_ROVER || - navConfig()->fw.useFwNavYawControl - ) { - ENABLE_STATE(FW_HEADING_USE_YAW); - } else { - DISABLE_STATE(FW_HEADING_USE_YAW); - } -} - void navigationInit(void) { /* Initial state */ @@ -4223,15 +4211,6 @@ void navigationInit(void) /* Use system config */ navigationUsePIDs(); - if ( - currentMixerConfig.platformType == PLATFORM_BOAT || - currentMixerConfig.platformType == PLATFORM_ROVER || - navConfig()->fw.useFwNavYawControl - ) { - ENABLE_STATE(FW_HEADING_USE_YAW); - } else { - DISABLE_STATE(FW_HEADING_USE_YAW); - } #if defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) /* configure WP missions at boot */ #ifdef USE_MULTI_MISSION diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index b6ff19f711..cf4289e14a 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -479,7 +479,6 @@ typedef struct { } navSystemStatus_t; void navigationUsePIDs(void); -void navigationInitYawControl(void); void navigationInit(void); /* Position estimator update functions */ From 167db6ec5913ec115aeda5b5e6a22f43e12b99ae Mon Sep 17 00:00:00 2001 From: shota Date: Thu, 27 Jul 2023 12:09:26 +0900 Subject: [PATCH 031/122] add sannity check in Platform specific RC modes, Add sanity check in mixer_profile switching --- docs/MixerProfile.md | 2 ++ src/main/fc/fc_core.c | 4 ++-- src/main/flight/mixer_profile.c | 7 +++++-- src/main/flight/pid.c | 2 +- src/main/flight/pid_autotune.c | 2 +- src/main/navigation/navigation.c | 6 +++--- 6 files changed, 14 insertions(+), 9 deletions(-) diff --git a/docs/MixerProfile.md b/docs/MixerProfile.md index 08fcae804c..e586cfc401 100644 --- a/docs/MixerProfile.md +++ b/docs/MixerProfile.md @@ -139,6 +139,7 @@ It is recommended to have some amount of control surface (elevon / elevator) map 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 @@ -171,6 +172,7 @@ mmix 4 -1.200 0.000 0.000 0.000 ### RC mode settings It is recommend that the pilot uses a RC mode switch to activate modes or switch profiles. +Profile files Switching is not available until the runtime sensor calibration is done. Switching is NOT available when navigation mode is activate or position controller is activate, including altitude hold. `mixer_profile` 1 will be used as default, `mixer_profile` 2 will be used when the `MIXER PROFILE 2` mode box is activated. Once successfully set, you can see the profiles / model preview etc. will switch accordingly when you view the relevant INAV Configurator tabs. Checking these tabs in the INAV Configurator will help make the setup easier. diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index b5bb2fc322..df194954c4 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -697,14 +697,14 @@ void processRx(timeUs_t currentTimeUs) #if defined(USE_MAG) if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) { - if (IS_RC_MODE_ACTIVE(BOXHEADFREE)) { + if (IS_RC_MODE_ACTIVE(BOXHEADFREE) && STATE(MULTIROTOR)) { if (!FLIGHT_MODE(HEADFREE_MODE)) { ENABLE_FLIGHT_MODE(HEADFREE_MODE); } } else { DISABLE_FLIGHT_MODE(HEADFREE_MODE); } - if (IS_RC_MODE_ACTIVE(BOXHEADADJ)) { + if (IS_RC_MODE_ACTIVE(BOXHEADADJ) && STATE(MULTIROTOR)) { headFreeModeHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw); // acquire new heading } } diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 926cab96a9..12fe15a1ee 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -14,6 +14,8 @@ #include "common/axis.h" #include "flight/pid.h" #include "flight/servos.h" +#include "navigation/navigation.h" +#include "navigation/navigation_private.h" #include "fc/fc_core.h" #include "fc/config.h" @@ -172,7 +174,8 @@ bool checkMixerProfileHotSwitchAvalibility(void) void outputProfileUpdateTask(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); - isInMixerTransition = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION); + 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))); + isInMixerTransition = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION) && (!navBoxModesEnabled) && ((posControl.navState == NAV_STATE_IDLE) || (posControl.navState == NAV_STATE_ALTHOLD_IN_PROGRESS)); outputProfileHotSwitch((int) IS_RC_MODE_ACTIVE(BOXMIXERPROFILE)); } @@ -201,7 +204,7 @@ bool outputProfileHotSwitch(int profile_index) } // do not allow switching when user activated navigation mode 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))); - if (ARMING_FLAG(ARMED) && navBoxModesEnabled){ + if (navBoxModesEnabled || IS_RC_MODE_ACTIVE(BOXNAVALTHOLD) || posControl.navState != NAV_STATE_IDLE){ // LOG_INFO(PWM, "mixer switch failed, navModesEnabled"); return false; } diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index eb9abb4b55..13a7c45d78 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -1067,7 +1067,7 @@ void FAST_CODE pidController(float dT) return; } - bool canUseFpvCameraMix = true; + bool canUseFpvCameraMix = STATE(MULTIROTOR); uint8_t headingHoldState = getHeadingHoldState(); // In case Yaw override is active, we engage the Heading Hold state diff --git a/src/main/flight/pid_autotune.c b/src/main/flight/pid_autotune.c index d9688f1e82..6b59f93117 100755 --- a/src/main/flight/pid_autotune.c +++ b/src/main/flight/pid_autotune.c @@ -130,7 +130,7 @@ void autotuneStart(void) void autotuneUpdateState(void) { - if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE) && ARMING_FLAG(ARMED)) { + if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE) && STATE(AIRPLANE) && ARMING_FLAG(ARMED)) { if (!FLIGHT_MODE(AUTO_TUNE)) { autotuneStart(); ENABLE_FLIGHT_MODE(AUTO_TUNE); diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 780122e724..091a124518 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -3789,14 +3789,14 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) } // CRUISE has priority over COURSE_HOLD and AH - if (IS_RC_MODE_ACTIVE(BOXNAVCRUISE)) { + if (IS_RC_MODE_ACTIVE(BOXNAVCRUISE) && STATE(AIRPLANE)) { 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)) { + if (IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD) && STATE(AIRPLANE)) { 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; } @@ -4373,7 +4373,7 @@ bool navigationRTHAllowsLanding(void) bool isNavLaunchEnabled(void) { - return IS_RC_MODE_ACTIVE(BOXNAVLAUNCH) || feature(FEATURE_FW_LAUNCH); + return (IS_RC_MODE_ACTIVE(BOXNAVLAUNCH) || feature(FEATURE_FW_LAUNCH)) && STATE(AIRPLANE); } bool abortLaunchAllowed(void) From 5242ad2b35219a387b566e3c8404a5ede214d7b2 Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 29 Jul 2023 02:05:04 +0900 Subject: [PATCH 032/122] mixer profile sitl support --- .gitignore | 3 ++- src/main/target/SITL/target.h | 3 +++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/.gitignore b/.gitignore index ea13b9f178..f23f0dfd9f 100644 --- a/.gitignore +++ b/.gitignore @@ -15,11 +15,12 @@ startup_stm32f10x_md_gcc.s .vscode/ cov-int* /build/ +/build_SITL/ /obj/ /patches/ /tools/ /downloads/ -/debug/ +/debug/ /release/ # script-generated files diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h index 5ec93c583c..5c829f6e7c 100644 --- a/src/main/target/SITL/target.h +++ b/src/main/target/SITL/target.h @@ -69,6 +69,9 @@ #define USE_GPS_FAKE #define USE_RANGEFINDER_FAKE #define USE_RX_SIM +#define ENABLE_MIXER_PROFILE_MCFW_HOTSWAP +#undef MAX_MIXER_PROFILE_COUNT +#define MAX_MIXER_PROFILE_COUNT 2 #undef USE_DASHBOARD From 1d34800388d4501d5a430c3b880dd1b7f5807c1d Mon Sep 17 00:00:00 2001 From: shota Date: Sun, 30 Jul 2023 22:36:24 +0900 Subject: [PATCH 033/122] initinal failsafe support for mixer profile --- src/main/fc/fc_core.c | 2 +- src/main/fc/settings.yaml | 24 +++ src/main/flight/failsafe.c | 49 ++++- src/main/flight/failsafe.h | 10 + src/main/flight/mixer.c | 2 +- src/main/flight/mixer_profile.c | 250 ++++++++++++++++++----- src/main/flight/mixer_profile.h | 30 ++- src/main/flight/servos.c | 2 +- src/main/io/osd.c | 2 + src/main/io/osd.h | 1 + src/main/io/osd_dji_hd.c | 2 + src/main/navigation/navigation.c | 40 +++- src/main/navigation/navigation.h | 4 + src/main/navigation/navigation_private.h | 1 + 14 files changed, 350 insertions(+), 69 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index df194954c4..9eea10e4aa 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -638,7 +638,7 @@ void processRx(timeUs_t currentTimeUs) bool canUseHorizonMode = true; - if ((IS_RC_MODE_ACTIVE(BOXANGLE) || failsafeRequiresAngleMode() || navigationRequiresAngleMode()) && sensors(SENSOR_ACC)) { + if ((IS_RC_MODE_ACTIVE(BOXANGLE) || failsafeRequiresAngleMode() || navigationRequiresAngleMode() || mixerATRequiresAngleMode()) && sensors(SENSOR_ACC)) { // bumpless transfer to Level mode canUseHorizonMode = false; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 9064ef63ad..01265e60c2 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1173,6 +1173,30 @@ groups: default_value: OFF field: mixer_config.PIDProfileLinking type: bool + - name: mixer_switch_on_fs_rth + description: "If set to on, mixer_profile will switch on failsafe RTH" + default_value: OFF + field: mixer_config.switchOnFSRTH + type: bool + - name: mixer_switch_on_fs_land + description: "If set to on, mixer_profile will switch on failsafe Landing" + default_value: OFF + field: mixer_config.switchOnFSLand + type: bool + - name: mixer_switch_on_fs_stab_timer + description: "If swith mixer_profile on failsafe is required, Wait for this many decisecond(0.1s) before using mixerTransition input for servo and motor mixer" + default_value: 0 + field: mixer_config.switchOnFSStabilizationTimer + min: 0 + max: 200 + - name: mixer_switch_on_fs_trans_timer + description: "If swith mixer_profile on failsafe is required, Activate MixerTransion mode for this many decisecond(0.1s) before the actual mixer_profile switch" + default_value: 0 + field: mixer_config.switchOnFSTransitionTimer + min: 0 + max: 200 + + - name: PG_REVERSIBLE_MOTORS_CONFIG type: reversibleMotorsConfig_t diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c index ab48fba2c6..71f5a74ec5 100644 --- a/src/main/flight/failsafe.c +++ b/src/main/flight/failsafe.c @@ -43,6 +43,7 @@ #include "fc/settings.h" #include "flight/failsafe.h" +#include "flight/mixer_profile.h" #include "flight/mixer.h" #include "flight/pid.h" @@ -430,8 +431,14 @@ void failsafeUpdateState(void) switch (failsafeState.activeProcedure) { case FAILSAFE_PROCEDURE_AUTO_LANDING: // Use Emergency Landing if Nav defined (otherwise stabilize and set Throttle to specified level). - failsafeActivate(FAILSAFE_LANDING); - activateForcedEmergLanding(); + if(mixerATUpdateState(FAILSAFE_LANDING)) + { + failsafeActivate(FAILSAFE_LANDING); + activateForcedEmergLanding(); + } + else{ + failsafeActivate(FAILSAFE_MIXER_SWITCHING); + } break; case FAILSAFE_PROCEDURE_DROP_IT: @@ -441,9 +448,16 @@ void failsafeUpdateState(void) break; case FAILSAFE_PROCEDURE_RTH: - // Proceed to handling & monitoring RTH navigation - failsafeActivate(FAILSAFE_RETURN_TO_HOME); - activateForcedRTH(); + if(mixerATUpdateState(FAILSAFE_RETURN_TO_HOME)) + { + // Proceed to handling & monitoring RTH navigation + failsafeActivate(FAILSAFE_RETURN_TO_HOME); + activateForcedRTH(); + } + else{ + failsafeActivate(FAILSAFE_MIXER_SWITCHING); + activateForcedAltHold(); + } break; case FAILSAFE_PROCEDURE_NONE: default: @@ -466,6 +480,31 @@ void failsafeUpdateState(void) } break; + case FAILSAFE_MIXER_SWITCHING: + //enters when mixer switching is required + if (receivingRxDataAndNotFailsafeMode && sticksAreMoving) { + mixerATUpdateState(FAILSAFE_RX_LOSS_RECOVERED); + failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED; + reprocessState = true; + } else { + if (armed) { + beeperMode = BEEPER_RX_LOST; + } + if (mixerATUpdateState(FAILSAFE_MIXER_SWITCHING)){ + failsafeActivate(FAILSAFE_RX_LOSS_DETECTED); //throw back to failsafe_rx_loss_detected to perform designated procedure + } + else + { + failsafeState.phase = FAILSAFE_MIXER_SWITCHING; //wait + } + if (!armed) { + failsafeState.receivingRxDataPeriodPreset = PERIOD_OF_30_SECONDS; // require 30 seconds of valid rxData + failsafeState.phase = FAILSAFE_LANDED; + reprocessState = true; + } + } + break; + case FAILSAFE_RETURN_TO_HOME: if (receivingRxDataAndNotFailsafeMode && sticksAreMoving) { abortForcedRTH(); diff --git a/src/main/flight/failsafe.h b/src/main/flight/failsafe.h index 7cd88acd59..015cd04045 100644 --- a/src/main/flight/failsafe.h +++ b/src/main/flight/failsafe.h @@ -97,6 +97,10 @@ typedef enum { * and transition into FAILSAFE_RX_LOSS_MONITORING immediately. This is * the first recovery phase enabled when failsafe_procedure = DROP. */ + FAILSAFE_MIXER_SWITCHING, + /* Failsafe is executing MIXER_PROFILE_SWITCHING. This phase is triggered + if a MIXER_PROFILE_SWITCHING is required by the failsafe process + */ FAILSAFE_RX_LOSS_MONITORING, /* This phase will wait until the RX connection is * working for some time and if and only if switch arming @@ -134,6 +138,12 @@ typedef enum { EMERG_LAND_HAS_LANDED // Emergency landing is active and has landed. } emergLandState_e; +typedef enum { + ALTHOLD_IDLE = 0, // Altitude hold is waiting + ALTHOLD_IN_PROGRESS // Altitude hold is activated +} altHoldState_e; + + typedef struct failsafeState_s { int16_t events; bool monitoring; // Flag that failsafe is monitoring RC link diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 1f144dc60c..9ba9a76441 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -618,7 +618,7 @@ void FAST_CODE mixTable(void) motor[i] = motorZeroCommand; } //spin stopped motors only in mixer transition mode - if (isInMixerTransition && currentMixer[i].throttle <= -1.05f && currentMixer[i].throttle >= -2.0f && (!feature(FEATURE_REVERSIBLE_MOTORS))) { + if (isMixerTransitionMixing && currentMixer[i].throttle <= -1.05f && currentMixer[i].throttle >= -2.0f && (!feature(FEATURE_REVERSIBLE_MOTORS))) { motor[i] = -currentMixer[i].throttle * 1000; motor[i] = constrain(motor[i], throttleRangeMin, throttleRangeMax); } diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 12fe15a1ee..cdfdf148d5 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -14,6 +14,7 @@ #include "common/axis.h" #include "flight/pid.h" #include "flight/servos.h" +#include "flight/failsafe.h" #include "navigation/navigation.h" #include "navigation/navigation_private.h" @@ -30,59 +31,69 @@ mixerConfig_t currentMixerConfig; int currentMixerProfileIndex; -bool isInMixerTransition; +bool isMixerTransitionMixing; +bool isMixerTransitionMixing_requested; +mixerProfileAT_t mixerProfileAT; PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1); void pgResetFn_mixerProfiles(mixerProfile_t *instance) { - for (int i = 0; i < MAX_MIXER_PROFILE_COUNT; i++) { + for (int i = 0; i < MAX_MIXER_PROFILE_COUNT; i++) + { RESET_CONFIG(mixerProfile_t, &instance[i], - .mixer_config = { - .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT, - .platformType = SETTING_PLATFORM_TYPE_DEFAULT, - .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, - .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only - .outputMode = SETTING_OUTPUT_MODE_DEFAULT, - .motorstopOnLow = SETTING_MOTORSTOP_ON_LOW_DEFAULT, - .PIDProfileLinking = SETTING_MIXER_PID_PROFILE_LINKING_DEFAULT - } - ); - for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) { + .mixer_config = { + .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT, + .platformType = SETTING_PLATFORM_TYPE_DEFAULT, + .hasFlaps = SETTING_HAS_FLAPS_DEFAULT, + .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, // This flag is not available in CLI and used by Configurator only + .outputMode = SETTING_OUTPUT_MODE_DEFAULT, + .motorstopOnLow = SETTING_MOTORSTOP_ON_LOW_DEFAULT, + .PIDProfileLinking = SETTING_MIXER_PID_PROFILE_LINKING_DEFAULT, + .switchOnFSRTH = SETTING_MIXER_SWITCH_ON_FS_RTH_DEFAULT, + .switchOnFSLand = SETTING_MIXER_SWITCH_ON_FS_LAND_DEFAULT, + .switchOnFSStabilizationTimer = SETTING_MIXER_SWITCH_ON_FS_STAB_TIMER_DEFAULT, + .switchOnFSTransitionTimer = SETTING_MIXER_SWITCH_ON_FS_TRANS_TIMER_DEFAULT, + }); + for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) + { RESET_CONFIG(motorMixer_t, &instance[i].MotorMixers[j], - .throttle=0, - .roll=0, - .pitch=0, - .yaw=0 - ); + .throttle = 0, + .roll = 0, + .pitch = 0, + .yaw = 0); } - for (int j = 0; j < MAX_SERVO_RULES; j++) { + for (int j = 0; j < MAX_SERVO_RULES; j++) + { RESET_CONFIG(servoMixer_t, &instance[i].ServoMixers[j], - .targetChannel = 0, - .inputSource = 0, - .rate = 0, - .speed = 0 + .targetChannel = 0, + .inputSource = 0, + .rate = 0, + .speed = 0 #ifdef USE_PROGRAMMING_FRAMEWORK - ,.conditionId = -1, + , + .conditionId = -1, #endif ); } } } -void mixerConfigInit(void){ - currentMixerProfileIndex=getConfigMixerProfile(); - currentMixerConfig=*mixerConfig(); +void mixerConfigInit(void) +{ + currentMixerProfileIndex = getConfigMixerProfile(); + currentMixerConfig = *mixerConfig(); servosInit(); mixerUpdateStateFlags(); mixerInit(); - if(currentMixerConfig.PIDProfileLinking){ + if (currentMixerConfig.PIDProfileLinking) + { LOG_INFO(PWM, "mixer switch pidInit"); setConfigProfile(getConfigMixerProfile()); pidInit(); pidInitFilters(); schedulePidGainsUpdate(); - navigationUsePIDs(); //set navigation pid gains + navigationUsePIDs(); // set navigation pid gains } } @@ -129,12 +140,119 @@ void mixerConfigInit(void){ // } // } +bool mixerATRequiresAngleMode(void) +{ + return mixerProfileAT.phase == MIXERAT_PHASE_TRANSITIONING; +} + +void setMixerProfileAT(void) +{ + mixerProfileAT.phase = MIXERAT_PHASE_TRANSITIONING; + mixerProfileAT.transitionStartTime = millis(); + mixerProfileAT.transitionStabEndTime = millis() + (timeMs_t)mixerConfig()->switchOnFSStabilizationTimer * 100; + mixerProfileAT.transitionTransEndTime = mixerProfileAT.transitionStabEndTime + (timeMs_t)mixerConfig()->switchOnFSTransitionTimer * 100; + activateForcedAltHold(); +} + +void performMixerProfileAT(int nextProfileIndex) +{ + abortForcedAltHold(); + isMixerTransitionMixing_requested = false; + outputProfileHotSwitch(nextProfileIndex); + mixerProfileAT.phase = MIXERAT_PHASE_IDLE; +} + +void abortMixerProfileAT(void) +{ + abortForcedAltHold(); + isMixerTransitionMixing_requested = false; + mixerProfileAT.phase = MIXERAT_PHASE_IDLE; +} + +bool mixerATUpdateState(failsafePhase_e required_fs_phase) +{ + //set mixer profile automated transition according to failsafe phase + //on non vtol setups , behave as normal + if ((!STATE(AIRPLANE)) && (!STATE(MULTIROTOR))) + { + return true; + } + if (!isModeActivationConditionPresent(BOXMIXERPROFILE)) + { + return true; + } + int nextProfileIndex = 0; + bool reprocessState=false; + do + { + nextProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT; + switch (mixerProfileAT.phase) + { + case MIXERAT_PHASE_IDLE: + //check if mixerAT is required + if ((required_fs_phase == FAILSAFE_RETURN_TO_HOME) && mixerConfig()->switchOnFSRTH) + { + if(!mixerConfigByIndex(nextProfileIndex)->switchOnFSRTH)//check next mixer_profile setting is valid + { + mixerProfileAT.phase=MIXERAT_PHASE_TRANSITION_INITIALIZE; + reprocessState = true; + } + } + else if ((required_fs_phase == FAILSAFE_LANDING) && mixerConfig()->switchOnFSLand) + { + if(!mixerConfigByIndex(nextProfileIndex)->switchOnFSLand)//check next mixer_profile setting is valid + { + mixerProfileAT.phase=MIXERAT_PHASE_TRANSITION_INITIALIZE; + reprocessState = true; + } + } + else + { + //return true if mixerAT condition is met or setting is not valid + return true; + } + break; + case MIXERAT_PHASE_TRANSITION_INITIALIZE: + setMixerProfileAT(); + reprocessState = true; + break; + case MIXERAT_PHASE_TRANSITIONING: + if (required_fs_phase==FAILSAFE_RX_LOSS_RECOVERED) + { + abortMixerProfileAT(); + reprocessState = true; + } + else + { + if (millis() < mixerProfileAT.transitionStabEndTime) + { + isMixerTransitionMixing_requested = false; + } + else{ + isMixerTransitionMixing_requested = true; + } + if (millis() > mixerProfileAT.transitionTransEndTime) + { + performMixerProfileAT(nextProfileIndex); + reprocessState = true; + //transition is done + } + } + break; + default: + break; + } + } + while (reprocessState); + return true; +} + bool checkMixerProfileHotSwitchAvalibility(void) { static int allow_hot_switch = -1; - //pwm mapping maps outputs based on platformtype, check if mapping remain unchanged after the switch - //do not allow switching between multi rotor and non multi rotor if sannity check fails - if (MAX_MIXER_PROFILE_COUNT!=2) + // pwm mapping maps outputs based on platformtype, check if mapping remain unchanged after the switch + // do not allow switching between multi rotor and non multi rotor if sannity check fails + if (MAX_MIXER_PROFILE_COUNT != 2) { return false; } @@ -161,26 +279,44 @@ bool checkMixerProfileHotSwitchAvalibility(void) allow_hot_switch = 0; return false; } - //not necessary when map motor/servos of all mixer profiles on the first boot - //do not allow switching if motor or servos counts are different - // if ((computeMotorCountByMixerProfileIndex(0) != computeMotorCountByMixerProfileIndex(1)) || (computeServoCountByMixerProfileIndex(0) != computeServoCountByMixerProfileIndex(1))) - // { - // allow_hot_switch = 0; - // return false; - // } + // not necessary when map motor/servos of all mixer profiles on the first boot + // do not allow switching if motor or servos counts are different + // if ((computeMotorCountByMixerProfileIndex(0) != computeMotorCountByMixerProfileIndex(1)) || (computeServoCountByMixerProfileIndex(0) != computeServoCountByMixerProfileIndex(1))) + // { + // allow_hot_switch = 0; + // return false; + // } allow_hot_switch = 1; return true; } -void outputProfileUpdateTask(timeUs_t currentTimeUs) { - UNUSED(currentTimeUs); - 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))); - isInMixerTransition = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION) && (!navBoxModesEnabled) && ((posControl.navState == NAV_STATE_IDLE) || (posControl.navState == NAV_STATE_ALTHOLD_IN_PROGRESS)); - outputProfileHotSwitch((int) IS_RC_MODE_ACTIVE(BOXMIXERPROFILE)); - +bool isNavBoxModesEnabled(void) +{ + return 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))); } -//switch mixerprofile without reboot +void outputProfileUpdateTask(timeUs_t currentTimeUs) +{ + UNUSED(currentTimeUs); + + // transition mode input for servo mix and motor mix + if (failsafePhase() == FAILSAFE_IDLE) + { + isMixerTransitionMixing_requested = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION) && (!isNavBoxModesEnabled()); // update BOXMIXERTRANSITION_input + } + isMixerTransitionMixing = isMixerTransitionMixing_requested && ((posControl.navState == NAV_STATE_IDLE) ||(posControl.navState == NAV_STATE_ALTHOLD_IN_PROGRESS)); + + if (failsafePhase() == FAILSAFE_IDLE) + { + // do not allow switching when user activated navigation mode + if (!isNavBoxModesEnabled()) + { + outputProfileHotSwitch((int)IS_RC_MODE_ACTIVE(BOXMIXERPROFILE)); + } + } +} + +// switch mixerprofile without reboot bool outputProfileHotSwitch(int profile_index) { static bool allow_hot_switch = true; @@ -199,24 +335,26 @@ bool outputProfileHotSwitch(int profile_index) // LOG_INFO(PWM, "invalid mixer profile index"); return false; } - if (areSensorsCalibrating()) {//it seems like switching before sensors calibration complete will cause pid stops to respond, especially in D,TODO + if (areSensorsCalibrating()) + { // it seems like switching before sensors calibration complete will cause pid stops to respond, especially in D,TODO return false; } - // do not allow switching when user activated navigation mode - 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))); - if (navBoxModesEnabled || IS_RC_MODE_ACTIVE(BOXNAVALTHOLD) || posControl.navState != NAV_STATE_IDLE){ - // LOG_INFO(PWM, "mixer switch failed, navModesEnabled"); - return false; - } - if (!checkMixerProfileHotSwitchAvalibility()){ + if (!checkMixerProfileHotSwitchAvalibility()) + { // LOG_INFO(PWM, "mixer switch failed, checkMixerProfileHotSwitchAvalibility"); return false; } - if (!setConfigMixerProfile(profile_index)){ + if (posControl.navState != NAV_STATE_IDLE) + { + // LOG_INFO(PWM, "mixer switch failed, navState != NAV_STATE_IDLE"); + return false; + } + if (!setConfigMixerProfile(profile_index)) + { // LOG_INFO(PWM, "mixer switch failed to set config"); return false; } - stopMotorsNoDelay(); + stopMotorsNoDelay(); // not necessary, but just in case something goes wrong. But will a short period of stop command cause problem? mixerConfigInit(); return true; } diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index 25d4e79362..d145b949ce 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -1,7 +1,7 @@ #pragma once #include "config/parameter_group.h" - +#include "flight/failsafe.h" #include "flight/mixer.h" #include "flight/servos.h" @@ -17,6 +17,10 @@ typedef struct mixerConfig_s { uint8_t outputMode; bool motorstopOnLow; bool PIDProfileLinking; + bool switchOnFSRTH; + bool switchOnFSLand; + int16_t switchOnFSStabilizationTimer; + int16_t switchOnFSTransitionTimer; } mixerConfig_t; typedef struct mixerProfile_s { mixerConfig_t mixer_config; @@ -26,9 +30,31 @@ typedef struct mixerProfile_s { PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); + +//mixerProfile Automated Transition PHASE +typedef enum { + MIXERAT_PHASE_IDLE, + MIXERAT_PHASE_TRANSITION_INITIALIZE, + MIXERAT_PHASE_TRANSITIONING, + MIXERAT_PHASE_DONE, +} mixerProfileATState_t; + +typedef struct mixerProfileAT_s { + mixerProfileATState_t phase; + bool transitionInputMixing; + timeMs_t transitionStartTime; + timeMs_t transitionStabEndTime; + timeMs_t transitionTransEndTime; + bool lastTransitionInputMixing; + bool lastMixerProfile; +} mixerProfileAT_t; +extern mixerProfileAT_t mixerProfileAT; +bool mixerATRequiresAngleMode(void); +bool mixerATUpdateState(failsafePhase_e required_fs_phase); + extern mixerConfig_t currentMixerConfig; extern int currentMixerProfileIndex; -extern bool isInMixerTransition; +extern bool isMixerTransitionMixing; #define mixerConfig() (&(mixerProfiles(systemConfig()->current_mixer_profile_index)->mixer_config)) #define mixerConfigMutable() ((mixerConfig_t *) mixerConfig()) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 4b421d4118..e310545670 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -321,7 +321,7 @@ void servoMixer(float dT) input[INPUT_STABILIZED_THROTTLE] = mixerThrottleCommand - 1000 - 500; // Since it derives from rcCommand or mincommand and must be [-500:+500] - input[INPUT_MIXER_TRANSITION] = isInMixerTransition * 500; //fixed value + input[INPUT_MIXER_TRANSITION] = isMixerTransitionMixing * 500; //fixed value // center the RC input value around the RC middle value // by subtracting the RC middle value from the RC input value, we get: diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 63312af46c..b0be974385 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -945,6 +945,8 @@ static const char * osdFailsafePhaseMessage(void) case FAILSAFE_LANDING: // This should be considered an emergengy landing return OSD_MESSAGE_STR(OSD_MSG_EMERG_LANDING_FS); + case FAILSAFE_MIXER_SWITCHING: + return OSD_MESSAGE_STR(OSD_MSG_MIXER_SWITCHING_FS); case FAILSAFE_RX_LOSS_MONITORING: // Only reachable from FAILSAFE_LANDED, which performs // a disarm. Since aircraft has been disarmed, we no diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 2dad5ceb81..ab608caf6f 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -88,6 +88,7 @@ #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_MIXER_SWITCHING_FS "(FS MIXER SWITCHING)" #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" diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index e79ddc0dfd..72cfc781aa 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -558,6 +558,8 @@ static char * osdFailsafePhaseMessage(void) case FAILSAFE_LANDING: // This should be considered an emergengy landing return OSD_MESSAGE_STR("(EMRGY LANDING)"); + case FAILSAFE_MIXER_SWITCHING: + return OSD_MESSAGE_STR("(MIXER SWITCHING)"); case FAILSAFE_RX_LOSS_MONITORING: // Only reachable from FAILSAFE_LANDED, which performs // a disarm. Since aircraft has been disarmed, we no diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 091a124518..7ffa8c3388 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -3740,6 +3740,11 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) } } + // Failsafe_Altitude hold for vtol transition (can override MANUAL) + if (posControl.flags.forcedAltHoldActivated && canActivateAltHold) { + return NAV_FSM_EVENT_SWITCH_TO_ALTHOLD; + } + // Failsafe_RTH (can override MANUAL) if (posControl.flags.forcedRTHActivated) { // If we request forced RTH - attempt to activate it no matter what @@ -3789,14 +3794,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; } @@ -4193,6 +4198,7 @@ void navigationInit(void) posControl.flags.forcedRTHActivated = false; posControl.flags.forcedEmergLandingActivated = false; + posControl.flags.forcedAltHoldActivated = false; posControl.waypointCount = 0; posControl.activeWaypointIndex = 0; posControl.waypointListValid = false; @@ -4316,6 +4322,34 @@ emergLandState_e getStateOfForcedEmergLanding(void) } } + +/*----------------------------------------------------------- + * Ability to mixer_profile(vtol) switch on external event + *-----------------------------------------------------------*/ +void activateForcedAltHold(void) +{ + posControl.flags.forcedAltHoldActivated = true; + navProcessFSMEvents(selectNavEventFromBoxModeInput()); +} + +void abortForcedAltHold(void) +{ + // Disable emergency landing and make sure we back out of navigation mode to IDLE + // If any navigation mode was active prior to emergency landing it will be re-enabled with next RX update + posControl.flags.forcedAltHoldActivated = false; + navProcessFSMEvents(NAV_FSM_EVENT_SWITCH_TO_IDLE); +} + +altHoldState_e getStateOfForcedAltHold(void) +{ + /* If forced emergency landing activated and in EMERG state */ + if (posControl.flags.forcedAltHoldActivated && (navGetStateFlags(posControl.navState) & NAV_CTL_ALT)) { + return ALTHOLD_IN_PROGRESS; + } else { + return ALTHOLD_IDLE; + } +} + bool isWaypointMissionRTHActive(void) { return (navGetStateFlags(posControl.navState) & NAV_AUTO_RTH) && IS_RC_MODE_ACTIVE(BOXNAVWP) && @@ -4373,7 +4407,7 @@ bool navigationRTHAllowsLanding(void) bool isNavLaunchEnabled(void) { - return (IS_RC_MODE_ACTIVE(BOXNAVLAUNCH) || feature(FEATURE_FW_LAUNCH)) && STATE(AIRPLANE); + return IS_RC_MODE_ACTIVE(BOXNAVLAUNCH) || feature(FEATURE_FW_LAUNCH); } bool abortLaunchAllowed(void) diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index cf4289e14a..2bae5f8a72 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -588,6 +588,10 @@ void activateForcedEmergLanding(void); void abortForcedEmergLanding(void); emergLandState_e getStateOfForcedEmergLanding(void); +void activateForcedAltHold(void); +void abortForcedAltHold(void); +altHoldState_e getStateOfForcedAltHold(void); + /* Getter functions which return data about the state of the navigation system */ bool navigationInAutomaticThrottleMode(void); bool navigationIsControllingThrottle(void); diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index 0598467d28..096fac5426 100644 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -103,6 +103,7 @@ typedef struct navigationFlags_s { // Failsafe actions bool forcedRTHActivated; bool forcedEmergLandingActivated; + bool forcedAltHoldActivated; /* Landing detector */ bool resetLandingDetector; From e46ccfe7d5536bce377e869e31f597c9fdea1e6b Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 31 Jul 2023 00:17:10 +0900 Subject: [PATCH 034/122] minor bug fix on failsafe mixertransition --- src/main/flight/failsafe.c | 1 - src/main/flight/mixer_profile.c | 36 ++++++++++++++++++--------------- 2 files changed, 20 insertions(+), 17 deletions(-) diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c index 71f5a74ec5..e244392ffe 100644 --- a/src/main/flight/failsafe.c +++ b/src/main/flight/failsafe.c @@ -456,7 +456,6 @@ void failsafeUpdateState(void) } else{ failsafeActivate(FAILSAFE_MIXER_SWITCHING); - activateForcedAltHold(); } break; case FAILSAFE_PROCEDURE_NONE: diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index cdfdf148d5..8207bb0835 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -147,10 +147,17 @@ bool mixerATRequiresAngleMode(void) void setMixerProfileAT(void) { - mixerProfileAT.phase = MIXERAT_PHASE_TRANSITIONING; mixerProfileAT.transitionStartTime = millis(); - mixerProfileAT.transitionStabEndTime = millis() + (timeMs_t)mixerConfig()->switchOnFSStabilizationTimer * 100; - mixerProfileAT.transitionTransEndTime = mixerProfileAT.transitionStabEndTime + (timeMs_t)mixerConfig()->switchOnFSTransitionTimer * 100; + if (isMixerTransitionMixing && STATE(MULTIROTOR)) + { + mixerProfileAT.transitionStabEndTime = mixerProfileAT.transitionStartTime; + } + else + { + mixerProfileAT.transitionStabEndTime = mixerProfileAT.transitionStartTime + (timeMs_t)currentMixerConfig.switchOnFSStabilizationTimer * 100; + } + mixerProfileAT.transitionTransEndTime = mixerProfileAT.transitionStabEndTime + (timeMs_t)currentMixerConfig.switchOnFSTransitionTimer * 100; + mixerProfileAT.phase = MIXERAT_PHASE_TRANSITIONING; activateForcedAltHold(); } @@ -171,6 +178,7 @@ void abortMixerProfileAT(void) bool mixerATUpdateState(failsafePhase_e required_fs_phase) { + //return true if mixerAT condition is met or setting is not valid //set mixer profile automated transition according to failsafe phase //on non vtol setups , behave as normal if ((!STATE(AIRPLANE)) && (!STATE(MULTIROTOR))) @@ -182,15 +190,17 @@ bool mixerATUpdateState(failsafePhase_e required_fs_phase) return true; } int nextProfileIndex = 0; - bool reprocessState=false; + bool reprocessState; do { + reprocessState=false; nextProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT; switch (mixerProfileAT.phase) { case MIXERAT_PHASE_IDLE: + // LOG_INFO(PWM, "MIXERAT_PHASE_IDLE"); //check if mixerAT is required - if ((required_fs_phase == FAILSAFE_RETURN_TO_HOME) && mixerConfig()->switchOnFSRTH) + if ((required_fs_phase == FAILSAFE_RETURN_TO_HOME) && currentMixerConfig.switchOnFSRTH) { if(!mixerConfigByIndex(nextProfileIndex)->switchOnFSRTH)//check next mixer_profile setting is valid { @@ -198,7 +208,7 @@ bool mixerATUpdateState(failsafePhase_e required_fs_phase) reprocessState = true; } } - else if ((required_fs_phase == FAILSAFE_LANDING) && mixerConfig()->switchOnFSLand) + else if ((required_fs_phase == FAILSAFE_LANDING) && currentMixerConfig.switchOnFSLand) { if(!mixerConfigByIndex(nextProfileIndex)->switchOnFSLand)//check next mixer_profile setting is valid { @@ -206,29 +216,22 @@ bool mixerATUpdateState(failsafePhase_e required_fs_phase) reprocessState = true; } } - else - { - //return true if mixerAT condition is met or setting is not valid - return true; - } break; case MIXERAT_PHASE_TRANSITION_INITIALIZE: + // LOG_INFO(PWM, "MIXERAT_PHASE_IDLE"); setMixerProfileAT(); reprocessState = true; break; case MIXERAT_PHASE_TRANSITIONING: + // LOG_INFO(PWM, "MIXERAT_PHASE_IDLE"); if (required_fs_phase==FAILSAFE_RX_LOSS_RECOVERED) { abortMixerProfileAT(); - reprocessState = true; } else { - if (millis() < mixerProfileAT.transitionStabEndTime) + if (millis() > mixerProfileAT.transitionStabEndTime) { - isMixerTransitionMixing_requested = false; - } - else{ isMixerTransitionMixing_requested = true; } if (millis() > mixerProfileAT.transitionTransEndTime) @@ -237,6 +240,7 @@ bool mixerATUpdateState(failsafePhase_e required_fs_phase) reprocessState = true; //transition is done } + return false; } break; default: From 310bb097a5bdc533fc6ebf4a1ddc5f37a5d03e63 Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 31 Jul 2023 03:12:25 +0900 Subject: [PATCH 035/122] modification on airmodes --- src/main/fc/fc_core.c | 4 ++-- src/main/flight/mixer_profile.c | 1 + 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 9eea10e4aa..a7e1cf5352 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -737,7 +737,7 @@ void processRx(timeUs_t currentTimeUs) } else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER) { if (throttleIsLow) { - if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { + if (STATE(AIRMODE_ACTIVE)) { if ((rollPitchStatus == CENTERED) || (ifMotorstopFeatureEnabled() && !STATE(FIXED_WING_LEGACY))) { ENABLE_STATE(ANTI_WINDUP); } @@ -756,7 +756,7 @@ void processRx(timeUs_t currentTimeUs) } else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER_ONCE) { if (throttleIsLow) { - if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { + if (STATE(AIRMODE_ACTIVE)) { if ((rollPitchStatus == CENTERED) && !STATE(ANTI_WINDUP_DEACTIVATED)) { ENABLE_STATE(ANTI_WINDUP); } diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 8207bb0835..1875cb4bfc 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -92,6 +92,7 @@ void mixerConfigInit(void) setConfigProfile(getConfigMixerProfile()); pidInit(); pidInitFilters(); + pidResetErrorAccumulators(); schedulePidGainsUpdate(); navigationUsePIDs(); // set navigation pid gains } From 384439a809f10f4bc9e0cb8f3ab3375b29eea68f Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 31 Jul 2023 23:25:00 +0900 Subject: [PATCH 036/122] automated transition --- src/main/flight/failsafe.c | 13 +-- src/main/flight/mixer_profile.c | 66 ++++++------- src/main/flight/mixer_profile.h | 10 +- src/main/navigation/navigation.c | 115 ++++++++++++++++++++--- src/main/navigation/navigation.h | 6 +- src/main/navigation/navigation_private.h | 9 +- 6 files changed, 156 insertions(+), 63 deletions(-) diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c index e244392ffe..2fa27cff14 100644 --- a/src/main/flight/failsafe.c +++ b/src/main/flight/failsafe.c @@ -431,7 +431,7 @@ void failsafeUpdateState(void) switch (failsafeState.activeProcedure) { case FAILSAFE_PROCEDURE_AUTO_LANDING: // Use Emergency Landing if Nav defined (otherwise stabilize and set Throttle to specified level). - if(mixerATUpdateState(FAILSAFE_LANDING)) + if(mixerATUpdateState(MIXERAT_REQUEST_LAND)) { failsafeActivate(FAILSAFE_LANDING); activateForcedEmergLanding(); @@ -448,7 +448,7 @@ void failsafeUpdateState(void) break; case FAILSAFE_PROCEDURE_RTH: - if(mixerATUpdateState(FAILSAFE_RETURN_TO_HOME)) + if(mixerATUpdateState(MIXERAT_REQUEST_RTH)) { // Proceed to handling & monitoring RTH navigation failsafeActivate(FAILSAFE_RETURN_TO_HOME); @@ -482,19 +482,16 @@ void failsafeUpdateState(void) case FAILSAFE_MIXER_SWITCHING: //enters when mixer switching is required if (receivingRxDataAndNotFailsafeMode && sticksAreMoving) { - mixerATUpdateState(FAILSAFE_RX_LOSS_RECOVERED); + mixerATUpdateState(MIXERAT_REQUEST_ABORT); failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED; reprocessState = true; } else { if (armed) { beeperMode = BEEPER_RX_LOST; } - if (mixerATUpdateState(FAILSAFE_MIXER_SWITCHING)){ + if (mixerATUpdateState(MIXERAT_REQUEST_NONE)){ failsafeActivate(FAILSAFE_RX_LOSS_DETECTED); //throw back to failsafe_rx_loss_detected to perform designated procedure - } - else - { - failsafeState.phase = FAILSAFE_MIXER_SWITCHING; //wait + reprocessState = true; } if (!armed) { failsafeState.receivingRxDataPeriodPreset = PERIOD_OF_30_SECONDS; // require 30 seconds of valid rxData diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 1875cb4bfc..779a6c7f11 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -143,41 +143,31 @@ void mixerConfigInit(void) bool mixerATRequiresAngleMode(void) { - return mixerProfileAT.phase == MIXERAT_PHASE_TRANSITIONING; + return (mixerProfileAT.phase == MIXERAT_PHASE_TRANSITIONING) || (mixerProfileAT.phase == MIXERAT_PHASE_STAB_AND_CLIMB); } void setMixerProfileAT(void) { mixerProfileAT.transitionStartTime = millis(); - if (isMixerTransitionMixing && STATE(MULTIROTOR)) - { - mixerProfileAT.transitionStabEndTime = mixerProfileAT.transitionStartTime; - } - else - { - mixerProfileAT.transitionStabEndTime = mixerProfileAT.transitionStartTime + (timeMs_t)currentMixerConfig.switchOnFSStabilizationTimer * 100; - } + mixerProfileAT.transitionStabEndTime = mixerProfileAT.transitionStartTime + (timeMs_t)currentMixerConfig.switchOnFSStabilizationTimer * 100; mixerProfileAT.transitionTransEndTime = mixerProfileAT.transitionStabEndTime + (timeMs_t)currentMixerConfig.switchOnFSTransitionTimer * 100; - mixerProfileAT.phase = MIXERAT_PHASE_TRANSITIONING; - activateForcedAltHold(); + activateMIXERATHelper(); } void performMixerProfileAT(int nextProfileIndex) { - abortForcedAltHold(); + abortMIXERATHelper(); isMixerTransitionMixing_requested = false; outputProfileHotSwitch(nextProfileIndex); - mixerProfileAT.phase = MIXERAT_PHASE_IDLE; } void abortMixerProfileAT(void) { - abortForcedAltHold(); + abortMIXERATHelper(); isMixerTransitionMixing_requested = false; - mixerProfileAT.phase = MIXERAT_PHASE_IDLE; } -bool mixerATUpdateState(failsafePhase_e required_fs_phase) +bool mixerATUpdateState(mixerProfileATRequest_t required_action) { //return true if mixerAT condition is met or setting is not valid //set mixer profile automated transition according to failsafe phase @@ -196,12 +186,16 @@ bool mixerATUpdateState(failsafePhase_e required_fs_phase) { reprocessState=false; nextProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT; + if (required_action==MIXERAT_REQUEST_ABORT){ + abortMixerProfileAT(); + mixerProfileAT.phase = MIXERAT_PHASE_IDLE; + } switch (mixerProfileAT.phase) { case MIXERAT_PHASE_IDLE: // LOG_INFO(PWM, "MIXERAT_PHASE_IDLE"); //check if mixerAT is required - if ((required_fs_phase == FAILSAFE_RETURN_TO_HOME) && currentMixerConfig.switchOnFSRTH) + if ((required_action == MIXERAT_REQUEST_RTH) && currentMixerConfig.switchOnFSRTH && STATE(MULTIROTOR)) { if(!mixerConfigByIndex(nextProfileIndex)->switchOnFSRTH)//check next mixer_profile setting is valid { @@ -209,7 +203,7 @@ bool mixerATUpdateState(failsafePhase_e required_fs_phase) reprocessState = true; } } - else if ((required_fs_phase == FAILSAFE_LANDING) && currentMixerConfig.switchOnFSLand) + else if ((required_action == MIXERAT_REQUEST_LAND) && currentMixerConfig.switchOnFSLand && STATE(AIRPLANE)) { if(!mixerConfigByIndex(nextProfileIndex)->switchOnFSLand)//check next mixer_profile setting is valid { @@ -221,28 +215,26 @@ bool mixerATUpdateState(failsafePhase_e required_fs_phase) case MIXERAT_PHASE_TRANSITION_INITIALIZE: // LOG_INFO(PWM, "MIXERAT_PHASE_IDLE"); setMixerProfileAT(); + mixerProfileAT.phase = MIXERAT_PHASE_STAB_AND_CLIMB; reprocessState = true; break; + case MIXERAT_PHASE_STAB_AND_CLIMB: + isMixerTransitionMixing_requested = false; + if (millis() > mixerProfileAT.transitionStabEndTime){ + mixerProfileAT.phase = MIXERAT_PHASE_TRANSITIONING; + reprocessState = true; + } + return false; + break; case MIXERAT_PHASE_TRANSITIONING: - // LOG_INFO(PWM, "MIXERAT_PHASE_IDLE"); - if (required_fs_phase==FAILSAFE_RX_LOSS_RECOVERED) - { - abortMixerProfileAT(); - } - else - { - if (millis() > mixerProfileAT.transitionStabEndTime) - { - isMixerTransitionMixing_requested = true; - } - if (millis() > mixerProfileAT.transitionTransEndTime) - { - performMixerProfileAT(nextProfileIndex); - reprocessState = true; - //transition is done - } - return false; + isMixerTransitionMixing_requested = true; + if (millis() > mixerProfileAT.transitionTransEndTime){ + performMixerProfileAT(nextProfileIndex); + mixerProfileAT.phase = MIXERAT_PHASE_IDLE; + reprocessState = true; + //transition is done } + return false; break; default: break; @@ -309,7 +301,7 @@ void outputProfileUpdateTask(timeUs_t currentTimeUs) { isMixerTransitionMixing_requested = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION) && (!isNavBoxModesEnabled()); // update BOXMIXERTRANSITION_input } - isMixerTransitionMixing = isMixerTransitionMixing_requested && ((posControl.navState == NAV_STATE_IDLE) ||(posControl.navState == NAV_STATE_ALTHOLD_IN_PROGRESS)); + isMixerTransitionMixing = isMixerTransitionMixing_requested && ((posControl.navState == NAV_STATE_IDLE) ||(posControl.navState == NAV_STATE_MIXERAT_IN_PROGRESS)); if (failsafePhase() == FAILSAFE_IDLE) { diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index d145b949ce..22eb484185 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -31,10 +31,18 @@ typedef struct mixerProfile_s { PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); +typedef enum { + MIXERAT_REQUEST_NONE, //no request, stats checking only + MIXERAT_REQUEST_RTH, + MIXERAT_REQUEST_LAND, + MIXERAT_REQUEST_ABORT, +} mixerProfileATRequest_t; + //mixerProfile Automated Transition PHASE typedef enum { MIXERAT_PHASE_IDLE, MIXERAT_PHASE_TRANSITION_INITIALIZE, + MIXERAT_PHASE_STAB_AND_CLIMB, MIXERAT_PHASE_TRANSITIONING, MIXERAT_PHASE_DONE, } mixerProfileATState_t; @@ -50,7 +58,7 @@ typedef struct mixerProfileAT_s { } mixerProfileAT_t; extern mixerProfileAT_t mixerProfileAT; bool mixerATRequiresAngleMode(void); -bool mixerATUpdateState(failsafePhase_e required_fs_phase); +bool mixerATUpdateState(mixerProfileATRequest_t required_action); extern mixerConfig_t currentMixerConfig; extern int currentMixerProfileIndex; diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 7ffa8c3388..70b739b5cc 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -314,6 +314,8 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_EMERGENCY_LANDING_FINIS static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_INITIALIZE(navigationFSMState_t previousState); static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_WAIT(navigationFSMState_t previousState); static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_IN_PROGRESS(navigationFSMState_t previousState); +static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_INITIALIZE(navigationFSMState_t previousState); +static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_IN_PROGRESS(navigationFSMState_t previousState); static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { /** Idle state ******************************************************/ @@ -334,6 +336,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_LAUNCH] = NAV_STATE_LAUNCH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -370,6 +373,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -406,6 +410,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, /** CRUISE_HOLD mode ************************************************/ @@ -442,6 +447,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -464,6 +470,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -501,6 +508,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -523,6 +531,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -562,6 +571,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -582,6 +592,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D] = NAV_STATE_POSHOLD_3D_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -602,6 +613,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -623,6 +635,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -642,6 +655,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -660,6 +674,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D] = NAV_STATE_POSHOLD_3D_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -691,6 +706,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D] = NAV_STATE_POSHOLD_3D_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -747,6 +763,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -771,6 +788,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -792,6 +810,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -813,6 +832,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -847,6 +867,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -866,6 +887,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -884,6 +906,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -947,6 +970,43 @@ 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, + .onEntry = navOnEnteringState_NAV_STATE_MIXERAT_INITIALIZE, + .timeoutMs = 0, + .stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE_FW | NAV_REQUIRE_THRTILT, + .mapToFlightModes = NAV_ALTHOLD_MODE, + .mwState = MW_NAV_STATE_NONE, + .mwError = MW_NAV_ERROR_NONE, + .onEvent = { + [NAV_FSM_EVENT_SUCCESS] = NAV_STATE_MIXERAT_IN_PROGRESS, + [NAV_FSM_EVENT_ERROR] = NAV_STATE_IDLE, + [NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE, + } + }, + + [NAV_STATE_MIXERAT_IN_PROGRESS] = { + .persistentId = NAV_PERSISTENT_ID_MIXERAT_IN_PROGRESS, + .onEntry = navOnEnteringState_NAV_STATE_MIXERAT_IN_PROGRESS, + .timeoutMs = 10, + .stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE_FW | NAV_REQUIRE_THRTILT, + .mapToFlightModes = NAV_ALTHOLD_MODE, + .mwState = MW_NAV_STATE_NONE, + .mwError = MW_NAV_ERROR_NONE, + .onEvent = { + [NAV_FSM_EVENT_TIMEOUT] = NAV_STATE_MIXERAT_IN_PROGRESS, // re-process the state + [NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE, + [NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D] = NAV_STATE_POSHOLD_3D_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + } + }, }; static navigationFSMStateFlags_t navGetStateFlags(navigationFSMState_t state) @@ -1864,6 +1924,35 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_IN_PROGRESS(navi return NAV_FSM_EVENT_NONE; } +static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_INITIALIZE(navigationFSMState_t previousState) +{ + UNUSED(previousState); + resetGCSFlags(); + + // Prepare altitude controller + setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z); // This will reset surface offset + + return NAV_FSM_EVENT_SUCCESS; +} + +static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_IN_PROGRESS(navigationFSMState_t previousState) +{ + UNUSED(previousState); + + // Climb to safe altitude and turn to correct direction + if ( (STATE(MULTIROTOR)) && (mixerProfileAT.phase==MIXERAT_PHASE_STAB_AND_CLIMB)) { + updateClimbRateToAltitudeController(navConfig()->general.max_auto_climb_rate, ROC_TO_ALT_NORMAL); + // fpVector3_t tmp_pos = navGetCurrentActualPositionAndVelocity()->pos; + // tmp_pos.z = tmp_pos.z + navConfig()->general.max_auto_climb_rate; + // setDesiredPosition(&tmp_pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z); + } else { + // climb to perform the transition + //set the desired position to the current position to enable althold only + setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z); + } + return NAV_FSM_EVENT_NONE; +} + static navigationFSMState_t navSetNewFSMState(navigationFSMState_t newState) { navigationFSMState_t previousState; @@ -3740,9 +3829,9 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) } } - // Failsafe_Altitude hold for vtol transition (can override MANUAL) - if (posControl.flags.forcedAltHoldActivated && canActivateAltHold) { - return NAV_FSM_EVENT_SWITCH_TO_ALTHOLD; + // Altitude hold for vtol transition (can override MANUAL) + if (posControl.flags.mixerATHelperActivated && canActivateAltHold) { + return NAV_FSM_EVENT_SWITCH_TO_MIXERAT; } // Failsafe_RTH (can override MANUAL) @@ -3794,14 +3883,14 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) } // CRUISE has priority over COURSE_HOLD and AH - if (IS_RC_MODE_ACTIVE(BOXNAVCRUISE)) { + if (IS_RC_MODE_ACTIVE(BOXNAVCRUISE) && STATE(AIRPLANE)) { 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)) { + if (IS_RC_MODE_ACTIVE(BOXNAVCOURSEHOLD) && STATE(AIRPLANE)) { 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; } @@ -4198,7 +4287,7 @@ void navigationInit(void) posControl.flags.forcedRTHActivated = false; posControl.flags.forcedEmergLandingActivated = false; - posControl.flags.forcedAltHoldActivated = false; + posControl.flags.mixerATHelperActivated = false; posControl.waypointCount = 0; posControl.activeWaypointIndex = 0; posControl.waypointListValid = false; @@ -4326,24 +4415,24 @@ emergLandState_e getStateOfForcedEmergLanding(void) /*----------------------------------------------------------- * Ability to mixer_profile(vtol) switch on external event *-----------------------------------------------------------*/ -void activateForcedAltHold(void) +void activateMIXERATHelper(void) { - posControl.flags.forcedAltHoldActivated = true; + posControl.flags.mixerATHelperActivated = true; navProcessFSMEvents(selectNavEventFromBoxModeInput()); } -void abortForcedAltHold(void) +void abortMIXERATHelper(void) { // Disable emergency landing and make sure we back out of navigation mode to IDLE // If any navigation mode was active prior to emergency landing it will be re-enabled with next RX update - posControl.flags.forcedAltHoldActivated = false; + posControl.flags.mixerATHelperActivated = false; navProcessFSMEvents(NAV_FSM_EVENT_SWITCH_TO_IDLE); } -altHoldState_e getStateOfForcedAltHold(void) +altHoldState_e getStateOfMIXERATHelper(void) { /* If forced emergency landing activated and in EMERG state */ - if (posControl.flags.forcedAltHoldActivated && (navGetStateFlags(posControl.navState) & NAV_CTL_ALT)) { + if (posControl.flags.mixerATHelperActivated && (navGetStateFlags(posControl.navState) & NAV_CTL_ALT)) { return ALTHOLD_IN_PROGRESS; } else { return ALTHOLD_IDLE; @@ -4407,7 +4496,7 @@ bool navigationRTHAllowsLanding(void) bool isNavLaunchEnabled(void) { - return IS_RC_MODE_ACTIVE(BOXNAVLAUNCH) || feature(FEATURE_FW_LAUNCH); + return (IS_RC_MODE_ACTIVE(BOXNAVLAUNCH) || feature(FEATURE_FW_LAUNCH)) && STATE(AIRPLANE); } bool abortLaunchAllowed(void) diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 2bae5f8a72..a9b23e9b32 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -588,9 +588,9 @@ void activateForcedEmergLanding(void); void abortForcedEmergLanding(void); emergLandState_e getStateOfForcedEmergLanding(void); -void activateForcedAltHold(void); -void abortForcedAltHold(void); -altHoldState_e getStateOfForcedAltHold(void); +void activateMIXERATHelper(void); +void abortMIXERATHelper(void); +altHoldState_e getStateOfMIXERATHelper(void); /* Getter functions which return data about the state of the navigation system */ bool navigationInAutomaticThrottleMode(void); diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index 096fac5426..78ecef6f1f 100644 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -103,7 +103,7 @@ typedef struct navigationFlags_s { // Failsafe actions bool forcedRTHActivated; bool forcedEmergLandingActivated; - bool forcedAltHoldActivated; + bool mixerATHelperActivated; /* Landing detector */ bool resetLandingDetector; @@ -156,6 +156,7 @@ typedef enum { NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD, NAV_FSM_EVENT_SWITCH_TO_CRUISE, NAV_FSM_EVENT_SWITCH_TO_COURSE_ADJ, + NAV_FSM_EVENT_SWITCH_TO_MIXERAT, NAV_FSM_EVENT_STATE_SPECIFIC_1, // State-specific event NAV_FSM_EVENT_STATE_SPECIFIC_2, // State-specific event @@ -227,6 +228,9 @@ typedef enum { NAV_PERSISTENT_ID_UNUSED_4 = 37, // was NAV_STATE_WAYPOINT_HOVER_ABOVE_HOME NAV_PERSISTENT_ID_RTH_TRACKBACK = 38, + NAV_PERSISTENT_ID_MIXERAT_INITIALIZE = 39, + NAV_PERSISTENT_ID_MIXERAT_IN_PROGRESS = 40, + } navigationPersistentId_e; typedef enum { @@ -274,6 +278,9 @@ typedef enum { NAV_STATE_CRUISE_IN_PROGRESS, NAV_STATE_CRUISE_ADJUSTING, + NAV_STATE_MIXERAT_INITIALIZE, + NAV_STATE_MIXERAT_IN_PROGRESS, + NAV_STATE_COUNT, } navigationFSMState_t; From 7c8b9976b71bec193c8bcd4ed70e1daa7ad82567 Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 2 Aug 2023 00:44:22 +0900 Subject: [PATCH 037/122] automatic mixer profile switching on rth and land --- src/main/fc/fc_core.c | 2 +- src/main/fc/settings.yaml | 35 +++-- src/main/flight/failsafe.c | 45 +------ src/main/flight/failsafe.h | 10 -- src/main/flight/mixer_profile.c | 158 +++++++--------------- src/main/flight/mixer_profile.h | 28 ++-- src/main/io/osd.c | 2 - src/main/io/osd.h | 1 - src/main/io/osd_dji_hd.c | 2 - src/main/navigation/navigation.c | 164 ++++++++++++++--------- src/main/navigation/navigation.h | 6 +- src/main/navigation/navigation_private.h | 6 +- 12 files changed, 192 insertions(+), 267 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index a7e1cf5352..e6358080aa 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -638,7 +638,7 @@ void processRx(timeUs_t currentTimeUs) bool canUseHorizonMode = true; - if ((IS_RC_MODE_ACTIVE(BOXANGLE) || failsafeRequiresAngleMode() || navigationRequiresAngleMode() || mixerATRequiresAngleMode()) && sensors(SENSOR_ACC)) { + if ((IS_RC_MODE_ACTIVE(BOXANGLE) || failsafeRequiresAngleMode() || navigationRequiresAngleMode()) && sensors(SENSOR_ACC)) { // bumpless transfer to Level mode canUseHorizonMode = false; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 01265e60c2..bf6aeb40cb 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: mixer_switch_on_event + values: ["OFF", "ON", "ON_FS_ONLY"] + enum: mixerProfileSwitchOnEvent_e constants: RPYL_PID_MIN: 0 @@ -1173,26 +1176,22 @@ groups: default_value: OFF field: mixer_config.PIDProfileLinking type: bool - - name: mixer_switch_on_fs_rth - description: "If set to on, mixer_profile will switch on failsafe RTH" - default_value: OFF - field: mixer_config.switchOnFSRTH - type: bool - - name: mixer_switch_on_fs_land - description: "If set to on, mixer_profile will switch on failsafe Landing" - default_value: OFF - field: mixer_config.switchOnFSLand - type: bool - - name: mixer_switch_on_fs_stab_timer - description: "If swith mixer_profile on failsafe is required, Wait for this many decisecond(0.1s) before using mixerTransition input for servo and motor mixer" - default_value: 0 - field: mixer_config.switchOnFSStabilizationTimer - min: 0 - max: 200 - - name: mixer_switch_on_fs_trans_timer + - name: mixer_switch_on_rth + description: "If set to on, mixer_profile will switch when it is heading home" + default_value: "OFF" + field: mixer_config.switchOnRTH + table: mixer_switch_on_event + type: uint8_t + - name: mixer_switch_on_land + description: "If set to on, mixer_profile will switch when Landing" + default_value: "OFF" + field: mixer_config.switchOnLand + table: mixer_switch_on_event + type: uint8_t + - name: mixer_switch_trans_timer description: "If swith mixer_profile on failsafe is required, Activate MixerTransion mode for this many decisecond(0.1s) before the actual mixer_profile switch" default_value: 0 - field: mixer_config.switchOnFSTransitionTimer + field: mixer_config.switchTransitionTimer min: 0 max: 200 diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c index 2fa27cff14..ab48fba2c6 100644 --- a/src/main/flight/failsafe.c +++ b/src/main/flight/failsafe.c @@ -43,7 +43,6 @@ #include "fc/settings.h" #include "flight/failsafe.h" -#include "flight/mixer_profile.h" #include "flight/mixer.h" #include "flight/pid.h" @@ -431,14 +430,8 @@ void failsafeUpdateState(void) switch (failsafeState.activeProcedure) { case FAILSAFE_PROCEDURE_AUTO_LANDING: // Use Emergency Landing if Nav defined (otherwise stabilize and set Throttle to specified level). - if(mixerATUpdateState(MIXERAT_REQUEST_LAND)) - { - failsafeActivate(FAILSAFE_LANDING); - activateForcedEmergLanding(); - } - else{ - failsafeActivate(FAILSAFE_MIXER_SWITCHING); - } + failsafeActivate(FAILSAFE_LANDING); + activateForcedEmergLanding(); break; case FAILSAFE_PROCEDURE_DROP_IT: @@ -448,15 +441,9 @@ void failsafeUpdateState(void) break; case FAILSAFE_PROCEDURE_RTH: - if(mixerATUpdateState(MIXERAT_REQUEST_RTH)) - { - // Proceed to handling & monitoring RTH navigation - failsafeActivate(FAILSAFE_RETURN_TO_HOME); - activateForcedRTH(); - } - else{ - failsafeActivate(FAILSAFE_MIXER_SWITCHING); - } + // Proceed to handling & monitoring RTH navigation + failsafeActivate(FAILSAFE_RETURN_TO_HOME); + activateForcedRTH(); break; case FAILSAFE_PROCEDURE_NONE: default: @@ -479,28 +466,6 @@ void failsafeUpdateState(void) } break; - case FAILSAFE_MIXER_SWITCHING: - //enters when mixer switching is required - if (receivingRxDataAndNotFailsafeMode && sticksAreMoving) { - mixerATUpdateState(MIXERAT_REQUEST_ABORT); - failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED; - reprocessState = true; - } else { - if (armed) { - beeperMode = BEEPER_RX_LOST; - } - if (mixerATUpdateState(MIXERAT_REQUEST_NONE)){ - failsafeActivate(FAILSAFE_RX_LOSS_DETECTED); //throw back to failsafe_rx_loss_detected to perform designated procedure - reprocessState = true; - } - if (!armed) { - failsafeState.receivingRxDataPeriodPreset = PERIOD_OF_30_SECONDS; // require 30 seconds of valid rxData - failsafeState.phase = FAILSAFE_LANDED; - reprocessState = true; - } - } - break; - case FAILSAFE_RETURN_TO_HOME: if (receivingRxDataAndNotFailsafeMode && sticksAreMoving) { abortForcedRTH(); diff --git a/src/main/flight/failsafe.h b/src/main/flight/failsafe.h index 015cd04045..7cd88acd59 100644 --- a/src/main/flight/failsafe.h +++ b/src/main/flight/failsafe.h @@ -97,10 +97,6 @@ typedef enum { * and transition into FAILSAFE_RX_LOSS_MONITORING immediately. This is * the first recovery phase enabled when failsafe_procedure = DROP. */ - FAILSAFE_MIXER_SWITCHING, - /* Failsafe is executing MIXER_PROFILE_SWITCHING. This phase is triggered - if a MIXER_PROFILE_SWITCHING is required by the failsafe process - */ FAILSAFE_RX_LOSS_MONITORING, /* This phase will wait until the RX connection is * working for some time and if and only if switch arming @@ -138,12 +134,6 @@ typedef enum { EMERG_LAND_HAS_LANDED // Emergency landing is active and has landed. } emergLandState_e; -typedef enum { - ALTHOLD_IDLE = 0, // Altitude hold is waiting - ALTHOLD_IN_PROGRESS // Altitude hold is activated -} altHoldState_e; - - typedef struct failsafeState_s { int16_t events; bool monitoring; // Flag that failsafe is monitoring RC link diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 779a6c7f11..f2b6708727 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -34,6 +34,7 @@ int currentMixerProfileIndex; bool isMixerTransitionMixing; bool isMixerTransitionMixing_requested; mixerProfileAT_t mixerProfileAT; +int nextProfileIndex; PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1); @@ -50,10 +51,9 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) .outputMode = SETTING_OUTPUT_MODE_DEFAULT, .motorstopOnLow = SETTING_MOTORSTOP_ON_LOW_DEFAULT, .PIDProfileLinking = SETTING_MIXER_PID_PROFILE_LINKING_DEFAULT, - .switchOnFSRTH = SETTING_MIXER_SWITCH_ON_FS_RTH_DEFAULT, - .switchOnFSLand = SETTING_MIXER_SWITCH_ON_FS_LAND_DEFAULT, - .switchOnFSStabilizationTimer = SETTING_MIXER_SWITCH_ON_FS_STAB_TIMER_DEFAULT, - .switchOnFSTransitionTimer = SETTING_MIXER_SWITCH_ON_FS_TRANS_TIMER_DEFAULT, + .switchOnRTH = SETTING_MIXER_SWITCH_ON_RTH_DEFAULT, + .switchOnLand = SETTING_MIXER_SWITCH_ON_LAND_DEFAULT, + .switchTransitionTimer = SETTING_MIXER_SWITCH_TRANS_TIMER_DEFAULT, }); for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) { @@ -83,12 +83,13 @@ void mixerConfigInit(void) { currentMixerProfileIndex = getConfigMixerProfile(); currentMixerConfig = *mixerConfig(); + nextProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT; servosInit(); mixerUpdateStateFlags(); mixerInit(); if (currentMixerConfig.PIDProfileLinking) { - LOG_INFO(PWM, "mixer switch pidInit"); + // LOG_INFO(PWM, "mixer switch pidInit"); setConfigProfile(getConfigMixerProfile()); pidInit(); pidInitFilters(); @@ -98,77 +99,14 @@ void mixerConfigInit(void) } } -// static int computeMotorCountByMixerProfileIndex(int index) -// { -// int motorCount = 0; -// const motorMixer_t* temp_motormixers=mixerMotorMixersByIndex(index)[0]; -// for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) { -// // check if done -// if (temp_motormixers[i].throttle == 0.0f) { -// break; -// } -// motorCount++; -// } -// return motorCount; -// } - -// static int computeServoCountByMixerProfileIndex(int index) -// { -// int servoRuleCount = 0; -// int minServoIndex = 255; -// int maxServoIndex = 0; - -// const servoMixer_t* temp_servomixers=mixerServoMixersByIndex(index)[0]; -// for (int i = 0; i < MAX_SERVO_RULES; i++) { -// if (temp_servomixers[i].rate == 0) -// break; - -// if (temp_servomixers[i].targetChannel < minServoIndex) { -// minServoIndex = temp_servomixers[i].targetChannel; -// } - -// if (temp_servomixers[i].targetChannel > maxServoIndex) { -// maxServoIndex = temp_servomixers[i].targetChannel; -// } -// // LOG_INFO(PWM, "i:%d, minServoIndex:%d, maxServoIndex:%d",i,minServoIndex,maxServoIndex); -// servoRuleCount++; -// } -// if (servoRuleCount) { -// return 1 + maxServoIndex - minServoIndex; -// } -// else { -// return 0; -// } -// } - -bool mixerATRequiresAngleMode(void) -{ - return (mixerProfileAT.phase == MIXERAT_PHASE_TRANSITIONING) || (mixerProfileAT.phase == MIXERAT_PHASE_STAB_AND_CLIMB); -} - void setMixerProfileAT(void) { mixerProfileAT.transitionStartTime = millis(); - mixerProfileAT.transitionStabEndTime = mixerProfileAT.transitionStartTime + (timeMs_t)currentMixerConfig.switchOnFSStabilizationTimer * 100; - mixerProfileAT.transitionTransEndTime = mixerProfileAT.transitionStabEndTime + (timeMs_t)currentMixerConfig.switchOnFSTransitionTimer * 100; - activateMIXERATHelper(); + mixerProfileAT.transitionTransEndTime = mixerProfileAT.transitionStartTime + (timeMs_t)currentMixerConfig.switchTransitionTimer * 100; } -void performMixerProfileAT(int nextProfileIndex) +bool checkMixerATRequired(mixerProfileATRequest_e required_action) { - abortMIXERATHelper(); - isMixerTransitionMixing_requested = false; - outputProfileHotSwitch(nextProfileIndex); -} - -void abortMixerProfileAT(void) -{ - abortMIXERATHelper(); - isMixerTransitionMixing_requested = false; -} - -bool mixerATUpdateState(mixerProfileATRequest_t required_action) -{ //return true if mixerAT condition is met or setting is not valid //set mixer profile automated transition according to failsafe phase //on non vtol setups , behave as normal @@ -180,56 +118,59 @@ bool mixerATUpdateState(mixerProfileATRequest_t required_action) { return true; } - int nextProfileIndex = 0; + + if ((required_action == MIXERAT_REQUEST_RTH) && (currentMixerConfig.switchOnRTH!=MIXERAT_ON_EVENT_OFF) && STATE(MULTIROTOR)) + { + if ((currentMixerConfig.switchOnRTH==MIXERAT_ON_EVENT_ON_FS_ONLY) && (!FLIGHT_MODE(FAILSAFE_MODE))) + { + return false; + } + //check next mixer_profile setting is valid + return mixerConfigByIndex(nextProfileIndex)->switchOnRTH == MIXERAT_ON_EVENT_OFF ? true:false; + + } + else if ((required_action == MIXERAT_REQUEST_LAND) && (currentMixerConfig.switchOnLand!=MIXERAT_ON_EVENT_OFF) && STATE(AIRPLANE)) + { + if ((currentMixerConfig.switchOnLand==MIXERAT_ON_EVENT_ON_FS_ONLY) && (!FLIGHT_MODE(FAILSAFE_MODE))) + { + return false; + } + //check next mixer_profile setting is valid + return mixerConfigByIndex(nextProfileIndex)->switchOnLand == MIXERAT_ON_EVENT_OFF ? true:false; + } + return false; +} + +bool mixerATUpdateState(mixerProfileATRequest_e required_action) +{ bool reprocessState; do { reprocessState=false; - nextProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT; if (required_action==MIXERAT_REQUEST_ABORT){ - abortMixerProfileAT(); + isMixerTransitionMixing_requested = false; mixerProfileAT.phase = MIXERAT_PHASE_IDLE; + return true; } - switch (mixerProfileAT.phase) - { + switch (mixerProfileAT.phase){ case MIXERAT_PHASE_IDLE: - // LOG_INFO(PWM, "MIXERAT_PHASE_IDLE"); //check if mixerAT is required - if ((required_action == MIXERAT_REQUEST_RTH) && currentMixerConfig.switchOnFSRTH && STATE(MULTIROTOR)) - { - if(!mixerConfigByIndex(nextProfileIndex)->switchOnFSRTH)//check next mixer_profile setting is valid - { - mixerProfileAT.phase=MIXERAT_PHASE_TRANSITION_INITIALIZE; - reprocessState = true; - } - } - else if ((required_action == MIXERAT_REQUEST_LAND) && currentMixerConfig.switchOnFSLand && STATE(AIRPLANE)) - { - if(!mixerConfigByIndex(nextProfileIndex)->switchOnFSLand)//check next mixer_profile setting is valid - { - mixerProfileAT.phase=MIXERAT_PHASE_TRANSITION_INITIALIZE; - reprocessState = true; - } + if (checkMixerATRequired(required_action)){ + mixerProfileAT.phase=MIXERAT_PHASE_TRANSITION_INITIALIZE; + reprocessState = true; } break; case MIXERAT_PHASE_TRANSITION_INITIALIZE: // LOG_INFO(PWM, "MIXERAT_PHASE_IDLE"); setMixerProfileAT(); - mixerProfileAT.phase = MIXERAT_PHASE_STAB_AND_CLIMB; + mixerProfileAT.phase = MIXERAT_PHASE_TRANSITIONING; reprocessState = true; break; - case MIXERAT_PHASE_STAB_AND_CLIMB: - isMixerTransitionMixing_requested = false; - if (millis() > mixerProfileAT.transitionStabEndTime){ - mixerProfileAT.phase = MIXERAT_PHASE_TRANSITIONING; - reprocessState = true; - } - return false; - break; case MIXERAT_PHASE_TRANSITIONING: isMixerTransitionMixing_requested = true; if (millis() > mixerProfileAT.transitionTransEndTime){ - performMixerProfileAT(nextProfileIndex); + isMixerTransitionMixing_requested = false; + outputProfileHotSwitch(nextProfileIndex); mixerProfileAT.phase = MIXERAT_PHASE_IDLE; reprocessState = true; //transition is done @@ -295,22 +236,17 @@ bool isNavBoxModesEnabled(void) void outputProfileUpdateTask(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); - + bool nav_mixerAT_inuse = (posControl.navState == NAV_STATE_MIXERAT_IN_PROGRESS || posControl.navState == NAV_STATE_MIXERAT_ABORT); // transition mode input for servo mix and motor mix - if (failsafePhase() == FAILSAFE_IDLE) + if (!FLIGHT_MODE(FAILSAFE_MODE) && (!nav_mixerAT_inuse)) { - isMixerTransitionMixing_requested = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION) && (!isNavBoxModesEnabled()); // update BOXMIXERTRANSITION_input - } - isMixerTransitionMixing = isMixerTransitionMixing_requested && ((posControl.navState == NAV_STATE_IDLE) ||(posControl.navState == NAV_STATE_MIXERAT_IN_PROGRESS)); - - if (failsafePhase() == FAILSAFE_IDLE) - { - // do not allow switching when user activated navigation mode if (!isNavBoxModesEnabled()) { outputProfileHotSwitch((int)IS_RC_MODE_ACTIVE(BOXMIXERPROFILE)); } + isMixerTransitionMixing_requested = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION) && (!isNavBoxModesEnabled()); // update BOXMIXERTRANSITION_input } + isMixerTransitionMixing = isMixerTransitionMixing_requested && ((posControl.navState == NAV_STATE_IDLE) || nav_mixerAT_inuse); } // switch mixerprofile without reboot @@ -341,7 +277,7 @@ bool outputProfileHotSwitch(int profile_index) // LOG_INFO(PWM, "mixer switch failed, checkMixerProfileHotSwitchAvalibility"); return false; } - if (posControl.navState != NAV_STATE_IDLE) + if ((posControl.navState != NAV_STATE_IDLE) && (posControl.navState != NAV_STATE_MIXERAT_IN_PROGRESS)) { // LOG_INFO(PWM, "mixer switch failed, navState != NAV_STATE_IDLE"); return false; diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index 22eb484185..b6016e7286 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -9,6 +9,12 @@ #define MAX_MIXER_PROFILE_COUNT 2 #endif +typedef enum { + MIXERAT_ON_EVENT_OFF, //no request, stats checking only + MIXERAT_ON_EVENT_ON, + MIXERAT_ON_EVENT_ON_FS_ONLY, +} mixerProfileSwitchOnEvent_e; + typedef struct mixerConfig_s { int8_t motorDirectionInverted; uint8_t platformType; @@ -17,10 +23,9 @@ typedef struct mixerConfig_s { uint8_t outputMode; bool motorstopOnLow; bool PIDProfileLinking; - bool switchOnFSRTH; - bool switchOnFSLand; - int16_t switchOnFSStabilizationTimer; - int16_t switchOnFSTransitionTimer; + mixerProfileSwitchOnEvent_e switchOnRTH; + mixerProfileSwitchOnEvent_e switchOnLand; + int16_t switchTransitionTimer; } mixerConfig_t; typedef struct mixerProfile_s { mixerConfig_t mixer_config; @@ -29,36 +34,31 @@ typedef struct mixerProfile_s { } mixerProfile_t; PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles); - - typedef enum { MIXERAT_REQUEST_NONE, //no request, stats checking only MIXERAT_REQUEST_RTH, MIXERAT_REQUEST_LAND, MIXERAT_REQUEST_ABORT, -} mixerProfileATRequest_t; +} mixerProfileATRequest_e; //mixerProfile Automated Transition PHASE typedef enum { MIXERAT_PHASE_IDLE, MIXERAT_PHASE_TRANSITION_INITIALIZE, - MIXERAT_PHASE_STAB_AND_CLIMB, MIXERAT_PHASE_TRANSITIONING, MIXERAT_PHASE_DONE, -} mixerProfileATState_t; +} mixerProfileATState_e; typedef struct mixerProfileAT_s { - mixerProfileATState_t phase; + mixerProfileATState_e phase; bool transitionInputMixing; timeMs_t transitionStartTime; timeMs_t transitionStabEndTime; timeMs_t transitionTransEndTime; - bool lastTransitionInputMixing; - bool lastMixerProfile; } mixerProfileAT_t; extern mixerProfileAT_t mixerProfileAT; -bool mixerATRequiresAngleMode(void); -bool mixerATUpdateState(mixerProfileATRequest_t required_action); +bool checkMixerATRequired(mixerProfileATRequest_e required_action); +bool mixerATUpdateState(mixerProfileATRequest_e required_action); extern mixerConfig_t currentMixerConfig; extern int currentMixerProfileIndex; diff --git a/src/main/io/osd.c b/src/main/io/osd.c index b0be974385..63312af46c 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -945,8 +945,6 @@ static const char * osdFailsafePhaseMessage(void) case FAILSAFE_LANDING: // This should be considered an emergengy landing return OSD_MESSAGE_STR(OSD_MSG_EMERG_LANDING_FS); - case FAILSAFE_MIXER_SWITCHING: - return OSD_MESSAGE_STR(OSD_MSG_MIXER_SWITCHING_FS); case FAILSAFE_RX_LOSS_MONITORING: // Only reachable from FAILSAFE_LANDED, which performs // a disarm. Since aircraft has been disarmed, we no diff --git a/src/main/io/osd.h b/src/main/io/osd.h index ab608caf6f..2dad5ceb81 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -88,7 +88,6 @@ #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_MIXER_SWITCHING_FS "(FS MIXER SWITCHING)" #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" diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 72cfc781aa..e79ddc0dfd 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -558,8 +558,6 @@ static char * osdFailsafePhaseMessage(void) case FAILSAFE_LANDING: // This should be considered an emergengy landing return OSD_MESSAGE_STR("(EMRGY LANDING)"); - case FAILSAFE_MIXER_SWITCHING: - return OSD_MESSAGE_STR("(MIXER SWITCHING)"); case FAILSAFE_RX_LOSS_MONITORING: // Only reachable from FAILSAFE_LANDED, which performs // a disarm. Since aircraft has been disarmed, we no diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 70b739b5cc..84a0658a5b 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -316,6 +316,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_WAIT(navigationF static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_IN_PROGRESS(navigationFSMState_t previousState); static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_INITIALIZE(navigationFSMState_t previousState); static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_IN_PROGRESS(navigationFSMState_t previousState); +static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_ABORT(navigationFSMState_t previousState); static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { /** Idle state ******************************************************/ @@ -373,7 +374,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -410,7 +410,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, /** CRUISE_HOLD mode ************************************************/ @@ -447,7 +446,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -470,7 +468,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -508,7 +505,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -531,7 +527,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -571,7 +566,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -592,7 +586,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D] = NAV_STATE_POSHOLD_3D_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -635,7 +628,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -655,7 +647,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -706,7 +697,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D] = NAV_STATE_POSHOLD_3D_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -763,7 +753,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -788,7 +777,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -810,7 +798,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -867,7 +854,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -887,7 +873,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -906,7 +891,6 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { [NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_MIXERAT] = NAV_STATE_MIXERAT_INITIALIZE, } }, @@ -976,7 +960,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { .persistentId = NAV_PERSISTENT_ID_MIXERAT_INITIALIZE, .onEntry = navOnEnteringState_NAV_STATE_MIXERAT_INITIALIZE, .timeoutMs = 0, - .stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE_FW | NAV_REQUIRE_THRTILT, + .stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE | NAV_REQUIRE_THRTILT | NAV_MIXERAT, .mapToFlightModes = NAV_ALTHOLD_MODE, .mwState = MW_NAV_STATE_NONE, .mwError = MW_NAV_ERROR_NONE, @@ -991,20 +975,29 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { .persistentId = NAV_PERSISTENT_ID_MIXERAT_IN_PROGRESS, .onEntry = navOnEnteringState_NAV_STATE_MIXERAT_IN_PROGRESS, .timeoutMs = 10, - .stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE_FW | NAV_REQUIRE_THRTILT, + .stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE | NAV_REQUIRE_THRTILT | NAV_MIXERAT, .mapToFlightModes = NAV_ALTHOLD_MODE, .mwState = MW_NAV_STATE_NONE, .mwError = MW_NAV_ERROR_NONE, .onEvent = { [NAV_FSM_EVENT_TIMEOUT] = NAV_STATE_MIXERAT_IN_PROGRESS, // re-process the state [NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE, - [NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_ALTHOLD_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D] = NAV_STATE_POSHOLD_3D_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_RTH_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_WAYPOINT_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_EMERGENCY_LANDING_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_COURSE_HOLD_INITIALIZE, - [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_CRUISE_INITIALIZE, + [NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME] = NAV_STATE_RTH_HEAD_HOME, // re-process the state + [NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING] = NAV_STATE_RTH_LANDING, + } + }, + [NAV_STATE_MIXERAT_ABORT] = { + .persistentId = NAV_PERSISTENT_ID_MIXERAT_ABORT, + .onEntry = navOnEnteringState_NAV_STATE_MIXERAT_ABORT, + .timeoutMs = 10, + .stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE | NAV_REQUIRE_THRTILT, + .mapToFlightModes = NAV_ALTHOLD_MODE, + .mwState = MW_NAV_STATE_NONE, + .mwError = MW_NAV_ERROR_NONE, + .onEvent = { + [NAV_FSM_EVENT_SUCCESS] = NAV_STATE_IDLE, + [NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE, + } }, }; @@ -1415,6 +1408,10 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_HEAD_HOME(navigatio return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING; } + if (checkMixerATRequired(MIXERAT_REQUEST_RTH)){ + return NAV_FSM_EVENT_SWITCH_TO_MIXERAT; + } + if (navConfig()->general.flags.rth_use_linear_descent && navConfig()->general.rth_home_altitude > 0) { // Check linear descent status uint32_t homeDistance = calculateDistanceToDestination(&posControl.rthState.homePosition.pos); @@ -1519,6 +1516,10 @@ 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; + } float descentVelLimited = 0; int32_t landingElevation = posControl.rthState.homeTmpWaypoint.z; @@ -1924,35 +1925,70 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_IN_PROGRESS(navi return NAV_FSM_EVENT_NONE; } +navigationFSMState_t navMixerATPendingState = NAV_STATE_IDLE; static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_INITIALIZE(navigationFSMState_t previousState) { - UNUSED(previousState); - resetGCSFlags(); - - // Prepare altitude controller - setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z); // This will reset surface offset + const navigationFSMStateFlags_t prevFlags = navGetStateFlags(previousState); + // Prepare altitude controller if idle, RTH or WP modes active or surface mode status changed + if (!(prevFlags & NAV_CTL_ALT) || (prevFlags & NAV_AUTO_RTH) || (prevFlags & NAV_AUTO_WP)) { + resetAltitudeController(false); + setupAltitudeController(); + } + setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z); + navMixerATPendingState = previousState; return NAV_FSM_EVENT_SUCCESS; } static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_IN_PROGRESS(navigationFSMState_t previousState) { UNUSED(previousState); - - // Climb to safe altitude and turn to correct direction - if ( (STATE(MULTIROTOR)) && (mixerProfileAT.phase==MIXERAT_PHASE_STAB_AND_CLIMB)) { - updateClimbRateToAltitudeController(navConfig()->general.max_auto_climb_rate, ROC_TO_ALT_NORMAL); - // fpVector3_t tmp_pos = navGetCurrentActualPositionAndVelocity()->pos; - // tmp_pos.z = tmp_pos.z + navConfig()->general.max_auto_climb_rate; - // setDesiredPosition(&tmp_pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z); - } else { - // climb to perform the transition - //set the desired position to the current position to enable althold only - setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z); + mixerProfileATRequest_e required_action; + switch (navMixerATPendingState) + { + case NAV_STATE_RTH_HEAD_HOME: + required_action = MIXERAT_REQUEST_RTH; + break; + case NAV_STATE_RTH_LANDING: + required_action = MIXERAT_REQUEST_LAND; + break; + default: + required_action = MIXERAT_REQUEST_NONE; + break; } + if (mixerATUpdateState(required_action)){ + // MixerAT is done, switch to next state + resetPositionController(); + resetAltitudeController(false); // Make sure surface tracking is not enabled uses global altitude, not AGL + mixerATUpdateState(MIXERAT_REQUEST_ABORT); + switch (navMixerATPendingState) + { + case NAV_STATE_RTH_HEAD_HOME: + setupAltitudeController(); + return NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME; + break; + case NAV_STATE_RTH_LANDING: + setupAltitudeController(); + return NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING; + break; + default: + return NAV_FSM_EVENT_SWITCH_TO_IDLE; + break; + } + } + + setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z); + return NAV_FSM_EVENT_NONE; } +static navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_ABORT(navigationFSMState_t previousState) +{ + UNUSED(previousState); + mixerATUpdateState(MIXERAT_REQUEST_ABORT); + return NAV_FSM_EVENT_SUCCESS; +} + static navigationFSMState_t navSetNewFSMState(navigationFSMState_t newState) { navigationFSMState_t previousState; @@ -4366,7 +4402,7 @@ void abortForcedRTH(void) rthState_e getStateOfForcedRTH(void) { /* If forced RTH activated and in AUTO_RTH or EMERG state */ - if (posControl.flags.forcedRTHActivated && (navGetStateFlags(posControl.navState) & (NAV_AUTO_RTH | NAV_CTL_EMERG))) { + if (posControl.flags.forcedRTHActivated && (navGetStateFlags(posControl.navState) & (NAV_AUTO_RTH | NAV_CTL_EMERG | NAV_MIXERAT))) { if (posControl.navState == NAV_STATE_RTH_FINISHED || posControl.navState == NAV_STATE_EMERGENCY_LANDING_FINISHED) { return RTH_HAS_LANDED; } @@ -4415,29 +4451,29 @@ emergLandState_e getStateOfForcedEmergLanding(void) /*----------------------------------------------------------- * Ability to mixer_profile(vtol) switch on external event *-----------------------------------------------------------*/ -void activateMIXERATHelper(void) -{ - posControl.flags.mixerATHelperActivated = true; - navProcessFSMEvents(selectNavEventFromBoxModeInput()); -} +// void activateMIXERATHelper(void) +// { +// posControl.flags.mixerATHelperActivated = true; +// navProcessFSMEvents(selectNavEventFromBoxModeInput()); +// } -void abortMIXERATHelper(void) -{ - // Disable emergency landing and make sure we back out of navigation mode to IDLE - // If any navigation mode was active prior to emergency landing it will be re-enabled with next RX update - posControl.flags.mixerATHelperActivated = false; - navProcessFSMEvents(NAV_FSM_EVENT_SWITCH_TO_IDLE); -} +// void abortMIXERATHelper(void) +// { +// // Disable emergency landing and make sure we back out of navigation mode to IDLE +// // If any navigation mode was active prior to emergency landing it will be re-enabled with next RX update +// posControl.flags.mixerATHelperActivated = false; +// navProcessFSMEvents(NAV_FSM_EVENT_SWITCH_TO_IDLE); +// } -altHoldState_e getStateOfMIXERATHelper(void) -{ - /* If forced emergency landing activated and in EMERG state */ - if (posControl.flags.mixerATHelperActivated && (navGetStateFlags(posControl.navState) & NAV_CTL_ALT)) { - return ALTHOLD_IN_PROGRESS; - } else { - return ALTHOLD_IDLE; - } -} +// altHoldState_e getStateOfMIXERATHelper(void) +// { +// /* If forced emergency landing activated and in EMERG state */ +// if (posControl.flags.mixerATHelperActivated && (navGetStateFlags(posControl.navState) & NAV_CTL_ALT)) { +// return ALTHOLD_IN_PROGRESS; +// } else { +// return ALTHOLD_IDLE; +// } +// } bool isWaypointMissionRTHActive(void) { diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index a9b23e9b32..b90cb3e521 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -588,9 +588,9 @@ void activateForcedEmergLanding(void); void abortForcedEmergLanding(void); emergLandState_e getStateOfForcedEmergLanding(void); -void activateMIXERATHelper(void); -void abortMIXERATHelper(void); -altHoldState_e getStateOfMIXERATHelper(void); +// void activateMIXERATHelper(void); +// void abortMIXERATHelper(void); +// altHoldState_e getStateOfMIXERATHelper(void); /* Getter functions which return data about the state of the navigation system */ bool navigationInAutomaticThrottleMode(void); diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index 78ecef6f1f..1b1506d0cd 100644 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -164,6 +164,7 @@ typedef enum { NAV_FSM_EVENT_STATE_SPECIFIC_4, // State-specific event NAV_FSM_EVENT_STATE_SPECIFIC_5, // State-specific event NAV_FSM_EVENT_STATE_SPECIFIC_6, // State-specific event + NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME = NAV_FSM_EVENT_STATE_SPECIFIC_3, NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING = NAV_FSM_EVENT_STATE_SPECIFIC_1, NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_RTH_LAND = NAV_FSM_EVENT_STATE_SPECIFIC_1, NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED = NAV_FSM_EVENT_STATE_SPECIFIC_2, @@ -230,7 +231,7 @@ typedef enum { NAV_PERSISTENT_ID_MIXERAT_INITIALIZE = 39, NAV_PERSISTENT_ID_MIXERAT_IN_PROGRESS = 40, - + NAV_PERSISTENT_ID_MIXERAT_ABORT = 41, } navigationPersistentId_e; typedef enum { @@ -280,6 +281,7 @@ typedef enum { NAV_STATE_MIXERAT_INITIALIZE, NAV_STATE_MIXERAT_IN_PROGRESS, + NAV_STATE_MIXERAT_ABORT, NAV_STATE_COUNT, } navigationFSMState_t; @@ -310,6 +312,8 @@ typedef enum { /* Additional flags */ NAV_CTL_LAND = (1 << 14), NAV_AUTO_WP_DONE = (1 << 15), //Waypoint mission reached the last waypoint and is idling + + NAV_MIXERAT = (1 << 16), //MIXERAT in progress } navigationFSMStateFlags_t; typedef struct { From 271c7988c8cfa1fbd07ba6c94f07a52db73a84e5 Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 2 Aug 2023 02:38:44 +0900 Subject: [PATCH 038/122] minor fix --- src/main/flight/mixer_profile.c | 6 +++--- src/main/navigation/navigation.c | 19 ++++++++++--------- src/main/navigation/navigation.h | 4 ---- src/main/navigation/navigation_private.h | 1 - 4 files changed, 13 insertions(+), 17 deletions(-) diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index f2b6708727..90cdfcca16 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -112,11 +112,11 @@ bool checkMixerATRequired(mixerProfileATRequest_e required_action) //on non vtol setups , behave as normal if ((!STATE(AIRPLANE)) && (!STATE(MULTIROTOR))) { - return true; + return false; } if (!isModeActivationConditionPresent(BOXMIXERPROFILE)) { - return true; + return false; } if ((required_action == MIXERAT_REQUEST_RTH) && (currentMixerConfig.switchOnRTH!=MIXERAT_ON_EVENT_OFF) && STATE(MULTIROTOR)) @@ -246,7 +246,7 @@ void outputProfileUpdateTask(timeUs_t currentTimeUs) } isMixerTransitionMixing_requested = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION) && (!isNavBoxModesEnabled()); // update BOXMIXERTRANSITION_input } - isMixerTransitionMixing = isMixerTransitionMixing_requested && ((posControl.navState == NAV_STATE_IDLE) || nav_mixerAT_inuse); + isMixerTransitionMixing = isMixerTransitionMixing_requested && ((posControl.navState == NAV_STATE_IDLE) || nav_mixerAT_inuse ||(posControl.navState == NAV_STATE_ALTHOLD_IN_PROGRESS)); } // switch mixerprofile without reboot diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 84a0658a5b..c63504c807 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -68,6 +68,7 @@ #define MR_RTH_CLIMB_OVERSHOOT_CM 100 // target this amount of cm *above* the target altitude to ensure it is actually reached (Vz > 0 at target alt) #define MR_RTH_CLIMB_MARGIN_MIN_CM 100 // start cruising home this amount of cm *before* reaching the cruise altitude (while continuing the ascend) #define MR_RTH_CLIMB_MARGIN_PERCENT 15 // on high RTH altitudes use even bigger margin - percent of the altitude set +#define MR_RTH_LAND_MARGIN_CM 2000 // pause landing if this amount of cm *before* remaining to the home point (2D distance) // Planes: #define FW_RTH_CLIMB_OVERSHOOT_CM 100 @@ -1408,7 +1409,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_HEAD_HOME(navigatio return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING; } - if (checkMixerATRequired(MIXERAT_REQUEST_RTH)){ + if (checkMixerATRequired(MIXERAT_REQUEST_RTH) && (calculateDistanceToDestination(&posControl.rthState.homePosition.pos) > (navConfig()->fw.loiter_radius * 3))){ return NAV_FSM_EVENT_SWITCH_TO_MIXERAT; } @@ -1522,10 +1523,16 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_LANDING(navigationF } float descentVelLimited = 0; - int32_t landingElevation = posControl.rthState.homeTmpWaypoint.z; + fpVector3_t tmpHomePos = posControl.rthState.homeTmpWaypoint; + uint32_t remaning_distance = calculateDistanceToDestination(&tmpHomePos); + + int32_t landingElevation = posControl.rthState.homeTmpWaypoint.z; + if(STATE(MULTIROTOR) && (remaning_distance>MR_RTH_LAND_MARGIN_CM)){ + descentVelLimited = navConfig()->general.land_minalt_vspd; + } // A safeguard - if surface altitude sensors is available and it is reading < 50cm altitude - drop to low descend speed - if ((posControl.flags.estAglStatus == EST_TRUSTED) && posControl.actualState.agl.pos.z < 50.0f) { + else if ((posControl.flags.estAglStatus == EST_TRUSTED) && posControl.actualState.agl.pos.z < 50.0f) { // land_descent_rate == 200 : descend speed = 30 cm/s, gentle touchdown // Do not allow descent velocity slower than -30cm/s so the landing detector works. descentVelLimited = navConfig()->general.land_minalt_vspd; @@ -3865,11 +3872,6 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) } } - // Altitude hold for vtol transition (can override MANUAL) - if (posControl.flags.mixerATHelperActivated && canActivateAltHold) { - return NAV_FSM_EVENT_SWITCH_TO_MIXERAT; - } - // Failsafe_RTH (can override MANUAL) if (posControl.flags.forcedRTHActivated) { // If we request forced RTH - attempt to activate it no matter what @@ -4323,7 +4325,6 @@ void navigationInit(void) posControl.flags.forcedRTHActivated = false; posControl.flags.forcedEmergLandingActivated = false; - posControl.flags.mixerATHelperActivated = false; posControl.waypointCount = 0; posControl.activeWaypointIndex = 0; posControl.waypointListValid = false; diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index b90cb3e521..cf4289e14a 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -588,10 +588,6 @@ void activateForcedEmergLanding(void); void abortForcedEmergLanding(void); emergLandState_e getStateOfForcedEmergLanding(void); -// void activateMIXERATHelper(void); -// void abortMIXERATHelper(void); -// altHoldState_e getStateOfMIXERATHelper(void); - /* Getter functions which return data about the state of the navigation system */ bool navigationInAutomaticThrottleMode(void); bool navigationIsControllingThrottle(void); diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index 1b1506d0cd..073fc59c99 100644 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -103,7 +103,6 @@ typedef struct navigationFlags_s { // Failsafe actions bool forcedRTHActivated; bool forcedEmergLandingActivated; - bool mixerATHelperActivated; /* Landing detector */ bool resetLandingDetector; From 1bdca4e02c09fff1a30ebc43fdaa429eb1486260 Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 2 Aug 2023 12:08:35 +0900 Subject: [PATCH 039/122] some clean up for mixer profile --- src/main/drivers/pwm_mapping.c | 4 ---- src/main/fc/settings.h | 3 --- src/main/flight/mixer.c | 7 +------ src/main/flight/mixer_profile.c | 12 ++---------- src/main/target/MATEKF405/CMakeLists.txt | 1 - src/main/target/MATEKF405/target.c | 16 ---------------- src/main/target/MATEKF405/target.h | 4 ---- 7 files changed, 3 insertions(+), 44 deletions(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 653404a4e2..a40faf965c 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -266,10 +266,6 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU else if (timHw->usageFlags & TIM_USE_MC_MOTOR) { type = MAP_TO_MOTOR_OUTPUT; } - else if (timHw->usageFlags & TIM_USE_MC_SERVO){ - type = MAP_TO_SERVO_OUTPUT; - } - } else { // Fixed wing or HELI (one/two motors and a lot of servos if (timHw->usageFlags & TIM_USE_FW_SERVO) { diff --git a/src/main/fc/settings.h b/src/main/fc/settings.h index ae7da85317..7fdfd66bf2 100644 --- a/src/main/fc/settings.h +++ b/src/main/fc/settings.h @@ -43,9 +43,6 @@ typedef enum { MODE_LOOKUP = (1 << SETTING_MODE_OFFSET), // 0x40 } setting_mode_e; -// #define SETTING_TYPE_MASK (0x0F) -// #define SETTING_SECTION_MASK (0x30) -// #define SETTING_MODE_MASK (0xC0) #define SETTING_TYPE_MASK (0x07) #define SETTING_SECTION_MASK (0x38) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 9ba9a76441..e3d255e491 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -446,14 +446,9 @@ void writeAllMotors(int16_t mc) writeMotors(); } - -void stopMotorsNoDelay(void) -{ - writeAllMotors(feature(FEATURE_REVERSIBLE_MOTORS) ? reversibleMotorsConfig()->neutral : motorConfig()->mincommand); -} void stopMotors(void) { - stopMotorsNoDelay(); + writeAllMotors(feature(FEATURE_REVERSIBLE_MOTORS) ? reversibleMotorsConfig()->neutral : motorConfig()->mincommand); delay(50); // give the timers and ESCs a chance to react. } diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 90cdfcca16..e264012e8c 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -107,8 +107,7 @@ void setMixerProfileAT(void) bool checkMixerATRequired(mixerProfileATRequest_e required_action) { - //return true if mixerAT condition is met or setting is not valid - //set mixer profile automated transition according to failsafe phase + //return false if mixerAT condition is not required or setting is not valid //on non vtol setups , behave as normal if ((!STATE(AIRPLANE)) && (!STATE(MULTIROTOR))) { @@ -217,13 +216,6 @@ bool checkMixerProfileHotSwitchAvalibility(void) allow_hot_switch = 0; return false; } - // not necessary when map motor/servos of all mixer profiles on the first boot - // do not allow switching if motor or servos counts are different - // if ((computeMotorCountByMixerProfileIndex(0) != computeMotorCountByMixerProfileIndex(1)) || (computeServoCountByMixerProfileIndex(0) != computeServoCountByMixerProfileIndex(1))) - // { - // allow_hot_switch = 0; - // return false; - // } allow_hot_switch = 1; return true; } @@ -287,7 +279,7 @@ bool outputProfileHotSwitch(int profile_index) // LOG_INFO(PWM, "mixer switch failed to set config"); return false; } - stopMotorsNoDelay(); // not necessary, but just in case something goes wrong. But will a short period of stop command cause problem? + // stopMotorsNoDelay(); // not necessary, but just in case something goes wrong. But will a short period of stop command cause problem? mixerConfigInit(); return true; } diff --git a/src/main/target/MATEKF405/CMakeLists.txt b/src/main/target/MATEKF405/CMakeLists.txt index 36d193a945..c4f839c1c1 100644 --- a/src/main/target/MATEKF405/CMakeLists.txt +++ b/src/main/target/MATEKF405/CMakeLists.txt @@ -1,4 +1,3 @@ target_stm32f405xg(MATEKF405) target_stm32f405xg(MATEKF405_SERVOS6) target_stm32f405xg(MATEKF405OSD) -target_stm32f405xg(MATEKF405VTOL) diff --git a/src/main/target/MATEKF405/target.c b/src/main/target/MATEKF405/target.c index 3f4d761834..40ebf626e5 100644 --- a/src/main/target/MATEKF405/target.c +++ b/src/main/target/MATEKF405/target.c @@ -23,21 +23,6 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM -#ifdef MATEKF405VTOL//development purpose, TODO: remove it in the release - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 UP(2,1) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S3 UP(2,1) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 UP(2,1) - - DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED , 0, 0), // S5 UP(1,7) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 UP(2,5) - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,7)!S5 UP(2,6) - - DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2 - - DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // TX4 UP(1,6) D(1,2)!S1 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // RX4 UP(1,6) D(1,4) -#else #ifdef MATEKF405_SERVOS6 DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 @@ -61,7 +46,6 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // TX4 UP(1,6) D(1,2)!S1 DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // RX4 UP(1,6) D(1,4) -#endif }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index e9aff02df4..fa2af63384 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -195,7 +195,3 @@ #define USE_ESC_SENSOR #define MAX_PWM_OUTPUT_PORTS 6 - -#ifdef MATEKF405VTOL -#define ENABLE_MIXER_PROFILE_MCFW_HOTSWAP -#endif \ No newline at end of file From c9ff9cd099a88570ee9fda857982092deb47e281 Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 2 Aug 2023 18:00:52 +0900 Subject: [PATCH 040/122] updates --- src/main/fc/settings.yaml | 13 ++++--------- src/main/flight/mixer_profile.c | 22 +++++++--------------- src/main/flight/mixer_profile.h | 10 ++-------- src/main/navigation/navigation.c | 16 ++++++++++++---- 4 files changed, 25 insertions(+), 36 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index bf6aeb40cb..56f2a7027f 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -190,9 +190,6 @@ tables: - name: nav_fw_wp_turn_smoothing values: ["OFF", "ON", "ON-CUT"] enum: wpFwTurnSmoothing_e - - name: mixer_switch_on_event - values: ["OFF", "ON", "ON_FS_ONLY"] - enum: mixerProfileSwitchOnEvent_e constants: RPYL_PID_MIN: 0 @@ -1178,16 +1175,14 @@ groups: type: bool - name: mixer_switch_on_rth description: "If set to on, mixer_profile will switch when it is heading home" - default_value: "OFF" + default_value: OFF field: mixer_config.switchOnRTH - table: mixer_switch_on_event - type: uint8_t + type: bool - name: mixer_switch_on_land description: "If set to on, mixer_profile will switch when Landing" - default_value: "OFF" + default_value: OFF field: mixer_config.switchOnLand - table: mixer_switch_on_event - type: uint8_t + type: bool - name: mixer_switch_trans_timer description: "If swith mixer_profile on failsafe is required, Activate MixerTransion mode for this many decisecond(0.1s) before the actual mixer_profile switch" default_value: 0 diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index e264012e8c..044cb027ab 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -93,7 +93,7 @@ void mixerConfigInit(void) setConfigProfile(getConfigMixerProfile()); pidInit(); pidInitFilters(); - pidResetErrorAccumulators(); + // pidResetErrorAccumulators(); schedulePidGainsUpdate(); navigationUsePIDs(); // set navigation pid gains } @@ -118,24 +118,16 @@ bool checkMixerATRequired(mixerProfileATRequest_e required_action) return false; } - if ((required_action == MIXERAT_REQUEST_RTH) && (currentMixerConfig.switchOnRTH!=MIXERAT_ON_EVENT_OFF) && STATE(MULTIROTOR)) + if ((required_action == MIXERAT_REQUEST_RTH) && (currentMixerConfig.switchOnRTH) && STATE(MULTIROTOR)) { - if ((currentMixerConfig.switchOnRTH==MIXERAT_ON_EVENT_ON_FS_ONLY) && (!FLIGHT_MODE(FAILSAFE_MODE))) - { - return false; - } - //check next mixer_profile setting is valid - return mixerConfigByIndex(nextProfileIndex)->switchOnRTH == MIXERAT_ON_EVENT_OFF ? true:false; + //check next mixer_profile setting is valid, need to be false + return mixerConfigByIndex(nextProfileIndex)->switchOnRTH? false:true; } - else if ((required_action == MIXERAT_REQUEST_LAND) && (currentMixerConfig.switchOnLand!=MIXERAT_ON_EVENT_OFF) && STATE(AIRPLANE)) + else if ((required_action == MIXERAT_REQUEST_LAND) && (currentMixerConfig.switchOnLand) && STATE(AIRPLANE)) { - if ((currentMixerConfig.switchOnLand==MIXERAT_ON_EVENT_ON_FS_ONLY) && (!FLIGHT_MODE(FAILSAFE_MODE))) - { - return false; - } - //check next mixer_profile setting is valid - return mixerConfigByIndex(nextProfileIndex)->switchOnLand == MIXERAT_ON_EVENT_OFF ? true:false; + //check next mixer_profile setting is valid, need to be false + return mixerConfigByIndex(nextProfileIndex)->switchOnLand? false:true; } return false; } diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index b6016e7286..89d85ae7ab 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -9,12 +9,6 @@ #define MAX_MIXER_PROFILE_COUNT 2 #endif -typedef enum { - MIXERAT_ON_EVENT_OFF, //no request, stats checking only - MIXERAT_ON_EVENT_ON, - MIXERAT_ON_EVENT_ON_FS_ONLY, -} mixerProfileSwitchOnEvent_e; - typedef struct mixerConfig_s { int8_t motorDirectionInverted; uint8_t platformType; @@ -23,8 +17,8 @@ typedef struct mixerConfig_s { uint8_t outputMode; bool motorstopOnLow; bool PIDProfileLinking; - mixerProfileSwitchOnEvent_e switchOnRTH; - mixerProfileSwitchOnEvent_e switchOnLand; + bool switchOnRTH; + bool switchOnLand; int16_t switchTransitionTimer; } mixerConfig_t; typedef struct mixerProfile_s { diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index c63504c807..1bed5e11ad 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -982,14 +982,22 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { .mwError = MW_NAV_ERROR_NONE, .onEvent = { [NAV_FSM_EVENT_TIMEOUT] = NAV_STATE_MIXERAT_IN_PROGRESS, // re-process the state - [NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_IDLE, - [NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME] = NAV_STATE_RTH_HEAD_HOME, // re-process the state - [NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING] = NAV_STATE_RTH_LANDING, + [NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME] = NAV_STATE_RTH_HEAD_HOME, //switch to its pending state + [NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING] = NAV_STATE_RTH_LANDING, //switch to its pending state + [NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_MIXERAT_ABORT, + [NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_MIXERAT_ABORT, + [NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D] = NAV_STATE_MIXERAT_ABORT, + [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_MIXERAT_ABORT, + [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_MIXERAT_ABORT, + [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_MIXERAT_ABORT, + [NAV_FSM_EVENT_SWITCH_TO_LAUNCH] = NAV_STATE_MIXERAT_ABORT, + [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_MIXERAT_ABORT, + [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_MIXERAT_ABORT, } }, [NAV_STATE_MIXERAT_ABORT] = { .persistentId = NAV_PERSISTENT_ID_MIXERAT_ABORT, - .onEntry = navOnEnteringState_NAV_STATE_MIXERAT_ABORT, + .onEntry = navOnEnteringState_NAV_STATE_MIXERAT_ABORT, //will not switch to its pending state .timeoutMs = 10, .stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE | NAV_REQUIRE_THRTILT, .mapToFlightModes = NAV_ALTHOLD_MODE, From 1188ff79fe762a5ee1d3d63e9773b5cacd1a7d02 Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 2 Aug 2023 19:49:02 +0900 Subject: [PATCH 041/122] fixes --- docs/Settings.md | 30 ++++++++++++++++++++++++++++++ src/main/flight/mixer.c | 2 +- src/main/flight/mixer_profile.h | 4 ++-- src/main/flight/servos.c | 2 +- src/main/navigation/navigation.c | 10 +--------- 5 files changed, 35 insertions(+), 13 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index cce1b16006..afa1329b64 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -2552,6 +2552,36 @@ If enabled, pid profile index will follow mixer profile index --- +### mixer_switch_on_land + +If set to on, mixer_profile will switch when Landing + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + +### mixer_switch_on_rth + +If set to on, mixer_profile will switch when it is heading home + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + +### mixer_switch_trans_timer + +If swith mixer_profile on failsafe is required, Activate MixerTransion mode for this many decisecond(0.1s) before the actual mixer_profile switch + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 200 | + +--- + ### mode_range_logic_operator Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode. diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index e3d255e491..ab8a701bc7 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -113,7 +113,7 @@ static void computeMotorCount(void) for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) { bool isMotorUsed = false; for(int j = 0; j< MAX_MIXER_PROFILE_COUNT; j++){ - if (mixerMotorMixersByIndex(j)[i]->throttle != 0.0f) { + if (mixerMotorMixersByIndex(j)[i].throttle != 0.0f) { isMotorUsed = true; } } diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index 89d85ae7ab..cda32f57a2 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -70,8 +70,8 @@ static inline const mixerProfile_t* mixerProfiles_CopyArray_by_index(int _index) #define customServoMixers_CopyArray() (mixerProfiles_CopyArray_by_index(systemConfig()->current_mixer_profile_index)->ServoMixers) #define mixerConfigByIndex(index) (&(mixerProfiles(index)->mixer_config)) -#define mixerMotorMixersByIndex(index) (&(mixerProfiles(index)->MotorMixers)) -#define mixerServoMixersByIndex(index) (&(mixerProfiles(index)->ServoMixers)) +#define mixerMotorMixersByIndex(index) (mixerProfiles(index)->MotorMixers) +#define mixerServoMixersByIndex(index) (mixerProfiles(index)->ServoMixers) bool outputProfileHotSwitch(int profile_index); bool checkMixerProfileHotSwitchAvalibility(void); diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index e310545670..1ccaefd462 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -199,7 +199,7 @@ void loadCustomServoMixer(void) memset(currentServoMixer, 0, sizeof(currentServoMixer)); for (int j = 0; j < MAX_MIXER_PROFILE_COUNT; j++) { - const servoMixer_t* tmp_customServoMixers = mixerServoMixersByIndex(j)[0]; + 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 diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 1bed5e11ad..de41be4767 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -982,17 +982,9 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { .mwError = MW_NAV_ERROR_NONE, .onEvent = { [NAV_FSM_EVENT_TIMEOUT] = NAV_STATE_MIXERAT_IN_PROGRESS, // re-process the state + [NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_MIXERAT_ABORT, [NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME] = NAV_STATE_RTH_HEAD_HOME, //switch to its pending state [NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING] = NAV_STATE_RTH_LANDING, //switch to its pending state - [NAV_FSM_EVENT_SWITCH_TO_IDLE] = NAV_STATE_MIXERAT_ABORT, - [NAV_FSM_EVENT_SWITCH_TO_ALTHOLD] = NAV_STATE_MIXERAT_ABORT, - [NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D] = NAV_STATE_MIXERAT_ABORT, - [NAV_FSM_EVENT_SWITCH_TO_RTH] = NAV_STATE_MIXERAT_ABORT, - [NAV_FSM_EVENT_SWITCH_TO_WAYPOINT] = NAV_STATE_MIXERAT_ABORT, - [NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING] = NAV_STATE_MIXERAT_ABORT, - [NAV_FSM_EVENT_SWITCH_TO_LAUNCH] = NAV_STATE_MIXERAT_ABORT, - [NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD] = NAV_STATE_MIXERAT_ABORT, - [NAV_FSM_EVENT_SWITCH_TO_CRUISE] = NAV_STATE_MIXERAT_ABORT, } }, [NAV_STATE_MIXERAT_ABORT] = { From 258a88ce154a4b0670e644f2953283c9152387f3 Mon Sep 17 00:00:00 2001 From: shota Date: Thu, 3 Aug 2023 20:31:34 +0900 Subject: [PATCH 042/122] no loiter waypoint for vtol --- src/main/flight/servos.c | 23 +--------------------- src/main/navigation/navigation_fixedwing.c | 5 +++++ 2 files changed, 6 insertions(+), 22 deletions(-) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 1ccaefd462..4d4bb497d1 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -70,27 +70,10 @@ PG_RESET_TEMPLATE(servoConfig_t, servoConfig, .servo_autotrim_rotation_limit = SETTING_SERVO_AUTOTRIM_ROTATION_LIMIT_DEFAULT ); -// PG_REGISTER_ARRAY_WITH_RESET_FN(servoMixer_t, MAX_SERVO_RULES, customServoMixers, PG_SERVO_MIXER, 1); - -// void pgResetFn_customServoMixers(servoMixer_t *instance) -// { -// for (int i = 0; i < MAX_SERVO_RULES; i++) { -// RESET_CONFIG(servoMixer_t, &instance[i], -// .targetChannel = 0, -// .inputSource = 0, -// .rate = 0, -// .speed = 0 -// #ifdef USE_PROGRAMMING_FRAMEWORK -// ,.conditionId = -1 -// #endif -// ); -// } -// } void Reset_servoMixers(servoMixer_t *instance) { - for (int i = 0; i < MAX_SERVO_RULES; i++) - { + for (int i = 0; i < MAX_SERVO_RULES; i++){ RESET_CONFIG(servoMixer_t, &instance[i], .targetChannel = 0, .inputSource = 0, @@ -171,10 +154,6 @@ void servosInit(void) servoOutputEnabled = true; mixerUsesServos = true; } - else { - servoOutputEnabled = false; - mixerUsesServos = false; - } for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) { servoComputeScalingFactors(i); diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index b82b4c5801..95ee2ca7dd 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -39,6 +39,7 @@ #include "flight/pid.h" #include "flight/imu.h" #include "flight/mixer.h" +#include "flight/mixer_profile.h" #include "fc/config.h" #include "fc/controlrate_profile.h" @@ -289,6 +290,10 @@ static void calculateVirtualPositionTarget_FW(float trackingPeriod) needToCalculateCircularLoiter = isNavHoldPositionActive() && (distanceToActualTarget <= (navLoiterRadius / TAN_15DEG)) && (distanceToActualTarget > 50.0f); + //if vtol landing is required, fly straight to homepoint + if ((posControl.navState == NAV_STATE_RTH_HEAD_HOME) && navigationRTHAllowsLanding() && checkMixerATRequired(MIXERAT_REQUEST_LAND)){ + needToCalculateCircularLoiter = false; + } /* WP turn smoothing with 2 options, 1: pass through WP, 2: cut inside turn missing WP * Works for turns > 30 degs and < 160 degs. From f96fd6402aa06a1c9bf933e6cc4b0cb94d546b14 Mon Sep 17 00:00:00 2001 From: shota Date: Fri, 4 Aug 2023 19:14:37 +0900 Subject: [PATCH 043/122] refactoring on pid i term --- src/main/flight/pid.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 13a7c45d78..fc7fa132fe 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -799,7 +799,7 @@ static float FAST_CODE applyItermRelax(const int axis, float currentPidSetpoint, const float setpointLpf = pt1FilterApply(&windupLpf[axis], currentPidSetpoint); const float setpointHpf = fabsf(currentPidSetpoint - setpointLpf); - const float itermRelaxFactor = MAX(0, 1 - setpointHpf / MC_ITERM_RELAX_SETPOINT_THRESHOLD); + const float itermRelaxFactor = MAX(0, 1 - setpointHpf / (FLIGHT_MODE(ANGLE_MODE) ? (MC_ITERM_RELAX_SETPOINT_THRESHOLD * 0.2f):MC_ITERM_RELAX_SETPOINT_THRESHOLD)); return itermErrorRate * itermRelaxFactor; } } @@ -1037,7 +1037,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; @@ -1135,8 +1135,8 @@ void FAST_CODE pidController(float dT) pidApplyFpvCameraAngleMix(pidState, currentControlRateProfile->misc.fpvCamAngleDegrees); } - // Prevent strong Iterm accumulation during stick inputs - antiWindupScaler = constrainf((1.0f - getMotorMixRange()) / motorItermWindupPoint, 0.0f, 1.0f); + // Prevent Iterm accumulation when motors are near its saturation + antiWindupScaler = constrainf((1.0f - getMotorMixRange() * MAX(2*motorItermWindupPoint,1)) / motorItermWindupPoint, 0.0f, 1.0f); for (int axis = 0; axis < 3; axis++) { // Apply setpoint rate of change limits From 75bd05a089bc463985b99f2ec17b49ec04c5f512 Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 5 Aug 2023 14:09:31 +0900 Subject: [PATCH 044/122] refactoring on pid iterm --- src/main/fc/settings.yaml | 14 +++++----- src/main/flight/pid.c | 57 +++++++++++++++++---------------------- src/main/flight/pid.h | 6 +---- 3 files changed, 33 insertions(+), 44 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 56f2a7027f..c50860fd57 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1851,12 +1851,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 @@ -1900,11 +1894,17 @@ groups: min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: iterm_windup - description: "Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)" + description: "Used to prevent Iterm accumulation on during maneuvers. Iterm accumulation will be dampened when motors are reaching it's limit (when requested motor correction range is close percentage specified by this parameter, when value is set below 50 no accumulation occors when iterm_windup+50 of motor correction range is reached)" default_value: 50 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 fc7fa132fe..63d976267c 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -79,7 +79,6 @@ typedef struct { // Rate integrator float errorGyroIf; - float errorGyroIfLimit; // Used for ANGLE filtering (PT1, we don't need super-sharpness here) pt1Filter_t angleFilterState; @@ -101,7 +100,6 @@ typedef struct { #endif uint16_t pidSumLimit; filterApply4FnPtr ptermFilterApplyFn; - bool itermLimitActive; bool itermFreezeActive; pt3Filter_t rateTargetFilter; @@ -264,8 +262,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, @@ -380,14 +378,12 @@ void pidResetErrorAccumulators(void) // Reset R/P/Y integrator for (int axis = 0; axis < 3; axis++) { pidState[axis].errorGyroIf = 0.0f; - pidState[axis].errorGyroIfLimit = 0.0f; } } void pidReduceErrorAccumulators(int8_t delta, uint8_t axis) { pidState[axis].errorGyroIf -= delta; - pidState[axis].errorGyroIfLimit -= delta; } float getTotalRateTarget(void) @@ -622,7 +618,7 @@ static void pidLevel(const float angleTarget, pidState_t *pidState, flight_dynam angleErrorDeg = DECIDEGREES_TO_DEGREES((float)angleFreefloatDeadband(DEGREES_TO_DECIDEGREES(navConfig()->fw.soaring_pitch_deadband), FD_PITCH)); if (!angleErrorDeg) { pidState->errorGyroIf = 0.0f; - pidState->errorGyroIfLimit = 0.0f; + // pidState->errorGyroIfLimit = 0.0f; } } @@ -728,14 +724,6 @@ static float dTermProcess(pidState_t *pidState, float currentRateTarget, float d return(newDTerm); } -static void applyItermLimiting(pidState_t *pidState) { - if (pidState->itermLimitActive) { - pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidState->errorGyroIfLimit, pidState->errorGyroIfLimit); - } else - { - pidState->errorGyroIfLimit = fabsf(pidState->errorGyroIf); - } -} static void nullRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT) { UNUSED(pidState); @@ -759,10 +747,9 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh pidState->errorGyroIf += rateError * pidState->kI * dT; } - 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 / 100.0f; + pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); } axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -pidState->pidSumLimit, +pidState->pidSumLimit); @@ -834,11 +821,19 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid itermErrorRate *= iTermAntigravityGain; #endif - pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) - + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); + if (!pidState->itermFreezeActive) { + pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) + + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); + } + + if (pidProfile()->pidItermLimitPercent != 0){ + float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent / 100.0f; + pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); + } + // Don't grow I-term if motors are at their limit - applyItermLimiting(pidState); + // applyItermLimiting(pidState); //merged with itermFreezeActive axisPID[axis] = newOutputLimited; @@ -1030,9 +1025,9 @@ static void pidApplyFpvCameraAngleMix(pidState_t *pidState, uint8_t fpvCameraAng pidState[YAW].rateTarget = constrainf(yawRate * cosCameraAngle + rollRate * sinCameraAngle, -GYRO_SATURATION_LIMIT, GYRO_SATURATION_LIMIT); } -void checkItermLimitingActive(pidState_t *pidState) +bool checkItermLimitingActive(pidState_t *pidState) { - bool shouldActivate; + bool shouldActivate=false; if (usedPidControllerType == PID_TYPE_PIFF) { shouldActivate = isFixedWingItermLimitActive(pidState->stickPosition); } else @@ -1040,25 +1035,24 @@ void checkItermLimitingActive(pidState_t *pidState) shouldActivate = mixerIsOutputSaturated(); //just in case, since it is already managed by itermWindupPointPercent } - pidState->itermLimitActive = STATE(ANTI_WINDUP) || shouldActivate; + return STATE(ANTI_WINDUP) || shouldActivate; } void checkItermFreezingActive(pidState_t *pidState, flight_dynamics_index_t axis) { + bool shouldActivate=false; if (usedPidControllerType == PID_TYPE_PIFF && pidProfile()->fixedWingYawItermBankFreeze != 0 && axis == FD_YAW) { // Do not allow yaw I-term to grow when bank angle is too large float bankAngle = DECIDEGREES_TO_DEGREES(attitude.values.roll); if (fabsf(bankAngle) > pidProfile()->fixedWingYawItermBankFreeze && !(FLIGHT_MODE(AUTO_TUNE) || FLIGHT_MODE(TURN_ASSISTANT) || navigationRequiresTurnAssistance())){ - pidState->itermFreezeActive = true; + shouldActivate |= true; } else { - pidState->itermFreezeActive = false; + shouldActivate |= false; } - } else - { - pidState->itermFreezeActive = false; } - + shouldActivate |=checkItermLimitingActive(pidState); + pidState->itermFreezeActive = shouldActivate; } void FAST_CODE pidController(float dT) @@ -1136,14 +1130,13 @@ void FAST_CODE pidController(float dT) } // Prevent Iterm accumulation when motors are near its saturation - antiWindupScaler = constrainf((1.0f - getMotorMixRange() * MAX(2*motorItermWindupPoint,1)) / motorItermWindupPoint, 0.0f, 1.0f); + antiWindupScaler = constrainf((1.0f - MAX(2*motorItermWindupPoint,1) * getMotorMixRange()) / motorItermWindupPoint, 0.0f, 1.0f); for (int axis = 0; axis < 3; axis++) { // Apply setpoint rate of change limits pidApplySetpointRateLimiting(&pidState[axis], axis, dT); // Step 4: Run gyro-driven control - checkItermLimitingActive(&pidState[axis]); checkItermFreezingActive(&pidState[axis], axis); pidControllerApplyFn(&pidState[axis], axis, dT); diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index e7d3981a07..8e2931c539 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 461497eff687da4fee324bbd0d9e30bf25d888e8 Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 5 Aug 2023 14:38:23 +0900 Subject: [PATCH 045/122] refactoring on pid motorItermWindupPoint --- src/main/flight/pid.c | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 20333071b0..9126bb5dcb 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -148,6 +148,7 @@ static EXTENDED_FASTRAM float dBoostMaxAtAlleceleration; static EXTENDED_FASTRAM uint8_t yawLpfHz; static EXTENDED_FASTRAM float motorItermWindupPoint; +static EXTENDED_FASTRAM float motorItermWindupPoint_inv; static EXTENDED_FASTRAM float antiWindupScaler; #ifdef USE_ANTIGRAVITY static EXTENDED_FASTRAM float iTermAntigravityGain; @@ -799,7 +800,7 @@ static float FAST_CODE applyItermRelax(const int axis, float currentPidSetpoint, const float setpointLpf = pt1FilterApply(&windupLpf[axis], currentPidSetpoint); const float setpointHpf = fabsf(currentPidSetpoint - setpointLpf); - const float itermRelaxFactor = MAX(0, 1 - setpointHpf / MC_ITERM_RELAX_SETPOINT_THRESHOLD); + const float itermRelaxFactor = MAX(0, 1 - setpointHpf / (FLIGHT_MODE(ANGLE_MODE) ? (MC_ITERM_RELAX_SETPOINT_THRESHOLD * 0.2f):MC_ITERM_RELAX_SETPOINT_THRESHOLD)); return itermErrorRate * itermRelaxFactor; } } @@ -1037,7 +1038,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; @@ -1138,8 +1139,8 @@ void FAST_CODE pidController(float dT) pidApplyFpvCameraAngleMix(pidState, currentControlRateProfile->misc.fpvCamAngleDegrees); } - // Prevent strong Iterm accumulation during stick inputs - antiWindupScaler = constrainf((1.0f - getMotorMixRange()) * motorItermWindupPoint, 0.0f, 1.0f); + // Prevent Iterm accumulation when motors are near its saturation + antiWindupScaler = constrainf((1.0f - getMotorMixRange() * MAX(2*motorItermWindupPoint,1)) * motorItermWindupPoint_inv, 0.0f, 1.0f); for (int axis = 0; axis < 3; axis++) { // Apply setpoint rate of change limits @@ -1181,7 +1182,9 @@ void pidInit(void) itermRelax = pidProfile()->iterm_relax; yawLpfHz = pidProfile()->yaw_lpf_hz; - motorItermWindupPoint = 1.0f / (1.0f - (pidProfile()->itermWindupPointPercent / 100.0f)); + motorItermWindupPoint = 1.0f - (pidProfile()->itermWindupPointPercent / 100.0f); + motorItermWindupPoint_inv = 1.0f / motorItermWindupPoint; + #ifdef USE_D_BOOST dBoostMin = pidProfile()->dBoostMin; From 2f75a764d96719cf29c168f0493631286143c753 Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 5 Aug 2023 14:09:31 +0900 Subject: [PATCH 046/122] refactoring on pid iterm --- src/main/fc/settings.yaml | 14 +++++----- src/main/flight/pid.c | 55 +++++++++++++++++---------------------- src/main/flight/pid.h | 6 +---- 3 files changed, 32 insertions(+), 43 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a0904af6f3..11a37c1ba6 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1821,12 +1821,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 @@ -1870,11 +1864,17 @@ groups: min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: iterm_windup - description: "Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)" + description: "Used to prevent Iterm accumulation on during maneuvers. Iterm accumulation will be dampened when motors are reaching it's limit (when requested motor correction range is close percentage specified by this parameter, when value is set below 50 no accumulation occors when iterm_windup+50 of motor correction range is reached)" default_value: 50 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 9126bb5dcb..969b2417eb 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -78,7 +78,6 @@ typedef struct { // Rate integrator float errorGyroIf; - float errorGyroIfLimit; // Used for ANGLE filtering (PT1, we don't need super-sharpness here) pt1Filter_t angleFilterState; @@ -100,7 +99,6 @@ typedef struct { #endif uint16_t pidSumLimit; filterApply4FnPtr ptermFilterApplyFn; - bool itermLimitActive; bool itermFreezeActive; pt3Filter_t rateTargetFilter; @@ -264,8 +262,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, @@ -380,14 +378,12 @@ void pidResetErrorAccumulators(void) // Reset R/P/Y integrator for (int axis = 0; axis < 3; axis++) { pidState[axis].errorGyroIf = 0.0f; - pidState[axis].errorGyroIfLimit = 0.0f; } } void pidReduceErrorAccumulators(int8_t delta, uint8_t axis) { pidState[axis].errorGyroIf -= delta; - pidState[axis].errorGyroIfLimit -= delta; } float getTotalRateTarget(void) @@ -622,7 +618,7 @@ static void pidLevel(const float angleTarget, pidState_t *pidState, flight_dynam angleErrorDeg = DECIDEGREES_TO_DEGREES((float)angleFreefloatDeadband(DEGREES_TO_DECIDEGREES(navConfig()->fw.soaring_pitch_deadband), FD_PITCH)); if (!angleErrorDeg) { pidState->errorGyroIf = 0.0f; - pidState->errorGyroIfLimit = 0.0f; + // pidState->errorGyroIfLimit = 0.0f; } } @@ -728,14 +724,6 @@ static float dTermProcess(pidState_t *pidState, float currentRateTarget, float d return(newDTerm); } -static void applyItermLimiting(pidState_t *pidState) { - if (pidState->itermLimitActive) { - pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidState->errorGyroIfLimit, pidState->errorGyroIfLimit); - } else - { - pidState->errorGyroIfLimit = fabsf(pidState->errorGyroIf); - } -} static void nullRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT, float dT_inv) { UNUSED(pidState); @@ -760,10 +748,9 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh pidState->errorGyroIf += rateError * pidState->kI * dT; } - 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 / 100.0f; + pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); } axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -pidState->pidSumLimit, +pidState->pidSumLimit); @@ -835,11 +822,19 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid itermErrorRate *= iTermAntigravityGain; #endif - pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) - + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); + if (!pidState->itermFreezeActive) { + pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) + + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); + } + + if (pidProfile()->pidItermLimitPercent != 0){ + float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent / 100.0f; + pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); + } + // Don't grow I-term if motors are at their limit - applyItermLimiting(pidState); + // applyItermLimiting(pidState); //merged with itermFreezeActive axisPID[axis] = newOutputLimited; @@ -1031,9 +1026,9 @@ static void pidApplyFpvCameraAngleMix(pidState_t *pidState, uint8_t fpvCameraAng pidState[YAW].rateTarget = constrainf(yawRate * cosCameraAngle + rollRate * sinCameraAngle, -GYRO_SATURATION_LIMIT, GYRO_SATURATION_LIMIT); } -void checkItermLimitingActive(pidState_t *pidState) +bool checkItermLimitingActive(pidState_t *pidState) { - bool shouldActivate; + bool shouldActivate=false; if (usedPidControllerType == PID_TYPE_PIFF) { shouldActivate = isFixedWingItermLimitActive(pidState->stickPosition); } else @@ -1041,25 +1036,24 @@ void checkItermLimitingActive(pidState_t *pidState) shouldActivate = mixerIsOutputSaturated(); //just in case, since it is already managed by itermWindupPointPercent } - pidState->itermLimitActive = STATE(ANTI_WINDUP) || shouldActivate; + return STATE(ANTI_WINDUP) || shouldActivate; } void checkItermFreezingActive(pidState_t *pidState, flight_dynamics_index_t axis) { + bool shouldActivate=false; if (usedPidControllerType == PID_TYPE_PIFF && pidProfile()->fixedWingYawItermBankFreeze != 0 && axis == FD_YAW) { // Do not allow yaw I-term to grow when bank angle is too large float bankAngle = DECIDEGREES_TO_DEGREES(attitude.values.roll); if (fabsf(bankAngle) > pidProfile()->fixedWingYawItermBankFreeze && !(FLIGHT_MODE(AUTO_TUNE) || FLIGHT_MODE(TURN_ASSISTANT) || navigationRequiresTurnAssistance())){ - pidState->itermFreezeActive = true; + shouldActivate |= true; } else { - pidState->itermFreezeActive = false; + shouldActivate |= false; } - } else - { - pidState->itermFreezeActive = false; } - + shouldActivate |=checkItermLimitingActive(pidState); + pidState->itermFreezeActive = shouldActivate; } void FAST_CODE pidController(float dT) @@ -1147,7 +1141,6 @@ void FAST_CODE pidController(float dT) pidApplySetpointRateLimiting(&pidState[axis], axis, dT); // Step 4: Run gyro-driven control - checkItermLimitingActive(&pidState[axis]); checkItermFreezingActive(&pidState[axis], axis); pidControllerApplyFn(&pidState[axis], axis, dT, dT_inv); 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 eac42ce6dfe0ee532fdd37b05cf76e35e9da233c Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 5 Aug 2023 14:43:07 +0900 Subject: [PATCH 047/122] update docs --- docs/Settings.md | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index dda075cee6..413480886e 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 @@ -1914,7 +1904,7 @@ Calculated 1G of Acc axis Z to use in INS ### iterm_windup -Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) +Used to prevent Iterm accumulation on during maneuvers. Iterm accumulation will be dampened when motors are reaching it's limit (when requested motor correction range is close percentage specified by this parameter, when value is set below 50 no accumulation occors when iterm_windup+50 of motor correction range is reached) | Default | Min | Max | | --- | --- | --- | @@ -4732,6 +4722,16 @@ Output function assignment mode. AUTO assigns outputs according to the default m --- +### 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` From 57bba67f86306c48bd10513fd3201e8ff9a5006e Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 5 Aug 2023 15:11:16 +0900 Subject: [PATCH 048/122] minor fix --- src/main/flight/pid.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 969b2417eb..76784a1460 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -749,7 +749,7 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh } if (pidProfile()->pidItermLimitPercent != 0){ - float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent / 100.0f; + float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent * 0.01f; pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); } @@ -828,7 +828,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid } if (pidProfile()->pidItermLimitPercent != 0){ - float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent / 100.0f; + float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent * 0.01f; pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); } From ecad9fe7494200d69056a9a9f8f593f5dd51a2d0 Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 7 Aug 2023 22:32:23 +0900 Subject: [PATCH 049/122] pid windup backcalc fix --- src/main/common/maths.h | 1 + src/main/flight/pid.c | 7 ++++++- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/src/main/common/maths.h b/src/main/common/maths.h index cc3d1bc517..fc8dbe3329 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -91,6 +91,7 @@ ) #define MIN(a, b) _CHOOSE(<, a, b) #define MAX(a, b) _CHOOSE(>, a, b) +#define SIGN(a) ((a >= 0) ? 1 : -1) #define _ABS_II(x, var) \ ( __extension__ ({ \ diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 76784a1460..639b1e838c 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -816,6 +816,11 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf + newCDTerm; const float newOutputLimited = constrainf(newOutput, -pidState->pidSumLimit, +pidState->pidSumLimit); + float backCalc = newOutputLimited - newOutput;//back-calculation anti-windup + if (SIGN(backCalc) == SIGN(pidState->errorGyroIf)) { + //back calculation anti-windup can only shrink integrator, will not push it to the opposite direction + backCalc = 0.0f; + } float itermErrorRate = applyItermRelax(axis, rateTarget, rateError); #ifdef USE_ANTIGRAVITY @@ -824,7 +829,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid if (!pidState->itermFreezeActive) { pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) - + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); + + (backCalc * pidState->kT * antiWindupScaler * dT); } if (pidProfile()->pidItermLimitPercent != 0){ From 5008f1b7a63c8204fbe31ab322542ac06521c361 Mon Sep 17 00:00:00 2001 From: shota Date: Mon, 7 Aug 2023 22:52:49 +0900 Subject: [PATCH 050/122] revert commit on pid --- src/main/fc/settings.yaml | 14 ++++----- src/main/flight/pid.c | 63 ++++++++++++++++++++++----------------- src/main/flight/pid.h | 6 +++- 3 files changed, 47 insertions(+), 36 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index c50860fd57..56f2a7027f 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1851,6 +1851,12 @@ 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 @@ -1894,17 +1900,11 @@ groups: min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: iterm_windup - description: "Used to prevent Iterm accumulation on during maneuvers. Iterm accumulation will be dampened when motors are reaching it's limit (when requested motor correction range is close percentage specified by this parameter, when value is set below 50 no accumulation occors when iterm_windup+50 of motor correction range is reached)" + description: "Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)" default_value: 50 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 63d976267c..13a7c45d78 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -79,6 +79,7 @@ typedef struct { // Rate integrator float errorGyroIf; + float errorGyroIfLimit; // Used for ANGLE filtering (PT1, we don't need super-sharpness here) pt1Filter_t angleFilterState; @@ -100,6 +101,7 @@ typedef struct { #endif uint16_t pidSumLimit; filterApply4FnPtr ptermFilterApplyFn; + bool itermLimitActive; bool itermFreezeActive; pt3Filter_t rateTargetFilter; @@ -262,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, @@ -378,12 +380,14 @@ void pidResetErrorAccumulators(void) // Reset R/P/Y integrator for (int axis = 0; axis < 3; axis++) { pidState[axis].errorGyroIf = 0.0f; + pidState[axis].errorGyroIfLimit = 0.0f; } } void pidReduceErrorAccumulators(int8_t delta, uint8_t axis) { pidState[axis].errorGyroIf -= delta; + pidState[axis].errorGyroIfLimit -= delta; } float getTotalRateTarget(void) @@ -618,7 +622,7 @@ static void pidLevel(const float angleTarget, pidState_t *pidState, flight_dynam angleErrorDeg = DECIDEGREES_TO_DEGREES((float)angleFreefloatDeadband(DEGREES_TO_DECIDEGREES(navConfig()->fw.soaring_pitch_deadband), FD_PITCH)); if (!angleErrorDeg) { pidState->errorGyroIf = 0.0f; - // pidState->errorGyroIfLimit = 0.0f; + pidState->errorGyroIfLimit = 0.0f; } } @@ -724,6 +728,14 @@ static float dTermProcess(pidState_t *pidState, float currentRateTarget, float d return(newDTerm); } +static void applyItermLimiting(pidState_t *pidState) { + if (pidState->itermLimitActive) { + pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidState->errorGyroIfLimit, pidState->errorGyroIfLimit); + } else + { + pidState->errorGyroIfLimit = fabsf(pidState->errorGyroIf); + } +} static void nullRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT) { UNUSED(pidState); @@ -747,9 +759,10 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh pidState->errorGyroIf += rateError * pidState->kI * dT; } - if (pidProfile()->pidItermLimitPercent != 0){ - float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent / 100.0f; - pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); + applyItermLimiting(pidState); + + if (pidProfile()->fixedWingItermThrowLimit != 0) { + pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidProfile()->fixedWingItermThrowLimit, pidProfile()->fixedWingItermThrowLimit); } axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -pidState->pidSumLimit, +pidState->pidSumLimit); @@ -786,7 +799,7 @@ static float FAST_CODE applyItermRelax(const int axis, float currentPidSetpoint, const float setpointLpf = pt1FilterApply(&windupLpf[axis], currentPidSetpoint); const float setpointHpf = fabsf(currentPidSetpoint - setpointLpf); - const float itermRelaxFactor = MAX(0, 1 - setpointHpf / (FLIGHT_MODE(ANGLE_MODE) ? (MC_ITERM_RELAX_SETPOINT_THRESHOLD * 0.2f):MC_ITERM_RELAX_SETPOINT_THRESHOLD)); + const float itermRelaxFactor = MAX(0, 1 - setpointHpf / MC_ITERM_RELAX_SETPOINT_THRESHOLD); return itermErrorRate * itermRelaxFactor; } } @@ -821,19 +834,11 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid itermErrorRate *= iTermAntigravityGain; #endif - if (!pidState->itermFreezeActive) { - pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) - + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); - } - - if (pidProfile()->pidItermLimitPercent != 0){ - float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent / 100.0f; - pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); - } - + pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) + + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); // Don't grow I-term if motors are at their limit - // applyItermLimiting(pidState); //merged with itermFreezeActive + applyItermLimiting(pidState); axisPID[axis] = newOutputLimited; @@ -1025,34 +1030,35 @@ static void pidApplyFpvCameraAngleMix(pidState_t *pidState, uint8_t fpvCameraAng pidState[YAW].rateTarget = constrainf(yawRate * cosCameraAngle + rollRate * sinCameraAngle, -GYRO_SATURATION_LIMIT, GYRO_SATURATION_LIMIT); } -bool checkItermLimitingActive(pidState_t *pidState) +void checkItermLimitingActive(pidState_t *pidState) { - bool shouldActivate=false; + bool shouldActivate; if (usedPidControllerType == PID_TYPE_PIFF) { shouldActivate = isFixedWingItermLimitActive(pidState->stickPosition); } else { - shouldActivate = mixerIsOutputSaturated(); //just in case, since it is already managed by itermWindupPointPercent + shouldActivate = mixerIsOutputSaturated(); } - return STATE(ANTI_WINDUP) || shouldActivate; + pidState->itermLimitActive = STATE(ANTI_WINDUP) || shouldActivate; } void checkItermFreezingActive(pidState_t *pidState, flight_dynamics_index_t axis) { - bool shouldActivate=false; if (usedPidControllerType == PID_TYPE_PIFF && pidProfile()->fixedWingYawItermBankFreeze != 0 && axis == FD_YAW) { // Do not allow yaw I-term to grow when bank angle is too large float bankAngle = DECIDEGREES_TO_DEGREES(attitude.values.roll); if (fabsf(bankAngle) > pidProfile()->fixedWingYawItermBankFreeze && !(FLIGHT_MODE(AUTO_TUNE) || FLIGHT_MODE(TURN_ASSISTANT) || navigationRequiresTurnAssistance())){ - shouldActivate |= true; + pidState->itermFreezeActive = true; } else { - shouldActivate |= false; + pidState->itermFreezeActive = false; } + } else + { + pidState->itermFreezeActive = false; } - shouldActivate |=checkItermLimitingActive(pidState); - pidState->itermFreezeActive = shouldActivate; + } void FAST_CODE pidController(float dT) @@ -1129,14 +1135,15 @@ void FAST_CODE pidController(float dT) pidApplyFpvCameraAngleMix(pidState, currentControlRateProfile->misc.fpvCamAngleDegrees); } - // Prevent Iterm accumulation when motors are near its saturation - antiWindupScaler = constrainf((1.0f - MAX(2*motorItermWindupPoint,1) * getMotorMixRange()) / motorItermWindupPoint, 0.0f, 1.0f); + // Prevent strong Iterm accumulation during stick inputs + antiWindupScaler = constrainf((1.0f - getMotorMixRange()) / motorItermWindupPoint, 0.0f, 1.0f); for (int axis = 0; axis < 3; axis++) { // Apply setpoint rate of change limits pidApplySetpointRateLimiting(&pidState[axis], axis, dT); // Step 4: Run gyro-driven control + checkItermLimitingActive(&pidState[axis]); checkItermFreezingActive(&pidState[axis], axis); pidControllerApplyFn(&pidState[axis], axis, dT); diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 8e2931c539..e7d3981a07 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -31,6 +31,10 @@ #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 @@ -117,9 +121,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 454387f24882fece82ffc86533c5b5f0c256127a Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 9 Aug 2023 15:02:46 +0900 Subject: [PATCH 051/122] updates on documents for mixer_profile --- docs/MixerProfile.md | 22 ++++++++++++++++++++-- docs/Settings.md | 10 +++++----- src/main/fc/settings.yaml | 10 +++++----- 3 files changed, 30 insertions(+), 12 deletions(-) diff --git a/docs/MixerProfile.md b/docs/MixerProfile.md index e586cfc401..b30753e631 100644 --- a/docs/MixerProfile.md +++ b/docs/MixerProfile.md @@ -147,12 +147,13 @@ The use of Transition Mode is recommended to enable further features and future 38 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: +Example: Increase servo 1 output by +45 with speed of maximum when transition mode is activated for tilted motor setup: ``` # rule no; servo index; input source; rate; speed; activate logic function number -smix 6 1 38 45 150 -1 +smix 6 1 38 45 0 -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. A faster tilting servo speed or more forwarded tilting servo position on transition input will reduce the time window. OR lower the throttle on the entering of the FW mode to mitigate the effect. #### Motor @@ -186,6 +187,23 @@ Set `MIXER TRANSITION` accordingly when you want to use `MIXER TRANSITION` input It is also possible to set it as 4 state switch by adding FW(profile1) with transition on. +### Automated Transition +This feature is mainly for RTH in a failsafe event. When set properly, model will use the FW mode to fly home efficiently, And land in the MC mode for easier landing. +Set `mixer_switch_on_rth` to `ON` in mixer_profile for MC mode. Set `mixer_switch_trans_timer` in mixer_profile for MC mode for the time required to gain airspeed for your model before entering to FW mode, for example, 50 ds. And set `mixer_switch_on_land` to `ON` in mixer_profile for FW mode to let the model land in MC mode. +``` +mixer_profile 2 +set mixer_switch_on_rth = ON +set mixer_switch_trans_timer = 50 +mixer_profile 1 +set mixer_switch_on_land = ON +save +``` + +`ON` for a mixer_profile\`s `mixer_switch_on_rth` or `mixer_switch_on_land` means to schedule a Automated Transition when RTH head home or RTH Land is requested by navigation controller. We need to schedule a Automated Transition in MC mode when it is heading home, So set `mixer_switch_on_rth` to `ON` for MC mixer_profile. We do not need a Automated Transition in FW mode when it is heading home, So set `mixer_switch_on_rth` to `OFF` for FW mixer_profile. + +When `mixer_switch_on_rth`:`OFF` and `mixer_switch_on_land`:`OFF` is set for all mixer_profiles(defaults). Model will not perform automated transition at all. + + ## Happy flying Remember that this is currently an emerging capability: diff --git a/docs/Settings.md b/docs/Settings.md index 7c6479ff9c..229b0b716a 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -2534,7 +2534,7 @@ This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly ### mixer_pid_profile_linking -If enabled, pid profile index will follow mixer profile index +If enabled, pid profile_index will follow mixer_profile index. Set to OFF(default) if you want to handle PID profile by your self. Recommend to set to ON on all mixer_profiles to let the mixer_profile handle the PID profile switching on a VTOL or mixed platform type setup. | Default | Min | Max | | --- | --- | --- | @@ -2544,7 +2544,7 @@ If enabled, pid profile index will follow mixer profile index ### mixer_switch_on_land -If set to on, mixer_profile will switch when Landing +If set to on, This mixer_profile will try to switch to another mixer_profile when RTH landing is requested, Only applies if this mixer_profile is a AIRPLANE platform_type. | Default | Min | Max | | --- | --- | --- | @@ -2554,7 +2554,7 @@ If set to on, mixer_profile will switch when Landing ### mixer_switch_on_rth -If set to on, mixer_profile will switch when it is heading home +If set to on, This mixer_profile will try to switch to another mixer_profile when RTH heading home is requested and distance to home is lager than 3*nav_fw_loiter_radius, Only applies if this mixer_profile is a MULTIROTOR or TRICOPTER platform_type. | Default | Min | Max | | --- | --- | --- | @@ -2564,7 +2564,7 @@ If set to on, mixer_profile will switch when it is heading home ### mixer_switch_trans_timer -If swith mixer_profile on failsafe is required, Activate MixerTransion mode for this many decisecond(0.1s) before the actual mixer_profile switch +If switch another mixer_profile is scheduled by mixer_switch_on_rth or mixer_switch_on_land. Activate Mixertransion motor/servo mixing for this many decisecond(0.1s) before the actual mixer_profile switch. | Default | Min | Max | | --- | --- | --- | @@ -2634,7 +2634,7 @@ Output frequency (in Hz) for motor pins. Applies only to brushed motors. ### motorstop_on_low -If enabled, motor will stop when throttle is low +If enabled, motor will stop when throttle is low on this mixer_profile | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index c50860fd57..80540cc396 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1164,27 +1164,27 @@ groups: field: mixer_config.outputMode table: output_mode - name: motorstop_on_low - description: "If enabled, motor will stop when throttle is low" + description: "If enabled, motor will stop when throttle is low on this mixer_profile" default_value: OFF field: mixer_config.motorstopOnLow type: bool - name: mixer_pid_profile_linking - description: "If enabled, pid profile index will follow mixer profile index" + description: "If enabled, pid profile_index will follow mixer_profile index. Set to OFF(default) if you want to handle PID profile by your self. Recommend to set to ON on all mixer_profiles to let the mixer_profile handle the PID profile switching on a VTOL or mixed platform type setup." default_value: OFF field: mixer_config.PIDProfileLinking type: bool - name: mixer_switch_on_rth - description: "If set to on, mixer_profile will switch when it is heading home" + description: "If set to on, This mixer_profile will try to switch to another mixer_profile when RTH heading home is requested and distance to home is lager than 3*nav_fw_loiter_radius, Only applies if this mixer_profile is a MULTIROTOR or TRICOPTER platform_type." default_value: OFF field: mixer_config.switchOnRTH type: bool - name: mixer_switch_on_land - description: "If set to on, mixer_profile will switch when Landing" + description: "If set to on, This mixer_profile will try to switch to another mixer_profile when RTH landing is requested, Only applies if this mixer_profile is a AIRPLANE platform_type." default_value: OFF field: mixer_config.switchOnLand type: bool - name: mixer_switch_trans_timer - description: "If swith mixer_profile on failsafe is required, Activate MixerTransion mode for this many decisecond(0.1s) before the actual mixer_profile switch" + description: "If switch another mixer_profile is scheduled by mixer_switch_on_rth or mixer_switch_on_land. Activate Mixertransion motor/servo mixing for this many decisecond(0.1s) before the actual mixer_profile switch." default_value: 0 field: mixer_config.switchTransitionTimer min: 0 From 6ac1bec25e33e9dbf912eeca5221423f76478b8d Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 12 Aug 2023 15:50:10 +0900 Subject: [PATCH 052/122] update the docs --- docs/MixerProfile.md | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/docs/MixerProfile.md b/docs/MixerProfile.md index b30753e631..db31e647a5 100644 --- a/docs/MixerProfile.md +++ b/docs/MixerProfile.md @@ -130,7 +130,7 @@ 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 stabilisation even in MR mode to get improved authority when airspeed is high. +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. @@ -147,13 +147,13 @@ The use of Transition Mode is recommended to enable further features and future 38 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 maximum when transition mode is activated for tilted motor setup: +Example: Increase servo 1 output by +45 with speed of 150 when transition mode is activated for tilted motor setup: ``` # rule no; servo index; input source; rate; speed; activate logic function number -smix 6 1 38 45 0 -1 +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. A faster tilting servo speed or more forwarded tilting servo position on transition input will reduce the time window. OR lower the throttle on the entering of the FW mode to mitigate the effect. +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 @@ -210,5 +210,5 @@ Remember that this is currently an emerging capability: * Test every thing on bench first. * Then try MR or FW mode separately see if there are any problems. -* Try it somewhere you can recover your model in case of fail-safe. Fail-safe behaviour is unknown at the current stage of development. -* Use the INAV Discord for help and setup questions; use the Github Issues for reporting bugs and unexpected behaviours. For reporting on Github, a CLI `diff all`, a DVR and a Blackbox log of the incident will assist investigation. +* Try it somewhere you can recover your model in case of fail-safe. Fail-safe behavior is unknown at the current stage of development. +* Use the INAV Discord for help and setup questions; use the Github Issues for reporting bugs and unexpected behaviors. For reporting on Github, a CLI `diff all`, a DVR and a Blackbox log of the incident will assist investigation. From c51f15f3ad0d84b9caa3911d67bb0ce59db74ea5 Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 12 Aug 2023 17:46:17 +0900 Subject: [PATCH 053/122] some cleanup --- src/main/navigation/navigation.c | 35 -------------------------------- 1 file changed, 35 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index de41be4767..3f57bcdb56 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -4448,34 +4448,6 @@ emergLandState_e getStateOfForcedEmergLanding(void) } } - -/*----------------------------------------------------------- - * Ability to mixer_profile(vtol) switch on external event - *-----------------------------------------------------------*/ -// void activateMIXERATHelper(void) -// { -// posControl.flags.mixerATHelperActivated = true; -// navProcessFSMEvents(selectNavEventFromBoxModeInput()); -// } - -// void abortMIXERATHelper(void) -// { -// // Disable emergency landing and make sure we back out of navigation mode to IDLE -// // If any navigation mode was active prior to emergency landing it will be re-enabled with next RX update -// posControl.flags.mixerATHelperActivated = false; -// navProcessFSMEvents(NAV_FSM_EVENT_SWITCH_TO_IDLE); -// } - -// altHoldState_e getStateOfMIXERATHelper(void) -// { -// /* If forced emergency landing activated and in EMERG state */ -// if (posControl.flags.mixerATHelperActivated && (navGetStateFlags(posControl.navState) & NAV_CTL_ALT)) { -// return ALTHOLD_IN_PROGRESS; -// } else { -// return ALTHOLD_IDLE; -// } -// } - bool isWaypointMissionRTHActive(void) { return (navGetStateFlags(posControl.navState) & NAV_AUTO_RTH) && IS_RC_MODE_ACTIVE(BOXNAVWP) && @@ -4487,13 +4459,6 @@ bool navigationIsExecutingAnEmergencyLanding(void) return navGetCurrentStateFlags() & NAV_CTL_EMERG; } - -bool navigationInAnyMode(void) -{ - navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); - return !(stateFlags == 0); -} - bool navigationInAutomaticThrottleMode(void) { navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); From 2c05e400485b8386e6c7b1d0252386653ff58ffd Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 27 Aug 2023 16:46:44 +0100 Subject: [PATCH 054/122] 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 524b0d0bf41f73f621f0677023abd1bc8b2a3012 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Mon, 28 Aug 2023 17:48:55 +0100 Subject: [PATCH 055/122] 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 1d0d5be21ef932b0848f1e04074aba427bcc9f23 Mon Sep 17 00:00:00 2001 From: shota Date: Fri, 1 Sep 2023 00:51:09 +0900 Subject: [PATCH 056/122] refactoring --- src/main/flight/servos.c | 14 +++++--------- 1 file changed, 5 insertions(+), 9 deletions(-) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 4d4bb497d1..fc0147ca3a 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -104,7 +104,6 @@ int16_t servo[MAX_SUPPORTED_SERVOS]; static uint8_t servoRuleCount = 0; 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 servoOutputEnabled; static bool mixerUsesServos; @@ -194,7 +193,7 @@ void loadCustomServoMixer(void) } memcpy(¤tServoMixer[servoRuleCount], &tmp_customServoMixers[i], sizeof(servoMixer_t)); - currentServoMixerActivative[servoRuleCount] = j==currentMixerProfileIndex; + currentServoMixer[servoRuleCount].rate = (j==currentMixerProfileIndex) ? currentServoMixer[servoRuleCount].rate : 0; //set rate to 0 if not active profile servoRuleCount++; } } @@ -353,9 +352,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 @@ -438,7 +434,7 @@ 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;} + if (currentServoMixer[i].rate==0) {continue;} // Reset servo middle accumulator const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; @@ -461,7 +457,7 @@ 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;} + if (currentServoMixer[i].rate==0) {continue;} const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; if (source == axis) { @@ -474,7 +470,7 @@ 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;} + if (currentServoMixer[i].rate==0) {continue;} const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; if (source == axis) { @@ -508,7 +504,7 @@ 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;} + if (currentServoMixer[i].rate==0) {continue;} const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; if (source == axis) { From 8161ef8dfbdf3f700bfed030aeaf42960208db3e Mon Sep 17 00:00:00 2001 From: shota Date: Thu, 7 Sep 2023 23:32:09 +0900 Subject: [PATCH 057/122] updates on mixer_profile --- src/main/fc/settings.yaml | 13 ++++--------- src/main/flight/mixer_profile.c | 24 +++++++++++------------- src/main/flight/mixer_profile.h | 3 +-- 3 files changed, 16 insertions(+), 24 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 06c351324a..a7622fe0c8 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1179,18 +1179,13 @@ groups: default_value: OFF field: mixer_config.PIDProfileLinking type: bool - - name: mixer_switch_on_rth - description: "If set to on, This mixer_profile will try to switch to another mixer_profile when RTH heading home is requested and distance to home is lager than 3*nav_fw_loiter_radius, Only applies if this mixer_profile is a MULTIROTOR or TRICOPTER platform_type." + - name: mixer_automated_switch + description: "If set to on, This mixer_profile will try to switch to another mixer_profile when 1.RTH heading home is requested and distance to home is lager than 3*nav_fw_loiter_radius on mixer_profile is a MULTIROTOR or TRICOPTER platform_type. 2. RTH landing is requested on this mixer_profile is a AIRPLANE platform_type" default_value: OFF - field: mixer_config.switchOnRTH - type: bool - - name: mixer_switch_on_land - description: "If set to on, This mixer_profile will try to switch to another mixer_profile when RTH landing is requested, Only applies if this mixer_profile is a AIRPLANE platform_type." - default_value: OFF - field: mixer_config.switchOnLand + field: mixer_config.automated_switch type: bool - name: mixer_switch_trans_timer - description: "If switch another mixer_profile is scheduled by mixer_switch_on_rth or mixer_switch_on_land. Activate Mixertransion motor/servo mixing for this many decisecond(0.1s) before the actual mixer_profile switch." + description: "If switch another mixer_profile is scheduled by mixer_automated_switch or mixer_automated_switch. Activate Mixertransion motor/servo mixing for this many decisecond(0.1s) before the actual mixer_profile switch." default_value: 0 field: mixer_config.switchTransitionTimer min: 0 diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 044cb027ab..d600c533eb 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -51,8 +51,7 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) .outputMode = SETTING_OUTPUT_MODE_DEFAULT, .motorstopOnLow = SETTING_MOTORSTOP_ON_LOW_DEFAULT, .PIDProfileLinking = SETTING_MIXER_PID_PROFILE_LINKING_DEFAULT, - .switchOnRTH = SETTING_MIXER_SWITCH_ON_RTH_DEFAULT, - .switchOnLand = SETTING_MIXER_SWITCH_ON_LAND_DEFAULT, + .automated_switch = SETTING_MIXER_AUTOMATED_SWITCH_DEFAULT, .switchTransitionTimer = SETTING_MIXER_SWITCH_TRANS_TIMER_DEFAULT, }); for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) @@ -93,7 +92,7 @@ void mixerConfigInit(void) setConfigProfile(getConfigMixerProfile()); pidInit(); pidInitFilters(); - // pidResetErrorAccumulators(); + pidResetErrorAccumulators(); //should be safer to reset error accumulators schedulePidGainsUpdate(); navigationUsePIDs(); // set navigation pid gains } @@ -118,16 +117,15 @@ bool checkMixerATRequired(mixerProfileATRequest_e required_action) return false; } - if ((required_action == MIXERAT_REQUEST_RTH) && (currentMixerConfig.switchOnRTH) && STATE(MULTIROTOR)) - { - //check next mixer_profile setting is valid, need to be false - return mixerConfigByIndex(nextProfileIndex)->switchOnRTH? false:true; - - } - else if ((required_action == MIXERAT_REQUEST_LAND) && (currentMixerConfig.switchOnLand) && STATE(AIRPLANE)) - { - //check next mixer_profile setting is valid, need to be false - return mixerConfigByIndex(nextProfileIndex)->switchOnLand? false:true; + if(currentMixerConfig.automated_switch){ + if ((required_action == MIXERAT_REQUEST_RTH) && STATE(MULTIROTOR)) + { + return true; + } + if ((required_action == MIXERAT_REQUEST_LAND) && STATE(AIRPLANE)) + { + return true; + } } return false; } diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index cda32f57a2..c833651c21 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -17,8 +17,7 @@ typedef struct mixerConfig_s { uint8_t outputMode; bool motorstopOnLow; bool PIDProfileLinking; - bool switchOnRTH; - bool switchOnLand; + bool automated_switch; int16_t switchTransitionTimer; } mixerConfig_t; typedef struct mixerProfile_s { From 454a2898e58cbfe208bec3976068e8e2bae77bce Mon Sep 17 00:00:00 2001 From: shota Date: Fri, 8 Sep 2023 00:02:58 +0900 Subject: [PATCH 058/122] add option to use tpa on yaw --- src/main/fc/controlrate_profile.c | 1 + src/main/fc/controlrate_profile_config_struct.h | 1 + src/main/fc/settings.yaml | 7 ++++++- src/main/flight/pid.c | 2 +- 4 files changed, 9 insertions(+), 2 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 11a37c1ba6..df5ecf7627 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1244,7 +1244,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 @@ -1255,6 +1255,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 diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 639b1e838c..06f7b92c80 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -527,7 +527,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; From 5cf1665335ed315bff9a80b76afe01d9b29e95cf Mon Sep 17 00:00:00 2001 From: shota Date: Fri, 8 Sep 2023 00:20:05 +0900 Subject: [PATCH 059/122] update the documents for mixer_profile --- docs/MixerProfile.md | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/docs/MixerProfile.md b/docs/MixerProfile.md index db31e647a5..0127da6774 100644 --- a/docs/MixerProfile.md +++ b/docs/MixerProfile.md @@ -189,19 +189,19 @@ It is also possible to set it as 4 state switch by adding FW(profile1) with tran ### Automated Transition This feature is mainly for RTH in a failsafe event. When set properly, model will use the FW mode to fly home efficiently, And land in the MC mode for easier landing. -Set `mixer_switch_on_rth` to `ON` in mixer_profile for MC mode. Set `mixer_switch_trans_timer` in mixer_profile for MC mode for the time required to gain airspeed for your model before entering to FW mode, for example, 50 ds. And set `mixer_switch_on_land` to `ON` in mixer_profile for FW mode to let the model land in MC mode. +Set `mixer_automated_switch` to `ON` in mixer_profile for MC mode. Set `mixer_switch_trans_timer` in mixer_profile for MC mode for the time required to gain airspeed for your model before entering to FW mode, for example, 50 ds. Finally set `mixer_automated_switch` to `ON` in mixer_profile for FW mode to let the model land in MC mode. ``` mixer_profile 2 -set mixer_switch_on_rth = ON +set mixer_automated_switch = ON set mixer_switch_trans_timer = 50 mixer_profile 1 -set mixer_switch_on_land = ON +set mixer_automated_switch = ON save ``` -`ON` for a mixer_profile\`s `mixer_switch_on_rth` or `mixer_switch_on_land` means to schedule a Automated Transition when RTH head home or RTH Land is requested by navigation controller. We need to schedule a Automated Transition in MC mode when it is heading home, So set `mixer_switch_on_rth` to `ON` for MC mixer_profile. We do not need a Automated Transition in FW mode when it is heading home, So set `mixer_switch_on_rth` to `OFF` for FW mixer_profile. +`ON` for a mixer_profile\`s `mixer_automated_switch` means to schedule a Automated Transition when RTH head home(applies for MC mixer_profile) or RTH Land(applies for FW mixer_profile) is requested by navigation controller. -When `mixer_switch_on_rth`:`OFF` and `mixer_switch_on_land`:`OFF` is set for all mixer_profiles(defaults). Model will not perform automated transition at all. +When `mixer_automated_switch`:`OFF` is set for all mixer_profiles(defaults). Model will not perform automated transition at all. ## Happy flying From e4ced70de73c4c90233ead12cd75dbbe7b5092f9 Mon Sep 17 00:00:00 2001 From: shota Date: Sun, 10 Sep 2023 19:09:09 +0900 Subject: [PATCH 060/122] update with timer overide --- docs/MixerProfile.md | 86 +++------------------ docs/Screenshots/timer_outputs.png | Bin 0 -> 17744 bytes docs/Settings.md | 44 +++++------ src/main/drivers/pwm_mapping.c | 14 ++++ src/main/drivers/pwm_mapping.h | 1 + src/main/fc/fc_init.c | 1 - src/main/flight/mixer_profile.c | 8 +- src/main/target/MATEKF405TE/CMakeLists.txt | 1 - src/main/target/MATEKF405TE/target.c | 18 +---- src/main/target/MATEKF405TE/target.h | 5 -- src/main/target/SITL/target.h | 1 - 11 files changed, 53 insertions(+), 126 deletions(-) create mode 100644 docs/Screenshots/timer_outputs.png diff --git a/docs/MixerProfile.md b/docs/MixerProfile.md index 0127da6774..c062863893 100644 --- a/docs/MixerProfile.md +++ b/docs/MixerProfile.md @@ -11,83 +11,18 @@ Please note that this is an emerging / experimental capability that will require ## Setup for VTOL - 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 change the source code `timerHardware` table to allow a consistent enumeration and thus mapping between MR and FW modes. -- For this reason, a **VTOL specific FC target is required**. This means that the pilot must build a custom target. In future there may be official VTOL FC targets. +- 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. +- A VTOL specific FC target was required in the early stage of the development, but thanks to `timer_output_mode` overrides, It is not needed anymore. - 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. -## FC target - -In order to keep motor and servo PWM mapping consistent and enable hot switching, the steps below are required. - -The following sections use a MATEKF405TE\_SD board (folder name `MATEKF405TE`) configured for VTOL as a example. - -The target name for VTOL build is `MATEKF405TE_SD_VTOL`, the standard target folder name is `MATEKF405TE`. - -### CMakeLists.text modifications - -#### Adding the VTOL target - -Add the VTOL target definition to `CMakeLists.txt`, i.e. the third line below. - -```c -target_stm32f405xg(MATEKF405TE) -target_stm32f405xg(MATEKF405TE_SD) -target_stm32f405xg(MATEKF405TE_SD_VTOL) //new target added -``` -### target.c modifications - -Two new enumerations are available to define the motors and servos used for VTOL. - -It is **important** to map all the PWM outputs to `TIM_USE_VTOL_MOTOR` or `TIM_USE_VTOL_SERVO` to ensure consistency between the MR mapping and FW mapping. - -For example, add the new section, encapsulated below by the `#ifdef MATEKF405TE_SD_VTOL` ... `else` section : - -```c -timerHardware_t timerHardware[] = { -#ifdef MATEKF405TE_SD_VTOL - // VTOL target specific mapping start from there - DEF_TIM(TIM8, CH4, PC9, TIM_USE_VTOL_MOTOR, 0, 0), // S1 for motor - DEF_TIM(TIM8, CH3, PC8, TIM_USE_VTOL_MOTOR, 0, 0), // S2 for motor - DEF_TIM(TIM1, CH3N, PB15, TIM_USE_VTOL_MOTOR, 0, 0), // S3 for motor - DEF_TIM(TIM1, CH1, PA8, TIM_USE_VTOL_MOTOR, 0, 1), // S4 for motor - - DEF_TIM(TIM2, CH4, PB11, TIM_USE_VTOL_SERVO, 0, 0), // S5 for servo - DEF_TIM(TIM2, CH3, PB10, TIM_USE_VTOL_SERVO, 0, 0), // S6 for servo - DEF_TIM(TIM2, CH2, PB3, TIM_USE_VTOL_SERVO, 0, 0), // S7 for servo - DEF_TIM(TIM2, CH1, PA15, TIM_USE_VTOL_SERVO, 0, 0), // S8 for servo - - DEF_TIM(TIM12, CH1, PB14, TIM_USE_VTOL_SERVO, 0, 0), // S9 for servo - DEF_TIM(TIM13, CH1, PA6, TIM_USE_VTOL_SERVO, 0, 0), // S10 for servo - DEF_TIM(TIM4, CH1, PB6, TIM_USE_VTOL_MOTOR, 0, 0), // S11 for motor - // VTOL target specific mapping ends here -#else - // Non VOTL target start from here - // .........omitted for brevity -#endif - DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), // 2812LED D(1,2,5) - DEF_TIM(TIM11, CH1, PB9, TIM_USE_BEEPER, 0, 0), // BEEPER PWM - - DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), //RX2 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 softserial1_Tx -}; -``` - -Note that using the VTOL enumerations does not affect the normal INAV requirement on the use of discrete timers for motors and servos. - -### target.h modification - -In `target.h`, define `ENABLE_MIXER_PROFILE_MCFW_HOTSWAP` to enable `mixer_profile` hot switching once you have set the `timer.c` PWM mapping: - -```c -#ifdef MATEKF405TE_SD_VTOL -#define ENABLE_MIXER_PROFILE_MCFW_HOTSWAP //Enable hot swap -#define MATEKF405TE_SD //Define the original target name keep its original configuration such as USBD_PRODUCT_STRING -#endif -``` - -Once the target is built, it can be flashed to the FC. - ## Configuration +### Timer overrides +![Alt text](Screenshots/timer_outputs.png) + +Set Output mode to `AUTO`. And set all servo/motor Timer outputs to `MOTORS` or `SERVOS`. This will result in a consistent mapping between MR and FW modes. +A Sanity check on timer overrides settings could potentially block Profile Switch for safety reasons. + +For SITL builds, is not necessary to set timer overrides. ### Profile Switch @@ -95,7 +30,7 @@ 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 support `mixer_profile`, so some of the settings have to be done in CLI. +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). @@ -209,6 +144,7 @@ When `mixer_automated_switch`:`OFF` is set for all mixer_profiles(defaults). Mod Remember that this is currently an emerging capability: * Test every thing on bench first. +* Remove the props and try `MIXER PROFILE 2`, `MIXER TRANSITION` RC modes while arming. * Then try MR or FW mode separately see if there are any problems. * Try it somewhere you can recover your model in case of fail-safe. Fail-safe behavior is unknown at the current stage of development. * Use the INAV Discord for help and setup questions; use the Github Issues for reporting bugs and unexpected behaviors. For reporting on Github, a CLI `diff all`, a DVR and a Blackbox log of the incident will assist investigation. diff --git a/docs/Screenshots/timer_outputs.png b/docs/Screenshots/timer_outputs.png new file mode 100644 index 0000000000000000000000000000000000000000..3675f64631e5495221e91abe3ce6b0e89fed10a4 GIT binary patch literal 17744 zcmeIaXH-*dgDxCUq$mi|JBW&aH0d2tdhaC^0i}f^y%!Y_snQ|zUIS7>hbUb-1c-ou z^b&d}v~T-7?^*NCnwhg^=9_ia`Eh<&62jhhcJ_VUSG)6BLrtELfQA4B0ud@IywU=J zu$e$0EGXU`;2A-lvpC=%ELSag8BoO#-3IXBw)G3u7a&ko%-u_K9N;njI|V~m5QwPb z&mXKFr{Xst(5n^2S1)wDOt)w6`{^8K?A~||+%gh^N!8-S$8EhGDe%yDdqJQQuKF40 zhHMx52LDSo@zTyjRz(HWv@DW0_;W4Tu2QFT*5S4+cJTb8CfWWhhoErkY=XOEi7p`{ zPZIF-8YXQXBNBYutcM=)#WO#858InNkE{W2rifF z+aS<8LM-6#hG-Br2xKe|!UBORSb~6efFh9wUWCSD0)f7{-zEluev4w`0WYWj@4p=N z5mYU&9z~tUdvmyk$*U>g2sGBu<(<4%-*yrFd9q#)n|+qz~sPY0v?G{ibT7U&yJ$tSF3qrqoi^c=*uYSr`h1z=-@O$*9u zv>*_ZObkRiRK4ZJ%j7HLi*yh13&Dy>eHYe^Lq;*+$DoHtEqLw+V)KbF=oDG6UWy?oTr1M zLI^=Q%WglD#``xqVsoyT=@7({wm{2)$zY@H2a|~BtGHt60U*%Gybpu)5p`6Ss3P~Z zy}X<7J3mZW^6~Uw{W|oG^-Fy&grPbG<7B(F<%jMb@NoyDziG^zYt*qr^gNKyN_=hu_zbVMpJ9is zK*4T3+~}h+HT-4mtI{3%!G?48B7du_tb^d4E3cfSEds`^7);lP$C%5OW;az|%-6cB zby@H06*KqU&IL>)siWi#im$d;%J^<_S7^?P(OLJP&+39A&0N4e;8v&*ZU)8qB|2ta zM4Qf$9ZK(f7Hw_WrBLmAH$8hmt%_O0Enwsv&5VH+S2^bdVD$B#Qq#xM&0U0;UeDfJ z@q@cU&jvc}XHRw!V@~NF21B)qn3ftM5NL?gno{~%2kTs}rEVqLfpAM>n@bz^YLm6EO>uP6Y_T^4?UBEHNf$-qdA1nec1CsQS(9qQUvWhqBw?ILz z6Nb3NZ-3>cmQ>n8@{o18y^~q~vh}Kx&CZ{OBU@$X{Z8Lz3?K~kyT)T$ZZ7U@goxx= zjH&gL4F+~h0rMoCa!4|0{jl%4xzgr*I0M(^2EArw;!c()|{2F{D}vm@orgvmS>KAMbwdqv;{) zriIFkZHdu3bt!+hGRJ^rK|&#I?o4XTP^XdqX=2!B9HQ;T&0e?NmH1FEFlU8tj<|vh zD*Bpa!His^V)bg_W{-UCT$rX*&emj&IFM92oGvHZj`fph^ZwA^@Ic6OQzY4(S9Duor!=)oh%eqt+M&7+0OeQ&^oJP(X$~@0Ae_Nq_6?( z8F~5N0huPp)^PvDP0tJg;7D^z^{@Y6R?3I}X%sW54~)K9ijkU(WsyJXk-FA&aBvvX z1J0F+)&ub_EPZ=_3)4>7mL0*>6!r&5eG0%>oxw2?+-(N4bkBg%tZUWVNe|RUP@e

oBr zCgVi0Zpa*sD`7wXF|?%ApvH)=ZENctm#}H&F6F?;>Bm<5cu>$?&3X0jkBZi(!LIx} z@ti)E>Jc?nxO4N_)wYS#Yy1wo0-LH)NL~GVbTSrHv^fSyxmmMbU1GMMuIJL z|6PxpYJbHFdt+b~xuBh{g}SVcUGkKkCgixSq{|iNpl<)gUs=2jT*k38daq{wXo~%O z|BgUiO!by_0sN{FHt9Kqq!BT?rbV;R_VaINB|~0bxDDN#J^TotK1CDy>?}~9oG%Yt zwbiw((LK?dao#pP&);Fg%kUlg@I%EPA;Y+k-dV3 z952rl zGD=I`YdX(`dgiRVXVvYF87@F|{>rc=Ns}@{DK1;Y++(Q8!;a>Z9&`H+rQH>^t;oXK15u-PSu9Fmy zNVvmj3ms%ecos1*Ef`qJ-(TAP0LRoe;58$)i99>yZ(K0}SXMTE15 zNZzc^&iveHgFI~43|#o^ki6r0LgGbmQkrF3wSo7Ibz`62ZrzZGuC}s2)N1?r&ij>< zdHA7-p*8&2cJ{`trmgB5ohvN!CXgGo+QU%OZrU?%L~Azjo%ir4F4YKAKXcrO${auV zZ5SDe1sa0*Q%a`?wyJYH8$FQndr5xdQ(qAkFIAqB!_jS=qpWIH4Zqe$DIvVoS!FV2 z4`+nnRcyN2)je!oD*BJWLIX2}CGI_UuGlS(EJir_1RUOkBME4We#}LV@DBxEgtu8- zId|0;ZW`63xu-j)PM&WGGg-f8X~$}9tk5hGQq^3gd|4enz zB|6Oo)|TiBqtS28@qBm?RiP~pD(Lg~uFzG2g7>vRSwx2?^C)Uhah-?W`CiRr~GMI=u#KU?P0+pM{^@vF3a zv?+@A5i2vt^`S}!f!3rv?WEPv4T6`I-bMijv`{nK5OR*M&jP=xG#-s~Woef}-NX-8 z9b)*6%OZON7g&G(j(`QWX02aVo_?oH1MlHtm=@bG8(FI4Dr;X|J+ut>+{j2o zO?!JsS|a9~#jMDa9pd;EmW)fOq0NojZR9~*mk-~zhlB|!#;K}T<(B)*YyY9;x>Knz zD&BK`oy&OV#s>$eJD_`1S9H?pv`cT3IVOJ9fQf7lC)Y{7B=irk)J0)3Qk8gf9-4k% z?0q(SvSQ_6tk1}PWDl7PO-9*`oRwhgT3*BiHz=i^Q`?!=YaS0h?f-E~GvPNTYK`_S zGHH>e6%=J5<7_^*+je|Aa0zX*h#5FCJ&dMtNYydN4T0-MxSb~4Ei_v6+5NH$K} zETftI7Imi;Q_{3N*_RkP8YQhP{c#x)xCd|YbxwVLBAzp~>UX^$(weNB!)k3Z!SKKbU0qvg(>v{b zaylJxwXDAWIqo}ZV5FsmdHN{dyZvowCZ1_YD&O#4MZ)(bw;9iJ5Q*2fYZb*~c}zEb z;THb@#_9NeJw#zvdvTFg9BDAP}?K2St65CZxp z9qZP&Se`Wrc4{pcAAf&ZU3ob1Ln5*1%66lwt1HLCaOpLSq2WgNE!TC4Ris-T7U*5{ z<{AlcdQ{RW?Y3ydmFl1*X;p;+o0D>%D}H6xq@SAtSjiX^+7@JqaW%3O13EgpJ|Ze zFd-qKsPu{TO9So1gGGnkXb191UJf!hDDaA36Zf(54c*~!2xEelxh?ybxpXFL+5rIp zHmN50xLKx^p-CF^b6KlpF6uU|^3&0FSMjn?2YT0&cz4kS`#YfD_Kl3vb-JY*-t3vr z^#pJdM_DK~a0t=~ikW6@?}HB4hEX{$Kc(y8);LU6zg6R?lAAq`EG;Y3y=uSjuD*%( z@!RmoaKkiN-rT(lm#ii_K}l(^{IA1$|9&SCbXy3M zkQNUc|2%cjU)1EF_K8FU$Ffl8fI}xXYgq-wU)E|=P^-blL$kp9kR!14_S88VZ^Uimk_$4GJ+8!+b&}8l`rz9tzQZ@@A1|JYd zVVc1L0W+rCo`UcTWB}}H?jt*to`!87Hdjf34xGv2(mF3|*72^SmMs}aTfOQ+m`+z2 z$ey=p@Ysswm~fw2NYYx!y{14o8_e7szZe`ss0&2pINU{TPfYJU?aM2xz3IrC#&lfB zZ2Jag!!o#BKH4#~s1I)&R=V&(m&ztMu1EH#>A~Fd9T4}Q;ZGAiTZ>`e*N%SEXACP& z8g(>v<+O=0j4zroxYykRVIumm9u+r@8LyaR*};5ujT1TMySYjQC(rUfscqb%MIH#?fypMBGM^+fm@cU!f>+((2 zEckegOzeOjW*t_7D3c`N&b1hRlX=0ugHJ*$jQ>97$ToVOqHM7~wn6z}( zqj<_v-K(XG#J16<_kmw>@$dVo*T>KlEIyt**|abTj5nKTqb(>Y(3`2G{iO8CEThsI ze0cQoaEh|6C=E(!D0CeCIn|_}60+-sFf9#`YoyL`Km;_Zy}ULrfy0dMUVAk6F_w;h zMg;ab2JUt*`8Yak34fArl)8*|ti9H^lXJZkX*v(p#2A{$Cy3G+v#L^8E)?!B+<{$O zMICU%PyFX9KO?yGSE5H6hJQ$u)qV}gS5lc*SLS!=kbz0qdt!kwpPRAXfHVA79&ejJ zJjRHlSItne3&mzrq!|-mPlk(1e={S5HoL1PmlnVI-hX@U;n1kAAuESF<-lCB5Eb!}(4G~H(OO^WhL3{QrOnQ7AP zVP?_6 zih5qW;s6z4mA8i2b-!+w_~qLwM<-g&7o~iUf$xRohnd>>0HyP<9uA75$0)*@i}ErU zn$$(BV<^<1n_ z=sCf5RhaC;Myz9R>+?mz96hgIcfGujLP-0(s}ro|JQ6ywS4aI;F+!v#!%jGj)%95w zb7$0E)y?^ZjBK&zxz6di?-6&6oQMR88C%+Fv!Naruno zmrToL4y=<2MbfQoka_a6OVE+gv9S?!#W0+0-JV^ZEky-7z!>KW%#5Khe6?a;mM0zD zu6j`s?Yp@mr5&HtY+&3+r~Li?!=BJD*r0}iR?wJE(KnjFi*Y$G5v{~B=ya1K%5c1e z)_KX%?rZxCy225G#b)gLveC|Nk99Lg^?FN0AGk-yYD-(QJP$r{KjWE>&@j8yPaJZV zW6!0Vz!XuSm(s3s*itsFb?8|0Iz3CcR2@bZdLK?m!PkS2Zxkhn$gIuBgB7RSEGvl+ z$9GLI@G26Vs?jyK>c_@dak&Wys=`z$p1|Sgu0U-SCSZ_#aM0MLkF>zb)V4OQ`3e63 zG-$I)tbIh1elfDRQ^ZQaYrK7`GOa~B7cDD;Q_>oUP!JA2I}q znXz81fde|ag~C>N`y%R6d+}Ask^PElrRKue&g`OVe}U}Dkph$eE+fwn<2vxU%g8)B z)%>Jc-^V7zrCBWMxpQW;&bCe=A5Od;6U-(Z_?(b@PlD5FLpgjsngaH1+O9f#+lAye zPN)}3V9d~?)A(9Q&V>Gv#afZ|vkt^@@D4TE$Vb<5|5fo^_mam=H)wwnsftNhy>kEV z5Na!A;WXwRD#ckIj^?gFrS#e|y+u!Q)b;7V$v|dEI?$SwF7D^>rZSr$%nB^$CUcu* zw0UY6VdH9~c7UDuWFsNfQut%$C5n}rHY&DIdWZzaDz(VwP6a2pt{1KP zYMDCa1fh}do)?gN(Ym0R)ml0*Ux7c-rS}F4lz!j%nGDW@-+M-_XA!(mp6;k{QjoM6 zbI@;bXC3rl{Ii(0iZVuy$>3qpG%V0sL9qJwt)EpdNuQ|vW<4L)f!B#0&cgnN0C}ED)3A+%4c~V-z>mqoZ3+-ldyIGtXY=K6+eYk%qLV ztZFS$@*di)bu+byZiGE-3Vh)ds0CP?k7T57f3cdFP`Y+u+w<`Z43?7dd5>L`p7q0t zU+Q^s8F^Gjpx``_h^g$=Wnk-b7}MB=S)Kdf0?fzpTFTC&?VJQYh3PrxwnK#+vDo!Y z_OF4t4?9`_X47>As)lKW^l9%WRB1~2W@)JEHVF+?{`6s#$|Xno8`V~?eYd{8JQsCa z|AO3nT?c$#1GbO9G@eT~sdZRgMP!;8!Zs6!`=wyIWek<$bB{E7~DzlrkIJ&))(k(5WBFM}yX zBwq)RPu>o>Ga>Gkl{r&mx?*+I$sqd`v*V)){y4nxU98-pCSn=fYPRqUSz{?XbAf!= zO7*K^jUnA3X8hM_2TT;R5CHQTuN@qouN=GHql9OSR8ab{Lub$FWc*`(vPjnK9@tLI zEvbE4`e@=)RolCn1r;K@&Xb!vEGEYWG}NhP`J z1K)92Z?NrI(cHO@$fJebBTS7x;{9p20Db-E0{H!wZ zx#Hd#89=C3rM>J{9}70y(X{}^`dg6lmO@Qw=7C~CA@R63`{O(ff$;Jld%b)n(^Ky# zx=KjI^;eagggP^F>6izVYy9vi_|67q1kRYqu_ z>j!eFJLrCtSM7I#Jo%-J4sud~^9&`U_9Qc32U22HxD-{QJsPu`Nk}S#`87hj zV&)YeU2&P!T8!I->OHJfh?rcX}Qn0QdJhh(k=am)8%Wq z;IB>tCHP05FQZSDIP2<+}m5+`{1_(X8$QMh-xNAnXN2P}{nKjLz)6I)#G{P{5;$3>OBNJ`Ba zG$lN?Ql_VUjt5q~`y>5Q_7?V!j@+$*C5#I5CRloGMHPqMC*6W&akBh zfz-(d_WwVZsb}c$N5kq9pwP|QCKqGc%m$N)c^9Z=_r~?xw@{315k3gSWq?n_6nj$Q zV)U7Y(V(K5Em?FX|JHloqi@|MKA1*2lLdQVgp?GhqSqC@zIu@1!#!s|%hW>7*|pjS z%lYI#!~1I&{EG-d-$1KAps9K{XrV;ai=LO9x@u{KUEEG1uJ?yW_#qP3j-T1<8Ao;! z-$Es3r#+|dC6@mxia)t#9t3A<|M*2$#w}mN=&c5h7N#HC&zxyehp*HmS{`%XL?OvH z&KzMC4f1^D{za-;usB91jU`sK`3qVdD~HNUII`~NdrPAN_aln!fSgyJQdfm!PpgK7 z=w59hP)NwJ)maN{DG7(DHp}y9eg-cCG9?G;Cqawd>}yW6ofc9I!%xyyZ^x?Bz!!QR z54oolQhN?-Z#zA#1U~<@BG+6z_l{v2ft}A2Mi+f{gS3It@ViPnzEiV4wu446QyyJb zy=Pk6-$&Y515McGPt%U0aB{9Ftpv~)hx%ygPT#Rf$yTM0RyVKU5QzIlaz>Q718yy5 z)O*^?yDBsAEo`#FD8FP^s_X)Rc>ItqT`jyKgHOE+Wmx7NQR@LaKF=+aG3oA3hWn1! zzg*i!=rVG0jv~R}^dYW%Ro$ujB14WswQkYXX${!G{_6q?ghxSJYv1&VQdDM|XHiS$ z_ncuM{$>zk#qQ1iVTNo_E>B!0GuhWi8F2{NO)qNhth%XjfKE?u+>7!1Y=}v0s4ijTC=) zIhr*jE@J6hrb++t=^$qIrtZ4o@_841gvfa;dD_s{7%!hrUAbPrD)IS>g+yz~6wqe) zed(SFz={BunDR$caGCzRdpG&C+NPJK>#01ooYh7hw-98h$%kI(dmhY?*3`7@#Zu8` znbp~1Tz{fZ71_NVy@-vQclClTKHvPtVsrZk0zL&4SzR2S$jNIswUCR(C;c&%hnZ9l zOKTi2v9j_>ofTOYq62 z!?N*&l)p?>wSQL#GWs#6=wl%{27b|WaU7&gdkggKy!^h|D-Uztn5iVXCbRxEbwV6! z;Knur-pgOLfxjz2f5+*TxBquFp{6Ucf%VZmz>Ne+@ACY~^Z%<|A{48WjDwBMNR?&J z_~hiO{R{QStgMjrk(>iB@gd-_ccO!FiAg0Rfdt-eB>TmQs80nPu8Vu0p%#VD4CtRH z3)(zZ%OCefeOEE5XqyUF5a^a_`>n844`#ndp^echmRO)W55qOEfUw>89@8JG#>Q6C zZWK`kYoB&JUePa^nj#x3FZDZ2-HQWk;i7(*6r{o*0w&0GJQ!p}G91YJo*kF9HA&OUE9t&) zZ@q*N=u(r0T6jm4zpiPArkPB`hMt*r*T1PYPA~=fWUrK{6HnyL$GuFUFTal{rq1X zO9=T6B2qv)sC2x#%f+cP=*Gb$vKA)_`K)KKmPK80v(6tyI{zOUzVo8fzw${oI?|I? zY8awgw!TIOtk+_J)-88%i3`}pSW)=IgQaD#Q3Lf(eq}_drn%fJ=Ms2lR-5ytl*;T6 zs7yhs|FFg_3+(Pf)wEn0g*Rt-h;J~&J(^#+N$MFu@zB4V5j)KN?rEg1szU~J@Ti{# zQOzn!Z@$4`=v&OZx)J~7jzGDl&`ae~@jRHpzT;(Dv&k^;G${$!!w3!ZiV(OoTwMzO zfa`<6i+p}%MG zAxX$RwJM8OzpzKSHdX9R2Wvir5R5(i5aRv3=+Lq;=i9hMEOS1hz2_^pw_7pW5r5>i zI-%&9Z%nA!>R;F3id1?lNR!3PcF^`#(CNO9L==oTg0&?;h6%<-Xy|7q+4wRaa- zcn93y(A)*_5NrN5nl%@Yt)6Z`TwI)JQn-U!GG}pkSX=R9L?5QM0Ij-?oM^!IB+%5O-=&A0?)b4bCDAHqZmKzNW+NZq>WZ`&Z%T8y)t$j*kwE5U+E&KQV z&Zx8xPy$_gTB4xy7Ol`Rke4K zRU!pj*em)Hoh(Oevm~5G305lbi-#Cm_t=|_OG{u8M0his%Qd-*Kc2A$JnK!UY%#?u za!}^hU|QE#eNjNJE(4|YP(mIiWbD{~%^zZqMOmuD-_KL{DFm4sF6wdsiYWvE(Sj-Kh ztclj({Z7ZJJm%5&z2-65XF6+<1NlDP9->M3B8O@?I>aPOO&0C)hK8w6)HCVGWd?jS zHDg;J2?o18mhGtCNxm84rMYCaCIvJM5On01{x10wec4y$g+W)tejmz>8wo47_(Usw zF9<39Ojq#r<*O*{%1;QEC-3+LY>He~KGQPEn3wnySTDAWkg3a^`LR#S%Qr!W(nV-^ zErRKV+nFEHNeVj6*`E$(h@qyMcL{$`Id*+n5)E)10#xxGVb2JS!6Uhb&|G$X0UTTB z4%rr(FW#gXYT!3ic$}#P0Tc2QpM{Y;yP>9$6qx}(qD9qCy&3OkDYr_9#@V*j;|ehS zvu$c9ZlINZ_*0vEl5qAmNmhLk3qh=G@e^VL01z`u5{XXuRctf-x7If(m7C-( zVN6Kk`cM{~%IA}$nzUm>Dy_ov&4n7LnO0=1nLmkT&VcDw{Oc~$s$!fl%N-AY*-C@= z+0G$4Unaewg{?^}rmgZe!H*oV?8j{s*Li1$w54-wp_$?Ln1kI)f-Ks<0a(u& z*0KN=IxVu0dom>F^FFDQUeQ@5RETfqDB>UR2+O=={{_52 z)S_<1L=55zcpHyhuLj)tQKWy7G}+=%@0O#VRhD)Th-+PT(LnDfd`5Gr-3Ob~DNpbHVC4hhK z4Xm{zLLq>g@`oQ5y&mYrUC28fIOao*8mj{|6AI8wzHON^g?p~_somJ1d$0Z;4KV9I zlqx7`X=#PPDJ;Pu@Y&7&O0Ak2wtPd~^Hsiu$LhMVPCicm7jnkLX(9+3k%VU4^6y^WxhvTS`@)>>3ca5W7$4uiv@|x)Om){>$&il~hDT$l*RVm*{j>-zN zs}G;{ZP=G-Se2L^PvC3{Yn2j|qF2nci~CY|$oj!=aMA>@CPea>2zMtHR;CU@p@P0y zV@-US$jkFX_w^CxqKWVJ;5z$Mq*AbX)2JD2(+*;&Rj!#AejI67PjRE#k#DJL*Elp? zH$Gi=;4Q&xRY@_q<0*L;Bt7pc5#&|4EIVJGwn?UuSzYNiT?bh7k8cusXId;R>Ml3M z!(BvA)|FIVV>9>I~%zmfh?tp7LExc%W~bJCr$v)*RdxG=)I8kq{3n7Bcx8+nftE za=n*Rxwh@YN*2QUBP$dd^}7ROLg}B(IfkW%ex@)sDu!<8NxKX^cAtCz`#L1WXM8hi zOT*eG;<{?n8Ajsq8}HMXcV|CaylZBKJa>$(ohUQJOJSAcwrBZeiHr8wpzKPZHn~KD#QF3!x_IDwuo_i0Ll5;c;h$5F}ciNW3Hr`{xK9TL?u5=FTd) zo9dr6>3{7=9_SE;1Y)jv^e2$TY`cV|t~R*HitnnryK?KZn!G`i{3L^2m^bE8{tH6L z_~1w!`>+j%UJLEbsw2uZ^5j);MDN3KpYy?_(nX{?EI8t|DlyxjP8W4yh{a0|$^I#wrj>iR+9_C(9xg=o6~H8s|X zKxTLVe?4tWOx9Rzx^%H#hiUq0#H$I9&ScTD&VbD)bg#E8b+@;k%D|IG#N?U+2%aS2 zGheNCz)Jo0hDMrStX|&dyjO@`xTujO|8tKi7O8yipgvkgz5Dn*ySlnMox%qK$f^S$ z-vq^z>wzZtnG;Q6*{%zwJz{DNYOmTba4rm}mVsl? zVrm?ve~n|QwzPL&+nDXlhfQLy z^Q(DG=Rm|EJ-y1=Qw|Q~@{jmDnJ`0ccJ}Jz&d@JAGdD)k9ffLR#DH%tZRU!=6OaIV zlOTBpD{=GF?PXgxa!X!_C33{@g*+H!8FsU^eyKtzZ*1iz+t>R1+LwQeXW!%H0KZD@ z?=hJPm3r(rSFVzpB%2WT>(m8Ij2cpSe=wC#o<%P5>n(ZV;NXs))xoswwno=AQQziu z^%*#qu%eKO(9bErm6>;y3VNzLCDN!CWTR)|5Y_GTu+R{r8%4nPFkBh-`1&YH`^J1z zZIX*;q%KM&wP7@835aubeI&bnobhkZn-7}TH(s(>igN%szidu3YuPN=i^~KFq zT3$LZX^r&h*TmegPW!H?@?4&JfP^sBb8!G3k_ro zjXjzMl~QsMj77bAIwa^E=8M zn$`WWzsn(mQy(&)voHd>P<-Ev1z_msSQf)OIvKLFWD*8MM2SgS2_h?*2fa)2$l%k>{y>gdeQ9p%_>?^bJ zIJ39@(_=aXEnZiO-lYTxoB(i0D<|eB^LL!dwgt;6i($4!;n;M`I&RG#V9*i^79d_B z3_p2vMRJKRA?I;iy{pC^ZpRggvip0ji~u%$4w}3RbU#Gr>KkHEZFew zQ}Yxw(6UbKoxk><~nl?%zgNzqjNLWt7x&o0r zWeC{|GoM$7^NOf^?hwh*inj>Uqe0XhB0Ya$=m`k)V6Y3c7;D`m8WJ^bh?U_Z{ygDP zsAsrYI6mI@D9IA>nQ&H*eg?wNM6ZZ^Z+8`mTEBTR!B>Z@Qt3_gWY7K(rZGnT@3K%1 zHku@N#HDBS=x-^Jw021`6`@~i`uhSOVJX-EjJ^9ms=yg8vY5QXLhq}`Ml)JtfN5y` zi&I7bNxMK3UTQo+mfuB4xo;=Es_G`{5Npm<`z8sa%c#q`sM66w>%(j0g?TKtDLlL8 zFYd>6e6p@kcs|E49+VPPWs588#qP}JRf!8Q_l@FAi3vy z&@0@7krlGMyVU!bhjKbvi5ZsB^oIdo91_`$zvt2Q9$hYEaVKgY^hird+{^0O&y9Ux=f#A_d&$Tk8LU> zOvvbHO*}2=%iD0(zjr=oz6~5ucZ^M2!TFBFxxla2JjLbZ&x%6krmNpZw9J`C-3NlV zp^f@Kq5c0X5HeT;`x0--|K|+G)9wFfF#cB!Mn*%cg9XzGzugyuf*14q*%UX`mVp4s zbajEovO@**8d4VBr$hC-bQ=#G?ul;KtZ^FU`~n2_R34@2+hk>chKypF11)Slezw$= z&KR83gG3a^?^*|7gTd{qQnupSMMVYI4mDe!%xYu?VbZwaef|)^`uI|8&LiFy?Mp2cX*|ax#g!>N z@hb3%je;AK%TJc4k`p2gg5!h-Z}#A+9mi(RsuD znUL8;arA5X#R|eT^3KhVsb#7YcxsdL_!o_(IG{7S^L6gxWidWTI=6vJT1$6toM0u% zst%?3O4aq%o;QmfXZmAP3Hkg#9P(AP)=%bKx%a4!c@k3LzjL2XLgJjSm;CDWPID+riD zOMblkv+4CwSTok64-&@~vm>g+``*5yxx|LScG&OX1*JbzjW%AZcO*$LDR-c)l^bWc_iz}Bk~cT5bc@b)E9LZ~eVNVz6xf=<=#-ETSs->93XOpS zKB@G)i!(vDiV59lc)eJ-MtuA3?=WwIC#EEusRUBnJr=4Casy8zBnT}#2}N>T`^pF> za(^nzNqa{XV=Wt>v} zC1UO!$$9x_ACim$_dioOZW)1rrGlPldTlT`tp-QpANkEc!fZ)=CV-2XesXfy`of zMVJ292KI$djGM!O*EKc3xwF@r=%s;?JP0Xz4Y;cRb|3ox{`)?BF4<3#k|^MHb)w)u dp^Xv-LEup8O|RX}4;&PvD696WLgw{{{|^^&+ZF%- literal 0 HcmV?d00001 diff --git a/docs/Settings.md b/docs/Settings.md index b291a80a2b..512b57e83d 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -2542,6 +2542,16 @@ This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly --- +### mixer_automated_switch + +If set to on, This mixer_profile will try to switch to another mixer_profile when 1.RTH heading home is requested and distance to home is lager than 3*nav_fw_loiter_radius on mixer_profile is a MULTIROTOR or TRICOPTER platform_type. 2. RTH landing is requested on this mixer_profile is a AIRPLANE platform_type + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + ### mixer_pid_profile_linking If enabled, pid profile_index will follow mixer_profile index. Set to OFF(default) if you want to handle PID profile by your self. Recommend to set to ON on all mixer_profiles to let the mixer_profile handle the PID profile switching on a VTOL or mixed platform type setup. @@ -2552,29 +2562,9 @@ If enabled, pid profile_index will follow mixer_profile index. Set to OFF(defaul --- -### mixer_switch_on_land - -If set to on, This mixer_profile will try to switch to another mixer_profile when RTH landing is requested, Only applies if this mixer_profile is a AIRPLANE platform_type. - -| Default | Min | Max | -| --- | --- | --- | -| OFF | OFF | ON | - ---- - -### mixer_switch_on_rth - -If set to on, This mixer_profile will try to switch to another mixer_profile when RTH heading home is requested and distance to home is lager than 3*nav_fw_loiter_radius, Only applies if this mixer_profile is a MULTIROTOR or TRICOPTER platform_type. - -| Default | Min | Max | -| --- | --- | --- | -| OFF | OFF | ON | - ---- - ### mixer_switch_trans_timer -If switch another mixer_profile is scheduled by mixer_switch_on_rth or mixer_switch_on_land. Activate Mixertransion motor/servo mixing for this many decisecond(0.1s) before the actual mixer_profile switch. +If switch another mixer_profile is scheduled by mixer_automated_switch or mixer_automated_switch. Activate Mixertransion motor/servo mixing for this many decisecond(0.1s) before the actual mixer_profile switch. | Default | Min | Max | | --- | --- | --- | @@ -5692,9 +5682,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 | | --- | --- | --- | diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index f15c29d899..7acc0c2944 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -244,6 +244,20 @@ static void timerHardwareOverride(timerHardware_t * timer) { } } +bool check_pwm_assigned_to_motor_or_servo(void) +{ + // Check TIM_USE_FW_* and TIM_USE_MC_* is consistent, If so, return true, means the pwm mapping will remain same between FW and MC + bool pwm_assigned_to_motor_or_servo = true; + for (int idx = 0; idx < timerHardwareCount; idx++) { + timerHardware_t *timHw = &timerHardware[idx]; + if (timHw->usageFlags & (TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO)) { + pwm_assigned_to_motor_or_servo &= (timHw->usageFlags == TIM_USE_VTOL_SERVO) | (timHw->usageFlags == TIM_USE_VTOL_MOTOR); + } + } + return pwm_assigned_to_motor_or_servo; +} + + bool pwmHasMotorOnTimer(timMotorServoHardware_t * timOutputs, HAL_Timer_t *tim) { for (int i = 0; i < timOutputs->maxTimMotorCount; ++i) { diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index e9b3a0f957..5b13fe72e3 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -73,6 +73,7 @@ typedef struct { } motorProtocolProperties_t; bool pwmMotorAndServoInit(void); +bool check_pwm_assigned_to_motor_or_servo(void); const motorProtocolProperties_t * getMotorProtocolProperties(motorPwmProtocolTypes_e proto); pwmInitError_e getPwmInitError(void); const char * getPwmInitErrorMessage(void); diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 634ab89e13..211c6f0704 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -305,7 +305,6 @@ void init(void) // Initialize servo and motor mixers // This needs to be called early to set up platform type correctly and count required motors & servos mixerConfigInit(); - checkMixerProfileHotSwitchAvalibility(); // Some sanity checking if (motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) { diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index d600c533eb..2d47c08ab3 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -191,17 +191,17 @@ bool checkMixerProfileHotSwitchAvalibility(void) { return true; } -#ifdef ENABLE_MIXER_PROFILE_MCFW_HOTSWAP - bool MCFW_hotswap_available = true; +#if defined(SITL_BUILD) + bool MCFW_pwm_settings_valid = true; #else - bool MCFW_hotswap_available = false; + bool MCFW_pwm_settings_valid = check_pwm_assigned_to_motor_or_servo(); #endif uint8_t platform_type0 = mixerConfigByIndex(0)->platformType; uint8_t platform_type1 = mixerConfigByIndex(1)->platformType; bool platform_type_mc0 = (platform_type0 == PLATFORM_MULTIROTOR) || (platform_type0 == PLATFORM_TRICOPTER); bool platform_type_mc1 = (platform_type1 == PLATFORM_MULTIROTOR) || (platform_type1 == PLATFORM_TRICOPTER); bool is_mcfw_switching = platform_type_mc0 ^ platform_type_mc1; - if ((!MCFW_hotswap_available) && is_mcfw_switching) + if ((!MCFW_pwm_settings_valid) && is_mcfw_switching) { allow_hot_switch = 0; return false; diff --git a/src/main/target/MATEKF405TE/CMakeLists.txt b/src/main/target/MATEKF405TE/CMakeLists.txt index d8fc13c77b..ce0150c7d3 100644 --- a/src/main/target/MATEKF405TE/CMakeLists.txt +++ b/src/main/target/MATEKF405TE/CMakeLists.txt @@ -1,3 +1,2 @@ target_stm32f405xg(MATEKF405TE) target_stm32f405xg(MATEKF405TE_SD) -target_stm32f405xg(MATEKF405TE_SD_VTOL) diff --git a/src/main/target/MATEKF405TE/target.c b/src/main/target/MATEKF405TE/target.c index 03c7d98807..70561e001f 100644 --- a/src/main/target/MATEKF405TE/target.c +++ b/src/main/target/MATEKF405TE/target.c @@ -25,22 +25,6 @@ #include "drivers/timer_def_stm32f4xx.h" timerHardware_t timerHardware[] = { -#ifdef MATEKF405TE_SD_VTOL -//With INAV firmware, DSHOT can not work on S3, S5,S7 because of DMA clash, pls use ONESHOT or MULTISHOT and calibrate ESC PWM range.<-copied from matek website - DEF_TIM(TIM8, CH4, PC9, TIM_USE_VTOL_MOTOR, 0, 0), // S1 D(2,7,7) UP217 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_VTOL_MOTOR, 0, 0), // S2 D(2,2,0) UP217 - DEF_TIM(TIM1, CH3N, PB15, TIM_USE_VTOL_MOTOR, 0, 0), // S3 D(2,6,0) UP256 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_VTOL_MOTOR, 0, 1), // S4 D(2,1,6) UP256 - - DEF_TIM(TIM2, CH4, PB11, TIM_USE_VTOL_SERVO, 0, 0), // S5 D(1,7,3) UP173 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_VTOL_SERVO, 0, 0), // S6 D(1,1,3) UP173 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_VTOL_SERVO, 0, 0), // S7 D(1,6,3) UP173 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_VTOL_SERVO, 0, 0), // S8 D(1,5,3) UP173 - - DEF_TIM(TIM12, CH1, PB14, TIM_USE_VTOL_SERVO, 0, 0), // S9 DMA NONE - DEF_TIM(TIM13, CH1, PA6, TIM_USE_VTOL_SERVO, 0, 0), // S10 DMA NONE - DEF_TIM(TIM4, CH1, PB6, TIM_USE_VTOL_MOTOR, 0, 0), // S11 D(1,0,2) -#else DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2,7,7) UP217 DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(2,2,0) UP217 DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 D(2,6,0) UP256 @@ -50,10 +34,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,1,3) UP173 DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,6,3) UP173 DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 D(1,5,3) UP173 + DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 DMA NONE DEF_TIM(TIM13, CH1, PA6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 DMA NONE DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11 D(1,0,2) -#endif DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), // 2812LED D(1,2,5) DEF_TIM(TIM11, CH1, PB9, TIM_USE_BEEPER, 0, 0), // BEEPER PWM diff --git a/src/main/target/MATEKF405TE/target.h b/src/main/target/MATEKF405TE/target.h index f4d94f6423..acaed9daf2 100644 --- a/src/main/target/MATEKF405TE/target.h +++ b/src/main/target/MATEKF405TE/target.h @@ -18,11 +18,6 @@ #pragma once #define USE_TARGET_CONFIG -#ifdef MATEKF405TE_SD_VTOL -#define ENABLE_MIXER_PROFILE_MCFW_HOTSWAP -#define MATEKF405TE_SD -#endif - #if defined(MATEKF405TE_SD) # define TARGET_BOARD_IDENTIFIER "MF4T" # define USBD_PRODUCT_STRING "MatekF405TE_SD" diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h index 1e23ec8f3e..3fbe45a5ca 100644 --- a/src/main/target/SITL/target.h +++ b/src/main/target/SITL/target.h @@ -69,7 +69,6 @@ #define USE_GPS_FAKE #define USE_RANGEFINDER_FAKE #define USE_RX_SIM -#define ENABLE_MIXER_PROFILE_MCFW_HOTSWAP #undef MAX_MIXER_PROFILE_COUNT #define MAX_MIXER_PROFILE_COUNT 2 From 3a332bfe7489187b7de5f7df17f066d05888b22b Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 10 Sep 2023 17:49:37 +0200 Subject: [PATCH 061/122] Simplify timer usage flags. A servo is a servo, no matter what the platform. A motor is a motor, no matter what the platform. Enum values changed, and compatibility macros added. Since the enum is not used in configuration, I don't expect regressions from this particular changes. --- src/main/drivers/pwm_mapping.c | 64 +++++++++++++++------------------- src/main/drivers/timer.h | 23 +++++++++--- 2 files changed, 47 insertions(+), 40 deletions(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index a3594af2de..4eba3809e5 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -279,7 +279,6 @@ uint8_t pwmClaimTimer(HAL_Timer_t *tim, uint32_t usageFlags) { void pwmEnsureEnoughtMotors(uint8_t motorCount) { uint8_t motorOnlyOutputs = 0; - uint8_t mcMotorOnlyOutputs = 0; for (int idx = 0; idx < timerHardwareCount; idx++) { timerHardware_t *timHw = &timerHardware[idx]; @@ -290,49 +289,28 @@ void pwmEnsureEnoughtMotors(uint8_t motorCount) continue; } - if (timHw->usageFlags & (TIM_USE_MC_MOTOR) && !(timHw->usageFlags & (TIM_USE_MC_SERVO))) { - mcMotorOnlyOutputs++; - mcMotorOnlyOutputs += pwmClaimTimer(timHw->tim, timHw->usageFlags); - } - if (timHw->usageFlags & (TIM_USE_FW_MOTOR) && !(timHw->usageFlags & (TIM_USE_FW_SERVO))) { + if (TIM_IS_MOTOR_ONLY(timHw->usageFlags)) { motorOnlyOutputs++; motorOnlyOutputs += pwmClaimTimer(timHw->tim, timHw->usageFlags); } } - if (mixerConfig()->platformType == PLATFORM_MULTIROTOR || - mixerConfig()->platformType == PLATFORM_TRICOPTER) { + for (int idx = 0; idx < timerHardwareCount; idx++) { + timerHardware_t *timHw = &timerHardware[idx]; - for (int idx = 0; mcMotorOnlyOutputs < motorCount && idx < timerHardwareCount; idx++) { - timerHardware_t *timHw = &timerHardware[idx]; - - if (checkPwmTimerConflicts(timHw)) { - continue; - } - - uint32_t mcFlags = timHw->usageFlags & (TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO); - - if (mcFlags && mcFlags != TIM_USE_MC_MOTOR) { - timHw->usageFlags &= ~TIM_USE_MC_SERVO; - timHw->usageFlags |= TIM_USE_MC_MOTOR; - mcMotorOnlyOutputs++; - mcMotorOnlyOutputs += pwmClaimTimer(timHw->tim, timHw->usageFlags); - } + if (checkPwmTimerConflicts(timHw)) { + continue; } - } else { - for (int idx = 0; motorOnlyOutputs < motorCount && idx < timerHardwareCount; idx++) { - timerHardware_t *timHw = &timerHardware[idx]; - if (checkPwmTimerConflicts(timHw)) { - continue; - } - - uint32_t fwFlags = timHw->usageFlags & (TIM_USE_FW_MOTOR | TIM_USE_FW_SERVO); - if (fwFlags && fwFlags != TIM_USE_FW_MOTOR) { - timHw->usageFlags &= ~TIM_USE_FW_SERVO; - timHw->usageFlags |= TIM_USE_FW_MOTOR; + if (TIM_IS_MOTOR(timHw->usageFlags) && !TIM_IS_MOTOR_ONLY(timHw->usageFlags)) { + if (motorOnlyOutputs < motorCount) { + timHw->usageFlags &= ~TIM_USE_SERVO; + timHw->usageFlags |= TIM_USE_MOTOR; motorOnlyOutputs++; motorOnlyOutputs += pwmClaimTimer(timHw->tim, timHw->usageFlags); + } else { + timHw->usageFlags &= ~TIM_USE_MOTOR; + pwmClaimTimer(timHw->tim, timHw->usageFlags); } } } @@ -340,6 +318,7 @@ void pwmEnsureEnoughtMotors(uint8_t motorCount) void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos) { + UNUSED(isMixerUsingServos); timOutputs->maxTimMotorCount = 0; timOutputs->maxTimServoCount = 0; @@ -351,7 +330,7 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU for (int idx = 0; idx < timerHardwareCount; idx++) { timerHardware_t *timHw = &timerHardware[idx]; - timerHardwareOverride(timHw); + //timerHardwareOverride(timHw); int type = MAP_TO_NONE; @@ -361,6 +340,20 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU continue; } + // Make sure first motorCount motor outputs get assigned to motor + if (TIM_IS_MOTOR(timHw->usageFlags) && (motorIdx < motorCount)) { + timHw->usageFlags = timHw->usageFlags & ~TIM_USE_SERVO; + pwmClaimTimer(timHw->tim, timHw->usageFlags); + motorIdx += 1; + } + + if (TIM_IS_SERVO(timHw->usageFlags) && !pwmHasMotorOnTimer(timOutputs, timHw->tim)) { + type = MAP_TO_SERVO_OUTPUT; + } else if (TIM_IS_MOTOR(timHw->usageFlags) && !pwmHasServoOnTimer(timOutputs, timHw->tim)) { + type = MAP_TO_MOTOR_OUTPUT; + } + +#if 0 // Determine if timer belongs to motor/servo if (mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER) { // Multicopter @@ -393,6 +386,7 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU type = MAP_TO_MOTOR_OUTPUT; } } +#endif switch(type) { case MAP_TO_MOTOR_OUTPUT: diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index b822114147..098bb820ed 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -110,16 +110,29 @@ typedef enum { TIM_USE_ANY = 0, TIM_USE_PPM = (1 << 0), TIM_USE_PWM = (1 << 1), - TIM_USE_MC_MOTOR = (1 << 2), // Multicopter motor output - TIM_USE_MC_SERVO = (1 << 3), // Multicopter servo output (i.e. TRI) + TIM_USE_MOTOR = (1 << 2), // Motor output + TIM_USE_SERVO = (1 << 3), // Servo output TIM_USE_MC_CHNFW = (1 << 4), // Deprecated and not used after removal of CHANNEL_FORWARDING feature - TIM_USE_FW_MOTOR = (1 << 5), - TIM_USE_FW_SERVO = (1 << 6), + //TIM_USE_FW_MOTOR = (1 << 5), // We no longer differentiate mc from fw on pwm allocation + //TIM_USE_FW_SERVO = (1 << 6), TIM_USE_LED = (1 << 24), TIM_USE_BEEPER = (1 << 25), } timerUsageFlag_e; -#define TIM_USE_OUTPUT_AUTO (TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR | TIM_USE_FW_SERVO) + +// Compability +#define TIM_USE_MC_MOTOR TIM_USE_MOTOR +#define TIM_USE_MC_SERVO TIM_USE_SERVO +#define TIM_USE_FW_MOTOR TIM_USE_MOTOR +#define TIM_USE_FW_SERVO TIM_USE_SERVO + +#define TIM_USE_OUTPUT_AUTO (TIM_USE_MOTOR | TIM_USE_SERVO) + +#define TIM_IS_MOTOR(flags) ((flags) & (TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR)) +#define TIM_IS_SERVO(flags) ((flags) & (TIM_USE_MC_SERVO | TIM_USE_FW_SERVO)) + +#define TIM_IS_MOTOR_ONLY(flags) (TIM_IS_MOTOR(flags) && !TIM_IS_SERVO(flags)) +#define TIM_IS_SERVO_ONLY(flags) (!TIM_IS_MOTOR(flags) && TIM_IS_SERVO(flags)) enum { TIMER_OUTPUT_NONE = 0x00, From 0c56f025132bfddebb11079b745ebe119a6d7c26 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 10 Sep 2023 19:31:55 +0200 Subject: [PATCH 062/122] Change all usages for TIM_USE_MC/FW_MOTOR/SERVO to the new TIM_USE_MOTOR/SERVO --- src/main/drivers/pwm_esc_detect.c | 2 +- src/main/drivers/pwm_mapping.c | 65 +++++++------------------------ src/main/drivers/timer.h | 4 +- 3 files changed, 18 insertions(+), 53 deletions(-) diff --git a/src/main/drivers/pwm_esc_detect.c b/src/main/drivers/pwm_esc_detect.c index 1cd3c72cd0..8abebbb7b1 100644 --- a/src/main/drivers/pwm_esc_detect.c +++ b/src/main/drivers/pwm_esc_detect.c @@ -38,7 +38,7 @@ uint8_t hardwareMotorType = MOTOR_UNKNOWN; void detectBrushedESC(void) { for (int i = 0; i < timerHardwareCount; i++) { - if (timerHardware[i].usageFlags & TIM_USE_MC_MOTOR) { + if (timerHardware[i].usageFlags & TIM_USE_MOTOR) { IO_t MotorDetectPin = IOGetByTag(timerHardware[i].tag); IOInit(MotorDetectPin, OWNER_SYSTEM, RESOURCE_INPUT, 0); IOConfigGPIO(MotorDetectPin, IOCFG_IPU); diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 4eba3809e5..830930f638 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -213,29 +213,29 @@ static bool checkPwmTimerConflicts(const timerHardware_t *timHw) static void timerHardwareOverride(timerHardware_t * timer) { if (mixerConfig()->outputMode == OUTPUT_MODE_SERVOS) { //Motors are rewritten as servos - if (timer->usageFlags & (TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR)) { - timer->usageFlags &= ~(TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR); - timer->usageFlags |= TIM_USE_MC_SERVO | TIM_USE_FW_SERVO; + if (TIM_IS_MOTOR(timer->usageFlags)) { + timer->usageFlags &= ~TIM_USE_MOTOR; + timer->usageFlags |= TIM_USE_SERVO; } } else if (mixerConfig()->outputMode == OUTPUT_MODE_MOTORS) { // Servos are rewritten as motors - if (timer->usageFlags & (TIM_USE_MC_SERVO | TIM_USE_FW_SERVO)) { - timer->usageFlags &= ~(TIM_USE_MC_SERVO | TIM_USE_FW_SERVO); - timer->usageFlags |= TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR; + if (TIM_IS_SERVO(timer->usageFlags)) { + timer->usageFlags &= ~TIM_USE_SERVO; + timer->usageFlags |= TIM_USE_MOTOR; } } switch (timerOverrides(timer2id(timer->tim))->outputMode) { case OUTPUT_MODE_MOTORS: - if (timer->usageFlags & (TIM_USE_MC_SERVO | TIM_USE_FW_SERVO)) { - timer->usageFlags &= ~(TIM_USE_MC_SERVO | TIM_USE_FW_SERVO); - timer->usageFlags |= TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR; + if (TIM_IS_SERVO(timer->usageFlags)) { + timer->usageFlags &= ~TIM_USE_SERVO; + timer->usageFlags |= TIM_USE_MOTOR; } break; case OUTPUT_MODE_SERVOS: - if (timer->usageFlags & (TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR)) { - timer->usageFlags &= ~(TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR); - timer->usageFlags |= TIM_USE_MC_SERVO | TIM_USE_FW_SERVO; + if (TIM_IS_MOTOR(timer->usageFlags)) { + timer->usageFlags &= ~TIM_USE_MOTOR; + timer->usageFlags |= TIM_USE_SERVO; } break; } @@ -342,7 +342,7 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU // Make sure first motorCount motor outputs get assigned to motor if (TIM_IS_MOTOR(timHw->usageFlags) && (motorIdx < motorCount)) { - timHw->usageFlags = timHw->usageFlags & ~TIM_USE_SERVO; + timHw->usageFlags &= ~TIM_USE_SERVO; pwmClaimTimer(timHw->tim, timHw->usageFlags); motorIdx += 1; } @@ -353,49 +353,14 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU type = MAP_TO_MOTOR_OUTPUT; } -#if 0 - // Determine if timer belongs to motor/servo - if (mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER) { - // Multicopter - - // Make sure first motorCount outputs get assigned to motor - if ((timHw->usageFlags & TIM_USE_MC_MOTOR) && (motorIdx < motorCount)) { - timHw->usageFlags = timHw->usageFlags & ~TIM_USE_MC_SERVO; - pwmClaimTimer(timHw->tim, timHw->usageFlags); - motorIdx += 1; - } - - // We enable mapping to servos if mixer is actually using them and it does not conflict with used motors - if (isMixerUsingServos && timHw->usageFlags & TIM_USE_MC_SERVO && !pwmHasMotorOnTimer(timOutputs, timHw->tim)) { - type = MAP_TO_SERVO_OUTPUT; - } else if (timHw->usageFlags & TIM_USE_MC_MOTOR && !pwmHasServoOnTimer(timOutputs, timHw->tim)) { - type = MAP_TO_MOTOR_OUTPUT; - } - } else { - // Make sure first motorCount motor outputs get assigned to motor - if ((timHw->usageFlags & TIM_USE_FW_MOTOR) && (motorIdx < motorCount)) { - timHw->usageFlags = timHw->usageFlags & ~TIM_USE_FW_SERVO; - pwmClaimTimer(timHw->tim, timHw->usageFlags); - motorIdx += 1; - } - - // Fixed wing or HELI (one/two motors and a lot of servos - if (timHw->usageFlags & TIM_USE_FW_SERVO && !pwmHasMotorOnTimer(timOutputs, timHw->tim)) { - type = MAP_TO_SERVO_OUTPUT; - } else if (timHw->usageFlags & TIM_USE_FW_MOTOR && !pwmHasServoOnTimer(timOutputs, timHw->tim)) { - type = MAP_TO_MOTOR_OUTPUT; - } - } -#endif - switch(type) { case MAP_TO_MOTOR_OUTPUT: - timHw->usageFlags &= (TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR); + timHw->usageFlags &= TIM_USE_MOTOR; timOutputs->timMotors[timOutputs->maxTimMotorCount++] = timHw; pwmClaimTimer(timHw->tim, timHw->usageFlags); break; case MAP_TO_SERVO_OUTPUT: - timHw->usageFlags &= (TIM_USE_MC_SERVO | TIM_USE_FW_SERVO); + timHw->usageFlags &= TIM_USE_SERVO; timOutputs->timServos[timOutputs->maxTimServoCount++] = timHw; pwmClaimTimer(timHw->tim, timHw->usageFlags); break; diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index 098bb820ed..12865fdc5d 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -128,8 +128,8 @@ typedef enum { #define TIM_USE_OUTPUT_AUTO (TIM_USE_MOTOR | TIM_USE_SERVO) -#define TIM_IS_MOTOR(flags) ((flags) & (TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR)) -#define TIM_IS_SERVO(flags) ((flags) & (TIM_USE_MC_SERVO | TIM_USE_FW_SERVO)) +#define TIM_IS_MOTOR(flags) ((flags) & TIM_USE_MOTOR) +#define TIM_IS_SERVO(flags) ((flags) & TIM_USE_SERVO) #define TIM_IS_MOTOR_ONLY(flags) (TIM_IS_MOTOR(flags) && !TIM_IS_SERVO(flags)) #define TIM_IS_SERVO_ONLY(flags) (!TIM_IS_MOTOR(flags) && TIM_IS_SERVO(flags)) From 8b0baebe4e0c85badedc9d5d9d38f548df3b0de4 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 12 Sep 2023 21:46:07 +0200 Subject: [PATCH 063/122] Remove commented out line --- src/main/drivers/pwm_mapping.c | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 830930f638..90d6ef3af3 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -330,8 +330,6 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU for (int idx = 0; idx < timerHardwareCount; idx++) { timerHardware_t *timHw = &timerHardware[idx]; - //timerHardwareOverride(timHw); - int type = MAP_TO_NONE; // Check for known conflicts (i.e. UART, LEDSTRIP, Rangefinder and ADC) From ec117409f2acd8517d613df174e5b6c935280e96 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 12 Sep 2023 23:54:37 +0200 Subject: [PATCH 064/122] Bulk target updates --- src/main/target/AIRBOTF4/target.c | 26 +++++------ src/main/target/AIRBOTF7/target.c | 12 ++--- src/main/target/ALIENFLIGHTF4/target.c | 26 +++++------ src/main/target/ALIENFLIGHTNGF7/target.c | 26 +++++------ src/main/target/ANYFC/target.c | 32 +++++++------- src/main/target/ANYFCF7/target.c | 32 +++++++------- src/main/target/ANYFCM7/target.c | 20 ++++----- src/main/target/AOCODARCF405AIO/target.c | 8 ++-- src/main/target/AOCODARCF4V2/target.c | 16 +++---- src/main/target/AOCODARCF7DUAL/target.c | 16 +++---- src/main/target/AOCODARCF7MINI/target.c | 18 ++++---- src/main/target/AOCODARCH7DUAL/target.c | 24 +++++----- src/main/target/ASGARD32F4/target.c | 8 ++-- src/main/target/ASGARD32F7/target.c | 8 ++-- src/main/target/ATOMRCF405NAVI/target.c | 16 +++---- src/main/target/AXISFLYINGF7PRO/target.c | 18 ++++---- src/main/target/BEEROTORF4/target.c | 16 +++---- src/main/target/BETAFLIGHTF4/target.c | 8 ++-- src/main/target/BETAFPVF405/config.c | 33 ++++++++++++++ src/main/target/BETAFPVF405/target.c | 43 ++++++++++++++++++ src/main/target/BETAFPVF435/target.c | 14 +++--- src/main/target/BETAFPVF722/target.c | 18 ++++---- src/main/target/BLACKPILL_F411/target.c | 12 ++--- src/main/target/BLUEJAYF4/target.c | 14 +++--- src/main/target/CLRACINGF4AIR/target.c | 24 +++++----- src/main/target/COLIBRI/target.c | 16 +++---- src/main/target/CRAZYBEEF4SX1280/config.c | 33 ++++++++++++++ src/main/target/CRAZYBEEF4SX1280/target.c | 44 +++++++++++++++++++ src/main/target/DALRCF405/target.c | 16 +++---- src/main/target/DALRCF722DUAL/target.c | 12 ++--- src/main/target/F4BY/target.c | 16 +++---- src/main/target/FF_F35_LIGHTNING/target.c | 12 ++--- src/main/target/FF_FORTINIF4/target.c | 8 ++-- src/main/target/FF_PIKOF4/target.c | 20 ++++----- src/main/target/FIREWORKSV2/target.c | 20 +++++---- src/main/target/FISHDRONEF4/target.c | 12 ++--- src/main/target/FLYCOLORF7MINI/target.c | 4 +- src/main/target/FLYWOOF405PRO/target.c | 16 +++---- src/main/target/FLYWOOF411/target.c | 16 +++---- src/main/target/FLYWOOF745/target.c | 20 ++++----- src/main/target/FLYWOOF7DUAL/target.c | 12 ++--- src/main/target/FOXEERF405/target.c | 16 +++---- src/main/target/FOXEERF722DUAL/target.c | 14 +++--- src/main/target/FOXEERF722V4/target.c | 16 +++---- src/main/target/FOXEERF745AIO/target.c | 8 ++-- src/main/target/FOXEERH743/target.c | 20 ++++----- src/main/target/FRSKYF4/target.c | 12 ++--- src/main/target/FRSKYPILOT/target.c | 24 +++++----- src/main/target/FRSKY_ROVERF7/target.c | 10 ++--- src/main/target/FURYF4OSD/target.c | 8 ++-- src/main/target/GEPRCF405/target.c | 12 ++--- src/main/target/GEPRCF722/target.c | 12 ++--- src/main/target/GEPRCF722_BT_HD/target.c | 16 +++---- src/main/target/GEPRC_F722_AIO/target.c | 8 ++-- src/main/target/HAKRCF405D/target.c | 12 ++--- src/main/target/HAKRCF405V2/target.c | 16 +++---- src/main/target/HAKRCF411D/target.c | 8 ++-- src/main/target/HAKRCF722V2/target.c | 16 +++---- src/main/target/HAKRCKD722/target.c | 16 +++---- src/main/target/HGLRCF722/target.c | 16 +++---- src/main/target/IFLIGHTF4_SUCCEXD/target.c | 8 ++-- src/main/target/IFLIGHTF4_TWING/target.c | 8 ++-- src/main/target/IFLIGHTF7_TWING/target.c | 16 +++---- src/main/target/IFLIGHT_BLITZ_F722/target.c | 17 ++++--- src/main/target/IFLIGHT_BLITZ_F7_AIO/target.c | 24 +++++----- src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c | 16 +++---- src/main/target/IFLIGHT_H743_AIO_V2/target.c | 10 ++--- src/main/target/IFLIGHT_JBF7PRO/target.c | 16 +++---- src/main/target/JHEH7AIO/target.c | 12 ++--- src/main/target/KAKUTEF4/target.c | 18 ++++---- src/main/target/KAKUTEF7/target.c | 14 +++--- src/main/target/KAKUTEF7MINIV3/target.c | 14 +++--- src/main/target/KAKUTEH7/target.c | 16 +++---- src/main/target/KAKUTEH7WING/target.c | 28 ++++++------ src/main/target/KROOZX/target.c | 20 ++++----- src/main/target/MAMBAF405US/target.c | 16 +++---- src/main/target/MAMBAF405_2022A/target.c | 12 ++--- src/main/target/MAMBAF722/target.c | 8 ++-- src/main/target/MAMBAF722_2022A/target.c | 16 +++---- src/main/target/MAMBAF722_WING/target.c | 16 +++---- src/main/target/MAMBAF722_X8/target.c | 16 +++---- src/main/target/MAMBAH743/target.c | 16 +++---- src/main/target/MATEKF405/target.c | 2 +- src/main/target/MATEKF405CAN/target.c | 16 +++---- src/main/target/MATEKF405SE/target.c | 18 ++++---- src/main/target/MATEKF405TE/target.c | 22 +++++----- src/main/target/MATEKF411/target.c | 14 +++--- src/main/target/MATEKF411SE/target.c | 12 ++--- src/main/target/MATEKF411TE/target.c | 14 +++--- src/main/target/MATEKF722PX/target.c | 20 ++++----- src/main/target/MATEKF722SE/CMakeLists.txt | 1 - src/main/target/MATEKF722SE/target.c | 21 ++++----- src/main/target/MATEKF765/target.c | 24 +++++----- src/main/target/NEUTRONRCF435MINI/target.c | 10 ++--- src/main/target/NEUTRONRCF435SE/target.c | 26 +++++------ src/main/target/NEUTRONRCF435WING/target.c | 18 ++++---- src/main/target/NEUTRONRCH7BT/target.c | 16 +++---- src/main/target/NOX/target.c | 8 ++-- src/main/target/OMNIBUSF4/target.c | 22 +++++----- src/main/target/OMNIBUSF7/target.c | 8 ++-- src/main/target/OMNIBUSF7NXT/target.c | 12 ++--- src/main/target/PIXRACER/target.c | 12 ++--- src/main/target/RADIX/target.c | 12 ++--- src/main/target/REVO/target.c | 24 +++++----- src/main/target/RUSH_BLADE_F7/target.c | 16 +++---- src/main/target/SAGEATF4/target.c | 22 +++++----- src/main/target/SKYSTARSF405HD/target.c | 8 ++-- src/main/target/SKYSTARSF722HD/target.c | 8 ++-- src/main/target/SKYSTARSH743HD/target.c | 16 +++---- src/main/target/SPARKY2/target.c | 12 ++--- src/main/target/SPEEDYBEEF4/target.c | 14 +++--- src/main/target/SPEEDYBEEF405MINI/target.c | 12 ++--- src/main/target/SPEEDYBEEF405V3/target.c | 16 +++---- src/main/target/SPEEDYBEEF405WING/target.c | 22 +++++----- src/main/target/SPEEDYBEEF7/target.c | 12 ++--- src/main/target/SPEEDYBEEF745AIO/target.c | 10 ++--- src/main/target/SPEEDYBEEF7MINI/target.c | 16 +++---- src/main/target/SPEEDYBEEF7V2/target.c | 10 ++--- src/main/target/SPEEDYBEEF7V3/target.c | 18 ++++---- src/main/target/SPRACINGF4EVO/target.c | 20 ++++----- src/main/target/SPRACINGF7DUAL/target.c | 28 ++++++------ src/main/target/TMOTORF7/target.c | 12 ++--- src/main/target/TMOTORF7V2/target.c | 18 ++++---- src/main/target/YUPIF4/target.c | 24 +++++----- src/main/target/YUPIF7/target.c | 18 ++++---- src/main/target/ZEEZF7/target.c | 40 ++++++++--------- 126 files changed, 1107 insertions(+), 959 deletions(-) create mode 100644 src/main/target/BETAFPVF405/config.c create mode 100644 src/main/target/BETAFPVF405/target.c create mode 100644 src/main/target/CRAZYBEEF4SX1280/config.c create mode 100644 src/main/target/CRAZYBEEF4SX1280/target.c diff --git a/src/main/target/AIRBOTF4/target.c b/src/main/target/AIRBOTF4/target.c index 8e324818d8..b2263a6805 100644 --- a/src/main/target/AIRBOTF4/target.c +++ b/src/main/target/AIRBOTF4/target.c @@ -24,20 +24,20 @@ #include "drivers/bus.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT D1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT D1_ST2 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3_OUT D1_ST6 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT D1_ST1 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO | TIM_USE_ANY, 0, 0), // S5_OUT / LED - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT - DEF_TIM(TIM4, CH1, PB6, TIM_USE_ANY, 0, 0), // LED D1_ST0, n/a on older AIRBOTF4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT D1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT D1_ST2 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3_OUT D1_ST6 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT D1_ST1 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_ANY, 0, 0), // S5_OUT / LED + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT + DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED | TIM_USE_ANY, 0, 0), // LED D1_ST0, n/a on older AIRBOTF4 - DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // PPM (5th pin on FlexiIO port) - DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN - DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // S3_IN - DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // S4_IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // S5_IN - DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // S6_IN + DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // PPM (5th pin on FlexiIO port) + DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN + DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_IN + DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_IN + DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_IN + DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_IN }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AIRBOTF7/target.c b/src/main/target/AIRBOTF7/target.c index a81988d0a6..4acf3ddca8 100644 --- a/src/main/target/AIRBOTF7/target.c +++ b/src/main/target/AIRBOTF7/target.c @@ -42,13 +42,13 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu1_mpu6500, DEVHW_MPU6500, GYRO_1_SPI_BUS, #endif timerHardware_t timerHardware[] = { - DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED - DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // Cam control, SS, UNUSED + DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED + DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // Cam control, SS, UNUSED - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0), //S1 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR, 0, 0), //S2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0), //S3 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0, 0), //S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), //S1 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), //S2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), //S3 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), //S4 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/ALIENFLIGHTF4/target.c b/src/main/target/ALIENFLIGHTF4/target.c index bb60067073..1943fd46f4 100644 --- a/src/main/target/ALIENFLIGHTF4/target.c +++ b/src/main/target/ALIENFLIGHTF4/target.c @@ -23,19 +23,19 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, 0, 1), // PWM1 - PA8 RC1 - DMA2_ST1 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0, 0), // PWM2 - PB0 RC2 - DMA1_ST5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0, 0), // PWM3 - PB1 RC3 - DMA1_ST7 - DEF_TIM(TIM1, CH2, PB14, TIM_USE_PWM, 0, 1), // PWM4 - PA14 RC4 - DMA2_ST2 - DEF_TIM(TIM1, CH3, PB15, TIM_USE_PWM | TIM_USE_LED, 0, 0), // PWM5 - PA15 RC5 - DMA2_ST6 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // PWM6 - PB8 OUT1 - DMA1_ST7 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // PWM7 - PB9 OUT2 - DMA_NONE - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM8 - PA0 OUT3 - DMA1_ST2 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM9 - PA1 OUT4 - DMA1_ST4 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM10 - PC6 OUT5 - DMA2_ST2 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM11 - PC7 OUT6 - DMA2_ST3 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // PWM13 - PC8 OUT7 - DMA2_ST4 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM13 - PC9 OUT8 - DMA2_ST7 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, 0, 1), // PWM1 - PA8 RC1 - DMA2_ST1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0, 0), // PWM2 - PB0 RC2 - DMA1_ST5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0, 0), // PWM3 - PB1 RC3 - DMA1_ST7 + DEF_TIM(TIM1, CH2, PB14, TIM_USE_PWM, 0, 1), // PWM4 - PA14 RC4 - DMA2_ST2 + DEF_TIM(TIM1, CH3, PB15, TIM_USE_PWM | TIM_USE_LED, 0, 0), // PWM5 - PA15 RC5 - DMA2_ST6 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM6 - PB8 OUT1 - DMA1_ST7 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM7 - PB9 OUT2 - DMA_NONE + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM8 - PA0 OUT3 - DMA1_ST2 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM9 - PA1 OUT4 - DMA1_ST4 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM10 - PC6 OUT5 - DMA2_ST2 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM11 - PC7 OUT6 - DMA2_ST3 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // PWM13 - PC8 OUT7 - DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM13 - PC9 OUT8 - DMA2_ST7 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/ALIENFLIGHTNGF7/target.c b/src/main/target/ALIENFLIGHTNGF7/target.c index 45b18c71a3..607f3150f4 100644 --- a/src/main/target/ALIENFLIGHTNGF7/target.c +++ b/src/main/target/ALIENFLIGHTNGF7/target.c @@ -23,19 +23,19 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM | TIM_USE_LED, 0, 1), // PPM - DMA2_ST1 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_SERVO, 0, 0), // PWM1 - DMA2_ST2 - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_SERVO, 0, 0), // PWM2 - DMA1_ST5 - DEF_TIM(TIM8, CH2N, PB14, TIM_USE_MC_SERVO, 0, 0), // PWM3 - DMA2_ST3 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO, 0, 0), // PWM4 - DMA1_ST7 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_SERVO, 0, 0), // PWM5 - DMA1_ST2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM6 - DMA2_ST4 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM7 - DMA1_ST4 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM8 - DMA2_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM9 - DMA1_ST2 - DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM10 - DMA2_ST6 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM11 - DMA1_ST7 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // PWM12 - DMA_NONE + DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM | TIM_USE_LED, 0, 1), // PPM - DMA2_ST1 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM1 - DMA2_ST2 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM2 - DMA1_ST5 + DEF_TIM(TIM8, CH2N, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM3 - DMA2_ST3 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM4 - DMA1_ST7 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM5 - DMA1_ST2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM6 - DMA2_ST4 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM7 - DMA1_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM8 - DMA2_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM9 - DMA1_ST2 + DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM10 - DMA2_ST6 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM11 - DMA1_ST7 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM12 - DMA_NONE }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/ANYFC/target.c b/src/main/target/ANYFC/target.c index f9dccae0f2..9275c14d28 100644 --- a/src/main/target/ANYFC/target.c +++ b/src/main/target/ANYFC/target.c @@ -23,23 +23,23 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // S1_IN - DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN - DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0), // S3_IN - DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0), // S4_IN - DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0), // S6_IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0), // S5_IN + DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // S1_IN + DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN + DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0), // S3_IN + DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0), // S4_IN + DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0), // S6_IN + DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0), // S5_IN - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S10_OUT 16 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6_OUT 12 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5_OUT 11 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT 7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT 8 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3_OUT 9 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT 10 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7_OUT 13 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8_OUT 14 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S9_OUT 15 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10_OUT 16 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT 12 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT 11 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT 7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT 8 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT 9 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT 10 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7_OUT 13 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8_OUT 14 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9_OUT 15 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/ANYFCF7/target.c b/src/main/target/ANYFCF7/target.c index c14bf1dbe4..56463c0b8c 100644 --- a/src/main/target/ANYFCF7/target.c +++ b/src/main/target/ANYFCF7/target.c @@ -23,23 +23,23 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN - DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN - DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_MC_SERVO, 0, 0 ), // S3_IN DMA2_ST2 DMA2_ST2 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_MC_SERVO, 0, 0 ), // S4_IN DMA2_ST3 DMA2_ST2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_MC_SERVO, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_MC_SERVO, 0, 0 ), // S6_IN DMA2_ST7 + DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN + DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN + DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_IN DMA2_ST2 DMA2_ST2 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4_IN DMA2_ST3 DMA2_ST2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6_IN DMA2_ST7 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S10_OUT 1 DMA1_ST7 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S6_OUT 2 DMA1_ST0 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S5_OUT - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1_OUT 4 DMA1_ST1 DMA1_ST3 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2_OUT 3 DMA1_ST4 - DEF_TIM(TIM9, CH2, PE6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3_OUT - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S4_OUT DMA1_ST5 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S7_OUT DMA1_ST2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_LED, 0, 0 ), // S8_OUT DMA1_ST6 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S9_OUT DMA1_ST4 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S10_OUT 1 DMA1_ST7 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6_OUT 2 DMA1_ST0 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_OUT + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0 ), // S1_OUT 4 DMA1_ST1 DMA1_ST3 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0 ), // S2_OUT 3 DMA1_ST4 + DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4_OUT DMA1_ST5 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S7_OUT DMA1_ST2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0 ), // S8_OUT DMA1_ST6 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S9_OUT DMA1_ST4 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/ANYFCM7/target.c b/src/main/target/ANYFCM7/target.c index 24f289afa6..cae2d80a7f 100644 --- a/src/main/target/ANYFCM7/target.c +++ b/src/main/target/ANYFCM7/target.c @@ -33,16 +33,16 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2 DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0 ), // S6_IN DMA2_ST7 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S10_OUT 1 DMA1_ST7 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S6_OUT 2 DMA1_ST1 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S5_OUT 3 DMA1_ST3 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S1_OUT 4 DMA1_ST7 DMA1_ST6 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2_OUT DMA1_ST4 - DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S3_OUT DMA2_ST6 DMA2_ST2 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_LED, 0, 0 ), // S4_OUT DMA1_ST5 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S7_OUT DMA1_ST2 - DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S8_OUT DMA2_ST6 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S9_OUT DMA1_ST4 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S10_OUT 1 DMA1_ST7 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6_OUT 2 DMA1_ST1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_OUT 3 DMA1_ST3 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S1_OUT 4 DMA1_ST7 DMA1_ST6 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT DMA1_ST4 + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3_OUT DMA2_ST6 DMA2_ST2 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0 ), // S4_OUT DMA1_ST5 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S7_OUT DMA1_ST2 + DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S8_OUT DMA2_ST6 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S9_OUT DMA1_ST4 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AOCODARCF405AIO/target.c b/src/main/target/AOCODARCF405AIO/target.c index 9548cb179a..f0612a7431 100644 --- a/src/main/target/AOCODARCF405AIO/target.c +++ b/src/main/target/AOCODARCF405AIO/target.c @@ -30,10 +30,10 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_C timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH2, PA10, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 DEF_TIM(TIM1, CH3N, PB1, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/AOCODARCF4V2/target.c b/src/main/target/AOCODARCF4V2/target.c index c18898b84c..db6130e9f3 100644 --- a/src/main/target/AOCODARCF4V2/target.c +++ b/src/main/target/AOCODARCF4V2/target.c @@ -27,16 +27,16 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S4 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S5 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S6 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S6 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S7 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S8 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S7 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S8 DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0 ), // LED_STRIP diff --git a/src/main/target/AOCODARCF7DUAL/target.c b/src/main/target/AOCODARCF7DUAL/target.c index f48fb445aa..ea76079ecf 100644 --- a/src/main/target/AOCODARCF7DUAL/target.c +++ b/src/main/target/AOCODARCF7DUAL/target.c @@ -32,15 +32,15 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), //PPM - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2, 2, 7) - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(2, 3, 7) - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 D(2, 4, 7) - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 D(2, 7, 7) + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(2, 2, 7) + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(2, 3, 7) + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 D(2, 4, 7) + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 D(2, 7, 7) - DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S5 D(1, 7, 5) - DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S6 D(1, 2, 5) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S7 D(1, 0, 2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S8 D(1, 3, 2) + DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MOTOR |TIM_USE_SERVO, 0, 0), // S5 D(1, 7, 5) + DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MOTOR |TIM_USE_SERVO, 0, 0), // S6 D(1, 2, 5) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR |TIM_USE_SERVO, 0, 0), // S7 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR |TIM_USE_SERVO, 0, 0), // S8 D(1, 3, 2) DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 0, 0), // LED_TRIP }; diff --git a/src/main/target/AOCODARCF7MINI/target.c b/src/main/target/AOCODARCF7MINI/target.c index 7b34bb05df..7e55ab5e9c 100644 --- a/src/main/target/AOCODARCF7MINI/target.c +++ b/src/main/target/AOCODARCF7MINI/target.c @@ -39,20 +39,20 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM, RX1 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(1, 4, 5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(1, 5, 4) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 D(1, 2, 5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(1, 5, 4) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 D(1, 2, 5) #if defined(AOCODARCF7MINI_V2) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 D(2, 4, 7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 D(2, 7, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 D(2, 4, 7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(2, 7, 7) #else - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 D(1, 6, 3) + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(1, 6, 3) #endif - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 D(1, 0, 2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 D(1, 3, 2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 D(1, 3, 2) DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED diff --git a/src/main/target/AOCODARCH7DUAL/target.c b/src/main/target/AOCODARCH7DUAL/target.c index 3bc551f5c4..055581a59e 100644 --- a/src/main/target/AOCODARCH7DUAL/target.c +++ b/src/main/target/AOCODARCH7DUAL/target.c @@ -32,20 +32,20 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270_2, DEVHW_BMI270, BMI270_SPI_BUS 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(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 3), // S4 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 4), // S5 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 5), // S6 - DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 6), // S7 - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 7), // S8 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 4), // S5 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 5), // S6 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 6), // S7 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 7), // S8 - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S9 - DEF_TIM(TIM4, CH4, PD15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S10 DMA_NONE - DEF_TIM(TIM15, CH1, PE5, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11 - DEF_TIM(TIM15, CH2, PE6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S12 DMA_NONE + DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9 + DEF_TIM(TIM4, CH4, PD15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 DMA_NONE + DEF_TIM(TIM15, CH1, PE5, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S11 + DEF_TIM(TIM15, CH2, PE6, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S12 DMA_NONE DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 DEF_TIM(TIM2, CH1, PA15, TIM_USE_BEEPER, 0, 0), // BEEPER PWM diff --git a/src/main/target/ASGARD32F4/target.c b/src/main/target/ASGARD32F4/target.c index 0fec1b2c79..ec69feec38 100644 --- a/src/main/target/ASGARD32F4/target.c +++ b/src/main/target/ASGARD32F4/target.c @@ -33,10 +33,10 @@ timerHardware_t timerHardware[] = { // DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0, 0), // PPM - timer clash with SS1_TX - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 1, 1), // M1 - D(2, 4, 7) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 1, 0), // M2 - D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 1, 0), // M3 - D(1, 2, 5) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 1, 0), // M4 - D(1, 3, 2) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 1, 1), // M1 - D(2, 4, 7) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), // M2 - D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0), // M3 - D(1, 2, 5) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 1, 0), // M4 - D(1, 3, 2) // DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0), // LED strip - timer clash with M4 output diff --git a/src/main/target/ASGARD32F7/target.c b/src/main/target/ASGARD32F7/target.c index 74ff860785..257523eceb 100644 --- a/src/main/target/ASGARD32F7/target.c +++ b/src/main/target/ASGARD32F7/target.c @@ -33,10 +33,10 @@ timerHardware_t timerHardware[] = { // DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0, 0), // PPM - timer clash with SS1_TX - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 1, 0), // M1 - D(2, 4, 7) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 1, 0), // M2 - D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 1, 0), // M3 - D(1, 2, 5) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 1, 0), // M4 - D(1, 6, 3) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 1, 0), // M1 - D(2, 4, 7) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1, 0), // M2 - D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1, 0), // M3 - D(1, 2, 5) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 1, 0), // M4 - D(1, 6, 3) DEF_TIM(TIM5, CH3, PA2, TIM_USE_LED, 0, 0), // TX2; SA port ---> LED - D(1, 0, 6) DEF_TIM(TIM1, CH2, PA9, TIM_USE_ANY, 0, 0), // SS1 }; diff --git a/src/main/target/ATOMRCF405NAVI/target.c b/src/main/target/ATOMRCF405NAVI/target.c index fa23597e92..0e6a22916e 100644 --- a/src/main/target/ATOMRCF405NAVI/target.c +++ b/src/main/target/ATOMRCF405NAVI/target.c @@ -34,14 +34,14 @@ #include "drivers/sensor.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED_STRIP }; diff --git a/src/main/target/AXISFLYINGF7PRO/target.c b/src/main/target/AXISFLYINGF7PRO/target.c index fc46a9c0b8..f0a1d9e972 100644 --- a/src/main/target/AXISFLYINGF7PRO/target.c +++ b/src/main/target/AXISFLYINGF7PRO/target.c @@ -23,17 +23,17 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S7 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP - DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM DEF_TIM(TIM12, CH2, PB15, TIM_USE_ANY, 0, 0), // CAM CONTROL }; diff --git a/src/main/target/BEEROTORF4/target.c b/src/main/target/BEEROTORF4/target.c index f359da03c1..78c7ef387e 100644 --- a/src/main/target/BEEROTORF4/target.c +++ b/src/main/target/BEEROTORF4/target.c @@ -26,14 +26,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN - DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 - DMAR: DMA2_ST5 - DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M2 - - DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // M3 - DMAR: DMA1_ST7 - DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // M4 - - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // M5 - DMAR: DMA2_ST1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // M6 - - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // M7 - DMAR: DMA1_ST2 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // M8 - DMAR: DMA1_ST6 + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M1 - DMAR: DMA2_ST5 + DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M2 - + DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M3 - DMAR: DMA1_ST7 + DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M4 - + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M5 - DMAR: DMA2_ST1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M6 - + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M7 - DMAR: DMA1_ST2 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M8 - DMAR: DMA1_ST6 DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, 0, 0), // LED_STRIP / TRANSPONDER - DMA1_ST7 }; diff --git a/src/main/target/BETAFLIGHTF4/target.c b/src/main/target/BETAFLIGHTF4/target.c index 2360b6a362..4bc7863386 100755 --- a/src/main/target/BETAFLIGHTF4/target.c +++ b/src/main/target/BETAFLIGHTF4/target.c @@ -27,10 +27,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH3, PB8, TIM_USE_PPM, 0, 0), // PPM // Motors - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT D1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT D1_ST2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3_OUT D1_ST6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT D1_ST1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT D1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT D1_ST2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT D1_ST6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT D1_ST1 // LED strip DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // D1_ST0 diff --git a/src/main/target/BETAFPVF405/config.c b/src/main/target/BETAFPVF405/config.c new file mode 100644 index 0000000000..cd5aa30d71 --- /dev/null +++ b/src/main/target/BETAFPVF405/config.c @@ -0,0 +1,33 @@ +/* + * 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 . + * + * This target has been autgenerated by bf2inav.py + */ + +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "fc/config.h" + +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + +} + diff --git a/src/main/target/BETAFPVF405/target.c b/src/main/target/BETAFPVF405/target.c new file mode 100644 index 0000000000..25ace257ac --- /dev/null +++ b/src/main/target/BETAFPVF405/target.c @@ -0,0 +1,43 @@ +/* + * 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 . + * + * This target has been autgenerated by bf2inav.py + */ + +#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" + +//BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); +//BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/BETAFPVF435/target.c b/src/main/target/BETAFPVF435/target.c index 815781e0c6..fc15230f19 100644 --- a/src/main/target/BETAFPVF435/target.c +++ b/src/main/target/BETAFPVF435/target.c @@ -30,15 +30,15 @@ #include "drivers/sensor.h" timerHardware_t timerHardware[] = { - DEF_TIM(TMR3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // TMR3_CH3 motor 1 - DEF_TIM(TMR3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 2), // TMR3_CH4 motor 2 - DEF_TIM(TMR2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 7), // TMR2_CH4 motor 3 - DEF_TIM(TMR2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 6), // TMR2_CH3 motor 4 + DEF_TIM(TMR3, CH3, PB0, TIM_USE_MOTOR, 0, 1), // TMR3_CH3 motor 1 + DEF_TIM(TMR3, CH4, PB1, TIM_USE_MOTOR, 0, 2), // TMR3_CH4 motor 2 + DEF_TIM(TMR2, CH4, PA3, TIM_USE_MOTOR, 0, 7), // TMR2_CH4 motor 3 + DEF_TIM(TMR2, CH3, PA2, TIM_USE_MOTOR, 0, 6), // TMR2_CH3 motor 4 - DEF_TIM(TMR8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO |TIM_USE_FW_MOTOR | TIM_USE_FW_SERVO | TIM_USE_ANY, 0, 4), // TMR8_CH3 motor 5 - DEF_TIM(TMR1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO |TIM_USE_FW_MOTOR | TIM_USE_FW_SERVO | TIM_USE_ANY, 0, 5), // TMR1_CH3 motor 6 + DEF_TIM(TMR8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_ANY, 0, 4), // TMR8_CH3 motor 5 + DEF_TIM(TMR1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_ANY, 0, 5), // TMR1_CH3 motor 6 DEF_TIM(TMR4, CH1, PB6, TIM_USE_LED, 0, 0), // TMR4_CH1 LED_STRIP }; -const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); \ No newline at end of file +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/BETAFPVF722/target.c b/src/main/target/BETAFPVF722/target.c index 6858f7e05b..5a2adfe8f4 100755 --- a/src/main/target/BETAFPVF722/target.c +++ b/src/main/target/BETAFPVF722/target.c @@ -25,20 +25,20 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM + DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // S1 D(1, 4, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0, 0), // S2 D(2, 3, 7) - DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR, 0, 0), // S3 D(2, 4, 7) - DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR, 0, 0), // S4 D(2, 7, 7) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S1 D(1, 4, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S2 D(2, 3, 7) + DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 0, 0), // S3 D(2, 4, 7) + DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR, 0, 0), // S4 D(2, 7, 7) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR, 0, 0), // S5 DMA1_ST2 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 DMA1_ST2 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0, 0), // S6 DMA2_ST6 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 DMA2_ST6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), //camera + DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), //camera - DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP D(1, 5, 3) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP D(1, 5, 3) }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/BLACKPILL_F411/target.c b/src/main/target/BLACKPILL_F411/target.c index a7f6215215..ff8fd54475 100644 --- a/src/main/target/BLACKPILL_F411/target.c +++ b/src/main/target/BLACKPILL_F411/target.c @@ -24,12 +24,12 @@ #include "drivers/pinio.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(1,4,5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(1,5,5) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 D(2,1,6) - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S4 D(2,2,6) - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S5 D(2,6,6) - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,7,2) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(1,4,5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(1,5,5) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 D(2,1,6) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4 D(2,2,6) + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S5 D(2,6,6) + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(1,7,2) DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 pad - softserial_tx2 diff --git a/src/main/target/BLUEJAYF4/target.c b/src/main/target/BLUEJAYF4/target.c index 3b6dbb4bda..ebdc83a979 100644 --- a/src/main/target/BLUEJAYF4/target.c +++ b/src/main/target/BLUEJAYF4/target.c @@ -25,13 +25,13 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1_OUT - DMA1_ST2 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2_OUT - DMA1_ST4 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3_OUT - DMA1_ST1 - DEF_TIM(TIM9, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S4_OUT - no DMA - // DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S4_OUT - DMA1_ST3 (Could be DMA1_ST1 with dmaopt=0) - DEF_TIM(TIM3, CH4, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_LED, 0, 0 ), // S5_OUT - DMA1_ST2 - DEF_TIM(TIM3, CH3, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S6_OUT - DMA1_ST7 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT - DMA1_ST2 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT - DMA1_ST4 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT - DMA1_ST1 + DEF_TIM(TIM9, CH2, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4_OUT - no DMA + //DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4_OUT - DMA1_ST3 (Could be DMA1_ST1 with dmaopt=0) + DEF_TIM(TIM3, CH4, PB0, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0 ), // S5_OUT - DMA1_ST2 + DEF_TIM(TIM3, CH3, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6_OUT - DMA1_ST7 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/CLRACINGF4AIR/target.c b/src/main/target/CLRACINGF4AIR/target.c index 490372c048..f44496bd3a 100644 --- a/src/main/target/CLRACINGF4AIR/target.c +++ b/src/main/target/CLRACINGF4AIR/target.c @@ -25,19 +25,19 @@ DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, 0, 0), #if defined(CLRACINGF4AIRV2) || defined(CLRACINGF4AIRV3) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM12, CH2, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), #else - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), - DEF_TIM(TIM9, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM9, CH2, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM12, CH2, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), #endif }; diff --git a/src/main/target/COLIBRI/target.c b/src/main/target/COLIBRI/target.c index dbeb9c083f..79760b4cf0 100755 --- a/src/main/target/COLIBRI/target.c +++ b/src/main/target/COLIBRI/target.c @@ -33,14 +33,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // S7_IN DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // S8_IN - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1_OUT - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2_OUT - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3_OUT - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5_OUT - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6_OUT - DEF_TIM(TIM10, CH1, PB8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S7_OUT - DEF_TIM(TIM11, CH1, PB9, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S8_OUT + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT + DEF_TIM(TIM12, CH2, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT + DEF_TIM(TIM12, CH1, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT + DEF_TIM(TIM10, CH1, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7_OUT + DEF_TIM(TIM11, CH1, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8_OUT DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0) }; diff --git a/src/main/target/CRAZYBEEF4SX1280/config.c b/src/main/target/CRAZYBEEF4SX1280/config.c new file mode 100644 index 0000000000..cd5aa30d71 --- /dev/null +++ b/src/main/target/CRAZYBEEF4SX1280/config.c @@ -0,0 +1,33 @@ +/* + * 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 . + * + * This target has been autgenerated by bf2inav.py + */ + +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "fc/config.h" + +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + +} + diff --git a/src/main/target/CRAZYBEEF4SX1280/target.c b/src/main/target/CRAZYBEEF4SX1280/target.c new file mode 100644 index 0000000000..6806179433 --- /dev/null +++ b/src/main/target/CRAZYBEEF4SX1280/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 . + * + * This target has been autgenerated by bf2inav.py + */ + +#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" + +//BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); +//BUSDEV_REGISTER_SPI_TAG(busdev_icm20689, DEVHW_ICM20689, ICM20689_SPI_BUS, ICM20689_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM20689_ALIGN); +//BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, 0, 0), + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/DALRCF405/target.c b/src/main/target/DALRCF405/target.c index add81e2b28..037f6772ce 100644 --- a/src/main/target/DALRCF405/target.c +++ b/src/main/target/DALRCF405/target.c @@ -24,14 +24,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S1 (1,7) - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 (2,2) - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 (2,6) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S4 (2,1) (2.3 2.6) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S5 (2,4) (2.2) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S6 (1,2) - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S7 (2,3) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 (2,7) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 (1,7) + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 (2,2) + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 (2,6) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4 (2,1) (2.3 2.6) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S5 (2,4) (2.2) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // S6 (1,2) + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S7 (2,3) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 (2,7) DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED STRIP(1,0) DEF_TIM(TIM2, CH1, PA5, TIM_USE_ANY, 0, 0), // FC CAM diff --git a/src/main/target/DALRCF722DUAL/target.c b/src/main/target/DALRCF722DUAL/target.c index 8ea225e412..e3ff39dae3 100644 --- a/src/main/target/DALRCF722DUAL/target.c +++ b/src/main/target/DALRCF722DUAL/target.c @@ -30,12 +30,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM ,0, 0), - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO,0,0), //S1 DMA2_ST2 T8CH1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO,0,0), //S2 DMA2_ST3 T8CH2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO,0,0), //S3 DMA2_ST4 T8CH3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO,0,0), //S4 DMA2_ST7 T8CH4 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR,0,0), //S5 DMA2_ST1 T1CH1 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR,0,0), //S6 DMA2_ST6 T1CH2 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO,0,0), //S1 DMA2_ST2 T8CH1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO,0,0), //S2 DMA2_ST3 T8CH2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO,0,0), //S3 DMA2_ST4 T8CH3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO,0,0), //S4 DMA2_ST7 T8CH4 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO,0,0), //S5 DMA2_ST1 T1CH1 // used to be fw motor + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO,0,0), //S6 DMA2_ST6 T1CH2 // used to be fw motor DEF_TIM(TIM2, CH1, PA15,TIM_USE_LED,0,0), //2812 STRIP DMA1_ST5 }; diff --git a/src/main/target/F4BY/target.c b/src/main/target/F4BY/target.c index 5565713c03..b2594e54ca 100644 --- a/src/main/target/F4BY/target.c +++ b/src/main/target/F4BY/target.c @@ -15,14 +15,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH2, PD13, TIM_USE_PWM, 0, 0), // S7_IN DEF_TIM(TIM4, CH1, PD12, TIM_USE_PWM, 0, 0), // S8_IN - DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT - DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3_OUT - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5_OUT - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6_OUT - DEF_TIM(TIM1, CH3, PE13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7_OUT - DEF_TIM(TIM1, CH4, PE14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8_OUT + DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT + DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT + DEF_TIM(TIM1, CH3, PE13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7_OUT + DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8_OUT DEF_TIM(TIM9, CH2, PE6, TIM_USE_ANY, 0, 0), // sonar echo if needed }; diff --git a/src/main/target/FF_F35_LIGHTNING/target.c b/src/main/target/FF_F35_LIGHTNING/target.c index 61180587f0..92e86f45b3 100644 --- a/src/main/target/FF_F35_LIGHTNING/target.c +++ b/src/main/target/FF_F35_LIGHTNING/target.c @@ -23,12 +23,12 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), DEF_TIM(TIM5, CH4, PA3, TIM_USE_ANY, 0, 0), diff --git a/src/main/target/FF_FORTINIF4/target.c b/src/main/target/FF_FORTINIF4/target.c index 853104d01f..90ea1edcc3 100644 --- a/src/main/target/FF_FORTINIF4/target.c +++ b/src/main/target/FF_FORTINIF4/target.c @@ -23,10 +23,10 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0 ), // S1_OUT - DMA1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0 ), // S2_OUT - DMA1_ST2 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1 ), // S3_OUT - DMA1_ST6 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0 ), // S4_OUT - DMA1_ST1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0 ), // S1_OUT - DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0 ), // S2_OUT - DMA1_ST2 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1 ), // S3_OUT - DMA1_ST6 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0 ), // S4_OUT - DMA1_ST1 DEF_TIM(TIM4, CH4, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED - DMA1_ST3 }; diff --git a/src/main/target/FF_PIKOF4/target.c b/src/main/target/FF_PIKOF4/target.c index ba3cfc5162..5a2de8b8cb 100644 --- a/src/main/target/FF_PIKOF4/target.c +++ b/src/main/target/FF_PIKOF4/target.c @@ -26,17 +26,17 @@ timerHardware_t timerHardware[] = { #if defined(FF_PIKOF4OSD) - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), - DEF_TIM(TIM3, CH3, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), - DEF_TIM(TIM3, CH4, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM3, CH3, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM3, CH4, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM12, CH1, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM12, CH2, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), #else - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), #endif DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0 ), }; diff --git a/src/main/target/FIREWORKSV2/target.c b/src/main/target/FIREWORKSV2/target.c index 133c2bd1d7..3d9042551e 100644 --- a/src/main/target/FIREWORKSV2/target.c +++ b/src/main/target/FIREWORKSV2/target.c @@ -47,17 +47,17 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM // Motor output 1: use different set of timers for MC and FW - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 1, 0), // S1_OUT D(1,7) - DEF_TIM(TIM8, CH2N, PB0, TIM_USE_FW_MOTOR, 1, 1), // S1_OUT D(2,2,0),D(2,3,7) + //DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM _USE_SERVO, 1, 0), // S1_OUT D(1,7) + DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // S1_OUT D(2,2,0),D(2,3,7) // used to fw motor // Motor output 2: use different set of timers for MC and FW - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 1, 0), // S2_OUT D(1,2) - DEF_TIM(TIM8, CH3N, PB1, TIM_USE_FW_MOTOR, 1, 1), // S2_OUT D(2,2,0),D(2,4,7) + //DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S2_OUT D(1,2) + DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // S2_OUT D(2,2,0),D(2,4,7) // used to be fw motor - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1), // S3_OUT D(1,6) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S4_OUT D(1,5) - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5_OUT D(1,7) - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6_OUT D(1,8) + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // S3_OUT D(1,6) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4_OUT D(1,5) + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT D(1,7) + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT D(1,8) DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip D(1,0) @@ -66,6 +66,7 @@ timerHardware_t timerHardware[] = { const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); +/* TODO: add DSHOT_DMAR? #ifdef USE_DSHOT void validateAndFixTargetConfig(void) { @@ -76,4 +77,5 @@ void validateAndFixTargetConfig(void) } } } -#endif \ No newline at end of file +#endif +*/ diff --git a/src/main/target/FISHDRONEF4/target.c b/src/main/target/FISHDRONEF4/target.c index d12423798f..a096896656 100644 --- a/src/main/target/FISHDRONEF4/target.c +++ b/src/main/target/FISHDRONEF4/target.c @@ -30,12 +30,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH4, PB11, TIM_USE_PWM, 0, 0 ), DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM, 0, 0 ), - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), + DEF_TIM(TIM12, CH1, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM12, CH2, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0 ), }; diff --git a/src/main/target/FLYCOLORF7MINI/target.c b/src/main/target/FLYCOLORF7MINI/target.c index 146aa9fe1c..dec2cf1aee 100644 --- a/src/main/target/FLYCOLORF7MINI/target.c +++ b/src/main/target/FLYCOLORF7MINI/target.c @@ -29,8 +29,8 @@ 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(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 diff --git a/src/main/target/FLYWOOF405PRO/target.c b/src/main/target/FLYWOOF405PRO/target.c index 753f904613..7d818b2eca 100644 --- a/src/main/target/FLYWOOF405PRO/target.c +++ b/src/main/target/FLYWOOF405PRO/target.c @@ -22,15 +22,15 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(1,3,2) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(1,0,2) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(1,3,2) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(1,0,2) - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 D(1,7,5) - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 D(1,2,5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 D(2,4,7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 D(1,7,5) + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 D(1,2,5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 D(2,4,7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 DEF_TIM(TIM1, CH2, PA9, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) diff --git a/src/main/target/FLYWOOF411/target.c b/src/main/target/FLYWOOF411/target.c index 56d8e7afb4..ca5b5abfde 100644 --- a/src/main/target/FLYWOOF411/target.c +++ b/src/main/target/FLYWOOF411/target.c @@ -27,20 +27,20 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH1, PA2, TIM_USE_PPM, 0, 0), // PPM IN #ifdef FLYWOOF411_V2 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1 - D(2,1) - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - D(1,6) - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - D(1,1) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - D(1,5) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1 - D(2,1) + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - D(1,6) + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - D(1,1) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - D(1,5) DEF_TIM(TIM4, CH1, PB6, TIM_USE_ANY, 0, 0), // SOFTSERIAL_1_TX_PIN - D(1,0) DEF_TIM(TIM4, CH2, PB7, TIM_USE_ANY, 0, 0), // SOFTSERIAL_1_RX_PIN - D(1,3) DEF_TIM(TIM3, CH3, PB0, TIM_USE_ANY, 0, 0), // RSSI_ADC_CHANNEL 1-7 DEF_TIM(TIM3, CH1, PB4, TIM_USE_ANY, 0, 0), // 1-4 DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, 0, 0), // LED 1,2 #else - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S1_OUT 2,1 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S2_OUT 2,2 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3_OUT 2,6 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4_OUT 1,7 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1_OUT 2,1 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2_OUT 2,2 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT 2,6 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR , 0, 0), // S4_OUT 1,7 DEF_TIM(TIM3, CH4, PB1, TIM_USE_ANY, 0, 0), // RSSI 1,2 DEF_TIM(TIM5, CH4, PA3, TIM_USE_ANY, 0, 1), // RX2 1,0 diff --git a/src/main/target/FLYWOOF745/target.c b/src/main/target/FLYWOOF745/target.c index 302add553e..ebc20d52ec 100644 --- a/src/main/target/FLYWOOF745/target.c +++ b/src/main/target/FLYWOOF745/target.c @@ -30,17 +30,17 @@ #include "drivers/pinio.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6 + DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 , DMA1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M2 , DMA1_ST2 - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // M3 , DMA2_ST2 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // M4 , DMA2_ST4 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M5 , DMA2_ST7 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M6 , DMA1_ST1 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M7 , DMA1_ST4 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M8 , DMA1_ST5 - DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_STRIP, DMA1_ST0 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // M1 , DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // M2 , DMA1_ST2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // M3 , DMA2_ST2 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // M4 , DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M5 , DMA2_ST7 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M6 , DMA1_ST1 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M7 , DMA1_ST4 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M8 , DMA1_ST5 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_STRIP, DMA1_ST0 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/FLYWOOF7DUAL/target.c b/src/main/target/FLYWOOF7DUAL/target.c index 1af1457249..83326ea4b6 100644 --- a/src/main/target/FLYWOOF7DUAL/target.c +++ b/src/main/target/FLYWOOF7DUAL/target.c @@ -40,12 +40,12 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_2, DEVHW_MPU6500, GYRO_2_SPI_BUS, GYRO timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH1, PC6, TIM_USE_PPM, 0, 0), // PPM&SBUS - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - D(1,2) - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - D(1,4) - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - D(1,6) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - D(1,5) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 - D(2,4) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 - D(2,1) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - D(1,2) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - D(1,4) + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - D(1,6) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - D(1,5) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - D(2,4) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - D(2,1) DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP(1,5) }; diff --git a/src/main/target/FOXEERF405/target.c b/src/main/target/FOXEERF405/target.c index cf367ba00c..9c48d9badc 100644 --- a/src/main/target/FOXEERF405/target.c +++ b/src/main/target/FOXEERF405/target.c @@ -24,16 +24,16 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 (1,7) - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 (1,4) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 (2,4) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 (2,7) - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 (2,2) - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 (2,3) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 (1,7) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 (1,4) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 (2,4) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 (2,7) + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 (2,2) + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 (2,3) - DEF_TIM(TIM1, CH3, PA10, TIM_USE_LED, 0, 0), // LED STRIP(2,6) + DEF_TIM(TIM1, CH3, PA10, TIM_USE_LED, 0, 0), // LED STRIP(2,6) - //DEF_TIM(TIM2, CH2, PB3, TIM_USE_CAMERA_CONTROL, 0, 0), // Reserved (Cam Control for BF) + //DEF_TIM(TIM2, CH2, PB3, TIM_USE_CAMERA_CONTROL, 0, 0), // Reserved (Cam Control for BF) }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/FOXEERF722DUAL/target.c b/src/main/target/FOXEERF722DUAL/target.c index fca041e07a..588b926fc9 100644 --- a/src/main/target/FOXEERF722DUAL/target.c +++ b/src/main/target/FOXEERF722DUAL/target.c @@ -31,16 +31,16 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, 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, 1), // S1 - D(2, 1, 6) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1 - D(2, 1, 6) #if defined(FOXEERF722V2) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 - D(2, 1, 6) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - D(2, 1, 6) #else - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - D(2, 6, 0) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - D(2, 6, 0) #endif - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - D(2, 7, 7) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - D(2, 4, 7) - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 - D(1, 4, 5) - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 - D(1, 5, 5) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - D(2, 7, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - D(2, 4, 7) + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - D(1, 4, 5) + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - D(1, 5, 5) DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED STRIP(1,5) diff --git a/src/main/target/FOXEERF722V4/target.c b/src/main/target/FOXEERF722V4/target.c index 2cadae4d77..457e7acd4b 100644 --- a/src/main/target/FOXEERF722V4/target.c +++ b/src/main/target/FOXEERF722V4/target.c @@ -25,16 +25,16 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1 - D(2, 1, 6) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 - D(2, 1, 6) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - D(2, 7, 7) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - D(2, 4, 7) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1 - D(2, 1, 6) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - D(2, 1, 6) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - D(2, 7, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - D(2, 4, 7) #ifdef FOXEERF722V4_X8 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 #endif DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED STRIP(1,5) diff --git a/src/main/target/FOXEERF745AIO/target.c b/src/main/target/FOXEERF745AIO/target.c index d3ef6a067d..f724f65913 100644 --- a/src/main/target/FOXEERF745AIO/target.c +++ b/src/main/target/FOXEERF745AIO/target.c @@ -27,10 +27,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP - D(2, 6, 0) - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR, 0, 0), // M1 - D(1, 4, 5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR, 0, 0), // M2 - D(1, 5, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0, 0), // M3 - D(1, 2, 5) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // M4 - D(1, 7, 5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // M1 - D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // M2 - D(1, 5, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // M3 - D(1, 2, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // M4 - D(1, 7, 5) }; diff --git a/src/main/target/FOXEERH743/target.c b/src/main/target/FOXEERH743/target.c index c8bc9e7ada..0d26747ae7 100644 --- a/src/main/target/FOXEERH743/target.c +++ b/src/main/target/FOXEERH743/target.c @@ -28,18 +28,18 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S2 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 3), // S4 - DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 4), // S5 - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 5), // S6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 6), // S7 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 7), // S8 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_SERVO | TIM_USE_SERVO, 0, 4), // S5 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_SERVO | TIM_USE_SERVO, 0, 5), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_SERVO | TIM_USE_SERVO, 0, 6), // S7 // used to be fw motor + DEF_TIM(TIM8, CH4, PC9, TIM_USE_SERVO | TIM_USE_SERVO, 0, 7), // S8 // used to be fw motor - DEF_TIM(TIM15, CH1, PE5, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 - DEF_TIM(TIM15, CH2, PE6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 + DEF_TIM(TIM15, CH1, PE5, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S9 + DEF_TIM(TIM15, CH2, PE6, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S10 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 }; diff --git a/src/main/target/FRSKYF4/target.c b/src/main/target/FRSKYF4/target.c index 39b1be4890..7d444a7174 100755 --- a/src/main/target/FRSKYF4/target.c +++ b/src/main/target/FRSKYF4/target.c @@ -23,12 +23,12 @@ #include "drivers/pwm_mapping.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S1_OUT - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S2_OUT - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S3_OUT - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S4_OUT - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S5_OUT - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S6_OUT + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S1_OUT + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S2_OUT + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S3_OUT + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4_OUT + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S5_OUT + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S6_OUT DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip }; diff --git a/src/main/target/FRSKYPILOT/target.c b/src/main/target/FRSKYPILOT/target.c index 8594a6f757..74f22eee6a 100644 --- a/src/main/target/FRSKYPILOT/target.c +++ b/src/main/target/FRSKYPILOT/target.c @@ -30,21 +30,21 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM1, CH3, PE13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM1, CH4, PE14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S9 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM1, CH3, PE13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9 #ifdef FRSKYPILOT_LED DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED | TIM_USE_LED, 0, 0), // S10 now LED, S11 & S12 UART 3 only #else - DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S10 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S11 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S12 + DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S11 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S12 #endif DEF_TIM(TIM5, CH1, PA0, TIM_USE_BEEPER, 0, 0), // beeper diff --git a/src/main/target/FRSKY_ROVERF7/target.c b/src/main/target/FRSKY_ROVERF7/target.c index 25a5889f64..6d8ecd0271 100755 --- a/src/main/target/FRSKY_ROVERF7/target.c +++ b/src/main/target/FRSKY_ROVERF7/target.c @@ -25,12 +25,12 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0), // M1 - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0), // M2 - DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MC_MOTOR, 0, 0), // M3 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR, 0, 0), // M1 + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR, 0, 0), // M2 + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MOTOR, 0, 0), // M3 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_SERVO, 0, 0), // Servo left - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_SERVO, 0, 0), // Servo right + DEF_TIM(TIM8, CH2, PC7, TIM_USE_SERVO, 0, 0), // Servo left + DEF_TIM(TIM8, CH1, PC6, TIM_USE_SERVO, 0, 0), // Servo right DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/FURYF4OSD/target.c b/src/main/target/FURYF4OSD/target.c index 8ca21cdc7d..61791d0230 100644 --- a/src/main/target/FURYF4OSD/target.c +++ b/src/main/target/FURYF4OSD/target.c @@ -24,10 +24,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH4, PC9, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S1_OUT - D(1, 6, 3) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S2_OUT - D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3_OUT - D(1, 2, 5) - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S4_OUT - D(1, 1, 3) + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S1_OUT - D(1, 6, 3) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT - D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT - D(1, 2, 5) + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4_OUT - D(1, 1, 3) DEF_TIM(TIM2, CH3, PB10, TIM_USE_ANY, 0, 0), DEF_TIM(TIM2, CH4, PB11, TIM_USE_ANY, 0, 0), DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, 0, 0 ), // LED_STRIP - DMA1_ST2_CH6 diff --git a/src/main/target/GEPRCF405/target.c b/src/main/target/GEPRCF405/target.c index ace9b30736..e8e94a18c6 100644 --- a/src/main/target/GEPRCF405/target.c +++ b/src/main/target/GEPRCF405/target.c @@ -31,12 +31,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), }; diff --git a/src/main/target/GEPRCF722/target.c b/src/main/target/GEPRCF722/target.c index 8e206e7b19..da376e545d 100644 --- a/src/main/target/GEPRCF722/target.c +++ b/src/main/target/GEPRCF722/target.c @@ -29,12 +29,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), diff --git a/src/main/target/GEPRCF722_BT_HD/target.c b/src/main/target/GEPRCF722_BT_HD/target.c index fa80baf92d..46299424cf 100644 --- a/src/main/target/GEPRCF722_BT_HD/target.c +++ b/src/main/target/GEPRCF722_BT_HD/target.c @@ -30,16 +30,16 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR | TIM_USE_MC_SERVO, 0, 0), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR | TIM_USE_MC_SERVO, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), }; diff --git a/src/main/target/GEPRC_F722_AIO/target.c b/src/main/target/GEPRC_F722_AIO/target.c index 6699298db6..b3f66b5ab8 100644 --- a/src/main/target/GEPRC_F722_AIO/target.c +++ b/src/main/target/GEPRC_F722_AIO/target.c @@ -29,10 +29,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), }; diff --git a/src/main/target/HAKRCF405D/target.c b/src/main/target/HAKRCF405D/target.c index 3e4e0f763c..8d5505e121 100644 --- a/src/main/target/HAKRCF405D/target.c +++ b/src/main/target/HAKRCF405D/target.c @@ -32,12 +32,12 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU600 timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 DEF_TIM(TIM4, CH1, PB8, TIM_USE_LED, 0, 0), // LED STRIP(2,6) diff --git a/src/main/target/HAKRCF405V2/target.c b/src/main/target/HAKRCF405V2/target.c index ba55aed031..9a599d56ae 100644 --- a/src/main/target/HAKRCF405V2/target.c +++ b/src/main/target/HAKRCF405V2/target.c @@ -22,14 +22,14 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1_OUT D2_ST4 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT D2_ST7 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3_OUT D2_ST1 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S4_OUT D2_ST2 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5_OUT D2_ST6 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT D1_ST4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7_OUT D1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8_OUT D1_ST2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1_OUT D2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT D2_ST7 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3_OUT D2_ST1 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4_OUT D2_ST2 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT D2_ST6 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT D1_ST4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7_OUT D1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8_OUT D1_ST2 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0), // D1_ST6 }; diff --git a/src/main/target/HAKRCF411D/target.c b/src/main/target/HAKRCF411D/target.c index 7f1abaf76a..72253eb94a 100644 --- a/src/main/target/HAKRCF411D/target.c +++ b/src/main/target/HAKRCF411D/target.c @@ -25,10 +25,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN - 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(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 DEF_TIM(TIM2, CH1, PA15, TIM_USE_ANY, 0, 0), // SOFTSERIAL_1_TX_PIN DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // SOFTSERIAL_1_RX_PIN diff --git a/src/main/target/HAKRCF722V2/target.c b/src/main/target/HAKRCF722V2/target.c index 6c8aec8d37..d423c1004b 100644 --- a/src/main/target/HAKRCF722V2/target.c +++ b/src/main/target/HAKRCF722V2/target.c @@ -33,14 +33,14 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, GYRO_SPI_BUS, GYRO1_CS_PIN, BUSDEV_REGISTER_SPI_TAG(busdev_bmi270_2, DEVHW_BMI270, GYRO_SPI_BUS, GYRO2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_BMI270_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0), // 2812LED diff --git a/src/main/target/HAKRCKD722/target.c b/src/main/target/HAKRCKD722/target.c index eb9b4d87c2..39d0d12404 100644 --- a/src/main/target/HAKRCKD722/target.c +++ b/src/main/target/HAKRCKD722/target.c @@ -32,14 +32,14 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU60 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(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/HGLRCF722/target.c b/src/main/target/HGLRCF722/target.c index faf6725705..716a9e37d5 100644 --- a/src/main/target/HGLRCF722/target.c +++ b/src/main/target/HGLRCF722/target.c @@ -37,14 +37,14 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S7 UP1-6 D(1, 0, 2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S8 UP1-6 D(1, 3, 2) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 UP1-6 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 UP1-6 D(1, 3, 2) DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 6, 0) DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM, RX2 diff --git a/src/main/target/IFLIGHTF4_SUCCEXD/target.c b/src/main/target/IFLIGHTF4_SUCCEXD/target.c index 32dde9fe87..ad9ab68c9e 100644 --- a/src/main/target/IFLIGHTF4_SUCCEXD/target.c +++ b/src/main/target/IFLIGHTF4_SUCCEXD/target.c @@ -26,10 +26,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR, 0, 0), - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR, 0, 0), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0, 0), + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), }; diff --git a/src/main/target/IFLIGHTF4_TWING/target.c b/src/main/target/IFLIGHTF4_TWING/target.c index a321b88cee..ebb02721d4 100644 --- a/src/main/target/IFLIGHTF4_TWING/target.c +++ b/src/main/target/IFLIGHTF4_TWING/target.c @@ -33,10 +33,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM // Motors - DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT D2_ST6 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2_OUT D1_ST2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3_OUT D1_ST6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT D1_ST1 + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT D2_ST6 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT D1_ST2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT D1_ST6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT D1_ST1 // LED strip DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // D1_ST0 diff --git a/src/main/target/IFLIGHTF7_TWING/target.c b/src/main/target/IFLIGHTF7_TWING/target.c index d596849dd5..f32db01de3 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.c +++ b/src/main/target/IFLIGHTF7_TWING/target.c @@ -32,16 +32,16 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_1_SPI_BUS, MPU6 timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR | TIM_USE_MC_SERVO, 0, 0), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR | TIM_USE_MC_SERVO, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), }; diff --git a/src/main/target/IFLIGHT_BLITZ_F722/target.c b/src/main/target/IFLIGHT_BLITZ_F722/target.c index 8bba266c36..736bc6b499 100644 --- a/src/main/target/IFLIGHT_BLITZ_F722/target.c +++ b/src/main/target/IFLIGHT_BLITZ_F722/target.c @@ -23,17 +23,16 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 DMA1_S2_CH5 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 DMA1_S7_CH5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 DMA1_S2_CH5 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 DMA1_S7_CH5 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 DMA2_S4_CH7 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 DMA2_S7_CH7 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 DMA1_S0_CH2 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 DMA1_S3_CH2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 DMA2_S4_CH7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 DMA2_S7_CH7 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 DMA1_S0_CH2 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 DMA1_S3_CH2 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 DMA1_S1_CH3 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S8 DMA1_S6_CH3 - + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 DMA1_S1_CH3 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S8 DMA1_S6_CH3 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // WS2812B }; diff --git a/src/main/target/IFLIGHT_BLITZ_F7_AIO/target.c b/src/main/target/IFLIGHT_BLITZ_F7_AIO/target.c index 3c26d72f80..4c244e27d2 100644 --- a/src/main/target/IFLIGHT_BLITZ_F7_AIO/target.c +++ b/src/main/target/IFLIGHT_BLITZ_F7_AIO/target.c @@ -30,20 +30,20 @@ //BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM2, CH2, PB3, TIM_USE_PPM, 0, 0), // PPM + DEF_TIM(TIM2, CH2, PB3, 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, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM1, CH3, PE13, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 - DEF_TIM(TIM1, CH4, PE14, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S2 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S4 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM1, CH3, PE13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_LED, 0, 0), // LED + DEF_TIM(TIM8, CH4, PC9, TIM_USE_LED, 0, 0), // LED }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c b/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c index 592fd20b4c..2f002c6d6b 100644 --- a/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c +++ b/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c @@ -32,14 +32,14 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_P timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1 - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1 + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/IFLIGHT_H743_AIO_V2/target.c b/src/main/target/IFLIGHT_H743_AIO_V2/target.c index 3e02bff3e3..88dada8ffe 100644 --- a/src/main/target/IFLIGHT_H743_AIO_V2/target.c +++ b/src/main/target/IFLIGHT_H743_AIO_V2/target.c @@ -27,12 +27,12 @@ #include "drivers/sensor.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // M2 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 2), // M3 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 3), // M4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // M1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 1), // M2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 2), // M3 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 3), // M4 - DEF_TIM( TIM1, CH1, PA8, TIM_USE_LED, 0, 4) // LED_2812 + DEF_TIM( TIM1, CH1, PA8, TIM_USE_LED, 0, 4) // LED_2812 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/IFLIGHT_JBF7PRO/target.c b/src/main/target/IFLIGHT_JBF7PRO/target.c index 7c8c15a741..9e97258451 100644 --- a/src/main/target/IFLIGHT_JBF7PRO/target.c +++ b/src/main/target/IFLIGHT_JBF7PRO/target.c @@ -27,14 +27,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S8 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S8 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/JHEH7AIO/target.c b/src/main/target/JHEH7AIO/target.c index 479816acdc..757d66a858 100644 --- a/src/main/target/JHEH7AIO/target.c +++ b/src/main/target/JHEH7AIO/target.c @@ -27,12 +27,12 @@ #include "drivers/sensor.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // M2 - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 2), // M3 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 3), // M4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // M1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 1), // M2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR, 0, 2), // M3 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR, 0, 3), // M4 - DEF_TIM( TIM4, CH1, PD12, TIM_USE_LED, 0, 4) // LED_2812 + DEF_TIM( TIM4, CH1, PD12, TIM_USE_LED, 0, 4) // LED_2812 }; -const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); \ No newline at end of file +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/KAKUTEF4/target.c b/src/main/target/KAKUTEF4/target.c index 27bded1f2f..c80cfb112f 100755 --- a/src/main/target/KAKUTEF4/target.c +++ b/src/main/target/KAKUTEF4/target.c @@ -31,23 +31,23 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), // PPM IN - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT - DMA1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT - DMA1_ST2 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3_OUT - DMA1_ST6 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT - DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT - DMA1_ST2 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3_OUT - DMA1_ST6 #if !defined(KAKUTEF4V23) - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S4_OUT - DMA1_ST1 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT - DMA1_ST1 #else - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT - DMA1_ST1 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5_OUT - DMA1_ST0 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT - DMA1_ST3 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT - DMA1_ST1 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT - DMA1_ST0 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT - DMA1_ST3 #endif #if defined(KAKUTEF4V2) || defined(KAKUTEF4V23) DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED_STRIP - DMA2_ST2 #else - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5_OUT - DMA1_ST2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S6_OUT - DMA2_ST4 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT - DMA1_ST2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S6_OUT - DMA2_ST4 DEF_TIM(TIM5, CH2, PA1, TIM_USE_LED, 0, 0), // LED_STRIP - DMA1_ST4 #endif }; diff --git a/src/main/target/KAKUTEF7/target.c b/src/main/target/KAKUTEF7/target.c index 249047470a..4cfa725996 100755 --- a/src/main/target/KAKUTEF7/target.c +++ b/src/main/target/KAKUTEF7/target.c @@ -29,14 +29,14 @@ #include "drivers/bus.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6 + DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 , DMA1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M2 , DMA1_ST2 - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // M3 , DMA2_ST2 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // M4 , DMA2_ST4 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M5 , DMA2_ST7 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M6 , DMA1_ST1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M1 , DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M2 , DMA1_ST2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // M3 , DMA2_ST2 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // M4 , DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M5 , DMA2_ST7 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M6 , DMA1_ST1 DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_STRIP, DMA1_ST0 }; diff --git a/src/main/target/KAKUTEF7MINIV3/target.c b/src/main/target/KAKUTEF7MINIV3/target.c index 3415db1edd..23815c6dc4 100644 --- a/src/main/target/KAKUTEF7MINIV3/target.c +++ b/src/main/target/KAKUTEF7MINIV3/target.c @@ -31,14 +31,14 @@ #include "drivers/pwm_mapping.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, 0), // S2 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S6 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // RX2 }; -const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); \ No newline at end of file +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/KAKUTEH7/target.c b/src/main/target/KAKUTEH7/target.c index 086d941f1c..1ea9cd3e68 100644 --- a/src/main/target/KAKUTEH7/target.c +++ b/src/main/target/KAKUTEH7/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_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_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(TIM5, CH1, PA0, TIM_USE_SERVO | TIM_USE_SERVO, 0, 4), // S5 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_SERVO | TIM_USE_SERVO, 0, 5), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_SERVO | TIM_USE_SERVO, 0, 6), // S7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_SERVO | TIM_USE_SERVO, 0, 7), // S8 DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 9), // LED_2812 }; diff --git a/src/main/target/KAKUTEH7WING/target.c b/src/main/target/KAKUTEH7WING/target.c index 2b880fc3b7..193b621a31 100644 --- a/src/main/target/KAKUTEH7WING/target.c +++ b/src/main/target/KAKUTEH7WING/target.c @@ -32,23 +32,23 @@ BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS // BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 - DEF_TIM(TIM1, CH3, PE13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3 - DEF_TIM(TIM1, CH4, PE14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 + DEF_TIM(TIM1, CH3, PE13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 + DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 3), // S4 - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 4), // S5 - DEF_TIM(TIM4, CH4, PD15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 DMA_NONE - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 5), // S7 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 6), // S8 + DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 4), // S5 + DEF_TIM(TIM4, CH4, PD15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 DMA_NONE + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 5), // S7 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 6), // S8 - DEF_TIM(TIM15,CH1, PE5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 7), // S9 - DEF_TIM(TIM15,CH2, PE6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S10 DMA_NONE - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S12 + DEF_TIM(TIM15,CH1, PE5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 7), // S9 + DEF_TIM(TIM15,CH2, PE6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 DMA_NONE + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S11 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S12 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S13 - //DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S14 / LED_2812 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S13 + //DEF_TIM(TIM2, CH1, PA15, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S14 / LED_2812 DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // S14 / LED_2812 diff --git a/src/main/target/KROOZX/target.c b/src/main/target/KROOZX/target.c index ba2519cefe..c77a77aaed 100755 --- a/src/main/target/KROOZX/target.c +++ b/src/main/target/KROOZX/target.c @@ -25,16 +25,16 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), // PPM IN - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR, 0, 0), // PWM4 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR, 0, 0), // PWM2 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR, 0, 0), // PWM3 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR, 0, 0), // PWM1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0, 0), // PWM5 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // PWM6 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR, 0, 0), // PWM7 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR, 0, 0), // PWM8 - DEF_TIM(TIM4, CH1, PB14, TIM_USE_MC_MOTOR, 0, 0), // PWM9 - DEF_TIM(TIM4, CH2, PB15, TIM_USE_MC_MOTOR, 0, 0), // PWM10 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0), // PWM4 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 0), // PWM2 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0), // PWM3 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR, 0, 0), // PWM1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // PWM5 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // PWM6 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // PWM7 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0), // PWM8 + DEF_TIM(TIM4, CH1, PB14, TIM_USE_MOTOR, 0, 0), // PWM9 + DEF_TIM(TIM4, CH2, PB15, TIM_USE_MOTOR, 0, 0), // PWM10 DEF_TIM(TIM8, CH1, PC6, TIM_USE_LED, 0, 0), // LED_STRIP }; diff --git a/src/main/target/MAMBAF405US/target.c b/src/main/target/MAMBAF405US/target.c index 06a09a2e40..cdceba21e4 100644 --- a/src/main/target/MAMBAF405US/target.c +++ b/src/main/target/MAMBAF405US/target.c @@ -28,15 +28,15 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN #ifdef MAMBAF405US_I2C - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S1 pin A9: DMA2 Stream 6 Channel 0 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S2 pin A8: DMA2 Stream 6 Channel 0 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3 pin C9: DMA2 Stream 7 Channel 7 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S4 pin C8: DMA2 Stream 2 Channel 0 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S1 pin A9: DMA2 Stream 6 Channel 0 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S2 pin A8: DMA2 Stream 6 Channel 0 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3 pin C9: DMA2 Stream 7 Channel 7 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 pin C8: DMA2 Stream 2 Channel 0 #else - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S4_OUT – D(2, 2, 6) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S3_OUT – D(2, 1, 6) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S2_OUT – D(2, 7, 7) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S1_OUT – D(2, 4, 7) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4_OUT – D(2, 2, 6) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3_OUT – D(2, 1, 6) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT – D(2, 7, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT – D(2, 4, 7) #endif DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) diff --git a/src/main/target/MAMBAF405_2022A/target.c b/src/main/target/MAMBAF405_2022A/target.c index 0e659296e8..aeded5cda9 100644 --- a/src/main/target/MAMBAF405_2022A/target.c +++ b/src/main/target/MAMBAF405_2022A/target.c @@ -26,12 +26,12 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S1 pin A9: DMA2 Stream 6 Channel 0 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S2 pin A8: DMA2 Stream 6 Channel 0 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3 pin C9: DMA2 Stream 7 Channel 7 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S4 pin C8: DMA2 Stream 2 Channel 0 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 1, 0 ), // S4 pin C8: DMA2 Stream 2 Channel 0 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 1, 0 ), // S4 pin C8: DMA2 Stream 2 Channel 0 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S1 pin A9: DMA2 Stream 6 Channel 0 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S2 pin A8: DMA2 Stream 6 Channel 0 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3 pin C9: DMA2 Stream 7 Channel 7 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 pin C8: DMA2 Stream 2 Channel 0 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM USE_SERVO, 1, 0 ), // S4 pin C8: DMA2 Stream 2 Channel 0 // used to be fw motor + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0 ), // S4 pin C8: DMA2 Stream 2 Channel 0 // used to be fw motor DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; diff --git a/src/main/target/MAMBAF722/target.c b/src/main/target/MAMBAF722/target.c index f7db2a3039..cb1073af53 100644 --- a/src/main/target/MAMBAF722/target.c +++ b/src/main/target/MAMBAF722/target.c @@ -27,10 +27,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1_OUT – D(2, 4, 7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2_OUT – D(2, 7, 7) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S3_OUT – D(2, 1, 6) - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S4_OUT – D(2, 2, 6) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT – D(2, 4, 7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT – D(2, 7, 7) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3_OUT – D(2, 1, 6) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4_OUT – D(2, 2, 6) DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; diff --git a/src/main/target/MAMBAF722_2022A/target.c b/src/main/target/MAMBAF722_2022A/target.c index 56f5483cbd..1b41cb437e 100644 --- a/src/main/target/MAMBAF722_2022A/target.c +++ b/src/main/target/MAMBAF722_2022A/target.c @@ -27,15 +27,15 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S3 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S6 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S8 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; diff --git a/src/main/target/MAMBAF722_WING/target.c b/src/main/target/MAMBAF722_WING/target.c index c39247afe5..c25d866183 100644 --- a/src/main/target/MAMBAF722_WING/target.c +++ b/src/main/target/MAMBAF722_WING/target.c @@ -25,15 +25,15 @@ #include "drivers/bus.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S3 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S6 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S8 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; diff --git a/src/main/target/MAMBAF722_X8/target.c b/src/main/target/MAMBAF722_X8/target.c index afe6e36359..f1e2f5e4db 100644 --- a/src/main/target/MAMBAF722_X8/target.c +++ b/src/main/target/MAMBAF722_X8/target.c @@ -27,15 +27,15 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S3 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S6 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S8 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; diff --git a/src/main/target/MAMBAH743/target.c b/src/main/target/MAMBAH743/target.c index f684670a22..11bdee8446 100644 --- a/src/main/target/MAMBAH743/target.c +++ b/src/main/target/MAMBAH743/target.c @@ -35,15 +35,15 @@ BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, timerHardware_t timerHardware[] = { - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S2 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 3), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 4), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 5), // S6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 6), // S7 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 7), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_SERVO | TIM_USE_SERVO, 0, 4), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_SERVO | TIM_USE_SERVO, 0, 5), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_SERVO | TIM_USE_SERVO, 0, 6), // S7 // used to be fw motor + DEF_TIM(TIM8, CH4, PC9, TIM_USE_SERVO | TIM_USE_SERVO, 0, 7), // S8 // used to be fw motor DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 }; diff --git a/src/main/target/MATEKF405/target.c b/src/main/target/MATEKF405/target.c index 047e0f3775..254707887b 100644 --- a/src/main/target/MATEKF405/target.c +++ b/src/main/target/MATEKF405/target.c @@ -29,7 +29,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 UP(2,1) DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 UP(2,1) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_LED , 0, 0), // S5 UP(1,7) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO | TIM_USE_LED , 0, 0), // S5 UP(1,7) DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 UP(2,5) DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(1,7)!S5 UP(2,6) diff --git a/src/main/target/MATEKF405CAN/target.c b/src/main/target/MATEKF405CAN/target.c index f4c9826ac8..b303ac8c34 100644 --- a/src/main/target/MATEKF405CAN/target.c +++ b/src/main/target/MATEKF405CAN/target.c @@ -22,15 +22,15 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1), // S1 D(2,2,7) - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1), // S2 D(2,3,7) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 1), // S3 D(2,4,7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S4 D(2,7,7) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S5 D(1,7,5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S6 D(1,2,5) + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // S1 D(2,2,7) + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // S2 D(2,3,7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // S3 D(2,4,7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4 D(2,7,7) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S5 D(1,7,5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S6 D(1,2,5) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S7 D(1,0,2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S8 D(1,3,2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S7 D(1,0,2) // used to be fw motor + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S8 D(1,3,2) // used to be fw motor DEF_TIM(TIM1, CH1, PA8, TIM_USE_BEEPER, 0, 0), // BEEPER PWM diff --git a/src/main/target/MATEKF405SE/target.c b/src/main/target/MATEKF405SE/target.c index c81fe5a7f0..ad7431699e 100644 --- a/src/main/target/MATEKF405SE/target.c +++ b/src/main/target/MATEKF405SE/target.c @@ -22,16 +22,16 @@ #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(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S1 D(1,3,2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 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(TIM12, CH1, PB14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S7 - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S8 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S9 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S3 D(1,7,5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4 D(1,2,5) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S5 D(2,4,7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S6 D(2,7,7) + DEF_TIM(TIM12, CH1, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S7 + DEF_TIM(TIM12, CH2, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S8 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S9 DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) diff --git a/src/main/target/MATEKF405TE/target.c b/src/main/target/MATEKF405TE/target.c index 70561e001f..03d6933676 100644 --- a/src/main/target/MATEKF405TE/target.c +++ b/src/main/target/MATEKF405TE/target.c @@ -25,19 +25,19 @@ #include "drivers/timer_def_stm32f4xx.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2,7,7) UP217 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(2,2,0) UP217 - DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 D(2,6,0) UP256 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S4 D(2,1,6) UP256 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(2,7,7) UP217 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(2,2,0) UP217 + DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 D(2,6,0) UP256 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4 D(2,1,6) UP256 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 D(1,7,3) UP173 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,1,3) UP173 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,6,3) UP173 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 D(1,5,3) UP173 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 D(1,7,3) UP173 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(1,1,3) UP173 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 D(1,6,3) UP173 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 D(1,5,3) UP173 - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 DMA NONE - DEF_TIM(TIM13, CH1, PA6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 DMA NONE - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S11 D(1,0,2) + DEF_TIM(TIM12, CH1, PB14, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S9 DMA NONE + DEF_TIM(TIM13, CH1, PA6, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S10 DMA NONE + DEF_TIM(TIM4, CH1, PB6, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S11 D(1,0,2) DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), // 2812LED D(1,2,5) DEF_TIM(TIM11, CH1, PB9, TIM_USE_BEEPER, 0, 0), // BEEPER PWM diff --git a/src/main/target/MATEKF411/target.c b/src/main/target/MATEKF411/target.c index c192e8c69d..b496a64eaa 100755 --- a/src/main/target/MATEKF411/target.c +++ b/src/main/target/MATEKF411/target.c @@ -25,14 +25,14 @@ timerHardware_t timerHardware[] = { // DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(1,4,5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(1,5,5) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 D(1,0,2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 D(1,3,2) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(1,4,5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(1,5,5) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 D(1,0,2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 D(1,3,2) - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 D(1,6,3) - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,1,3) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,5,3) - clash with S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S5 D(1,6,3) + DEF_TIM(TIM2, CH3, PB10, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S6 D(1,1,3) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S7 D(1,5,3) - clash with S2 DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), //softserial_tx2 - 2812LED TIM_USE_LED D(2,1,6) DEF_TIM(TIM5, CH1, PA0, TIM_USE_PPM, 0, 0), //use rssi pad for PPM/softserial_tx1 diff --git a/src/main/target/MATEKF411SE/target.c b/src/main/target/MATEKF411SE/target.c index 679df39607..97184fe611 100755 --- a/src/main/target/MATEKF411SE/target.c +++ b/src/main/target/MATEKF411SE/target.c @@ -24,13 +24,13 @@ #include "drivers/pinio.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(1,4,5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(1,5,5) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 D(2,1,6) - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S4 D(2,2,6) - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S5 D(2,6,6) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(1,4,5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(1,5,5) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 D(2,1,6) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4 D(2,2,6) + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S5 D(2,6,6) #ifndef MATEKF411SE_SS2_CH6 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,7,2) + DEF_TIM(TIM4, CH3, PB8, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S6 D(1,7,2) DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 pad - softserial_tx2 #else diff --git a/src/main/target/MATEKF411TE/target.c b/src/main/target/MATEKF411TE/target.c index 9bfad340f1..55c790c8ca 100644 --- a/src/main/target/MATEKF411TE/target.c +++ b/src/main/target/MATEKF411TE/target.c @@ -25,19 +25,19 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(1,0,2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(1,3,6) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 D(1,7,5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 D(1,2,5) - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 D(1,4,5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 D(1,5,5) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(1,0,2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(1,3,6) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 D(1,7,5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 D(1,2,5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 D(1,4,5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(1,5,5) DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), //Softserial1_TX DEF_TIM(TIM5, CH2, PA1, TIM_USE_ANY, 0, 0), //Softserial1_RX DEF_TIM(TIM2, CH1, PA15, TIM_USE_ANY, 0, 0), //Softserial2_TX DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), //Softserial2_RX - DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED | TIM_USE_MC_SERVO, 0, 0), //2812LED D(2,1,6) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED | TIM_USE_SERVO, 0, 0), //2812LED D(2,1,6) }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MATEKF722PX/target.c b/src/main/target/MATEKF722PX/target.c index 1db058f8fd..22d8ffcac4 100755 --- a/src/main/target/MATEKF722PX/target.c +++ b/src/main/target/MATEKF722PX/target.c @@ -24,19 +24,19 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 UP2-1 D(2, 4, 7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 UP2-1 D(2, 7, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 UP2-1 D(2, 4, 7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 UP2-1 D(2, 7, 7) - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP1-2 D(1, 4, 5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP1-2 D(1, 5, 5) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP1-2 D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP1-2 D(1, 2, 5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 UP1-2 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 UP1-2 D(1, 5, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP1-2 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP1-2 D(1, 2, 5) - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 UP1-7 D(1, 1, 3) - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S8 UP1-7 D(1, 6, 3) + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 UP1-7 D(1, 1, 3) + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S8 UP1-7 D(1, 6, 3) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 UP1-6 D(1, 0, 2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 UP1-6 D(1, 3, 2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9 UP1-6 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 UP1-6 D(1, 3, 2) DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 3, 6) diff --git a/src/main/target/MATEKF722SE/CMakeLists.txt b/src/main/target/MATEKF722SE/CMakeLists.txt index 75aa91ec0a..a541da229f 100644 --- a/src/main/target/MATEKF722SE/CMakeLists.txt +++ b/src/main/target/MATEKF722SE/CMakeLists.txt @@ -1,3 +1,2 @@ target_stm32f722xe(MATEKF722SE) target_stm32f722xe(MATEKF722MINI) -target_stm32f722xe(MATEKF722SE_8MOTOR) diff --git a/src/main/target/MATEKF722SE/target.c b/src/main/target/MATEKF722SE/target.c index 1ea322fb82..67cdad4a52 100644 --- a/src/main/target/MATEKF722SE/target.c +++ b/src/main/target/MATEKF722SE/target.c @@ -30,21 +30,16 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) -#if (defined(MATEKF722SE_8MOTOR)) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 UP1-6 D(1, 0, 2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 UP1-6 D(1, 3, 2) -#else - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S7 UP1-6 D(1, 0, 2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S8 UP1-6 D(1, 3, 2) -#endif + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 UP1-6 D(1, 0, 2) // used to be fw motor + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 UP1-6 D(1, 3, 2) // used to me fw motor DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 6, 0) diff --git a/src/main/target/MATEKF765/target.c b/src/main/target/MATEKF765/target.c index 0a4e42ac9c..e91c644147 100644 --- a/src/main/target/MATEKF765/target.c +++ b/src/main/target/MATEKF765/target.c @@ -34,21 +34,21 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu3, DEVHW_ICM42605, ICM42605_SPI_BUS, #endif timerHardware_t timerHardware[] = { - DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 UP(1,7), D(1,5,3) - DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 UP(1,7), D(1,6,3) + DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 UP(1,7), D(1,5,3) + DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 UP(1,7), D(1,6,3) - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP(1,0), D(1,0,6)* - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP(1,0), D(1,1,6) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP(1,2), D(1,7,5)** - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP(1,2), D(1,2,5) + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 UP(1,0), D(1,0,6)* + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 UP(1,0), D(1,1,6) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP(1,2), D(1,7,5)** + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP(1,2), D(1,2,5) - DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 UP(1,6), D(1,0,2)* - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8 UP(1,6), D(1,3,2) - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 UP(1,6), D(1,7,2)** - DEF_TIM(TIM4, CH4, PD15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 UP(1,6) + DEF_TIM(TIM4, CH1, PD12, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S7 UP(1,6), D(1,0,2)* + DEF_TIM(TIM4, CH2, PD13, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S8 UP(1,6), D(1,3,2) + DEF_TIM(TIM4, CH3, PD14, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S9 UP(1,6), D(1,7,2)** + DEF_TIM(TIM4, CH4, PD15, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S10 UP(1,6) - DEF_TIM(TIM9, CH1, PE5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S11 - DEF_TIM(TIM9, CH2, PE6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S12 + DEF_TIM(TIM9, CH1, PE5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S11 + DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S12 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED_2812 D(2,6,0) diff --git a/src/main/target/NEUTRONRCF435MINI/target.c b/src/main/target/NEUTRONRCF435MINI/target.c index 995bf8f3d1..a1bba9b765 100644 --- a/src/main/target/NEUTRONRCF435MINI/target.c +++ b/src/main/target/NEUTRONRCF435MINI/target.c @@ -28,12 +28,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TMR1, CH1, PA8, TIM_USE_ANY |TIM_USE_LED, 0,7), // PWM1 - LED MCO1 DMA1 CH2 - DEF_TIM(TMR4, CH1, PB6, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,0), // motor1 DMA2 CH7 - DEF_TIM(TMR4, CH2, PB7, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,2), // motor2 DMA2 CH6 - DEF_TIM(TMR2, CH4, PA3, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,1), // motor3 DMA2 CH5 - DEF_TIM(TMR3, CH4, PB1, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,3), // motor4 DMA2 CH4 + DEF_TIM(TMR4, CH1, PB6, TIM_USE_MOTOR|TIM_USE_SERVO, 0,0), // motor1 DMA2 CH7 + DEF_TIM(TMR4, CH2, PB7, TIM_USE_MOTOR|TIM_USE_SERVO, 0,2), // motor2 DMA2 CH6 + DEF_TIM(TMR2, CH4, PA3, TIM_USE_MOTOR|TIM_USE_SERVO, 0,1), // motor3 DMA2 CH5 + DEF_TIM(TMR3, CH4, PB1, TIM_USE_MOTOR|TIM_USE_SERVO, 0,3), // motor4 DMA2 CH4 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); - \ No newline at end of file + diff --git a/src/main/target/NEUTRONRCF435SE/target.c b/src/main/target/NEUTRONRCF435SE/target.c index 7eb72ead92..713139aa16 100644 --- a/src/main/target/NEUTRONRCF435SE/target.c +++ b/src/main/target/NEUTRONRCF435SE/target.c @@ -26,21 +26,21 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TMR5, CH1, PA0, TIM_USE_ANY, 0, 13), // TIM_USE_CAMERA_CONTROL - DEF_TIM(TMR5, CH2, PA1, TIM_USE_ANY |TIM_USE_LED, 0,7), // PWM1 - LED MCO1 DMA1 CH2 - DEF_TIM(TMR2, CH4, PA3, TIM_USE_ANY |TIM_USE_PPM, 0,6), // PWM2 - PPM DMA1 CH6 + DEF_TIM(TMR5, CH1, PA0, TIM_USE_ANY, 0, 13), // TIM_USE_CAMERA_CONTROL + DEF_TIM(TMR5, CH2, PA1, TIM_USE_ANY |TIM_USE_LED, 0,7), // PWM1 - LED MCO1 DMA1 CH2 + DEF_TIM(TMR2, CH4, PA3, TIM_USE_ANY |TIM_USE_PPM, 0,6), // PWM2 - PPM DMA1 CH6 - DEF_TIM(TMR8, CH4, PC9, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,0), // motor1 DMA2 CH7 - DEF_TIM(TMR8, CH3, PC8, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,2), // motor2 DMA2 CH6 - DEF_TIM(TMR3, CH2, PC7, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,1), // motor3 DMA2 CH5 - DEF_TIM(TMR3, CH1, PC6, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,3), // motor4 DMA2 CH4 + DEF_TIM(TMR8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0,0), // motor1 DMA2 CH7 + DEF_TIM(TMR8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0,2), // motor2 DMA2 CH6 + DEF_TIM(TMR3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0,1), // motor3 DMA2 CH5 + DEF_TIM(TMR3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0,3), // motor4 DMA2 CH4 + + DEF_TIM(TMR4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0,11), // PWM1 - OUT5 DMA1 CH7 + DEF_TIM(TMR4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0,10), // PWM2 - OUT6 DMA2 CH1 + DEF_TIM(TMR3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0,9), // PWM3 - OUT7 DMA2 CH2 + DEF_TIM(TMR3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0,8), // PWM4 - OUT8 DMA2 CH3 - DEF_TIM(TMR4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,11), // PWM1 - OUT5 DMA1 CH7 - DEF_TIM(TMR4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,10), // PWM2 - OUT6 DMA2 CH1 - DEF_TIM(TMR3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,9), // PWM3 - OUT7 DMA2 CH2 - DEF_TIM(TMR3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,8), // PWM4 - OUT8 DMA2 CH3 - }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); - \ No newline at end of file + diff --git a/src/main/target/NEUTRONRCF435WING/target.c b/src/main/target/NEUTRONRCF435WING/target.c index b64e1a5c8f..0220df8230 100644 --- a/src/main/target/NEUTRONRCF435WING/target.c +++ b/src/main/target/NEUTRONRCF435WING/target.c @@ -28,17 +28,17 @@ timerHardware_t timerHardware[] = { DEF_TIM(TMR1, CH1, PA8, TIM_USE_ANY |TIM_USE_LED, 0,7), // PWM1 - LED MCO1 DMA1 CH2 - DEF_TIM(TMR4, CH1, PB6, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,0), // motor1 DMA2 CH7 - DEF_TIM(TMR1, CH3, PA10, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,2), // motor2 DMA2 CH6 - DEF_TIM(TMR2, CH4, PA3, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,1), // motor3 DMA2 CH5 - DEF_TIM(TMR3, CH4, PB1, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,3), // motor4 DMA2 CH4 + DEF_TIM(TMR4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0,0), // motor1 DMA2 CH7 + DEF_TIM(TMR1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0,2), // motor2 DMA2 CH6 + DEF_TIM(TMR2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0,1), // motor3 DMA2 CH5 + DEF_TIM(TMR3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0,3), // motor4 DMA2 CH4 - DEF_TIM(TMR4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,10), // PWM1 - OUT5 DMA2 CH1 - DEF_TIM(TMR1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,9), // PWM2 - OUT6 DMA2 CH2 - DEF_TIM(TMR3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,8), // PWM3 - OUT7 DMA2 CH3 - DEF_TIM(TMR2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,11), // PWM4 - OUT8 DMA1 CH7 + DEF_TIM(TMR4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0,10), // PWM1 - OUT5 DMA2 CH1 + DEF_TIM(TMR1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0,9), // PWM2 - OUT6 DMA2 CH2 + DEF_TIM(TMR3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0,8), // PWM3 - OUT7 DMA2 CH3 + DEF_TIM(TMR2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0,11), // PWM4 - OUT8 DMA1 CH7 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); - \ No newline at end of file + diff --git a/src/main/target/NEUTRONRCH7BT/target.c b/src/main/target/NEUTRONRCH7BT/target.c index b65dc90634..74f2573486 100644 --- a/src/main/target/NEUTRONRCH7BT/target.c +++ b/src/main/target/NEUTRONRCH7BT/target.c @@ -27,15 +27,15 @@ #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(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 4), // S5 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 5), // S6 - DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 6), // S7 - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 7), // S8 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 3), // S4 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 4), // S5 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 5), // S6 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 6), // S7 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 7), // S8 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 }; diff --git a/src/main/target/NOX/target.c b/src/main/target/NOX/target.c index 0508a0155b..2481dae52c 100755 --- a/src/main/target/NOX/target.c +++ b/src/main/target/NOX/target.c @@ -27,10 +27,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH3, PB10, TIM_USE_PPM, 0, 0), //PPM DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 0, 0), //2812LED - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT - DEF_TIM(TIM1, CH1N, PA7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3_OUT - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT + DEF_TIM(TIM1, CH1N, PA7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT DEF_TIM(TIM9, CH1, PA2, TIM_USE_ANY, 0, 0), //UART2 TX DEF_TIM(TIM9, CH2, PA3, TIM_USE_ANY, 0, 0), //UART2 RX diff --git a/src/main/target/OMNIBUSF4/target.c b/src/main/target/OMNIBUSF4/target.c index 9c7e4b76a8..f1ba154606 100644 --- a/src/main/target/OMNIBUSF4/target.c +++ b/src/main/target/OMNIBUSF4/target.c @@ -36,27 +36,27 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), // S5_IN // pad labelled CH5 on OMNIBUSF4PRO DEF_TIM(TIM8, CH4, PC9, TIM_USE_ANY, 0, 0), // S6_IN // pad labelled CH6 on OMNIBUSF4PRO - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT D1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT D1_ST2 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3_OUT D1_ST6 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT D1_ST1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT D1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT D1_ST2 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3_OUT D1_ST6 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT D1_ST1 - // { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // MOTOR_3 + // { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_MOTOR | TIM_USE_SERVO }, // MOTOR_3 #if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !(defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5_OUT - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO 0, 0), // S5_OUT + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT #elif defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) DEF_TIM(TIM5, CH2, PA1, TIM_USE_ANY, 0, 0), // S5_OUT SOFTSERIAL DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // S6_OUT SOFTSERIAL #elif defined(OMNIBUSF4V3_S6_SS) - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5_OUT + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // S6_OUT SOFTSERIAL #elif defined(OMNIBUSF4PRO_LEDSTRIPM5) DEF_TIM(TIM5, CH2, PA1, TIM_USE_LED, 0, 0), // S5_OUT LED strip - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT #else - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO | TIM_USE_LED, 0, 0), // S5_OUT MOTOR, SERVO or LED - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0), // S5_OUT MOTOR, SERVO or LED + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT #endif #if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !defined(OMNIBUSF4PRO_LEDSTRIPM5) diff --git a/src/main/target/OMNIBUSF7/target.c b/src/main/target/OMNIBUSF7/target.c index c11e1629bf..e6cf7c8282 100644 --- a/src/main/target/OMNIBUSF7/target.c +++ b/src/main/target/OMNIBUSF7/target.c @@ -39,10 +39,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, 0, 0 ), // UART2_RX, joined with PE13 // DEF_TIM(TIM1, CH3, PE13, TIM_USE_NONE, 0, 0 ), // RC1 / PPM, unusable - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // M1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // M2 - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2 ), // M3 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // M4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // M1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // M2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2 ), // M3 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // M4 DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0 ), // LED }; diff --git a/src/main/target/OMNIBUSF7NXT/target.c b/src/main/target/OMNIBUSF7NXT/target.c index 6f92459630..e7573ae16d 100644 --- a/src/main/target/OMNIBUSF7NXT/target.c +++ b/src/main/target/OMNIBUSF7NXT/target.c @@ -39,14 +39,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM / UART1_RX // OUTPUT 1-4 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // D(1, 5, 5) - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // D(1, 4, 5) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // D(1, 2, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // D(1, 5, 5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // D(1, 4, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // D(1, 2, 5) // OUTPUT 5-6 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // D(2, 7, 7) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 1), // D(2, 2, 0) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // D(2, 7, 7) // used to be fw motor + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // D(2, 2, 0) // used to be fw motor // AUXILARY pins DEF_TIM(TIM1, CH2, PA9, TIM_USE_LED, 1, 0), // LED diff --git a/src/main/target/PIXRACER/target.c b/src/main/target/PIXRACER/target.c index 294c962f24..09ecffa6c1 100755 --- a/src/main/target/PIXRACER/target.c +++ b/src/main/target/PIXRACER/target.c @@ -39,13 +39,13 @@ BUSDEV_REGISTER_SPI_TAG(busdev_hmc5983_spi, DEVHW_HMC5883, MPU9250_SPI_BUS, timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH3, PB0, TIM_USE_PPM, 0, 0 ), // PPM shared uart6 pc7 - DEF_TIM(TIM1, CH4, PE14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S1_OUT - DEF_TIM(TIM1, CH3, PE13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S2_OUT - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3_OUT - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S4_OUT + DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT + DEF_TIM(TIM1, CH3, PE13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4_OUT - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S5_OUT - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S6_OUT + DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_OUT // used to be fw motor + DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6_OUT // used to be fw motor }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/RADIX/target.c b/src/main/target/RADIX/target.c index dd05a6b3ce..086d448030 100644 --- a/src/main/target/RADIX/target.c +++ b/src/main/target/RADIX/target.c @@ -26,12 +26,12 @@ /* TIMERS */ timerHardware_t timerHardware[] = { DEF_TIM(TIM12, CH1, PB14, TIM_USE_PPM, 0, 0), // PPM In - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR, 0, 0), // S1 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR, 0, 0), // S2 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR, 0, 0), // S3 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR, 0, 0), // S4 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0), // S5 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // S6 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), // Camera Control }; diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c index 7cd184b9f6..913083c72d 100644 --- a/src/main/target/REVO/target.c +++ b/src/main/target/REVO/target.c @@ -34,19 +34,19 @@ BUSDEV_REGISTER_I2C_TAG(busdev_mag3110, DEVHW_MAG3110, MAG_I2C_BUS_EXT, /* TIMERS */ timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT D1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT D1_ST2 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3_OUT D1_ST6 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT D1_ST1 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO | TIM_USE_ANY, 0, 0), // S5_OUT / LED - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT D1_ST2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT D1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT D1_ST2 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3_OUT D1_ST6 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT D1_ST1 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_ANY, 0, 0), // S5_OUT / LED + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT D1_ST2 - DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // PPM (5th pin on FlexiIO port) - DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN - DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // S3_IN - DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // S4_IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // S5_IN - DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // S6_IN + DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // PPM (5th pin on FlexiIO port) + DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN + DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_IN + DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_IN + DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_IN + DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_IN }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/RUSH_BLADE_F7/target.c b/src/main/target/RUSH_BLADE_F7/target.c index 565c8a2346..bca0f23cea 100644 --- a/src/main/target/RUSH_BLADE_F7/target.c +++ b/src/main/target/RUSH_BLADE_F7/target.c @@ -23,14 +23,14 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S5 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S6 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // S7 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // S8 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 // used to be fw motor + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 // used to be fw motor + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED STRIP #ifdef RUSH_BLADE_F7 diff --git a/src/main/target/SAGEATF4/target.c b/src/main/target/SAGEATF4/target.c index 3d8ed6feb5..63ab717851 100644 --- a/src/main/target/SAGEATF4/target.c +++ b/src/main/target/SAGEATF4/target.c @@ -27,20 +27,20 @@ timerHardware_t timerHardware[] = { DEF_TIM(TMR5, CH4, PA3, TIM_USE_PPM, 0, 4), // PPM UART2_RX_PIN DMA1 CH5 - DEF_TIM(TMR2, CH3, PB10, TIM_USE_ANY |TIM_USE_LED, 0,5), // PWM1 - LED MCO1 DMA1 CH6 - DEF_TIM(TMR2, CH4, PB11, TIM_USE_ANY |TIM_USE_BEEPER, 0,6), // PWM2 - BB DMA1 CH7 + DEF_TIM(TMR2, CH3, PB10, TIM_USE_ANY | TIM_USE_LED, 0,5), // PWM1 - LED MCO1 DMA1 CH6 + DEF_TIM(TMR2, CH4, PB11, TIM_USE_ANY | TIM_USE_BEEPER, 0,6), // PWM2 - BB DMA1 CH7 - DEF_TIM(TMR4, CH1, PB6, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,0), // motor1 DMA1 CH1 - DEF_TIM(TMR4, CH2, PB7, TIM_USE_MC_MOTOR|TIM_USE_FW_MOTOR, 0,1), // motor2 DMA1 CH2 - DEF_TIM(TMR2, CH1, PB8, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,2), // motor3 DMA1 CH3 - DEF_TIM(TMR2, CH2, PB9, TIM_USE_MC_MOTOR|TIM_USE_FW_SERVO, 0,3), // motor4 DMA1 CH4 + DEF_TIM(TMR4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0,0), // motor1 DMA1 CH1 + DEF_TIM(TMR4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0,1), // motor2 DMA1 CH2 + DEF_TIM(TMR2, CH1, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0,2), // motor3 DMA1 CH3 + DEF_TIM(TMR2, CH2, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0,3), // motor4 DMA1 CH4 - DEF_TIM(TMR3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,8), // PWM1 - OUT5 DMA2 CH2 DMA2_CHANNEL1->ADC - DEF_TIM(TMR3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,9), // PWM2 - OUT6 DMA2 CH3 - DEF_TIM(TMR3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,10), // PWM3 - OUT7 DMA2 CH4 - DEF_TIM(TMR3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0,11), // PWM4 - OUT8 DMA2 CH5 + DEF_TIM(TMR3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0,8), // PWM1 - OUT5 DMA2 CH2 DMA2_CHANNEL1->ADC + DEF_TIM(TMR3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0,9), // PWM2 - OUT6 DMA2 CH3 + DEF_TIM(TMR3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0,10), // PWM3 - OUT7 DMA2 CH4 + DEF_TIM(TMR3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0,11), // PWM4 - OUT8 DMA2 CH5 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); - \ No newline at end of file + diff --git a/src/main/target/SKYSTARSF405HD/target.c b/src/main/target/SKYSTARSF405HD/target.c index e6bec48b4c..0689dceb37 100644 --- a/src/main/target/SKYSTARSF405HD/target.c +++ b/src/main/target/SKYSTARSF405HD/target.c @@ -24,10 +24,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), }; diff --git a/src/main/target/SKYSTARSF722HD/target.c b/src/main/target/SKYSTARSF722HD/target.c index cf5906d915..8146885a16 100644 --- a/src/main/target/SKYSTARSF722HD/target.c +++ b/src/main/target/SKYSTARSF722HD/target.c @@ -24,10 +24,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH1, PB4, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // TIM3_CH3 / TIM8_CH3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // TIM3_CH4 / TIM8_CH4 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // TIM4_CH1 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // TIM4_CH2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // TIM3_CH3 / TIM8_CH3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // TIM3_CH4 / TIM8_CH4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // TIM4_CH1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // TIM4_CH2 // used to be fw motor DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0), }; diff --git a/src/main/target/SKYSTARSH743HD/target.c b/src/main/target/SKYSTARSH743HD/target.c index 07a2b0ef70..6fb3cfd27d 100644 --- a/src/main/target/SKYSTARSH743HD/target.c +++ b/src/main/target/SKYSTARSH743HD/target.c @@ -30,16 +30,16 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270_1, DEVHW_BMI270, IMU1_SPI_BUS, IMU1_CS BUSDEV_REGISTER_SPI_TAG(busdev_bmi270_2, DEVHW_BMI270, IMU2_SPI_BUS, IMU2_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU2_ALIGN); 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(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - DEF_TIM(TIM4, CH1, PD12, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3 - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 3), // S4 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 4), // S5 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 5), // S6 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 6), // S7 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 7), // S8 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 4), // S5 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 5), // S6 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 6), // S7 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 7), // S8 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 }; diff --git a/src/main/target/SPARKY2/target.c b/src/main/target/SPARKY2/target.c index c5ae5109e9..881b7ddd5a 100644 --- a/src/main/target/SPARKY2/target.c +++ b/src/main/target/SPARKY2/target.c @@ -30,12 +30,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0 ), // S4_IN DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0 ), // S5_IN - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1_OUT - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2_OUT - DEF_TIM(TIM9, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3_OUT - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S4_OUT - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S5_OUT - GPIO_PartialRemap_TIM3 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S6_OUT + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT + DEF_TIM(TIM9, CH2, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4_OUT + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_OUT - GPIO_PartialRemap_TIM3 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6_OUT }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SPEEDYBEEF4/target.c b/src/main/target/SPEEDYBEEF4/target.c index be21bfbb26..c3c68ed9bc 100644 --- a/src/main/target/SPEEDYBEEF4/target.c +++ b/src/main/target/SPEEDYBEEF4/target.c @@ -26,14 +26,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP(1,2) - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 UP(2,1) - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP(2,1) - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP(2,1) + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 UP(1,2) + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 UP(2,1) + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 UP(2,1) + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 UP(2,1) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S5 UP(1,7) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S6 UP(2,5) - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 D(1,7)!S5 UP(2,6) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP(1,7) // used to be fw motor + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP(2,5) // used to be fw motor + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 D(1,7)!S5 UP(2,6) DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED D(1,0) UP(2,6) }; diff --git a/src/main/target/SPEEDYBEEF405MINI/target.c b/src/main/target/SPEEDYBEEF405MINI/target.c index 1118940e6f..ba27b5e3c3 100644 --- a/src/main/target/SPEEDYBEEF405MINI/target.c +++ b/src/main/target/SPEEDYBEEF405MINI/target.c @@ -27,14 +27,14 @@ #include "drivers/sensor.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S1 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1, 0), // S2 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S3 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S2 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S3 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4 #ifdef SPEEDYBEEF405MINI_6OUTPUTS - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // CAM_CTRL - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // LED + DEF_TIM(TIM12, CH1, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // CAM_CTRL + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // LED #else DEF_TIM(TIM12, CH1, PB14, TIM_USE_ANY, 1, 0), // CAM_CTRL DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED diff --git a/src/main/target/SPEEDYBEEF405V3/target.c b/src/main/target/SPEEDYBEEF405V3/target.c index fffac26520..a2f0859bd5 100644 --- a/src/main/target/SPEEDYBEEF405V3/target.c +++ b/src/main/target/SPEEDYBEEF405V3/target.c @@ -35,15 +35,15 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 DEF_TIM(TIM8, CH4, PC9, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/SPEEDYBEEF405WING/target.c b/src/main/target/SPEEDYBEEF405WING/target.c index a06d783801..2d978e1977 100644 --- a/src/main/target/SPEEDYBEEF405WING/target.c +++ b/src/main/target/SPEEDYBEEF405WING/target.c @@ -22,19 +22,19 @@ #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(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S1 D(1,3,2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 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(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S3 D(1,7,5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4 D(1,2,5) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S5 D(2,4,7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S6 D(2,7,7) - DEF_TIM(TIM8, CH2N,PB14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1, 0), // S7 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S8 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S9 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S10 - DEF_TIM(TIM1, CH3N,PB15, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 1, 0), // S11 + DEF_TIM(TIM8, CH2N,PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S7 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_SERVO | TIM_USE_SERVO, 1, 0), // S8 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_SERVO | TIM_USE_SERVO, 1, 0), // S9 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_SERVO | TIM_USE_SERVO, 1, 0), // S10 + DEF_TIM(TIM1, CH3N,PB15, TIM_USE_SERVO | TIM_USE_SERVO, 1, 0), // S11 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 softserial1_Tx diff --git a/src/main/target/SPEEDYBEEF7/target.c b/src/main/target/SPEEDYBEEF7/target.c index d454579204..b7489c75bb 100644 --- a/src/main/target/SPEEDYBEEF7/target.c +++ b/src/main/target/SPEEDYBEEF7/target.c @@ -26,13 +26,13 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S5 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED | TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // LED/S6 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // LED/S6 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SPEEDYBEEF745AIO/target.c b/src/main/target/SPEEDYBEEF745AIO/target.c index 8a97ac96bc..2c03c86e42 100644 --- a/src/main/target/SPEEDYBEEF745AIO/target.c +++ b/src/main/target/SPEEDYBEEF745AIO/target.c @@ -30,13 +30,13 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // S1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0, 0), // S2 - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR, 0, 2), // S3 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR, 0, 1), // S4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR, 0, 2), // S3 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR, 0, 1), // S4 DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // Camera Control }; -const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); \ No newline at end of file +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SPEEDYBEEF7MINI/target.c b/src/main/target/SPEEDYBEEF7MINI/target.c index 7cc2506b66..14f10a79be 100644 --- a/src/main/target/SPEEDYBEEF7MINI/target.c +++ b/src/main/target/SPEEDYBEEF7MINI/target.c @@ -33,16 +33,16 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, #endif timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S7 UP1-6 D(1, 0, 2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S8 UP1-6 D(1, 3, 2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 UP1-6 D(1, 0, 2) // used to be fw motor + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 UP1-6 D(1, 3, 2) // used to be fw motor DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED D(2, 6, 0) diff --git a/src/main/target/SPEEDYBEEF7V2/target.c b/src/main/target/SPEEDYBEEF7V2/target.c index 60b8641073..b44fd0703d 100644 --- a/src/main/target/SPEEDYBEEF7V2/target.c +++ b/src/main/target/SPEEDYBEEF7V2/target.c @@ -29,14 +29,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S1 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S2 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 // used to be fw motor DEF_TIM(TIM8, CH2N, PB0, TIM_USE_LED, 0, 0), // LED DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), // Camera Control }; -const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); \ No newline at end of file +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SPEEDYBEEF7V3/target.c b/src/main/target/SPEEDYBEEF7V3/target.c index ad2eaf1353..b716b7f5c7 100644 --- a/src/main/target/SPEEDYBEEF7V3/target.c +++ b/src/main/target/SPEEDYBEEF7V3/target.c @@ -33,17 +33,17 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU600 timerHardware_t timerHardware[] = { - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 Clash with S2, DSHOT does not work - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 Clash with S2, DSHOT does not work + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), // Camera Control }; -const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); \ No newline at end of file +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SPRACINGF4EVO/target.c b/src/main/target/SPRACINGF4EVO/target.c index a52df8997d..da49369295 100755 --- a/src/main/target/SPRACINGF4EVO/target.c +++ b/src/main/target/SPRACINGF4EVO/target.c @@ -26,21 +26,21 @@ timerHardware_t timerHardware[] = DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM | TIM_USE_PWM, 0, 0), // PPM / PWM1 / UART2 RX DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // PPM / PWM2 / UART2 TX - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // ESC 1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // ESC 2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // ESC 3 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // ESC 4 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // ESC 1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // ESC 2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 3 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // ESC 4 #if defined(SPRACINGF4EVO_REV) && (SPRACINGF4EVO_REV >= 2) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // ESC 5 / Conflicts with USART5_RX / SPI3_RX - SPI3_RX can be mapped to DMA1_ST3_CH0 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // ESC 6 / Conflicts with USART3_RX + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 5 / Conflicts with USART5_RX / SPI3_RX - SPI3_RX can be mapped to DMA1_ST3_CH0 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 6 / Conflicts with USART3_RX #else - DEF_TIM(TIM10, CH1, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // ESC 5 - DEF_TIM(TIM11, CH1, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // ESC 6 + DEF_TIM(TIM10, CH1, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 5 + DEF_TIM(TIM11, CH1, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 6 #endif - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // ESC 7 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // ESC 8 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 7 // used to be fw motor + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 8 // used to be fw motor DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), // LED Strip }; diff --git a/src/main/target/SPRACINGF7DUAL/target.c b/src/main/target/SPRACINGF7DUAL/target.c index 533cc17c58..f47d1a0835 100644 --- a/src/main/target/SPRACINGF7DUAL/target.c +++ b/src/main/target/SPRACINGF7DUAL/target.c @@ -39,34 +39,34 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // PPM / PWM2 / UART2 TX #if (SPRACINGF7DUAL_REV <= 1) - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR, 0, 0), // ESC 1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), // ESC 1 #else - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0), // ESC 1 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // ESC 1 #endif - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR, 0, 0), // ESC 2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0), // ESC 3 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), // ESC 2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // ESC 3 #if (SPRACINGF7DUAL_REV <= 1) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0), // ESC 4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // ESC 4 #else - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR, 0, 0), // ESC 4 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), // ESC 4 #endif - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR, 0, 0), // ESC 5 / Conflicts with USART5_RX / SPI3_RX - SPI3_RX can be mapped to DMA1_ST3_CH0 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0, 0), // ESC 6 / Conflicts with USART3_RX - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0, 0), // ESC 7 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 0, 0), // ESC 8 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // ESC 5 / Conflicts with USART5_RX / SPI3_RX - SPI3_RX can be mapped to DMA1_ST3_CH0 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // ESC 6 / Conflicts with USART3_RX + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // ESC 7 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // ESC 8 DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), // LED Strip // Additional 2 PWM channels available on UART3 RX/TX pins // However, when using led strip the timer cannot be used, but no code appears to prevent that right now - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR, 0, 0), // Shared with UART3 TX PIN and SPI3 TX (OSD) - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR, 0, 0), // Shared with UART3 RX PIN + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0), // Shared with UART3 TX PIN and SPI3 TX (OSD) + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR, 0, 0), // Shared with UART3 RX PIN //DEF_TIM(TIM1, CH1, PA8, USE_TRANSPONDER, 0, 0), // Transponder // Additional 2 PWM channels available on UART1 RX/TX pins // However, when using transponder the timer cannot be used, but no code appears to prevent that right now - DEF_TIM(TIM1, CH2, PA9, TIM_USE_FW_SERVO | TIM_USE_PWM, 0, 1), // PWM 3 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_FW_SERVO | TIM_USE_PWM, 0, 1), // PWM 4 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_SERVO | TIM_USE_PWM, 0, 1), // PWM 3 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_SERVO | TIM_USE_PWM, 0, 1), // PWM 4 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/TMOTORF7/target.c b/src/main/target/TMOTORF7/target.c index 966bc54d3a..d50b3b9981 100644 --- a/src/main/target/TMOTORF7/target.c +++ b/src/main/target/TMOTORF7/target.c @@ -29,13 +29,13 @@ // BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), DEF_TIM(TIM2, CH1, PA15, TIM_USE_PPM, 0, 0), DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), diff --git a/src/main/target/TMOTORF7V2/target.c b/src/main/target/TMOTORF7V2/target.c index 0a995a8ac2..d010b2c4b6 100644 --- a/src/main/target/TMOTORF7V2/target.c +++ b/src/main/target/TMOTORF7V2/target.c @@ -26,17 +26,17 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM - 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, 0), // S2 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED - DEF_TIM(TIM2, CH2, PB3, TIM_USE_PWM | TIM_USE_FW_SERVO, 0, 0), // "C.C" + DEF_TIM(TIM2, CH2, PB3, TIM_USE_PWM | TIM_USE_SERVO, 0, 0), // "C.C" }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/YUPIF4/target.c b/src/main/target/YUPIF4/target.c index d98374c7f1..a115a3cf44 100644 --- a/src/main/target/YUPIF4/target.c +++ b/src/main/target/YUPIF4/target.c @@ -24,23 +24,23 @@ #include "drivers/bus.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_PPM, 0, 0 ), // PPM IN + DEF_TIM(TIM8, CH3, PC8, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1_OUT - DMA1_ST2 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2_OUT - DMA1_ST4 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3_OUT - DMA1_ST1 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S4_OUT - DMA1_ST6 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S5_OUT - DMA1_ST7 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT - DMA1_ST2 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT - DMA1_ST4 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT - DMA1_ST1 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4_OUT - DMA1_ST6 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_OUT - DMA1_ST7 #if defined (YUPIF4R2) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO | TIM_USE_LED, 0, 0 ), - DEF_TIM(TIM12, CH1, PB14, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM OPT + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0 ), + DEF_TIM(TIM12, CH1, PB14, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM OPT #elif (YUPIF4MINI) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), - DEF_TIM(TIM3, CH4, PC9, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM3, CH4, PC9, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM #else - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO | TIM_USE_LED, 0, 0 ), - DEF_TIM(TIM3, CH4, PC9, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0 ), + DEF_TIM(TIM3, CH4, PC9, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM #endif }; diff --git a/src/main/target/YUPIF7/target.c b/src/main/target/YUPIF7/target.c index 3794e7032c..cddfeabda5 100644 --- a/src/main/target/YUPIF7/target.c +++ b/src/main/target/YUPIF7/target.c @@ -24,15 +24,15 @@ #include "drivers/bus.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_PPM, 0, 1 ), // PPM IN - DEF_TIM(TIM2, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1_OUT - DMA1_ST2 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S2_OUT - DMA1_ST4 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S3_OUT - DMA1_ST1 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S4_OUT - DMA1_ST6 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S5_OUT - DMA1_ST7 - LED Control - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO | TIM_USE_LED, 0, 0 ), // S6_OUT - DEF_TIM(TIM4, CH2, PB7, TIM_USE_ANY, 0, 0 ), // ANY - DEF_TIM(TIM12, CH1, PB14, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM + DEF_TIM(TIM8, CH3, PC8, TIM_USE_PPM, 0, 1 ), // PPM IN + DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT - DMA1_ST2 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT - DMA1_ST4 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT - DMA1_ST1 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4_OUT - DMA1_ST6 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_OUT - DMA1_ST7 - LED Control + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0 ), // S6_OUT + DEF_TIM(TIM4, CH2, PB7, TIM_USE_ANY, 0, 0 ), // ANY + DEF_TIM(TIM12, CH1, PB14, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/ZEEZF7/target.c b/src/main/target/ZEEZF7/target.c index 9901d7f83b..2c57917515 100755 --- a/src/main/target/ZEEZF7/target.c +++ b/src/main/target/ZEEZF7/target.c @@ -27,32 +27,32 @@ timerHardware_t timerHardware[] = { #ifdef ZEEZF7V3 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 1), // S5 - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // S6 - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // S7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // S8 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S5 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 #endif #ifdef ZEEZF7V2 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 #endif #ifdef ZEEZF7 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR, 0, 0), // S1 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0, 0), // S2 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR, 0, 0), // S3 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR, 0, 0), // S4 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 #endif DEF_TIM(TIM1, CH2N, PB0, TIM_USE_LED , 0, 0), // LED STRIP From c703129fa8f87bd59dc3a22fe7eecf78574136ef Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 12 Sep 2023 23:57:02 +0200 Subject: [PATCH 065/122] remove targets added by accident. --- src/main/target/BETAFPVF405/config.c | 33 ----------------- src/main/target/BETAFPVF405/target.c | 43 ---------------------- src/main/target/CRAZYBEEF4SX1280/config.c | 33 ----------------- src/main/target/CRAZYBEEF4SX1280/target.c | 44 ----------------------- 4 files changed, 153 deletions(-) delete mode 100644 src/main/target/BETAFPVF405/config.c delete mode 100644 src/main/target/BETAFPVF405/target.c delete mode 100644 src/main/target/CRAZYBEEF4SX1280/config.c delete mode 100644 src/main/target/CRAZYBEEF4SX1280/target.c diff --git a/src/main/target/BETAFPVF405/config.c b/src/main/target/BETAFPVF405/config.c deleted file mode 100644 index cd5aa30d71..0000000000 --- a/src/main/target/BETAFPVF405/config.c +++ /dev/null @@ -1,33 +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 . - * - * This target has been autgenerated by bf2inav.py - */ - -#include - -#include "platform.h" - -#include "fc/fc_msp_box.h" -#include "fc/config.h" - -#include "io/piniobox.h" - -void targetConfiguration(void) -{ - -} - diff --git a/src/main/target/BETAFPVF405/target.c b/src/main/target/BETAFPVF405/target.c deleted file mode 100644 index 25ace257ac..0000000000 --- a/src/main/target/BETAFPVF405/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 . - * - * This target has been autgenerated by bf2inav.py - */ - -#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" - -//BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); -//BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); - -timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), - -}; - -const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/CRAZYBEEF4SX1280/config.c b/src/main/target/CRAZYBEEF4SX1280/config.c deleted file mode 100644 index cd5aa30d71..0000000000 --- a/src/main/target/CRAZYBEEF4SX1280/config.c +++ /dev/null @@ -1,33 +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 . - * - * This target has been autgenerated by bf2inav.py - */ - -#include - -#include "platform.h" - -#include "fc/fc_msp_box.h" -#include "fc/config.h" - -#include "io/piniobox.h" - -void targetConfiguration(void) -{ - -} - diff --git a/src/main/target/CRAZYBEEF4SX1280/target.c b/src/main/target/CRAZYBEEF4SX1280/target.c deleted file mode 100644 index 6806179433..0000000000 --- a/src/main/target/CRAZYBEEF4SX1280/target.c +++ /dev/null @@ -1,44 +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 . - * - * This target has been autgenerated by bf2inav.py - */ - -#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" - -//BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); -//BUSDEV_REGISTER_SPI_TAG(busdev_icm20689, DEVHW_ICM20689, ICM20689_SPI_BUS, ICM20689_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM20689_ALIGN); -//BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); - -timerHardware_t timerHardware[] = { - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, 0, 0), - -}; - -const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); From 0ab67ab9ea0c4f9ac44a3a99bfb2679ca5ba4be0 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 17 Sep 2023 11:10:53 -0500 Subject: [PATCH 066/122] docs/ipf: Fix typos and clarify wording --- docs/Programming Framework.md | 32 +++++++++++++++--- docs/assets/images/ipf_set_get_rc_channel.png | Bin 0 -> 12113 bytes 2 files changed, 27 insertions(+), 5 deletions(-) create mode 100644 docs/assets/images/ipf_set_get_rc_channel.png diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index a5b9a3fdbc..42a4f2a83f 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -1,17 +1,28 @@ # INAV Programming Framework -INAV Programming Framework (abbr. IPF) is a mechanism that allows to evaluate cenrtain flight parameters (RC channels, switches, altitude, distance, timers, other logic conditions) and use the value of evaluated expression in different places of INAV. Currently, the result of LCs can be used in: +INAV Programming Framework (IPF) is a mechanism that allows you to to create +custom functionality in INAV. You can choose for certain actions to be done, +based on custom conditions you select. + +Logic conditions can be based on things such as RC channel values, switches, altitude, +distance, timers, etc. The conditions you create can also make use of other conditions +you've entered previously. +The results can be used in: * [Servo mixer](Mixer.md) to activate/deactivate certain servo mix rulers * To activate/deactivate system overrides -INAV Programming Framework coinsists of: +INAV Programming Framework consists of: -* Logic Conditions - each Logic Condition can be understood as a single command, a single line of code -* Global Variables - variables that can store values from and for LogiC Conditions and servo mixer +* Logic Conditions - each Logic Condition can be understood as a single command, a single line of code. Each logic condition consists of: + * an operator (action), such as "plus" or "set vtx power" + * one or two operands (nouns), which the action acts upon. Operands are often numbers, such as a channel value or the distance to home. + * "activator" condition - optional. This condition is only active when another condition is true +* Global Variables - variables that can store values from and for Logic Conditions and servo mixer * Programming PID - general purpose, user configurable PID controllers -IPF can be edited using INAV Configurator user interface, or via CLI +IPF can be edited using INAV Configurator user interface, or via CLI. To use COnfigurator, click the tab labeled +"Programming". The various options shown in Configurator are described below. ## Logic Conditions @@ -310,3 +321,14 @@ Steps: 2. Scale range [0:1000] to [0:3] 3. Increase range by `1` to have the range of [1:4] 4. Assign LC#2 to VTX power function + +## Common issues / questions about IPF + +One common mistake involves setting RC channel values. To override (set) the +value of a specific RC channel, choose "Override RC value", then for operand A +choose *value* and enter the channel number. Choosing "get RC value" is a common mistake, +which does something other than what you probably want. + +![screenshot of override an RC channel with a value](./assets/images/ipf_set_get_rc_channel.png) + + diff --git a/docs/assets/images/ipf_set_get_rc_channel.png b/docs/assets/images/ipf_set_get_rc_channel.png new file mode 100644 index 0000000000000000000000000000000000000000..01b6bf64ae79cfa957be71288b8af1f4326e89ab GIT binary patch literal 12113 zcmb7~by!v3_U^ZegoGg70!nvEOLuoGNOzZjNP~cMNF%W~(%m54-Q6u9-FI@n=bZb; z{oVUKS09nJ_S$=|HRl{-yzghs5Jhe&L|)rD*qWGI8ABk{QC?B}l5OvaIt)}gUeb!~zh3>G>0I`jmb}IcJ5(`q z{6!&8qVDx`If7^`T#44o<>fBJiPjD+4FnA#^jnC%v%RuY)T@UCEbVqTyZK1h3li5u zNT$9CY=#9sKiT-_Dho@D9(KL{h@Uqci(hcNtQTXFY>VUPg|@D#dg`IS0vB7`Dh`y- zK9e8QkD-RS`MFt)jdCAi25BlO2M>ivpw_)UrkFBLSbB#`gyUw?Et$6&BGPV{8NR`3 zA|~=S?F||oO#Di?(>UM+$Fx${c);^7F1*8RFYA;!8byQ{JsA=PD~vi51zAa(Ls|Bx znc(IMsl%<5L(e*`ZAByBo*kN=%4vOA#@W_$ z^tAl5cKSq8MI(f8c^Ms#M)AC^tG<5D^X5XfyqUD?%Au!?BeELI3%sF>gec_U@oz?B zUJN*cWGAWR2!UWvfq%tM)_Ntkz)1urDLFBOEhG$dxTh7L#-+e1d?ztYClOm~YhxQH zh=_ynMCUe4q4{rusOhsL z(P-X|3YVs+pczzi{YNGDE{ZgAZhS!xTmenaR(!FBiF_8tA~O@4^SuK>ce@H z_sfvnUx~ttV|*j|Lz$Gx?_X2P85)u+L$Q)%DGAoRc0a;khE`UxFk7P@X z7ihdxQ^RQYO8?&T>658xOk$#Du6T5GG&pqH9)9BN>^$<}5b^5jYQDza@8{2-wDvG| z4vt#ZyB8WZ`mI#IgS!59^&hgQ`xZS5BPwbj8a@13zBkP{FFbDt-S~Zx-IN#L9#-wp z+{eX~C$s?XR_jI+fxnIaA;YvKpClVm=fMI^?WA+yxcaDTyag+JR$N%Kcux_@h~koq zP!J)JD?{q@&*&W!Ge(xoQ9eCA^)JO}7=u@#jcXd-d3EjG%%QA*+6boRoyuW} z${A&#IjRL-?2p{6tgrQcynVU}$C~$vNMx99(I@NS^9Gr}zK_pAKNDYbBsemKA>6-I z+(G>J_+uf$eT8jOBt+s7a>OUzun^rXDe3ao(dG#DxC@_#n4zWczZcei3eh8QX)R18 zls`xrR-AI%;XWr>lzAAq!+s#Ga7MRcxW2fRKS^3=lcH%36n$2!D}Q=yM!rh^F4;Sl zGthc_p^D2Z$(|70&CkzbtPJ>K~qcFusV>{ox#LSzffVwW2}WoK{8h zgMuq2CZX-Lb?j;*#=y*E^czOKIJ5nRXxgTrTHU>4%+Rq~P;oDR^JxUu&{dk1)bv*a zSHa(%fh>bwLSe^nC+rZLNdP_?SZv5eVEn8`6X%^Y@ zuNUY#jye$Ux>L;O0nbC%!YFXc_3Bbln+T5_j*A)L}QEHi>(3;8)TLmmf(W zKVl<(?@nJHw)@1yg!yC*eiP|+yyyKL(hc|VHXIwmz)!D&^TZ!XYqKM9+%}FiDV|9P zk^UlT=7VYcVa?5gRaI3LRx{B8Uf1XZ1lN;+n!38W)6G6UN#+F_#U`iQBXLD1w^t|Z z*0ZWR#bRMNHFb4m?k6TW4Yjqka0m!v*%B{*{rY8RXZK++g?ql)=OJM0@}PR@=={8M zc9wvbm$&m9zKF7NG`UxAEDgP8NrrZa>F7@>xaZFsxtK&rNl9G}7v<#TBOHcgY2R{k z#%GEIy(mzU(<=Lf1cgF#BJy%`%bfQnr(icR3IakhGRS&*dQQ&H_6`oOP#LKMGMmUC z7oRTNqIK9KX}S56mcv>TEfdF}a(T+eDF-P}678MflP*{bPCXdcbu+@OadV6;EG$l| z=?FL*uBRrHjVstIdJ7N#wAG6ZCM5qQYLhSI#W=D5hWEFC9s!N$!}f3{yTy2LI3ZV= z&x7~v-JMps3F=yBxF;PKyXzla?P{Al@!g2X$Sp8NDS|#}H8t$yOWUy}7wK%+n~=uP`4Aj1;&IW-}cO4!R|n)vR-(5fBiNCXkYoGu|DC!ok5c z#EY-4t#N<8WR4`^Uj<2-`~?j)rrcTcMP~2N5W=$dUk*qEePeG5RgR8GLMCb`kHwU7 zk=o9g)5u{KyTYz}7t@}Sdd{xpVg@&4$@(s0e9q@#FgcMUQ)CbAu!F6LHHcPFFdd8; zi~Xvo$w0DLfqEe`2S>-)Sj^Fp9U2K=cazsmFnH{R1wH8gdQVIeuPfu1-&ZA-l^qik zadJO6X~aaIK7DHE?L5ZwzhV1avB~P$+TIhyS%wE`tYG802vp8h>T3Z&z}mWbu>o?7gQwh zg&RSn-tQF@BHP>Bm7VqLoI+3uIZIp)v>O^4nAzCce*ga3((=B}^{~iEP8k{t2Fu9W zI=rBO?)dol{fMydTbcOba#Mw0g@rrgP)zWg%CU|P4u)sD6Q_qu>5O`H%WG?Gg*w%c z={je+rluw^{L3pVLQ_S0TGckGS^HsWT{niz>10uoc<=09>r`1O5ykX;y1m{jMj_<< zHa@Nj=D2$ts>1Dc&0gf*u)*2hL4Q}a*zwN5t=kLZ*XdICMg(D}St zpSkGOLS)u5RtPg2J6&~(yWUAw!v!ns)PrD$i}r>;k5;K+j#h;0#zxkfEpGTnre=Tn z^4|C2TDJpo)~lOxNPaI73@o|tNl86lo;;Jz;jo%UH#IdSr=ZwbsOO@gq0w#9t@y=8 zMHSTDE!oi6=zhA5;qC41v_Bn%NhM!m*zqEsUQ5`?sUoW=Kc9NCP)EYdj2gu3Cu8GG zD6|K}(DBicBF|wWi&05M#X1;~{&d0g{QP`cHtm3b0RNz%nAFt5;9xNciM7qmz=((l z2PP4Xgpv|wkf)?4Fo}u7LHJBgPUei_FldW5d*8*9e`yPPxpjHG29g`AL^L!? zYU<#*YFmwM_uDzt%@Y(7zC@Kg`KajVr!6aOK|Mo5T>}HCMn*=Dg8>!^2s&~)I%E+M z5mr{(3-b8}cQz6dl6TzPU=i54x^~UZCa3bcz9=|-k(iW(frFF#Gb(yEI3&b6V?8@SK* z9vU|qL3woE9arMHm?+SYl9he)`ZWX<6;->^qNBz4nL(c!HxG}Yk&$0`II6n3`t9kM z0;ni-oR9|BLlSZExHe9E~7^O1}g{02Dn7> z&8s)BLZTfX>lO%iMK!gKo*pT4>QZoRO&t!yT4iNrj(9l18!D>*Oif~9;_~Y1@8ahB z7cIGRKk)e6m|um!foJi4xO3%k{qwE9o>wM;apQQct9#>b!lVwXg0?mRm}w=mfzHlA zQ1t1tLcdN;NvfH*_4bA~dR~l{8Ow~1k0-L3qTw>?D!!Y4+R7$xz?8gxC-p-?QAz2^ zdkK}ToWaqUJcZaS?Fsx47#xBQf_Ks}vc!XDEK9tRrjHT7-q$)iijAd1RkfMw+i%~# zbq@_uv9XoQB9JjK$l1@&&HXSR%f&!PZ>h4L!y54eE0UF!wWPFEDHJa0#}7Jg6Ju`6 zp_r&Bp@C$MxGXVL0(M1|`kb5``_*V0^wmol5YcF{>dK(ONE+VUS2YLT{{K7B$bzy zMKSQcdJ6$@LdD0I!k|+%oFViK@|H>;N|g2ZVmNF7ZW}`I}1>Q zk%vRnvchAi6dVp_IY5d1wN7MdW)=*OOI;J=95f+S@Wjr1?eB%{!Z6;K*!m6Lo~y#c$H%}? zza|vw>FH_j=okUXJi|K(3csiNvFr9QSq?Y<5Z_I7taE>R zyZ`>a6$#&^Cv@{*u384aFna5HEm9Cqu;~`T#=;^LWZt5pqF-9&fy>Juyzj3}#p=q- z*?_)S?!nwhwIdbumQ5G%irrj{rFXo$cJ4qolWMwLMeZnB47=R?VcXr`{{~1SubcDI z53OHmwbZntwv_a;(QSK^o^FrkAQKP}^#9;`39{_B@G$+*nVA_g3k$;!AHL`^nr;oI zKHhPUy@xoEEi<6@D5UYN_&nUCD}So+dAPTlDGTuThg)~xHXTf9ZEN!bOB=aQRg3^i zYu){cwKIaaAXt(?zabG+Flu%(bchwV=INh9qw%2g$ph>z20|P!_^qjSgPs98;vA35 zOR^uzVVi}V9G2QE)EHO?DfgT+*!5v&b5nG@c(kz4xX>M~ormi!U1PL3QSy)Xw^z4E zZ7=C{YrfNI6xr=fG5|R^Q1Y?uvEUC3$c^wGP8E|nZVh&{w)*lohn{zDPZkp5hI$k^D}fhhRDLB+-6 zv`UQ51?esT%(lF|{QhiZ7|=WMwRj)FCjy%{TWvek;C>QYrCU;6ZMyP1pg)y20mLS= z`RE&y{=`Rd5MT_JzAEC|;oTR9h}* zAhhBCe2n$=MnT&4Eau|$5W8=P_e(SBP3qFnZBYdob<07$nC~}}+=2TuZN-A#USJRq zU%oV*fT=wSlav&q{(%8}4ht-xX{4jx0NJ5lqzlFJWnpH1&CVVRGHkMOUwmd!k$ka! zVMz(S0Uje)2EA_oN(mCm~2vzJ#$M1%?O308Aepkkns zlaqt;Y62|8CleDxGc(DHKMVMR-hA5H#)m7%6B-5>uU`EwGwzd=l6v$Az;--lxPX8T znPQ{W_7I@8hBHMFEXMPFfnWm#g_4B@!_)Id!#hpwj&D)SPmARK{vPNspk;0_sCYrn;wVlh6rCsj^`axV0H#O6#h zzNTUdI_2Hje^=+Xp%FhO){I;rs2?ttJ$iUj`mEF8WKizb``GAeZKJ|`5`Nuox0gm> z;fh9t5M?9AJ6-j1)+!lSZsd}6MMj&;d;npS^!ty5u+mHxnrf9x`-ez~sHs@_!7}G; zm6?pl*r=yyA#Za8NuKAC?-hcXxkXf3)Zie6kHo0RMd0ejwwPD;_4qJU2qeJEp|l6) z!#sDCZJsX#vmBRncT7#Q=h%9vb*nq;SH)8S(ovWU#df|x*>v2Z`!4Ifefu^?cT3Am zS20b%(9lry=Mix(EX_dP2Cb5Eik7Rf%EHSrZ)3Pe zL^Lh*4dYuhR5er{u5DS@xj#;od)hllJElb`WPG$KZ9PFysD2CygU1K0rLyfC@1c>2 z47#Wja_omCPdBDJ@_T)~rg>*>h5?<`vca5v&bxPkXob9rikdAeV?i^XhD=n-3a?}O zN(xQGWGr!0=6JI;L=;5x{{dyU;Z^aRwS5IPgwGh{80LxR?OpAPqpz)WrVZzQS5>TS z{{3rtU(y$}?n0A#XnavXsnk~6$ToP8x}>8QYp)AmDW##1ogG(yb09hr}ODm8^HJls1Y!ws%8Ww783DC;VQOEpOn3#{c z7Qmw{Tq-wH)ZC(?KgbtEGP1Iwv~e%;cD?rg;cmJ`oc|Cn5EpR&5U=lS&TE~hs%mPb z6%|;h|MEfVk&n1?|Kfpw6aL>} zq3`>5s{dfe|A8d>E-#1{MuZ@_+AJ}0i4bFAe!<wws&;po!+c> zqLSCSFgVYzhA|zbFlTBnB&g-dkB5JIV{@R*T5aW?!}F8N_U~)fXoUCYU8F{u#fvv% zWCd2f2s1O=gm{P|6mG5*=Xtu7!iD=Yh1OOpAR zWUWV~>SEp59veGjM3s;bWPE=zyvg%?ncYe=PPea#)Mve&)JIjSmf-rDy{ath?mJoW zXMP|~m4~Kq`+8zVidDAmJbW6YnWXRtTI+4t4cPrD*cngBVtQaXX!^O}`GmyOu(RP& zOYH4iorYg`9CzC`kugz8&=l9@Qc{K!t}P#+zULJbOxDyfQhYwx8MALy6d0i9&h5-l zsL@2pFCr4ypRSO8yr!h0fs6LfB!5lFh89N_#b82aZY~_1=Bmn4V^?cMlRGd9r-UeD z?6*M4MnH&3PrU5xL!u2#Hhb#3d=LW!I?z0TZfCK;eRWOA<@e0mU1*|rX{N_|aD36M#wW9r5F1KT6nbb4D?CtK#T70^+GFdPOuV8Vdnkal-;bVNc! z%aw>E(bUpfSzc~Q;dZP6Z$utCp0jOUIXDQftmJTUaRFo~@aNArV%M=WDw-u9geqSR z{gjG9q)o#;60ir-_EGl%{~-%LbO*4+v0S+|m*;{-DQRi)LuvedcXHoI__d`had2<| z`iW;T>I5Q2i)JC#^?qk8Z>-kQ6u4Y)n+SW8g(|v3z&;=U{R>mKZZaREYzPaIg*_wW zw4y$f2i6uNt;17xD^ftXSmI@d+4iBijZHwG$x^+_9osA`#ao5eY;gV`Pk&DK~XIS{90DGLQ$I z5TIJHu&`paY(IQ>EhHp#d39CldZ-Wd1~V(G;c|;FFy$%@P}-L0w=#gGFgWvZaKr%t zp+4gdc&A@N0xl5W^m=u%+uLUGjC#Gmpy08ap#zQWZcYq-k})wI2Dk^J66Oxif-gow zMFrJ00Q}Y*Z*zaW$K-MG=P`d-PX1b1ZuOJ>!5RMjJNnaS&jJK!yMZ*lT8~k9=dd2U zYO5Gh%RZr0|CK8&w~F)6Sl+WEkdw0Ksx@l%o8stdAG%0SHLJdz|M`>1ZX?U@=*Z*l zv07n;zeC97u)URzedTO1`7;7aGkbjv8PC`I!IPUi&cY!!G+Z)&qFR;0&WJ|r*{`b@7U@CHkoq(0K^&`{(YhD^7>dO}hUW2bh{~ ze*^Hv?fQoZ0-PFfmLC9z%gdwkxxdOAb-y@VQUF5J3^)N&uTuXO>GBNPY4QzT`ve)BXMZM~FH&7;)Hi6H%mBPtKrk19FX5u56NU5E}6|NE`+} zcN_}o0-%}q9U%3m%iG)Cm6lVze38k?$-OxdnpLK7DedRM1>fBZ;B zr~a#DW+utyV3x(CA5Y9v9kh*r(OX~tbbEVyxnDl?&inQqPcbvsrnQB}(I!iI#m|K- zF)@N9zN88V@1?grvN9Cz0|es)99ix+=Q*Q=L`0$9t_D5>e)XhiMCU3Z(`bz=1{r;AN`C|CS@wWcN}tQjbW6(8FI-|_Nd z;^RvlE;dR@Nv-_d=!2}UucPDRhg4T{0dV(wXebg`JO=<))PHHVg7gp^5urW~%wI>H z^By89s+gQy_^)5|pk>MJcJvx}2COxRjCo5>k3vURpnN7OAz}3KqiPfn`88x{b7U;}%dK=D z`J3~D$9@G85|WvvCEboWu*iUYM1rKUy0ZhtQuDk#BGb~+y1l2 z<6eLX_4=>X5_#Tt%+yt4QDHby57B0)2dfcH(0b3Lg4GJk@eKJ=cpE`nEVr?3r~Q0( z1?i7t7E_F6OD{=O>*Uu~T^BPa3Tjnu<)1K{j|ZDr&ozw=H33lG-!D5pF#)VHHCv;8 zqsOODpE3#x!hZZ9@A{I0B3rt0ZlT^43UXG!Uk^7okVt~7 zsyOei&nVu$eO{|ul-Or%VbKdNiIRK+Krm^YSDPW-F7}&0npotY8ahXlf=3TY{(fe7O>&si{d#UK=+eCuN$Ok&z)xz`@35 z)St)#mdM(lKk@*Ef*5}C`pp}E1%WGn5LiEzX#xWS!EjUe*45Mis15(6yxbAG(ggxP zGb>BDP`lD>p{|mgpPc-wg5Vt%SlA$tlla_O0Wwu{YJ!Cc>`oOAfn=G){P8KktQnve z2WF)N^iwPffD#uGQNg@`s)UhGc%Iu;Oi#v1oTu_awv&?Me@HYdQRFn(h7oi$uPH}} z9J`SJ)kq{<=xu#+V!zfsT@f;jMm&9gck#xc@mkthjSFTKmmU>`0X9Ma_7Q)Tr641t zLUeI{ZZcb84!}l<^&F?zO8~#ZzkNdiU?`ScXvpJkh_D=&xUaiA12o;FN3!5i38(`X zMn^~A*{}L57nfyZyk8-T>j36rcw%A$RHyzlenJrDIr)iEQBlz!-S6+^WM#igzR8(A znE5WLB@YAngxo?Ap#Nr{3Ic-e4Tn#x_|Km|2hB?iLc*}j%uI3%r7}~4vR^QmMXfmm zc+*;4eK5}pDX{3qTNtOLbLd65l!8K@R175qg_tK6EcYkOMx7{W0$#9Sl=Gc22_<#L zgp<>qu>?kWw?Lq*jJhJ;a&aYql5KyyDhAqL`EKfQBLi$;bHwoID6K{|XeP0n4MQ?i zyCgvmg@xU9<@fUrICmKtnNO@qqldp-><=q{#!LVGd|lpiRBf|B&dmHB@F;EQLT|Fc zsluMfUagl0pjX^Z+lrMFz_c08{zN+P^W$du_>_uD?st|RuWZ;7{!okopZlGdCnrCl zIGvkR#a^l%4?FwO^(ykKdY8A}2iiqG7sOM|H)xooq;+1`G?X2KYo5fJ7IRe$AcOhG zm1=1^IIsdidb&S@`DHMb_nBCmD=-RbC_l^X;*G^8hz zR4^A5Y%3ZgIv;?Aiwv6eO_*-On3@z(_8Nn2o2~*u<^h?1rrMSi8HYYUS}hLSon(ST z`HT`p87OPBN2$$erAWla%$xxV66k>=4y-1mm6oyqQ%A((BspT!6+sLb_dVG5kRhz| zc6)c1c2kT&x8|`3h=0S&96l-778etHPDPc+nq5MrkOoqD&NyFN84o-rrR;~tg2(3` z4Z6TQd|X|tYAk^GAFp;ud(4#@Aq)-?QL%~35Rl73fQi$8}(tkS=@T$3+GWeYt zE&1lLPe|&0=?fab4jaALpd;J?nn(DYR(POE2s&Ie1my#I#!rrap zs#F-)$M34Ds*g>BX>dQFEledKkS6$W8$%%x!ED@%g+?kM8$&6VZ_q42%&8X-S``)k=V!42m?Jx-F@7HC+;N6TM<%~NU3yBrNCDTfxR?gk4J+95@i_UwvOfZBy}rv}V|TEbV-$#eO1b2A&^#F# z9)1m~2529%g7HpCNl6410<<@Q$tWFXZe?q_-lYS*$PS>&9(x&&rj(8@4D57JGaLQe z9)kIpBSnJHz)jO(;tvAozhkqI~`O%S*vq#pBy*s~KUi z0G~W=@OTyC57zYB^74BZmny@J94M3qEbh;zBN8Cm%7nKHm9pW(aGAhv6#mewpyI3_ z;I5B=B0OGheFg-#or}vRI5GyB9eb8D6V%;r#Juqs6ynQ(Xn_9Jqqm(ZHpnX}IjWp> z0Ts5UzJ6_QFAQ{WL9}du^rT8a{tN9oU#$QK5C{rZ)>lASfK(*^;lqbG(cQ(LF3)XA zV>-ikYOL@fU48g>%rqn~8Y+zt6#9adH~2i-7giUh!qdaPN{@${9CXuO&3R5ZsI@}x zZbE4E6SKELd7)Kj6ZrKtuJHkj)){OiOfV?Xdk-KbNIpFWHPdOeg`;f9Uaw)@tX9ckVToSx{bIP$u~bAuBeU$@7iPf5_%Nm#s9V>l}@&@NAfXj);iUCF3=v3ME#|Y7R6sb{zvZhC0G%um-3O~ z8hMEg=W(Iw-#a zI9g?2gbcmG60}f3Z|f@KGJu+$ky?iIedSo|$t*S^+(eLcGYtUWZgvm%Iycj$?-eKD zcUtdmwgqwHaS3qwiX(S({X)$&UZdYSs(KhHs2CXma1OSjBKuLeU3j3wVB32;A1$ot z*%{rS0 Date: Tue, 19 Sep 2023 14:06:06 +0200 Subject: [PATCH 067/122] Drop support for NMEA GPS devices --- src/main/CMakeLists.txt | 1 - src/main/fc/settings.yaml | 4 +- src/main/io/gps.c | 11 +- src/main/io/gps.h | 3 +- src/main/io/gps_nmea.c | 340 --------------------------------- src/main/io/gps_private.h | 3 - src/main/target/common.h | 2 - src/main/telemetry/telemetry.h | 6 - src/test/unit/target.h | 1 - src/utils/rename-ifdefs.py | 1 - 10 files changed, 5 insertions(+), 367 deletions(-) delete mode 100755 src/main/io/gps_nmea.c diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index c6d445900a..fc918466ac 100755 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -504,7 +504,6 @@ main_sources(COMMON_SRC io/gps.h io/gps_ublox.c io/gps_ublox_utils.c - io/gps_nmea.c io/gps_msp.c io/gps_fake.c io/gps_private.h diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 2602868c4d..08698cf80b 100755 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -44,7 +44,7 @@ tables: values: ["VELNED", "TURNRATE","ADAPTIVE"] enum: imu_inertia_comp_method_e - name: gps_provider - values: ["NMEA", "UBLOX", "UBLOX7", "MSP", "FAKE"] + values: ["UBLOX", "UBLOX7", "MSP", "FAKE"] enum: gpsProvider_e - name: gps_sbas_mode values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "NONE"] @@ -2242,7 +2242,7 @@ groups: max: 10 default_value: 0.2 - name: inav_w_z_gps_v - description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero" + description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors." field: w_z_gps_v min: 0 max: 10 diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 4d7380e84d..0fae3a7f31 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -77,13 +77,6 @@ gpsSolutionData_t gpsSol; baudRate_e gpsToSerialBaudRate[GPS_BAUDRATE_COUNT] = { BAUD_115200, BAUD_57600, BAUD_38400, BAUD_19200, BAUD_9600, BAUD_230400, BAUD_460800, BAUD_921600 }; static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = { - /* NMEA GPS */ -#ifdef USE_GPS_PROTO_NMEA - { false, MODE_RX, gpsRestartNMEA, &gpsHandleNMEA }, -#else - { false, 0, NULL, NULL }, -#endif - /* UBLOX binary */ #ifdef USE_GPS_PROTO_UBLOX { false, MODE_RXTX, &gpsRestartUBLOX, &gpsHandleUBLOX }, @@ -113,7 +106,7 @@ static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = { }; -PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 4); +PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 5); PG_RESET_TEMPLATE(gpsConfig_t, gpsConfig, .provider = SETTING_GPS_PROVIDER_DEFAULT, @@ -264,7 +257,7 @@ void gpsPreInit(void) { // Make sure gpsProvider is known when gpsMagDetect is called gpsState.gpsConfig = gpsConfig(); - gpsState.baseTimeoutMs = (gpsState.gpsConfig->provider == GPS_NMEA) ? GPS_TIMEOUT*2 : GPS_TIMEOUT; + gpsState.baseTimeoutMs = GPS_TIMEOUT; } void gpsInit(void) diff --git a/src/main/io/gps.h b/src/main/io/gps.h index 99b6aafbdf..09cdbafb82 100755 --- a/src/main/io/gps.h +++ b/src/main/io/gps.h @@ -33,8 +33,7 @@ #define GPS_DEGREES_DIVIDER 10000000L typedef enum { - GPS_NMEA = 0, - GPS_UBLOX, + GPS_UBLOX = 0, GPS_UBLOX7PLUS, GPS_MSP, GPS_FAKE, diff --git a/src/main/io/gps_nmea.c b/src/main/io/gps_nmea.c deleted file mode 100755 index c5c3b420db..0000000000 --- a/src/main/io/gps_nmea.c +++ /dev/null @@ -1,340 +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 . - */ - -#include -#include -#include -#include -#include - -#include "platform.h" - -#if defined(USE_GPS) && (defined(USE_GPS_PROTO_NMEA)) - -#include "build/build_config.h" -#include "build/debug.h" - -#include "common/axis.h" -#include "common/gps_conversion.h" -#include "common/maths.h" -#include "common/utils.h" - -#include "drivers/serial.h" -#include "drivers/time.h" - -#include "fc/config.h" -#include "fc/runtime_config.h" - -#include "io/serial.h" -#include "io/gps.h" -#include "io/gps_private.h" - -#include "scheduler/protothreads.h" - -/* This is a light implementation of a GPS frame decoding - This should work with most of modern GPS devices configured to output 5 frames. - It assumes there are some NMEA GGA frames to decode on the serial bus - Now verifies checksum correctly before applying data - - Here we use only the following data : - - latitude - - longitude - - GPS fix is/is not ok - - GPS num sat (4 is enough to be +/- reliable) - // added by Mis - - GPS altitude (for OSD displaying) - - GPS speed (for OSD displaying) -*/ - -#define NO_FRAME 0 -#define FRAME_GGA 1 -#define FRAME_RMC 2 - -static uint32_t grab_fields(char *src, uint8_t mult) -{ // convert string to uint32 - uint32_t i; - uint32_t tmp = 0; - for (i = 0; src[i] != 0; i++) { - if (src[i] == '.') { - i++; - if (mult == 0) - break; - else - src[i + mult] = 0; - } - tmp *= 10; - if (src[i] >= '0' && src[i] <= '9') - tmp += src[i] - '0'; - if (i >= 15) - return 0; // out of bounds - } - return tmp; -} - -typedef struct gpsDataNmea_s { - bool fix; - int32_t latitude; - int32_t longitude; - uint8_t numSat; - int32_t altitude; - uint16_t speed; - uint16_t ground_course; - uint16_t hdop; - uint32_t time; - uint32_t date; -} gpsDataNmea_t; - -#define NMEA_BUFFER_SIZE 16 - -static bool gpsNewFrameNMEA(char c) -{ - static gpsDataNmea_t gps_Msg; - - uint8_t frameOK = 0; - static uint8_t param = 0, offset = 0, parity = 0; - static char string[NMEA_BUFFER_SIZE]; - static uint8_t checksum_param, gps_frame = NO_FRAME; - - switch (c) { - case '$': - param = 0; - offset = 0; - parity = 0; - break; - case ',': - case '*': - string[offset] = 0; - if (param == 0) { //frame identification - gps_frame = NO_FRAME; - if (strcmp(string, "GPGGA") == 0 || strcmp(string, "GNGGA") == 0) { - gps_frame = FRAME_GGA; - } - else if (strcmp(string, "GPRMC") == 0 || strcmp(string, "GNRMC") == 0) { - gps_frame = FRAME_RMC; - } - } - - switch (gps_frame) { - case FRAME_GGA: //************* GPGGA FRAME parsing - switch (param) { - // case 1: // Time information - // break; - case 2: - gps_Msg.latitude = GPS_coord_to_degrees(string); - break; - case 3: - if (string[0] == 'S') - gps_Msg.latitude *= -1; - break; - case 4: - gps_Msg.longitude = GPS_coord_to_degrees(string); - break; - case 5: - if (string[0] == 'W') - gps_Msg.longitude *= -1; - break; - case 6: - if (string[0] > '0') { - gps_Msg.fix = true; - } else { - gps_Msg.fix = false; - } - break; - case 7: - gps_Msg.numSat = grab_fields(string, 0); - break; - case 8: - gps_Msg.hdop = grab_fields(string, 1) * 10; // hdop - break; - case 9: - gps_Msg.altitude = grab_fields(string, 1) * 10; // altitude in cm - break; - } - break; - case FRAME_RMC: //************* GPRMC FRAME parsing - // $GNRMC,130059.00,V,,,,,,,110917,,,N*62 - switch (param) { - case 1: - gps_Msg.time = grab_fields(string, 2); - break; - case 7: - gps_Msg.speed = ((grab_fields(string, 1) * 5144L) / 1000L); // speed in cm/s added by Mis - break; - case 8: - gps_Msg.ground_course = (grab_fields(string, 1)); // ground course deg * 10 - break; - case 9: - gps_Msg.date = grab_fields(string, 0); - break; - } - break; - } - - param++; - offset = 0; - if (c == '*') - checksum_param = 1; - else - parity ^= c; - break; - case '\r': - case '\n': - if (checksum_param) { //parity checksum - uint8_t checksum = 16 * ((string[0] >= 'A') ? string[0] - 'A' + 10 : string[0] - '0') + ((string[1] >= 'A') ? string[1] - 'A' + 10 : string[1] - '0'); - if (checksum == parity) { - gpsStats.packetCount++; - switch (gps_frame) { - case FRAME_GGA: - frameOK = 1; - gpsSol.numSat = gps_Msg.numSat; - if (gps_Msg.fix) { - gpsSol.fixType = GPS_FIX_3D; // NMEA doesn't report fix type, assume 3D - - gpsSol.llh.lat = gps_Msg.latitude; - gpsSol.llh.lon = gps_Msg.longitude; - gpsSol.llh.alt = gps_Msg.altitude; - - // EPH/EPV are unreliable for NMEA as they are not real accuracy - gpsSol.hdop = gpsConstrainHDOP(gps_Msg.hdop); - gpsSol.eph = gpsConstrainEPE(gps_Msg.hdop * GPS_HDOP_TO_EPH_MULTIPLIER); - gpsSol.epv = gpsConstrainEPE(gps_Msg.hdop * GPS_HDOP_TO_EPH_MULTIPLIER); - gpsSol.flags.validEPE = false; - } - else { - gpsSol.fixType = GPS_NO_FIX; - } - - // NMEA does not report VELNED - gpsSol.flags.validVelNE = false; - gpsSol.flags.validVelD = false; - break; - case FRAME_RMC: - gpsSol.groundSpeed = gps_Msg.speed; - gpsSol.groundCourse = gps_Msg.ground_course; - - // This check will miss 00:00:00.00, but we shouldn't care - next report will be valid - if (gps_Msg.date != 0 && gps_Msg.time != 0) { - gpsSol.time.year = (gps_Msg.date % 100) + 2000; - gpsSol.time.month = (gps_Msg.date / 100) % 100; - gpsSol.time.day = (gps_Msg.date / 10000) % 100; - gpsSol.time.hours = (gps_Msg.time / 1000000) % 100; - gpsSol.time.minutes = (gps_Msg.time / 10000) % 100; - gpsSol.time.seconds = (gps_Msg.time / 100) % 100; - gpsSol.time.millis = (gps_Msg.time & 100) * 10; - gpsSol.flags.validTime = true; - } - else { - gpsSol.flags.validTime = false; - } - - break; - } // end switch - } - else { - gpsStats.errors++; - } - } - checksum_param = 0; - break; - default: - if (offset < (NMEA_BUFFER_SIZE-1)) { // leave 1 byte to trailing zero - string[offset++] = c; - - // only checksum if character is recorded and used (will cause checksum failure on dropped characters) - if (!checksum_param) - parity ^= c; - } - } - return frameOK; -} - -static ptSemaphore_t semNewDataReady; - -STATIC_PROTOTHREAD(gpsProtocolReceiverThread) -{ - ptBegin(gpsProtocolReceiverThread); - - while (1) { - // Wait until there are bytes to consume - ptWait(serialRxBytesWaiting(gpsState.gpsPort)); - - // Consume bytes until buffer empty of until we have full message received - while (serialRxBytesWaiting(gpsState.gpsPort)) { - uint8_t newChar = serialRead(gpsState.gpsPort); - if (gpsNewFrameNMEA(newChar)) { - gpsSol.flags.validVelNE = false; - gpsSol.flags.validVelD = false; - ptSemaphoreSignal(semNewDataReady); - break; - } - } - } - - ptEnd(0); -} - -STATIC_PROTOTHREAD(gpsProtocolStateThreadNMEA) -{ - ptBegin(gpsProtocolStateThreadNMEA); - - // Change baud rate - ptWait(isSerialTransmitBufferEmpty(gpsState.gpsPort)); - if (gpsState.gpsConfig->autoBaud != GPS_AUTOBAUD_OFF) { - // Cycle through available baud rates and hope that we will match GPS - serialSetBaudRate(gpsState.gpsPort, baudRates[gpsToSerialBaudRate[gpsState.autoBaudrateIndex]]); - gpsState.autoBaudrateIndex = (gpsState.autoBaudrateIndex + 1) % GPS_BAUDRATE_COUNT; - ptDelayMs(GPS_BAUD_CHANGE_DELAY); - } - else { - // Set baud rate - serialSetBaudRate(gpsState.gpsPort, baudRates[gpsToSerialBaudRate[gpsState.baudrateIndex]]); - } - - // No configuration is done for pure NMEA modules - - // GPS setup done, reset timeout - gpsSetProtocolTimeout(gpsState.baseTimeoutMs); - - // GPS is ready - execute the gpsProcessNewSolutionData() based on gpsProtocolReceiverThread semaphore - while (1) { - ptSemaphoreWait(semNewDataReady); - gpsProcessNewSolutionData(); - } - - ptEnd(0); -} - -void gpsHandleNMEA(void) -{ - // Run the protocol threads - gpsProtocolReceiverThread(); - gpsProtocolStateThreadNMEA(); - - // If thread stopped - signal communication loss and restart - if (ptIsStopped(ptGetHandle(gpsProtocolReceiverThread)) || ptIsStopped(ptGetHandle(gpsProtocolStateThreadNMEA))) { - gpsSetState(GPS_LOST_COMMUNICATION); - } -} - -void gpsRestartNMEA(void) -{ - ptSemaphoreInit(semNewDataReady); - ptRestart(ptGetHandle(gpsProtocolReceiverThread)); - ptRestart(ptGetHandle(gpsProtocolStateThreadNMEA)); -} - -#endif diff --git a/src/main/io/gps_private.h b/src/main/io/gps_private.h index 765318d1fc..9136fdcf83 100755 --- a/src/main/io/gps_private.h +++ b/src/main/io/gps_private.h @@ -76,9 +76,6 @@ void gpsSetProtocolTimeout(timeMs_t timeoutMs); extern void gpsRestartUBLOX(void); extern void gpsHandleUBLOX(void); -extern void gpsRestartNMEA(void); -extern void gpsHandleNMEA(void); - extern void gpsRestartMSP(void); extern void gpsHandleMSP(void); diff --git a/src/main/target/common.h b/src/main/target/common.h index 815b3ae41c..4207f62ce5 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -121,8 +121,6 @@ #define USE_I2C_IO_EXPANDER -#define USE_GPS_PROTO_NMEA - #define USE_TELEMETRY_SIM #define USE_TELEMETRY_MAVLINK #define USE_MSP_OVER_TELEMETRY diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h index e6146a0393..c7edad973b 100644 --- a/src/main/telemetry/telemetry.h +++ b/src/main/telemetry/telemetry.h @@ -30,12 +30,6 @@ #include "io/serial.h" - -typedef enum { - FRSKY_FORMAT_DMS = 0, - FRSKY_FORMAT_NMEA -} frskyGpsCoordFormat_e; - typedef enum { LTM_RATE_NORMAL, LTM_RATE_MEDIUM, diff --git a/src/test/unit/target.h b/src/test/unit/target.h index ac7617a63e..5272583764 100755 --- a/src/test/unit/target.h +++ b/src/test/unit/target.h @@ -21,7 +21,6 @@ #define USE_MAG #define USE_BARO #define USE_GPS -#define USE_GPS_PROTO_NMEA #define USE_GPS_PROTO_UBLOX #define USE_DASHBOARD #define USE_TELEMETRY diff --git a/src/utils/rename-ifdefs.py b/src/utils/rename-ifdefs.py index bf3f7826d2..a70a950243 100644 --- a/src/utils/rename-ifdefs.py +++ b/src/utils/rename-ifdefs.py @@ -27,7 +27,6 @@ RENAMES = [ 'TELEMETRY_LTM', 'TELEMETRY_FRSKY', 'CMS', - 'GPS_PROTO_NMEA', 'GPS_PROTO_UBLOX_NEO7PLUS', 'TELEMETRY_HOTT', 'TELEMETRY_IBUS', From 4448318f531c67cbd8f581d715d70c28ced77ac8 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 19 Sep 2023 14:06:52 +0200 Subject: [PATCH 068/122] Docs update --- docs/Settings.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Settings.md b/docs/Settings.md index 8ffe22f5de..2787cea251 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1864,7 +1864,7 @@ Weight of GPS altitude measurements in estimated altitude. Setting is used only ### inav_w_z_gps_v -Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero +Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. | Default | Min | Max | | --- | --- | --- | From 49e69f0aaaa022f3c6772c2dbc92dfc33f7d95cf Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 20 Sep 2023 01:12:48 +0900 Subject: [PATCH 069/122] revert changes of pid controller --- docs/Settings.md | 34 +++------ src/main/common/maths.h | 1 - src/main/fc/controlrate_profile.c | 1 - .../fc/controlrate_profile_config_struct.h | 1 - src/main/fc/settings.yaml | 21 ++---- src/main/flight/pid.c | 75 +++++++++---------- src/main/flight/pid.h | 6 +- 7 files changed, 62 insertions(+), 77 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 70fc630535..2ddf6249e1 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1222,6 +1222,16 @@ 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 @@ -1914,7 +1924,7 @@ Calculated 1G of Acc axis Z to use in INS ### iterm_windup -Used to prevent Iterm accumulation on during maneuvers. Iterm accumulation will be dampened when motors are reaching it's limit (when requested motor correction range is close percentage specified by this parameter, when value is set below 50 no accumulation occors when iterm_windup+50 of motor correction range is reached) +Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) | Default | Min | Max | | --- | --- | --- | @@ -4762,16 +4772,6 @@ 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,19 +5672,9 @@ 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 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. +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. | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/common/maths.h b/src/main/common/maths.h index fc8dbe3329..cc3d1bc517 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -91,7 +91,6 @@ ) #define MIN(a, b) _CHOOSE(<, a, b) #define MAX(a, b) _CHOOSE(>, a, b) -#define SIGN(a) ((a >= 0) ? 1 : -1) #define _ABS_II(x, var) \ ( __extension__ ({ \ diff --git a/src/main/fc/controlrate_profile.c b/src/main/fc/controlrate_profile.c index c8b144e136..18f5bd343b 100644 --- a/src/main/fc/controlrate_profile.c +++ b/src/main/fc/controlrate_profile.c @@ -44,7 +44,6 @@ 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 e403853760..e07c328560 100644 --- a/src/main/fc/controlrate_profile_config_struct.h +++ b/src/main/fc/controlrate_profile_config_struct.h @@ -29,7 +29,6 @@ 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 036ca7d5c9..bfa596c781 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 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." + 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." default_value: 0 field: throttle.dynPID min: 0 @@ -1278,11 +1278,6 @@ 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 @@ -1856,6 +1851,12 @@ 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 @@ -1899,17 +1900,11 @@ groups: min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: iterm_windup - description: "Used to prevent Iterm accumulation on during maneuvers. Iterm accumulation will be dampened when motors are reaching it's limit (when requested motor correction range is close percentage specified by this parameter, when value is set below 50 no accumulation occors when iterm_windup+50 of motor correction range is reached)" + description: "Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)" default_value: 50 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 03458c5842..2bb4ab7035 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -79,6 +79,7 @@ typedef struct { // Rate integrator float errorGyroIf; + float errorGyroIfLimit; // Used for ANGLE filtering (PT1, we don't need super-sharpness here) pt1Filter_t angleFilterState; @@ -100,6 +101,7 @@ typedef struct { #endif uint16_t pidSumLimit; filterApply4FnPtr ptermFilterApplyFn; + bool itermLimitActive; bool itermFreezeActive; pt3Filter_t rateTargetFilter; @@ -147,7 +149,6 @@ static EXTENDED_FASTRAM float dBoostMaxAtAlleceleration; static EXTENDED_FASTRAM uint8_t yawLpfHz; static EXTENDED_FASTRAM float motorItermWindupPoint; -static EXTENDED_FASTRAM float motorItermWindupPoint_inv; static EXTENDED_FASTRAM float antiWindupScaler; #ifdef USE_ANTIGRAVITY static EXTENDED_FASTRAM float iTermAntigravityGain; @@ -263,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, @@ -379,12 +380,14 @@ void pidResetErrorAccumulators(void) // Reset R/P/Y integrator for (int axis = 0; axis < 3; axis++) { pidState[axis].errorGyroIf = 0.0f; + pidState[axis].errorGyroIfLimit = 0.0f; } } void pidReduceErrorAccumulators(int8_t delta, uint8_t axis) { pidState[axis].errorGyroIf -= delta; + pidState[axis].errorGyroIfLimit -= delta; } float getTotalRateTarget(void) @@ -528,7 +531,7 @@ void updatePIDCoefficients(void) pidState[axis].kT = 0.0f; } else { - const float axisTPA = (axis == FD_YAW && (!currentControlRateProfile->throttle.dynPID_on_YAW)) ? 1.0f : tpaFactor; + const float axisTPA = (axis == FD_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; @@ -619,7 +622,7 @@ static void pidLevel(const float angleTarget, pidState_t *pidState, flight_dynam angleErrorDeg = DECIDEGREES_TO_DEGREES((float)angleFreefloatDeadband(DEGREES_TO_DECIDEGREES(navConfig()->fw.soaring_pitch_deadband), FD_PITCH)); if (!angleErrorDeg) { pidState->errorGyroIf = 0.0f; - // pidState->errorGyroIfLimit = 0.0f; + pidState->errorGyroIfLimit = 0.0f; } } @@ -725,6 +728,14 @@ static float dTermProcess(pidState_t *pidState, float currentRateTarget, float d return(newDTerm); } +static void applyItermLimiting(pidState_t *pidState) { + if (pidState->itermLimitActive) { + pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidState->errorGyroIfLimit, pidState->errorGyroIfLimit); + } else + { + pidState->errorGyroIfLimit = fabsf(pidState->errorGyroIf); + } +} static void nullRateController(pidState_t *pidState, flight_dynamics_index_t axis, float dT, float dT_inv) { UNUSED(pidState); @@ -749,9 +760,10 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh pidState->errorGyroIf += rateError * pidState->kI * dT; } - if (pidProfile()->pidItermLimitPercent != 0){ - float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent * 0.01f; - pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); + applyItermLimiting(pidState); + + if (pidProfile()->fixedWingItermThrowLimit != 0) { + pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidProfile()->fixedWingItermThrowLimit, pidProfile()->fixedWingItermThrowLimit); } axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -pidState->pidSumLimit, +pidState->pidSumLimit); @@ -788,7 +800,7 @@ static float FAST_CODE applyItermRelax(const int axis, float currentPidSetpoint, const float setpointLpf = pt1FilterApply(&windupLpf[axis], currentPidSetpoint); const float setpointHpf = fabsf(currentPidSetpoint - setpointLpf); - const float itermRelaxFactor = MAX(0, 1 - setpointHpf / (FLIGHT_MODE(ANGLE_MODE) ? (MC_ITERM_RELAX_SETPOINT_THRESHOLD * 0.2f):MC_ITERM_RELAX_SETPOINT_THRESHOLD)); + const float itermRelaxFactor = MAX(0, 1 - setpointHpf / MC_ITERM_RELAX_SETPOINT_THRESHOLD); return itermErrorRate * itermRelaxFactor; } } @@ -817,30 +829,17 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf + newCDTerm; const float newOutputLimited = constrainf(newOutput, -pidState->pidSumLimit, +pidState->pidSumLimit); - float backCalc = newOutputLimited - newOutput;//back-calculation anti-windup - if (SIGN(backCalc) == SIGN(pidState->errorGyroIf)) { - //back calculation anti-windup can only shrink integrator, will not push it to the opposite direction - backCalc = 0.0f; - } float itermErrorRate = applyItermRelax(axis, rateTarget, rateError); #ifdef USE_ANTIGRAVITY itermErrorRate *= iTermAntigravityGain; #endif - if (!pidState->itermFreezeActive) { - pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) - + (backCalc * pidState->kT * antiWindupScaler * dT); - } - - if (pidProfile()->pidItermLimitPercent != 0){ - float itermLimit = pidState->pidSumLimit * pidProfile()->pidItermLimitPercent * 0.01f; - pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -itermLimit, +itermLimit); - } - + pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) + + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT); // Don't grow I-term if motors are at their limit - // applyItermLimiting(pidState); //merged with itermFreezeActive + applyItermLimiting(pidState); axisPID[axis] = newOutputLimited; @@ -1027,34 +1026,35 @@ static void pidApplyFpvCameraAngleMix(pidState_t *pidState, uint8_t fpvCameraAng pidState[YAW].rateTarget = constrainf(yawRate * cosCameraAngle + rollRate * sinCameraAngle, -GYRO_SATURATION_LIMIT, GYRO_SATURATION_LIMIT); } -bool checkItermLimitingActive(pidState_t *pidState) +void checkItermLimitingActive(pidState_t *pidState) { - bool shouldActivate=false; + bool shouldActivate; if (usedPidControllerType == PID_TYPE_PIFF) { shouldActivate = isFixedWingItermLimitActive(pidState->stickPosition); } else { - shouldActivate = mixerIsOutputSaturated(); //just in case, since it is already managed by itermWindupPointPercent + shouldActivate = mixerIsOutputSaturated(); } - return STATE(ANTI_WINDUP) || shouldActivate; + pidState->itermLimitActive = STATE(ANTI_WINDUP) || shouldActivate; } void checkItermFreezingActive(pidState_t *pidState, flight_dynamics_index_t axis) { - bool shouldActivate=false; if (usedPidControllerType == PID_TYPE_PIFF && pidProfile()->fixedWingYawItermBankFreeze != 0 && axis == FD_YAW) { // Do not allow yaw I-term to grow when bank angle is too large float bankAngle = DECIDEGREES_TO_DEGREES(attitude.values.roll); if (fabsf(bankAngle) > pidProfile()->fixedWingYawItermBankFreeze && !(FLIGHT_MODE(AUTO_TUNE) || FLIGHT_MODE(TURN_ASSISTANT) || navigationRequiresTurnAssistance())){ - shouldActivate |= true; + pidState->itermFreezeActive = true; } else { - shouldActivate |= false; + pidState->itermFreezeActive = false; } + } else + { + pidState->itermFreezeActive = false; } - shouldActivate |=checkItermLimitingActive(pidState); - pidState->itermFreezeActive = shouldActivate; + } void FAST_CODE pidController(float dT) @@ -1134,14 +1134,15 @@ void FAST_CODE pidController(float dT) pidApplyFpvCameraAngleMix(pidState, currentControlRateProfile->misc.fpvCamAngleDegrees); } - // Prevent Iterm accumulation when motors are near its saturation - antiWindupScaler = constrainf((1.0f - getMotorMixRange() * MAX(2*motorItermWindupPoint,1)) * motorItermWindupPoint_inv, 0.0f, 1.0f); + // Prevent strong Iterm accumulation during stick inputs + antiWindupScaler = constrainf((1.0f - getMotorMixRange()) * motorItermWindupPoint, 0.0f, 1.0f); for (int axis = 0; axis < 3; axis++) { // Apply setpoint rate of change limits pidApplySetpointRateLimiting(&pidState[axis], axis, dT); // Step 4: Run gyro-driven control + checkItermLimitingActive(&pidState[axis]); checkItermFreezingActive(&pidState[axis], axis); pidControllerApplyFn(&pidState[axis], axis, dT, dT_inv); @@ -1176,9 +1177,7 @@ void pidInit(void) itermRelax = pidProfile()->iterm_relax; yawLpfHz = pidProfile()->yaw_lpf_hz; - motorItermWindupPoint = 1.0f - (pidProfile()->itermWindupPointPercent / 100.0f); - motorItermWindupPoint_inv = 1.0f / motorItermWindupPoint; - + motorItermWindupPoint = 1.0f / (1.0f - (pidProfile()->itermWindupPointPercent / 100.0f)); #ifdef USE_D_BOOST dBoostMin = pidProfile()->dBoostMin; diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 7c61b7cec2..de0e3126b7 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -31,6 +31,10 @@ #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 @@ -117,9 +121,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 24ffa37b3a18500f7d8a8db1254c323a1431ce25 Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 20 Sep 2023 20:01:26 +0900 Subject: [PATCH 070/122] minor fix --- src/main/drivers/pwm_mapping.c | 2 +- src/main/drivers/pwm_mapping.h | 2 +- src/main/fc/fc_msp.c | 6 ++++-- src/main/flight/mixer_profile.c | 2 +- src/main/flight/mixer_profile.h | 1 - 5 files changed, 7 insertions(+), 6 deletions(-) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index d502fd6c14..54ee0ad121 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -228,7 +228,7 @@ static void timerHardwareOverride(timerHardware_t * timer) { } } -bool check_pwm_assigned_to_motor_or_servo(void) +bool checkPwmAssignedToMotorOrServo(void) { // Check TIM_USE_FW_* and TIM_USE_MC_* is consistent, If so, return true, means the pwm mapping will remain same between FW and MC bool pwm_assigned_to_motor_or_servo = true; diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 5b13fe72e3..155975d004 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -73,7 +73,7 @@ typedef struct { } motorProtocolProperties_t; bool pwmMotorAndServoInit(void); -bool check_pwm_assigned_to_motor_or_servo(void); +bool checkPwmAssignedToMotorOrServo(void); const motorProtocolProperties_t * getMotorProtocolProperties(motorPwmProtocolTypes_e proto); pwmInitError_e getPwmInitError(void); const char * getPwmInitErrorMessage(void); diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 5a363bdff0..8b62fdba39 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1466,7 +1466,8 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF case MSP2_INAV_MIXER: sbufWriteU8(dst, mixerConfig()->motorDirectionInverted); - sbufWriteU16(dst, 0); + sbufWriteU8(dst, 0); + sbufWriteU8(dst, mixerConfig()->motorstopOnLow); sbufWriteU8(dst, mixerConfig()->platformType); sbufWriteU8(dst, mixerConfig()->hasFlaps); sbufWriteU16(dst, mixerConfig()->appliedMixerPreset); @@ -2867,7 +2868,8 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) case MSP2_INAV_SET_MIXER: if (dataSize == 9) { mixerConfigMutable()->motorDirectionInverted = sbufReadU8(src); - sbufReadU16(src); // Was yaw_jump_prevention_limit + sbufReadU8(src); // Was yaw_jump_prevention_limit + mixerConfigMutable()->motorstopOnLow = sbufReadU8(src); mixerConfigMutable()->platformType = sbufReadU8(src); mixerConfigMutable()->hasFlaps = sbufReadU8(src); mixerConfigMutable()->appliedMixerPreset = sbufReadU16(src); diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 5901c3419e..3248c13b2d 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -193,7 +193,7 @@ bool checkMixerProfileHotSwitchAvalibility(void) #if defined(SITL_BUILD) bool MCFW_pwm_settings_valid = true; #else - bool MCFW_pwm_settings_valid = check_pwm_assigned_to_motor_or_servo(); + bool MCFW_pwm_settings_valid = checkPwmAssignedToMotorOrServo(); #endif uint8_t platform_type0 = mixerConfigByIndex(0)->platformType; uint8_t platform_type1 = mixerConfigByIndex(1)->platformType; diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index c833651c21..cb040665ce 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -14,7 +14,6 @@ typedef struct mixerConfig_s { uint8_t platformType; bool hasFlaps; int16_t appliedMixerPreset; - uint8_t outputMode; bool motorstopOnLow; bool PIDProfileLinking; bool automated_switch; From e4984a52929d982d9dec1bed1105f238aaaf1b5d Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 23 Sep 2023 01:27:07 +0900 Subject: [PATCH 071/122] minor fix --- src/main/flight/mixer_profile.c | 51 +++++---------------------------- 1 file changed, 7 insertions(+), 44 deletions(-) diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 3248c13b2d..5010b65031 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -106,7 +106,6 @@ void setMixerProfileAT(void) bool checkMixerATRequired(mixerProfileATRequest_e required_action) { //return false if mixerAT condition is not required or setting is not valid - //on non vtol setups , behave as normal if ((!STATE(AIRPLANE)) && (!STATE(MULTIROTOR))) { return false; @@ -131,6 +130,7 @@ bool checkMixerATRequired(mixerProfileATRequest_e required_action) bool mixerATUpdateState(mixerProfileATRequest_e required_action) { + //return true if mixerAT is done or not required bool reprocessState; do { @@ -175,66 +175,30 @@ bool mixerATUpdateState(mixerProfileATRequest_e required_action) bool checkMixerProfileHotSwitchAvalibility(void) { - static int allow_hot_switch = -1; - // pwm mapping maps outputs based on platformtype, check if mapping remain unchanged after the switch - // do not allow switching between multi rotor and non multi rotor if sannity check fails if (MAX_MIXER_PROFILE_COUNT != 2) { return false; } - if (allow_hot_switch == 0) - { - return false; - } - if (allow_hot_switch == 1) - { - return true; - } -#if defined(SITL_BUILD) - bool MCFW_pwm_settings_valid = true; -#else - bool MCFW_pwm_settings_valid = checkPwmAssignedToMotorOrServo(); -#endif - uint8_t platform_type0 = mixerConfigByIndex(0)->platformType; - uint8_t platform_type1 = mixerConfigByIndex(1)->platformType; - bool platform_type_mc0 = (platform_type0 == PLATFORM_MULTIROTOR) || (platform_type0 == PLATFORM_TRICOPTER); - bool platform_type_mc1 = (platform_type1 == PLATFORM_MULTIROTOR) || (platform_type1 == PLATFORM_TRICOPTER); - bool is_mcfw_switching = platform_type_mc0 ^ platform_type_mc1; - if ((!MCFW_pwm_settings_valid) && is_mcfw_switching) - { - allow_hot_switch = 0; - return false; - } - allow_hot_switch = 1; return true; } -bool isNavBoxModesEnabled(void) -{ - return 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))); -} - void outputProfileUpdateTask(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); - bool nav_mixerAT_inuse = (posControl.navState == NAV_STATE_MIXERAT_IN_PROGRESS || posControl.navState == NAV_STATE_MIXERAT_ABORT); + bool mixerAT_inuse = mixerProfileAT.phase != MIXERAT_PHASE_IDLE; // transition mode input for servo mix and motor mix - if (!FLIGHT_MODE(FAILSAFE_MODE) && (!nav_mixerAT_inuse)) + if (!FLIGHT_MODE(FAILSAFE_MODE) && (!mixerAT_inuse)) { - if (!isNavBoxModesEnabled()) - { - outputProfileHotSwitch((int)IS_RC_MODE_ACTIVE(BOXMIXERPROFILE)); - } - isMixerTransitionMixing_requested = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION) && (!isNavBoxModesEnabled()); // update BOXMIXERTRANSITION_input + outputProfileHotSwitch((int)IS_RC_MODE_ACTIVE(BOXMIXERPROFILE)); + isMixerTransitionMixing_requested = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION); } - isMixerTransitionMixing = isMixerTransitionMixing_requested && ((posControl.navState == NAV_STATE_IDLE) || nav_mixerAT_inuse ||(posControl.navState == NAV_STATE_ALTHOLD_IN_PROGRESS)); + isMixerTransitionMixing = isMixerTransitionMixing_requested && ((posControl.navState == NAV_STATE_IDLE) || mixerAT_inuse ||(posControl.navState == NAV_STATE_ALTHOLD_IN_PROGRESS)); } // switch mixerprofile without reboot bool outputProfileHotSwitch(int profile_index) { static bool allow_hot_switch = true; - // does not work with timerHardwareOverride,need to set mixerConfig()->outputMode == OUTPUT_MODE_AUTO // LOG_INFO(PWM, "OutputProfileHotSwitch"); if (!allow_hot_switch) { @@ -250,7 +214,7 @@ bool outputProfileHotSwitch(int profile_index) return false; } if (areSensorsCalibrating()) - { // it seems like switching before sensors calibration complete will cause pid stops to respond, especially in D,TODO + { // it seems like switching before sensors calibration complete will cause pid stops to respond, especially in D return false; } if (!checkMixerProfileHotSwitchAvalibility()) @@ -268,7 +232,6 @@ bool outputProfileHotSwitch(int profile_index) // LOG_INFO(PWM, "mixer switch failed to set config"); return false; } - // stopMotorsNoDelay(); // not necessary, but just in case something goes wrong. But will a short period of stop command cause problem? mixerConfigInit(); return true; } From ab380053b2db464a555ac72b94d371bfe6c477aa Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 23 Sep 2023 01:00:29 +0200 Subject: [PATCH 072/122] add missing comma --- src/main/target/OMNIBUSF4/target.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/target/OMNIBUSF4/target.c b/src/main/target/OMNIBUSF4/target.c index f1ba154606..a8a2124198 100644 --- a/src/main/target/OMNIBUSF4/target.c +++ b/src/main/target/OMNIBUSF4/target.c @@ -43,7 +43,8 @@ timerHardware_t timerHardware[] = { // { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_MOTOR | TIM_USE_SERVO }, // MOTOR_3 #if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !(defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO 0, 0), // S5_OUT + + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT #elif defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) DEF_TIM(TIM5, CH2, PA1, TIM_USE_ANY, 0, 0), // S5_OUT SOFTSERIAL From 4219b5e1e543949af943111db68fd8a7adcff42d Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 23 Sep 2023 01:18:08 +0200 Subject: [PATCH 073/122] Add missing _ --- src/main/target/MAMBAF405_2022A/target.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/MAMBAF405_2022A/target.c b/src/main/target/MAMBAF405_2022A/target.c index aeded5cda9..238b280046 100644 --- a/src/main/target/MAMBAF405_2022A/target.c +++ b/src/main/target/MAMBAF405_2022A/target.c @@ -20,7 +20,7 @@ #include "platform.h" #include "drivers/io.h" -#include "drivers/timer.h" +//#include "drivers/timer.h" #include "drivers/pwm_mapping.h" #include "drivers/bus.h" @@ -30,7 +30,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S2 pin A8: DMA2 Stream 6 Channel 0 DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3 pin C9: DMA2 Stream 7 Channel 7 DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 pin C8: DMA2 Stream 2 Channel 0 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM USE_SERVO, 1, 0 ), // S4 pin C8: DMA2 Stream 2 Channel 0 // used to be fw motor + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0 ), // S4 pin C8: DMA2 Stream 2 Channel 0 // used to be fw motor DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0 ), // S4 pin C8: DMA2 Stream 2 Channel 0 // used to be fw motor DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) From f8a0cf65334f3ca92458f14176222b5fdcb55f98 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 23 Sep 2023 11:02:46 +0200 Subject: [PATCH 074/122] Sample work around for targets with quad centric timer allocationsw --- src/main/target/AIKONF4/config.c | 29 +++++++++++++++++++++++++++++ src/main/target/AIKONF4/target.c | 14 +++++++------- 2 files changed, 36 insertions(+), 7 deletions(-) create mode 100644 src/main/target/AIKONF4/config.c diff --git a/src/main/target/AIKONF4/config.c b/src/main/target/AIKONF4/config.c new file mode 100644 index 0000000000..782ee126d2 --- /dev/null +++ b/src/main/target/AIKONF4/config.c @@ -0,0 +1,29 @@ +/* + * 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 . + */ + +#include +#include + +#include + +#include "drivers/pwm_mapping.h" + +void targetConfiguration(void) +{ + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM3))->outputMode = OUTPUT_MODE_MOTORS; +} diff --git a/src/main/target/AIKONF4/target.c b/src/main/target/AIKONF4/target.c index 43c52dbd23..4268fd1864 100644 --- a/src/main/target/AIKONF4/target.c +++ b/src/main/target/AIKONF4/target.c @@ -29,13 +29,13 @@ timerHardware_t timerHardware[] = { // DEF_TIM(TIM2, CH2, PB3, TIM_USE_CAMERA_CONTROL, 0, 0), // There is not camera control in INAV - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S6 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_PPM | TIM_USE_LED, 0, 0), // LED & PPM (DMA1_ST0_CH2) + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_PPM | TIM_USE_LED, 0, 0), // LED & PPM (DMA1_ST0_CH2) }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); \ No newline at end of file From 898e95fb9a461fe08f6ef6ed7e54b5bf2e4e4043 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 23 Sep 2023 11:17:53 +0200 Subject: [PATCH 075/122] Update timer overrides default value This should improve INAV 6.x and older compatibility for fixed wing builds. --- src/main/target/AIKONF4/config.c | 8 +++---- src/main/target/DALRCF722DUAL/config.c | 29 +++++++++++++++++++++++++ src/main/target/DALRCF722DUAL/target.c | 12 +++++----- src/main/target/PIXRACER/config.c | 7 +++--- src/main/target/PIXRACER/target.c | 14 ++++++------ src/main/target/SKYSTARSF405HD/config.c | 4 ++++ src/main/target/SKYSTARSF405HD/target.c | 8 +++---- 7 files changed, 58 insertions(+), 24 deletions(-) create mode 100644 src/main/target/DALRCF722DUAL/config.c diff --git a/src/main/target/AIKONF4/config.c b/src/main/target/AIKONF4/config.c index 782ee126d2..c77bbfaf3a 100644 --- a/src/main/target/AIKONF4/config.c +++ b/src/main/target/AIKONF4/config.c @@ -1,18 +1,18 @@ /* - * This file is part of Cleanflight. + * This file is part of INAV. * - * Cleanflight is free software: you can redistribute it and/or modify + * 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. * - * Cleanflight is distributed in the hope that it will be useful, + * 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 Cleanflight. If not, see . + * along with INAV. If not, see . */ #include diff --git a/src/main/target/DALRCF722DUAL/config.c b/src/main/target/DALRCF722DUAL/config.c new file mode 100644 index 0000000000..e9e6c9fce0 --- /dev/null +++ b/src/main/target/DALRCF722DUAL/config.c @@ -0,0 +1,29 @@ +/* + * 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 + +#include "drivers/pwm_mapping.h" + +void targetConfiguration(void) +{ + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM1))->outputMode = OUTPUT_MODE_MOTORS; +} diff --git a/src/main/target/DALRCF722DUAL/target.c b/src/main/target/DALRCF722DUAL/target.c index e3ff39dae3..286c00539a 100644 --- a/src/main/target/DALRCF722DUAL/target.c +++ b/src/main/target/DALRCF722DUAL/target.c @@ -30,12 +30,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM ,0, 0), - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO,0,0), //S1 DMA2_ST2 T8CH1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO,0,0), //S2 DMA2_ST3 T8CH2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO,0,0), //S3 DMA2_ST4 T8CH3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO,0,0), //S4 DMA2_ST7 T8CH4 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO,0,0), //S5 DMA2_ST1 T1CH1 // used to be fw motor - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO,0,0), //S6 DMA2_ST6 T1CH2 // used to be fw motor + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO,0,0), //S1 DMA2_ST2 T8CH1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO,0,0), //S2 DMA2_ST3 T8CH2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO,0,0), //S3 DMA2_ST4 T8CH3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO,0,0), //S4 DMA2_ST7 T8CH4 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO,0,0), //S5 DMA2_ST1 T1CH1 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO,0,0), //S6 DMA2_ST6 T1CH2 DEF_TIM(TIM2, CH1, PA15,TIM_USE_LED,0,0), //2812 STRIP DMA1_ST5 }; diff --git a/src/main/target/PIXRACER/config.c b/src/main/target/PIXRACER/config.c index d538e04b50..130ce8538f 100755 --- a/src/main/target/PIXRACER/config.c +++ b/src/main/target/PIXRACER/config.c @@ -21,12 +21,13 @@ #include "config/feature.h" #include "fc/config.h" -#include "flight/mixer.h" -#include "io/serial.h" -#include "rx/rx.h" #include "sensors/compass.h" +#include "drivers/pwm_mapping.h" void targetConfiguration(void) { compassConfigMutable()->mag_align = CW90_DEG; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM4))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/PIXRACER/target.c b/src/main/target/PIXRACER/target.c index 09ecffa6c1..73c9d6937a 100755 --- a/src/main/target/PIXRACER/target.c +++ b/src/main/target/PIXRACER/target.c @@ -37,15 +37,15 @@ BUSDEV_REGISTER_I2C_TAG(busdev_mag3110, DEVHW_MAG3110, MAG_I2C_BUS, BUSDEV_REGISTER_SPI_TAG(busdev_hmc5983_spi, DEVHW_HMC5883, MPU9250_SPI_BUS, PE15, NONE, 1, DEVFLAGS_NONE, 0); timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_PPM, 0, 0 ), // PPM shared uart6 pc7 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_PPM, 0, 0), // PPM shared uart6 pc7 - DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT - DEF_TIM(TIM1, CH3, PE13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4_OUT + DEF_TIM(TIM1, CH4, PE14, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT + DEF_TIM(TIM1, CH3, PE13, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT + DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT + DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_OUT // used to be fw motor - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6_OUT // used to be fw motor + DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT + DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SKYSTARSF405HD/config.c b/src/main/target/SKYSTARSF405HD/config.c index a327f7a460..b34785c5b7 100644 --- a/src/main/target/SKYSTARSF405HD/config.c +++ b/src/main/target/SKYSTARSF405HD/config.c @@ -22,8 +22,12 @@ #include "io/serial.h" #include "rx/rx.h" +#include "drivers/pwm_mapping.h" void targetConfiguration(void) { serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_DJI_HD_OSD; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM2))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/SKYSTARSF405HD/target.c b/src/main/target/SKYSTARSF405HD/target.c index 0689dceb37..40ab18015a 100644 --- a/src/main/target/SKYSTARSF405HD/target.c +++ b/src/main/target/SKYSTARSF405HD/target.c @@ -24,10 +24,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), }; From f65a82a1fb387e4c1f5e537b69731c000a808e3f Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 23 Sep 2023 12:14:49 +0200 Subject: [PATCH 076/122] More bulk compatibility changes I will need help reviewing/testing these :) --- src/main/target/CLRACINGF4AIR/config.c | 5 ++++ src/main/target/CLRACINGF4AIR/target.c | 24 +++++++++---------- src/main/target/FIREWORKSV2/config.c | 4 ++++ src/main/target/FIREWORKSV2/target.c | 18 +++++++------- src/main/target/FOXEERH743/config.c | 5 +++- src/main/target/GEPRCF722_BT_HD/config.c | 3 +++ src/main/target/GEPRCF722_BT_HD/target.c | 20 ++++++++-------- src/main/target/IFLIGHTF7_TWING/config.c | 29 +++++++++++++++++++++++ src/main/target/IFLIGHTF7_TWING/target.c | 20 ++++++++-------- src/main/target/MAMBAF405_2022A/config.c | 1 + src/main/target/MAMBAF405_2022A/target.c | 1 - src/main/target/MAMBAH743/config.c | 4 ++++ src/main/target/MAMBAH743/target.c | 16 ++++++------- src/main/target/MATEKF405CAN/config.c | 4 ++++ src/main/target/MATEKF722SE/config.c | 5 ++++ src/main/target/MATEKF722SE/target.c | 22 ++++++++--------- src/main/target/OMNIBUSF7NXT/config.c | 4 ++++ src/main/target/OMNIBUSF7NXT/target.c | 12 +++++----- src/main/target/RUSH_BLADE_F7/config.c | 30 ++++++++++++++++++++++++ src/main/target/RUSH_BLADE_F7/target.c | 16 ++++++------- src/main/target/SKYSTARSF722HD/target.c | 8 +++---- src/main/target/SPEEDYBEEF4/config.c | 5 ++++ src/main/target/SPEEDYBEEF7MINI/config.c | 5 ++++ src/main/target/SPEEDYBEEF7V2/config.c | 5 ++++ src/main/target/SPRACINGF4EVO/config.c | 3 +++ src/main/target/SPRACINGF4EVO/target.c | 20 ++++++++-------- 26 files changed, 199 insertions(+), 90 deletions(-) create mode 100644 src/main/target/IFLIGHTF7_TWING/config.c create mode 100644 src/main/target/RUSH_BLADE_F7/config.c diff --git a/src/main/target/CLRACINGF4AIR/config.c b/src/main/target/CLRACINGF4AIR/config.c index fa0d0196d7..4e4234cb0a 100644 --- a/src/main/target/CLRACINGF4AIR/config.c +++ b/src/main/target/CLRACINGF4AIR/config.c @@ -52,4 +52,9 @@ void targetConfiguration(void) { compassConfigMutable()->mag_align = CW90_DEG; + +#if defined(CLRACINGF4AIRV2) || defined(CLRACINGF4AIRV3) + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM8))->outputMode = OUTPUT_MODE_MOTORS; +#endif } diff --git a/src/main/target/CLRACINGF4AIR/target.c b/src/main/target/CLRACINGF4AIR/target.c index f44496bd3a..54fa14c709 100644 --- a/src/main/target/CLRACINGF4AIR/target.c +++ b/src/main/target/CLRACINGF4AIR/target.c @@ -25,19 +25,19 @@ DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, 0, 0), #if defined(CLRACINGF4AIRV2) || defined(CLRACINGF4AIRV3) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), #else - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM9, CH2, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM9, CH2, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), #endif }; diff --git a/src/main/target/FIREWORKSV2/config.c b/src/main/target/FIREWORKSV2/config.c index ed075a2a9b..930df0630d 100644 --- a/src/main/target/FIREWORKSV2/config.c +++ b/src/main/target/FIREWORKSV2/config.c @@ -26,10 +26,14 @@ #include #include "drivers/io.h" +#include "drivers/pwm_mapping.h" #include "rx/rx.h" #include "io/serial.h" void targetConfiguration(void) { serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM8))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/FIREWORKSV2/target.c b/src/main/target/FIREWORKSV2/target.c index 3d9042551e..8e7cdb9575 100644 --- a/src/main/target/FIREWORKSV2/target.c +++ b/src/main/target/FIREWORKSV2/target.c @@ -44,20 +44,20 @@ BUSDEV_REGISTER_SPI_TAG(busdev_2_mpu6000, DEVHW_MPU6000, IMU_2_SPI_BUS, IMU_ BUSDEV_REGISTER_SPI_TAG(busdev_2_mpu6500, DEVHW_MPU6500, IMU_2_SPI_BUS, IMU_2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_2_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM + DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM // Motor output 1: use different set of timers for MC and FW - //DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM _USE_SERVO, 1, 0), // S1_OUT D(1,7) - DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // S1_OUT D(2,2,0),D(2,3,7) // used to fw motor + //DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM _USE_SERVO, 1, 0), // S1_OUT D(1,7) + DEF_TIM(TIM8, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 1, 1), // S1_OUT D(2,2,0),D(2,3,7) // used to fw motor // Motor output 2: use different set of timers for MC and FW - //DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S2_OUT D(1,2) - DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // S2_OUT D(2,2,0),D(2,4,7) // used to be fw motor + //DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0), // S2_OUT D(1,2) + DEF_TIM(TIM8, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 1, 1), // S2_OUT D(2,2,0),D(2,4,7) // used to be fw motor - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // S3_OUT D(1,6) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4_OUT D(1,5) - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT D(1,7) - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT D(1,8) + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 1, 1), // S3_OUT D(1,6) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 1, 0), // S4_OUT D(1,5) + DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT D(1,7) + DEF_TIM(TIM3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT D(1,8) DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip D(1,0) diff --git a/src/main/target/FOXEERH743/config.c b/src/main/target/FOXEERH743/config.c index b83a0a0d03..e6e31bace2 100644 --- a/src/main/target/FOXEERH743/config.c +++ b/src/main/target/FOXEERH743/config.c @@ -28,6 +28,7 @@ #include "drivers/sensor.h" #include "drivers/pwm_esc_detect.h" #include "drivers/pwm_output.h" +#include "drivers/pwm_mapping.h" #include "drivers/serial.h" #include "fc/rc_controls.h" @@ -53,5 +54,7 @@ void targetConfiguration(void) * UART1 is SerialRX */ serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_RX_SERIAL; - + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM8))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/GEPRCF722_BT_HD/config.c b/src/main/target/GEPRCF722_BT_HD/config.c index 1e3f19f4ba..119559fbe6 100644 --- a/src/main/target/GEPRCF722_BT_HD/config.c +++ b/src/main/target/GEPRCF722_BT_HD/config.c @@ -58,5 +58,8 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM4))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/GEPRCF722_BT_HD/target.c b/src/main/target/GEPRCF722_BT_HD/target.c index 46299424cf..d1f902eb69 100644 --- a/src/main/target/GEPRCF722_BT_HD/target.c +++ b/src/main/target/GEPRCF722_BT_HD/target.c @@ -28,20 +28,20 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), + DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // used to be fw motor + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // used to be fw motor - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), - DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), + DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/IFLIGHTF7_TWING/config.c b/src/main/target/IFLIGHTF7_TWING/config.c new file mode 100644 index 0000000000..c77bbfaf3a --- /dev/null +++ b/src/main/target/IFLIGHTF7_TWING/config.c @@ -0,0 +1,29 @@ +/* + * 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 + +#include "drivers/pwm_mapping.h" + +void targetConfiguration(void) +{ + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM3))->outputMode = OUTPUT_MODE_MOTORS; +} diff --git a/src/main/target/IFLIGHTF7_TWING/target.c b/src/main/target/IFLIGHTF7_TWING/target.c index f32db01de3..0412eba102 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.c +++ b/src/main/target/IFLIGHTF7_TWING/target.c @@ -30,20 +30,20 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6500, MPU6500_0_SPI_BUS, MPU6 BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_1_SPI_BUS, MPU6500_1_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_1_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), + DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // used to be fw motor + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // used to be fw motor + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // used to be fw motor - DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), + DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MAMBAF405_2022A/config.c b/src/main/target/MAMBAF405_2022A/config.c index 355605fd90..d632230c24 100644 --- a/src/main/target/MAMBAF405_2022A/config.c +++ b/src/main/target/MAMBAF405_2022A/config.c @@ -28,6 +28,7 @@ #include "drivers/sensor.h" #include "drivers/pwm_esc_detect.h" #include "drivers/pwm_output.h" +#include "drivers/pwm_mapping.h" #include "drivers/serial.h" #include "fc/rc_controls.h" diff --git a/src/main/target/MAMBAF405_2022A/target.c b/src/main/target/MAMBAF405_2022A/target.c index 238b280046..13396ecb26 100644 --- a/src/main/target/MAMBAF405_2022A/target.c +++ b/src/main/target/MAMBAF405_2022A/target.c @@ -20,7 +20,6 @@ #include "platform.h" #include "drivers/io.h" -//#include "drivers/timer.h" #include "drivers/pwm_mapping.h" #include "drivers/bus.h" diff --git a/src/main/target/MAMBAH743/config.c b/src/main/target/MAMBAH743/config.c index cc04e10319..7bc7d7b6fe 100644 --- a/src/main/target/MAMBAH743/config.c +++ b/src/main/target/MAMBAH743/config.c @@ -46,6 +46,7 @@ #include "telemetry/telemetry.h" #include "io/piniobox.h" +#include "drivers/pwm_mapping.h" void targetConfiguration(void) { @@ -65,4 +66,7 @@ void targetConfiguration(void) */ serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BAUD_115200; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM8))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/MAMBAH743/target.c b/src/main/target/MAMBAH743/target.c index 11bdee8446..46231fdbd7 100644 --- a/src/main/target/MAMBAH743/target.c +++ b/src/main/target/MAMBAH743/target.c @@ -35,15 +35,15 @@ BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, timerHardware_t timerHardware[] = { - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 3), // S4 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_SERVO | TIM_USE_SERVO, 0, 4), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_SERVO | TIM_USE_SERVO, 0, 5), // S6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_SERVO | TIM_USE_SERVO, 0, 6), // S7 // used to be fw motor - DEF_TIM(TIM8, CH4, PC9, TIM_USE_SERVO | TIM_USE_SERVO, 0, 7), // S8 // used to be fw motor + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 // used to be fw motor + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 // used to be fw motor DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 }; diff --git a/src/main/target/MATEKF405CAN/config.c b/src/main/target/MATEKF405CAN/config.c index b400704b00..78b1e8c985 100644 --- a/src/main/target/MATEKF405CAN/config.c +++ b/src/main/target/MATEKF405CAN/config.c @@ -22,6 +22,7 @@ #include "io/serial.h" #include "sensors/compass.h" #include "fc/config.h" +#include "drivers/pwm_mapping.h" void targetConfiguration(void) @@ -30,4 +31,7 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_GPS; // serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].gps_baudrateIndex = BAUD_115200; beeperConfigMutable()->pwmMode = true; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM4))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/MATEKF722SE/config.c b/src/main/target/MATEKF722SE/config.c index 7e47e5bf6b..94de7c47b8 100644 --- a/src/main/target/MATEKF722SE/config.c +++ b/src/main/target/MATEKF722SE/config.c @@ -19,6 +19,8 @@ #include "platform.h" +#include "drivers/pwm_mapping.h" + #include "fc/fc_msp_box.h" #include "io/piniobox.h" @@ -27,4 +29,7 @@ void targetConfiguration(void) { pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM4))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/MATEKF722SE/target.c b/src/main/target/MATEKF722SE/target.c index 67cdad4a52..6e469dfff3 100644 --- a/src/main/target/MATEKF722SE/target.c +++ b/src/main/target/MATEKF722SE/target.c @@ -30,22 +30,22 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 UP1-2 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 UP1-2 D(1, 5, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 UP1-2 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 UP1-2 D(1, 2, 5) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 UP1-7 D(1, 6, 3) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 UP1-6 D(1, 0, 2) // used to be fw motor - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 UP1-6 D(1, 3, 2) // used to me fw motor + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 UP1-6 D(1, 0, 2) // used to be fw motor + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 UP1-6 D(1, 3, 2) // used to me fw motor - DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 6, 0) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 6, 0) - DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM, RX2 + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM, RX2 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2 & softserial1 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2 & softserial1 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/OMNIBUSF7NXT/config.c b/src/main/target/OMNIBUSF7NXT/config.c index e5aff9dbf4..2fd2607b71 100644 --- a/src/main/target/OMNIBUSF7NXT/config.c +++ b/src/main/target/OMNIBUSF7NXT/config.c @@ -26,6 +26,7 @@ #include #include "drivers/io.h" +#include "drivers/pwm_mapping.h" #include "rx/rx.h" #include "io/serial.h" #include "io/ledstrip.h" @@ -34,4 +35,7 @@ void targetConfiguration(void) { DEFINE_LED(ledStripConfigMutable()->ledConfigs, 0, 0, COLOR_GREEN, 0, LED_FUNCTION_ARM_STATE, LED_FLAG_OVERLAY(LED_OVERLAY_WARNING), 0); // serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM8))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/OMNIBUSF7NXT/target.c b/src/main/target/OMNIBUSF7NXT/target.c index e7573ae16d..b1eb7332dc 100644 --- a/src/main/target/OMNIBUSF7NXT/target.c +++ b/src/main/target/OMNIBUSF7NXT/target.c @@ -39,14 +39,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM / UART1_RX // OUTPUT 1-4 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // D(1, 5, 5) - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // D(1, 4, 5) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // D(1, 2, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 1, 0), // D(1, 5, 5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 1, 0), // D(1, 4, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0), // D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0), // D(1, 2, 5) // OUTPUT 5-6 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // D(2, 7, 7) // used to be fw motor - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // D(2, 2, 0) // used to be fw motor + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 1, 0), // D(2, 7, 7) // used to be fw motor + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 1, 1), // D(2, 2, 0) // used to be fw motor // AUXILARY pins DEF_TIM(TIM1, CH2, PA9, TIM_USE_LED, 1, 0), // LED diff --git a/src/main/target/RUSH_BLADE_F7/config.c b/src/main/target/RUSH_BLADE_F7/config.c new file mode 100644 index 0000000000..d5a1430721 --- /dev/null +++ b/src/main/target/RUSH_BLADE_F7/config.c @@ -0,0 +1,30 @@ +/* + * 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 + +#include "drivers/pwm_mapping.h" + +void targetConfiguration(void) +{ + // To improve backwards compatibility with INAV versions 6.x and older + // Keeps m1-m4 on first 4 outputs in mc, otherwise would be s1, s2, s5, s6 + timerOverridesMutable(timer2id(TIM3))->outputMode = OUTPUT_MODE_MOTORS; +} diff --git a/src/main/target/RUSH_BLADE_F7/target.c b/src/main/target/RUSH_BLADE_F7/target.c index bca0f23cea..c50807f465 100644 --- a/src/main/target/RUSH_BLADE_F7/target.c +++ b/src/main/target/RUSH_BLADE_F7/target.c @@ -23,14 +23,14 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 // used to be fw motor - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 // used to be fw motor - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED STRIP #ifdef RUSH_BLADE_F7 diff --git a/src/main/target/SKYSTARSF722HD/target.c b/src/main/target/SKYSTARSF722HD/target.c index 8146885a16..72ac897455 100644 --- a/src/main/target/SKYSTARSF722HD/target.c +++ b/src/main/target/SKYSTARSF722HD/target.c @@ -24,10 +24,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH1, PB4, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // TIM3_CH3 / TIM8_CH3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // TIM3_CH4 / TIM8_CH4 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // TIM4_CH1 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // TIM4_CH2 // used to be fw motor + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // TIM3_CH3 / TIM8_CH3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // TIM3_CH4 / TIM8_CH4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // TIM4_CH1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // TIM4_CH2 // used to be fw motor, but would have a timer conflict with the line above DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0), }; diff --git a/src/main/target/SPEEDYBEEF4/config.c b/src/main/target/SPEEDYBEEF4/config.c index 6bf5f8877f..73ec5ed289 100644 --- a/src/main/target/SPEEDYBEEF4/config.c +++ b/src/main/target/SPEEDYBEEF4/config.c @@ -28,6 +28,7 @@ #include "drivers/sensor.h" #include "drivers/pwm_esc_detect.h" #include "drivers/pwm_output.h" +#include "drivers/pwm_mapping.h" #include "drivers/serial.h" #include "fc/rc_controls.h" @@ -52,4 +53,8 @@ void targetConfiguration(void) { serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].functionMask = FUNCTION_MSP; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM1))->outputMode = OUTPUT_MODE_MOTORS; + timerOverridesMutable(timer2id(TIM2))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/SPEEDYBEEF7MINI/config.c b/src/main/target/SPEEDYBEEF7MINI/config.c index 1e69aaa33c..3fa87ce9b2 100644 --- a/src/main/target/SPEEDYBEEF7MINI/config.c +++ b/src/main/target/SPEEDYBEEF7MINI/config.c @@ -19,6 +19,8 @@ #include "platform.h" +#include "drivers/pwm_mapping.h" + #include "fc/fc_msp_box.h" #include "io/piniobox.h" @@ -30,4 +32,7 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].msp_baudrateIndex = BAUD_115200; pinioBoxConfigMutable()->permanentId[0] = BOXARM; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM4))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/SPEEDYBEEF7V2/config.c b/src/main/target/SPEEDYBEEF7V2/config.c index dccd2e8a04..2ce54488c0 100644 --- a/src/main/target/SPEEDYBEEF7V2/config.c +++ b/src/main/target/SPEEDYBEEF7V2/config.c @@ -24,6 +24,8 @@ #include "platform.h" +#include "drivers/pwm_output.h" + #include "fc/fc_msp_box.h" #include "io/piniobox.h" @@ -32,4 +34,7 @@ void targetConfiguration(void) { pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM3))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/SPRACINGF4EVO/config.c b/src/main/target/SPRACINGF4EVO/config.c index fa1e802297..66501624a8 100755 --- a/src/main/target/SPRACINGF4EVO/config.c +++ b/src/main/target/SPRACINGF4EVO/config.c @@ -29,4 +29,7 @@ void targetConfiguration(void) barometerConfigMutable()->baro_hardware = BARO_BMP280; serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So SPRacingF3OSD users don't have to change anything. serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM1))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/SPRACINGF4EVO/target.c b/src/main/target/SPRACINGF4EVO/target.c index da49369295..deabe8665d 100755 --- a/src/main/target/SPRACINGF4EVO/target.c +++ b/src/main/target/SPRACINGF4EVO/target.c @@ -26,21 +26,21 @@ timerHardware_t timerHardware[] = DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM | TIM_USE_PWM, 0, 0), // PPM / PWM1 / UART2 RX DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // PPM / PWM2 / UART2 TX - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // ESC 1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // ESC 2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 3 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // ESC 4 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 1), // ESC 1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 1), // ESC 2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // ESC 3 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // ESC 4 #if defined(SPRACINGF4EVO_REV) && (SPRACINGF4EVO_REV >= 2) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 5 / Conflicts with USART5_RX / SPI3_RX - SPI3_RX can be mapped to DMA1_ST3_CH0 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 6 / Conflicts with USART3_RX + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // ESC 5 / Conflicts with USART5_RX / SPI3_RX - SPI3_RX can be mapped to DMA1_ST3_CH0 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // ESC 6 / Conflicts with USART3_RX #else - DEF_TIM(TIM10, CH1, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 5 - DEF_TIM(TIM11, CH1, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 6 + DEF_TIM(TIM10, CH1, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // ESC 5 + DEF_TIM(TIM11, CH1, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // ESC 6 #endif - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 7 // used to be fw motor - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // ESC 8 // used to be fw motor + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // ESC 7 // used to be fw motor + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // ESC 8 // used to be fw motor DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), // LED Strip }; From 66bf932e58eb1bd74c1ff4217536f7715e7f979b Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 23 Sep 2023 12:30:25 +0200 Subject: [PATCH 077/122] Fix includes --- src/main/target/SPEEDYBEEF7V2/config.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/SPEEDYBEEF7V2/config.c b/src/main/target/SPEEDYBEEF7V2/config.c index 2ce54488c0..c653b78b29 100644 --- a/src/main/target/SPEEDYBEEF7V2/config.c +++ b/src/main/target/SPEEDYBEEF7V2/config.c @@ -24,7 +24,7 @@ #include "platform.h" -#include "drivers/pwm_output.h" +#include "drivers/pwm_mapping.h" #include "fc/fc_msp_box.h" From 28751c2ddb481a3c11cdab4c4e9e393957cd3365 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 23 Sep 2023 12:39:26 +0200 Subject: [PATCH 078/122] Fix target build --- src/main/target/SPRACINGF4EVO/config.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/target/SPRACINGF4EVO/config.c b/src/main/target/SPRACINGF4EVO/config.c index 66501624a8..31e6b2d0fd 100755 --- a/src/main/target/SPRACINGF4EVO/config.c +++ b/src/main/target/SPRACINGF4EVO/config.c @@ -23,6 +23,7 @@ #include "io/serial.h" #include "sensors/barometer.h" #include "telemetry/telemetry.h" +#include "drivers/pwm_mapping.h" void targetConfiguration(void) { @@ -31,5 +32,5 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; // To improve backwards compatibility with INAV versions 6.x and older - timerOverridesMutable(timer2id(TIM1))->outputMode = OUTPUT_MODE_MOTORS; + timerOverridesMutable(timer2id(TIM3))->outputMode = OUTPUT_MODE_MOTORS; } From 8328870a454bddb3b13aa6770b49c18821677b09 Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 23 Sep 2023 22:09:28 +0900 Subject: [PATCH 079/122] minor fix --- docs/MixerProfile.md | 2 +- src/main/flight/mixer_profile.c | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/docs/MixerProfile.md b/docs/MixerProfile.md index cbb9bcba22..f6688feaee 100644 --- a/docs/MixerProfile.md +++ b/docs/MixerProfile.md @@ -106,7 +106,7 @@ Profile files Switching is not available until the runtime sensor calibration is `mixer_profile` 1 will be used as default, `mixer_profile` 2 will be used when the `MIXER PROFILE 2` mode box is activated. Once successfully set, you can see the profiles / model preview etc. will switch accordingly when you view the relevant INAV Configurator tabs. Checking these tabs in the INAV Configurator will help make the setup easier. -Set `MIXER TRANSITION` accordingly when you want to use `MIXER TRANSITION` input for motors and servos, Here is sample of using the `MIXER TRANSITION` mode: +Set `MIXER TRANSITION` accordingly when you want to use `MIXER TRANSITION` input for motors and servos. Here is sample of using the `MIXER TRANSITION` mode: ![Alt text](Screenshots/mixer_profile.png) diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 5010b65031..3b0b1fd18f 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -189,7 +189,9 @@ void outputProfileUpdateTask(timeUs_t currentTimeUs) // transition mode input for servo mix and motor mix if (!FLIGHT_MODE(FAILSAFE_MODE) && (!mixerAT_inuse)) { - outputProfileHotSwitch((int)IS_RC_MODE_ACTIVE(BOXMIXERPROFILE)); + if (isModeActivationConditionPresent(BOXMIXERPROFILE)){ + outputProfileHotSwitch(IS_RC_MODE_ACTIVE(BOXMIXERPROFILE) == 0 ? 0 : 1); + } isMixerTransitionMixing_requested = IS_RC_MODE_ACTIVE(BOXMIXERTRANSITION); } isMixerTransitionMixing = isMixerTransitionMixing_requested && ((posControl.navState == NAV_STATE_IDLE) || mixerAT_inuse ||(posControl.navState == NAV_STATE_ALTHOLD_IN_PROGRESS)); From 0e93fce97fde139b117863eb4ada718a0989a11d Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 23 Sep 2023 23:21:24 +0900 Subject: [PATCH 080/122] Revert "refactoring" This reverts commit 1d0d5be21ef932b0848f1e04074aba427bcc9f23. --- src/main/flight/servos.c | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index fc0147ca3a..4d4bb497d1 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -104,6 +104,7 @@ int16_t servo[MAX_SUPPORTED_SERVOS]; static uint8_t servoRuleCount = 0; 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 servoOutputEnabled; static bool mixerUsesServos; @@ -193,7 +194,7 @@ void loadCustomServoMixer(void) } memcpy(¤tServoMixer[servoRuleCount], &tmp_customServoMixers[i], sizeof(servoMixer_t)); - currentServoMixer[servoRuleCount].rate = (j==currentMixerProfileIndex) ? currentServoMixer[servoRuleCount].rate : 0; //set rate to 0 if not active profile + currentServoMixerActivative[servoRuleCount] = j==currentMixerProfileIndex; servoRuleCount++; } } @@ -352,6 +353,9 @@ 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 @@ -434,7 +438,7 @@ void processServoAutotrimMode(void) if (ARMING_FLAG(ARMED)) { for (int axis = FD_ROLL; axis <= FD_YAW; axis++) { for (int i = 0; i < servoRuleCount; i++) { - if (currentServoMixer[i].rate==0) {continue;} + if (!currentServoMixerActivative[i]) {continue;} // Reset servo middle accumulator const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; @@ -457,7 +461,7 @@ void processServoAutotrimMode(void) if (ARMING_FLAG(ARMED)) { for (int axis = FD_ROLL; axis <= FD_YAW; axis++) { for (int i = 0; i < servoRuleCount; i++) { - if (currentServoMixer[i].rate==0) {continue;} + if (!currentServoMixerActivative[i]) {continue;} const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; if (source == axis) { @@ -470,7 +474,7 @@ 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 (currentServoMixer[i].rate==0) {continue;} + if (!currentServoMixerActivative[i]) {continue;} const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; if (source == axis) { @@ -504,7 +508,7 @@ 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 (currentServoMixer[i].rate==0) {continue;} + if (!currentServoMixerActivative[i]) {continue;} const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; if (source == axis) { From bce692e94e5d89617c6cc33629e5bda09b725759 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 00:19:28 +0200 Subject: [PATCH 081/122] Update target pwm mapping --- src/main/target/FLYCOLORF7MINI/target.c | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/target/FLYCOLORF7MINI/target.c b/src/main/target/FLYCOLORF7MINI/target.c index dec2cf1aee..411a4fbe40 100644 --- a/src/main/target/FLYCOLORF7MINI/target.c +++ b/src/main/target/FLYCOLORF7MINI/target.c @@ -29,12 +29,12 @@ 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(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // WS2812B }; From f434ff9c73922189baa6b0481ed88347a8bdcc6a Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 00:29:40 +0200 Subject: [PATCH 082/122] AIO, only motors --- src/main/target/GEPRC_F722_AIO/target.c | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/target/GEPRC_F722_AIO/target.c b/src/main/target/GEPRC_F722_AIO/target.c index b3f66b5ab8..a8ee276fce 100644 --- a/src/main/target/GEPRC_F722_AIO/target.c +++ b/src/main/target/GEPRC_F722_AIO/target.c @@ -27,14 +27,14 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), + DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), + DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); From 117c83156364d27f4a2720456375dac9d87b0af6 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 00:33:05 +0200 Subject: [PATCH 083/122] Match fw config --- src/main/target/HGLRCF722/config.c | 38 ++++++++++++------------------ 1 file changed, 15 insertions(+), 23 deletions(-) diff --git a/src/main/target/HGLRCF722/config.c b/src/main/target/HGLRCF722/config.c index 4f04f3b4aa..912c662d05 100644 --- a/src/main/target/HGLRCF722/config.c +++ b/src/main/target/HGLRCF722/config.c @@ -1,37 +1,29 @@ /* - * This file is part of INAV Project. + * This file is part of INAV. * - * 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/. + * 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. * - * 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. + * 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 this program. If not, see http://www.gnu.org/licenses/. + * along with INAV. If not, see . */ +#include #include -#include "platform.h" +#include -#include "fc/fc_msp_box.h" - -#include "io/piniobox.h" +#include "drivers/pwm_mapping.h" void targetConfiguration(void) { - pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; - pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM4))->outputMode = OUTPUT_MODE_MOTORS; } From cacfa913fcd2bf2703d82bcf339e1048c5560329 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 00:37:31 +0200 Subject: [PATCH 084/122] Update config.c --- src/main/target/HGLRCF722/config.c | 37 ++++++++++++++++++++---------- 1 file changed, 25 insertions(+), 12 deletions(-) diff --git a/src/main/target/HGLRCF722/config.c b/src/main/target/HGLRCF722/config.c index 912c662d05..fd3d57037b 100644 --- a/src/main/target/HGLRCF722/config.c +++ b/src/main/target/HGLRCF722/config.c @@ -1,29 +1,42 @@ /* - * This file is part of INAV. + * This file is part of INAV Project. * - * 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. + * 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/. * - * 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. + * 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 INAV. If not, see . + * along with this program. If not, see http://www.gnu.org/licenses/. */ -#include #include -#include +#include "platform.h" #include "drivers/pwm_mapping.h" +#include "fc/fc_msp_box.h" + +#include "io/piniobox.h" + void targetConfiguration(void) { + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; + // To improve backwards compatibility with INAV versions 6.x and older timerOverridesMutable(timer2id(TIM4))->outputMode = OUTPUT_MODE_MOTORS; } From 9c153bd0e5934d965b10d7e1f326f39e01188b23 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 00:39:06 +0200 Subject: [PATCH 085/122] Update config.c --- src/main/target/IFLIGHTF7_TWING/config.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/IFLIGHTF7_TWING/config.c b/src/main/target/IFLIGHTF7_TWING/config.c index c77bbfaf3a..912c662d05 100644 --- a/src/main/target/IFLIGHTF7_TWING/config.c +++ b/src/main/target/IFLIGHTF7_TWING/config.c @@ -25,5 +25,5 @@ void targetConfiguration(void) { // To improve backwards compatibility with INAV versions 6.x and older - timerOverridesMutable(timer2id(TIM3))->outputMode = OUTPUT_MODE_MOTORS; + timerOverridesMutable(timer2id(TIM4))->outputMode = OUTPUT_MODE_MOTORS; } From 589abe0651d8b8548ed941a3f384beecc4aaad53 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 00:39:55 +0200 Subject: [PATCH 086/122] Update target.c --- src/main/target/IFLIGHTF7_TWING/target.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/target/IFLIGHTF7_TWING/target.c b/src/main/target/IFLIGHTF7_TWING/target.c index 0412eba102..6876f07b20 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.c +++ b/src/main/target/IFLIGHTF7_TWING/target.c @@ -37,11 +37,11 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // used to be fw motor + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // used to be fw motor - DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // used to be fw motor - DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // used to be fw motor + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), }; From 241e94d4c20a1292fd2e83b05e169b6e2902b609 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 00:47:58 +0200 Subject: [PATCH 087/122] Update config.c --- src/main/target/MAMBAF405_2022A/config.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/target/MAMBAF405_2022A/config.c b/src/main/target/MAMBAF405_2022A/config.c index d632230c24..ba3a5344c2 100644 --- a/src/main/target/MAMBAF405_2022A/config.c +++ b/src/main/target/MAMBAF405_2022A/config.c @@ -57,4 +57,7 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BAUD_115200; + + // To improve backwards compatibility with INAV versions 6.x and older + timerOverridesMutable(timer2id(TIM3))->outputMode = OUTPUT_MODE_MOTORS; } From 963a0051e8a597345055d06b1c4e98ba03606804 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 00:49:34 +0200 Subject: [PATCH 088/122] Update target.c --- src/main/target/MAMBAF722_2022A/target.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/target/MAMBAF722_2022A/target.c b/src/main/target/MAMBAF722_2022A/target.c index 1b41cb437e..f1e2f5e4db 100644 --- a/src/main/target/MAMBAF722_2022A/target.c +++ b/src/main/target/MAMBAF722_2022A/target.c @@ -32,10 +32,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3 DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S6 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S8 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; From 8cf5292abcc3d40d5929333ded6aa0b9474db435 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 00:50:34 +0200 Subject: [PATCH 089/122] Update target.c --- src/main/target/MAMBAF722_WING/target.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/target/MAMBAF722_WING/target.c b/src/main/target/MAMBAF722_WING/target.c index c25d866183..4b0925d9fb 100644 --- a/src/main/target/MAMBAF722_WING/target.c +++ b/src/main/target/MAMBAF722_WING/target.c @@ -30,10 +30,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3 DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S6 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0 ), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S8 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; From 941d407c7bda45ea4ccea7b5e25f6975a15fecb9 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 00:53:18 +0200 Subject: [PATCH 090/122] Update target.c --- src/main/target/MATEKF405TE/target.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/target/MATEKF405TE/target.c b/src/main/target/MATEKF405TE/target.c index 03d6933676..dc97455388 100644 --- a/src/main/target/MATEKF405TE/target.c +++ b/src/main/target/MATEKF405TE/target.c @@ -35,9 +35,9 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 D(1,6,3) UP173 DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 D(1,5,3) UP173 - DEF_TIM(TIM12, CH1, PB14, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S9 DMA NONE - DEF_TIM(TIM13, CH1, PA6, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S10 DMA NONE - DEF_TIM(TIM4, CH1, PB6, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S11 D(1,0,2) + DEF_TIM(TIM12, CH1, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9 DMA NONE + DEF_TIM(TIM13, CH1, PA6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 DMA NONE + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S11 D(1,0,2) DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), // 2812LED D(1,2,5) DEF_TIM(TIM11, CH1, PB9, TIM_USE_BEEPER, 0, 0), // BEEPER PWM From 113a9202914b6261a72cf21ea91f9a8f16990ce3 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 00:54:15 +0200 Subject: [PATCH 091/122] Update target.c --- src/main/target/MATEKF411/target.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/target/MATEKF411/target.c b/src/main/target/MATEKF411/target.c index b496a64eaa..2aae59cdf0 100755 --- a/src/main/target/MATEKF411/target.c +++ b/src/main/target/MATEKF411/target.c @@ -30,9 +30,9 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 D(1,0,2) DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 D(1,3,2) - DEF_TIM(TIM2, CH2, PB3, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S5 D(1,6,3) - DEF_TIM(TIM2, CH3, PB10, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S6 D(1,1,3) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S7 D(1,5,3) - clash with S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 D(1,6,3) + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(1,1,3) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 D(1,5,3) - clash with S2 DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), //softserial_tx2 - 2812LED TIM_USE_LED D(2,1,6) DEF_TIM(TIM5, CH1, PA0, TIM_USE_PPM, 0, 0), //use rssi pad for PPM/softserial_tx1 From 4882ab83567f62a0266c2642d1ba6b53102c585e Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 00:54:58 +0200 Subject: [PATCH 092/122] Update target.c --- src/main/target/MATEKF411SE/target.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/MATEKF411SE/target.c b/src/main/target/MATEKF411SE/target.c index 97184fe611..c47706b051 100755 --- a/src/main/target/MATEKF411SE/target.c +++ b/src/main/target/MATEKF411SE/target.c @@ -30,7 +30,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4 D(2,2,6) DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S5 D(2,6,6) #ifndef MATEKF411SE_SS2_CH6 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S6 D(1,7,2) + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(1,7,2) DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 pad - softserial_tx2 #else From ce884f0b4b89a2023102e35b2987784150a56e9d Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 01:00:46 +0200 Subject: [PATCH 093/122] Update target.c --- src/main/target/MATEKF765/target.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/target/MATEKF765/target.c b/src/main/target/MATEKF765/target.c index e91c644147..0754f8a864 100644 --- a/src/main/target/MATEKF765/target.c +++ b/src/main/target/MATEKF765/target.c @@ -42,10 +42,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP(1,2), D(1,7,5)** DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP(1,2), D(1,2,5) - DEF_TIM(TIM4, CH1, PD12, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S7 UP(1,6), D(1,0,2)* - DEF_TIM(TIM4, CH2, PD13, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S8 UP(1,6), D(1,3,2) - DEF_TIM(TIM4, CH3, PD14, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S9 UP(1,6), D(1,7,2)** - DEF_TIM(TIM4, CH4, PD15, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S10 UP(1,6) + DEF_TIM(TIM4, CH1, PD12, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 UP(1,6), D(1,0,2)* + DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 UP(1,6), D(1,3,2) + DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9 UP(1,6), D(1,7,2)** + DEF_TIM(TIM4, CH4, PD15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 UP(1,6) DEF_TIM(TIM9, CH1, PE5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S11 DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S12 From 556b7d613764a8c7bdbd3028b1c6d80bda0587fd Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 01:05:14 +0200 Subject: [PATCH 094/122] Update config.c --- src/main/target/RUSH_BLADE_F7/config.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/RUSH_BLADE_F7/config.c b/src/main/target/RUSH_BLADE_F7/config.c index d5a1430721..2d85f71ed7 100644 --- a/src/main/target/RUSH_BLADE_F7/config.c +++ b/src/main/target/RUSH_BLADE_F7/config.c @@ -26,5 +26,5 @@ void targetConfiguration(void) { // To improve backwards compatibility with INAV versions 6.x and older // Keeps m1-m4 on first 4 outputs in mc, otherwise would be s1, s2, s5, s6 - timerOverridesMutable(timer2id(TIM3))->outputMode = OUTPUT_MODE_MOTORS; + timerOverridesMutable(timer2id(TIM8))->outputMode = OUTPUT_MODE_MOTORS; } From 809f8192310282ac85b84aae065b6c5f5a4c17eb Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 01:06:24 +0200 Subject: [PATCH 095/122] Config.c not needed --- src/main/target/RUSH_BLADE_F7/config.c | 30 -------------------------- 1 file changed, 30 deletions(-) delete mode 100644 src/main/target/RUSH_BLADE_F7/config.c diff --git a/src/main/target/RUSH_BLADE_F7/config.c b/src/main/target/RUSH_BLADE_F7/config.c deleted file mode 100644 index 2d85f71ed7..0000000000 --- a/src/main/target/RUSH_BLADE_F7/config.c +++ /dev/null @@ -1,30 +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 - -#include "drivers/pwm_mapping.h" - -void targetConfiguration(void) -{ - // To improve backwards compatibility with INAV versions 6.x and older - // Keeps m1-m4 on first 4 outputs in mc, otherwise would be s1, s2, s5, s6 - timerOverridesMutable(timer2id(TIM8))->outputMode = OUTPUT_MODE_MOTORS; -} From 5ab025b6dad6aaeb5e4826cd79c19efa60c13079 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 12:26:14 +0200 Subject: [PATCH 096/122] TIM_USE_OUTPUT_AUTO instead of TIM_USE_MOTOR | TIM_USE_SERVO --- src/main/target/AIRBOTF4/target.c | 20 +++++----- src/main/target/AIRBOTF7/target.c | 8 ++-- src/main/target/ALIENFLIGHTF4/target.c | 16 ++++---- src/main/target/ALIENFLIGHTNGF7/target.c | 24 +++++------ src/main/target/ANYFC/target.c | 20 +++++----- src/main/target/ANYFCF7/target.c | 24 +++++------ src/main/target/AOCODARCF405AIO/target.c | 8 ++-- src/main/target/AOCODARCF4V2/target.c | 16 ++++---- src/main/target/AOCODARCF7DUAL/target.c | 8 ++-- src/main/target/AOCODARCF7MINI/target.c | 18 ++++----- src/main/target/AOCODARCH7DUAL/target.c | 20 +++++----- src/main/target/ATOMRCF405NAVI/target.c | 16 ++++---- src/main/target/AXISFLYINGF7PRO/target.c | 12 +++--- src/main/target/BEEROTORF4/target.c | 16 ++++---- src/main/target/BETAFLIGHTF4/target.c | 8 ++-- src/main/target/BETAFPVF435/target.c | 4 +- src/main/target/BETAFPVF722/target.c | 4 +- src/main/target/BLACKPILL_F411/target.c | 12 +++--- src/main/target/BLUEJAYF4/target.c | 14 +++---- src/main/target/COLIBRI/target.c | 16 ++++---- src/main/target/DALRCF405/target.c | 14 +++---- src/main/target/F4BY/target.c | 16 ++++---- src/main/target/FF_F35_LIGHTNING/target.c | 12 +++--- src/main/target/FF_FORTINIF4/target.c | 8 ++-- src/main/target/FF_PIKOF4/target.c | 20 +++++----- src/main/target/FISHDRONEF4/target.c | 12 +++--- src/main/target/FLYWOOF411/target.c | 14 +++---- src/main/target/FLYWOOF745/target.c | 12 +++--- src/main/target/FLYWOOF7DUAL/target.c | 12 +++--- src/main/target/FOXEERH743/target.c | 8 ++-- src/main/target/FRSKYF4/target.c | 12 +++--- src/main/target/FRSKYPILOT/target.c | 24 +++++------ src/main/target/FURYF4OSD/target.c | 8 ++-- src/main/target/GEPRCF405/target.c | 12 +++--- src/main/target/GEPRCF722/target.c | 12 +++--- src/main/target/HAKRCF405V2/target.c | 16 ++++---- src/main/target/HAKRCF411D/target.c | 8 ++-- src/main/target/HAKRCF722V2/target.c | 16 ++++---- src/main/target/HAKRCKD722/target.c | 16 ++++---- src/main/target/HGLRCF722/target.c | 16 ++++---- src/main/target/IFLIGHTF4_TWING/target.c | 8 ++-- src/main/target/IFLIGHT_BLITZ_F722/target.c | 16 ++++---- src/main/target/IFLIGHT_BLITZ_F7_AIO/target.c | 12 +++--- src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c | 16 ++++---- src/main/target/IFLIGHT_JBF7PRO/target.c | 16 ++++---- src/main/target/KAKUTEF4/target.c | 18 ++++----- src/main/target/KAKUTEF7/target.c | 12 +++--- src/main/target/KAKUTEF7MINIV3/target.c | 10 ++--- src/main/target/KAKUTEH7/target.c | 8 ++-- src/main/target/KAKUTEH7WING/target.c | 24 +++++------ src/main/target/MAMBAF405US/target.c | 16 ++++---- src/main/target/MAMBAF405_2022A/target.c | 12 +++--- src/main/target/MAMBAF722/target.c | 8 ++-- src/main/target/MAMBAF722_2022A/target.c | 16 ++++---- src/main/target/MAMBAF722_WING/target.c | 16 ++++---- src/main/target/MAMBAF722_X8/target.c | 16 ++++---- src/main/target/MATEKF411/target.c | 14 +++---- src/main/target/MATEKF411SE/target.c | 12 +++--- src/main/target/MATEKF411TE/target.c | 12 +++--- src/main/target/MATEKF722PX/target.c | 20 +++++----- src/main/target/MATEKF765/target.c | 24 +++++------ src/main/target/NEUTRONRCF435SE/target.c | 16 ++++---- src/main/target/NEUTRONRCF435WING/target.c | 16 ++++---- src/main/target/NEUTRONRCH7BT/target.c | 16 ++++---- src/main/target/NOX/target.c | 8 ++-- src/main/target/OMNIBUSF4/target.c | 20 +++++----- src/main/target/RADIX/target.c | 12 +++--- src/main/target/REVO/target.c | 20 +++++----- src/main/target/SAGEATF4/target.c | 16 ++++---- src/main/target/SKYSTARSH743HD/target.c | 16 ++++---- src/main/target/SPARKY2/target.c | 12 +++--- src/main/target/SPEEDYBEEF4/target.c | 14 +++---- src/main/target/SPEEDYBEEF405MINI/target.c | 4 +- src/main/target/SPEEDYBEEF405V3/target.c | 16 ++++---- src/main/target/SPEEDYBEEF7/target.c | 12 +++--- src/main/target/SPEEDYBEEF7MINI/target.c | 16 ++++---- src/main/target/SPEEDYBEEF7V2/target.c | 8 ++-- src/main/target/SPEEDYBEEF7V3/target.c | 16 ++++---- src/main/target/TMOTORF7/target.c | 12 +++--- src/main/target/TMOTORF7V2/target.c | 16 ++++---- src/main/target/YUPIF4/target.c | 16 ++++---- src/main/target/YUPIF7/target.c | 12 +++--- src/main/target/ZEEZF7/target.c | 40 +++++++++---------- 83 files changed, 596 insertions(+), 596 deletions(-) diff --git a/src/main/target/AIRBOTF4/target.c b/src/main/target/AIRBOTF4/target.c index b2263a6805..988543aa32 100644 --- a/src/main/target/AIRBOTF4/target.c +++ b/src/main/target/AIRBOTF4/target.c @@ -24,20 +24,20 @@ #include "drivers/bus.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT D1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT D1_ST2 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3_OUT D1_ST6 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT D1_ST1 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_ANY, 0, 0), // S5_OUT / LED - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT D1_ST2 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3_OUT D1_ST6 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO | TIM_USE_ANY, 0, 0), // S5_OUT / LED + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED | TIM_USE_ANY, 0, 0), // LED D1_ST0, n/a on older AIRBOTF4 DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // PPM (5th pin on FlexiIO port) DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN - DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_IN - DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_IN - DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_IN + DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S3_IN + DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S4_IN + DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S5_IN + DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S6_IN }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AIRBOTF7/target.c b/src/main/target/AIRBOTF7/target.c index 4acf3ddca8..22d2564821 100644 --- a/src/main/target/AIRBOTF7/target.c +++ b/src/main/target/AIRBOTF7/target.c @@ -45,10 +45,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // Cam control, SS, UNUSED - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), //S1 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), //S2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), //S3 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), //S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), //S1 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), //S2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), //S3 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), //S4 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/ALIENFLIGHTF4/target.c b/src/main/target/ALIENFLIGHTF4/target.c index 1943fd46f4..e7ee4cf552 100644 --- a/src/main/target/ALIENFLIGHTF4/target.c +++ b/src/main/target/ALIENFLIGHTF4/target.c @@ -28,14 +28,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0, 0), // PWM3 - PB1 RC3 - DMA1_ST7 DEF_TIM(TIM1, CH2, PB14, TIM_USE_PWM, 0, 1), // PWM4 - PA14 RC4 - DMA2_ST2 DEF_TIM(TIM1, CH3, PB15, TIM_USE_PWM | TIM_USE_LED, 0, 0), // PWM5 - PA15 RC5 - DMA2_ST6 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM6 - PB8 OUT1 - DMA1_ST7 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM7 - PB9 OUT2 - DMA_NONE - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM8 - PA0 OUT3 - DMA1_ST2 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM9 - PA1 OUT4 - DMA1_ST4 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM10 - PC6 OUT5 - DMA2_ST2 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM11 - PC7 OUT6 - DMA2_ST3 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // PWM13 - PC8 OUT7 - DMA2_ST4 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM13 - PC9 OUT8 - DMA2_ST7 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM6 - PB8 OUT1 - DMA1_ST7 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM7 - PB9 OUT2 - DMA_NONE + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM8 - PA0 OUT3 - DMA1_ST2 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM9 - PA1 OUT4 - DMA1_ST4 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM10 - PC6 OUT5 - DMA2_ST2 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM11 - PC7 OUT6 - DMA2_ST3 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // PWM13 - PC8 OUT7 - DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM13 - PC9 OUT8 - DMA2_ST7 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/ALIENFLIGHTNGF7/target.c b/src/main/target/ALIENFLIGHTNGF7/target.c index 607f3150f4..455747923e 100644 --- a/src/main/target/ALIENFLIGHTNGF7/target.c +++ b/src/main/target/ALIENFLIGHTNGF7/target.c @@ -24,18 +24,18 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM | TIM_USE_LED, 0, 1), // PPM - DMA2_ST1 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM1 - DMA2_ST2 - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM2 - DMA1_ST5 - DEF_TIM(TIM8, CH2N, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM3 - DMA2_ST3 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM4 - DMA1_ST7 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM5 - DMA1_ST2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM6 - DMA2_ST4 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM7 - DMA1_ST4 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM8 - DMA2_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM9 - DMA1_ST2 - DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM10 - DMA2_ST6 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM11 - DMA1_ST7 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // PWM12 - DMA_NONE + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM1 - DMA2_ST2 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM2 - DMA1_ST5 + DEF_TIM(TIM8, CH2N, PB14, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM3 - DMA2_ST3 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM4 - DMA1_ST7 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM5 - DMA1_ST2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM6 - DMA2_ST4 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM7 - DMA1_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM8 - DMA2_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM9 - DMA1_ST2 + DEF_TIM(TIM1, CH3N, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM10 - DMA2_ST6 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM11 - DMA1_ST7 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // PWM12 - DMA_NONE }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/ANYFC/target.c b/src/main/target/ANYFC/target.c index 9275c14d28..5353b58911 100644 --- a/src/main/target/ANYFC/target.c +++ b/src/main/target/ANYFC/target.c @@ -30,16 +30,16 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0), // S6_IN DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0), // S5_IN - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10_OUT 16 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT 12 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT 11 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT 7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT 8 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT 9 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT 10 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7_OUT 13 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8_OUT 14 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9_OUT 15 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S10_OUT 16 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT 12 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT 11 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT 7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT 8 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT 9 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT 10 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S7_OUT 13 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S8_OUT 14 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S9_OUT 15 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/ANYFCF7/target.c b/src/main/target/ANYFCF7/target.c index 56463c0b8c..21c0acbfea 100644 --- a/src/main/target/ANYFCF7/target.c +++ b/src/main/target/ANYFCF7/target.c @@ -25,21 +25,21 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN - DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_IN DMA2_ST2 DMA2_ST2 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4_IN DMA2_ST3 DMA2_ST2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6_IN DMA2_ST7 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_IN DMA2_ST2 DMA2_ST2 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4_IN DMA2_ST3 DMA2_ST2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_IN DMA2_ST7 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S10_OUT 1 DMA1_ST7 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6_OUT 2 DMA1_ST0 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_OUT + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S10_OUT 1 DMA1_ST7 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_OUT 2 DMA1_ST0 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5_OUT DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0 ), // S1_OUT 4 DMA1_ST1 DMA1_ST3 DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0 ), // S2_OUT 3 DMA1_ST4 - DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4_OUT DMA1_ST5 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S7_OUT DMA1_ST2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0 ), // S8_OUT DMA1_ST6 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S9_OUT DMA1_ST4 + DEF_TIM(TIM9, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_OUT + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4_OUT DMA1_ST5 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S7_OUT DMA1_ST2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO | TIM_USE_LED, 0, 0 ), // S8_OUT DMA1_ST6 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S9_OUT DMA1_ST4 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AOCODARCF405AIO/target.c b/src/main/target/AOCODARCF405AIO/target.c index f0612a7431..be225da1bf 100644 --- a/src/main/target/AOCODARCF405AIO/target.c +++ b/src/main/target/AOCODARCF405AIO/target.c @@ -30,10 +30,10 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_C timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH2, PA10, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 DEF_TIM(TIM1, CH3N, PB1, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/AOCODARCF4V2/target.c b/src/main/target/AOCODARCF4V2/target.c index db6130e9f3..8581cc5bf1 100644 --- a/src/main/target/AOCODARCF4V2/target.c +++ b/src/main/target/AOCODARCF4V2/target.c @@ -27,16 +27,16 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S6 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S6 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S7 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S8 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S7 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S8 DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0 ), // LED_STRIP diff --git a/src/main/target/AOCODARCF7DUAL/target.c b/src/main/target/AOCODARCF7DUAL/target.c index ea76079ecf..99494e94dd 100644 --- a/src/main/target/AOCODARCF7DUAL/target.c +++ b/src/main/target/AOCODARCF7DUAL/target.c @@ -32,10 +32,10 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), //PPM - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(2, 2, 7) - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(2, 3, 7) - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 D(2, 4, 7) - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 D(2, 7, 7) + DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(2, 2, 7) + DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(2, 3, 7) + DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 D(2, 4, 7) + DEF_TIM(TIM3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 D(2, 7, 7) DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MOTOR |TIM_USE_SERVO, 0, 0), // S5 D(1, 7, 5) DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MOTOR |TIM_USE_SERVO, 0, 0), // S6 D(1, 2, 5) diff --git a/src/main/target/AOCODARCF7MINI/target.c b/src/main/target/AOCODARCF7MINI/target.c index 7e55ab5e9c..34360bbc03 100644 --- a/src/main/target/AOCODARCF7MINI/target.c +++ b/src/main/target/AOCODARCF7MINI/target.c @@ -39,20 +39,20 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), // PPM, RX1 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(1, 4, 5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(1, 5, 4) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 D(1, 2, 5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(1, 5, 4) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 D(1, 2, 5) #if defined(AOCODARCF7MINI_V2) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 D(2, 4, 7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(2, 7, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(2, 4, 7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(2, 7, 7) #else - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(1, 6, 3) + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(1, 6, 3) #endif - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 D(1, 0, 2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 D(1, 3, 2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 D(1, 3, 2) DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED diff --git a/src/main/target/AOCODARCH7DUAL/target.c b/src/main/target/AOCODARCH7DUAL/target.c index 055581a59e..586f832648 100644 --- a/src/main/target/AOCODARCH7DUAL/target.c +++ b/src/main/target/AOCODARCH7DUAL/target.c @@ -32,18 +32,18 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270_2, DEVHW_BMI270, BMI270_SPI_BUS timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_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(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 4), // S5 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 5), // S6 - DEF_TIM(TIM4, CH1, PD12, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 6), // S7 - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 7), // S8 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9 - DEF_TIM(TIM4, CH4, PD15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 DMA_NONE + DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 + DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 DMA_NONE DEF_TIM(TIM15, CH1, PE5, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S11 DEF_TIM(TIM15, CH2, PE6, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S12 DMA_NONE diff --git a/src/main/target/ATOMRCF405NAVI/target.c b/src/main/target/ATOMRCF405NAVI/target.c index 0e6a22916e..7ff7ac3c39 100644 --- a/src/main/target/ATOMRCF405NAVI/target.c +++ b/src/main/target/ATOMRCF405NAVI/target.c @@ -34,14 +34,14 @@ #include "drivers/sensor.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED_STRIP }; diff --git a/src/main/target/AXISFLYINGF7PRO/target.c b/src/main/target/AXISFLYINGF7PRO/target.c index f0a1d9e972..5b066ec2b8 100644 --- a/src/main/target/AXISFLYINGF7PRO/target.c +++ b/src/main/target/AXISFLYINGF7PRO/target.c @@ -25,12 +25,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // S1 DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // S2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S7 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 1), // S7 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM diff --git a/src/main/target/BEEROTORF4/target.c b/src/main/target/BEEROTORF4/target.c index 78c7ef387e..28e6a77402 100644 --- a/src/main/target/BEEROTORF4/target.c +++ b/src/main/target/BEEROTORF4/target.c @@ -26,14 +26,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN - DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M1 - DMAR: DMA2_ST5 - DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M2 - - DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M3 - DMAR: DMA1_ST7 - DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M4 - - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M5 - DMAR: DMA2_ST1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M6 - - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M7 - DMAR: DMA1_ST2 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M8 - DMAR: DMA1_ST6 + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // M1 - DMAR: DMA2_ST5 + DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // M2 - + DEF_TIM(TIM2, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // M3 - DMAR: DMA1_ST7 + DEF_TIM(TIM2, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // M4 - + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // M5 - DMAR: DMA2_ST1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // M6 - + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // M7 - DMAR: DMA1_ST2 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // M8 - DMAR: DMA1_ST6 DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, 0, 0), // LED_STRIP / TRANSPONDER - DMA1_ST7 }; diff --git a/src/main/target/BETAFLIGHTF4/target.c b/src/main/target/BETAFLIGHTF4/target.c index 4bc7863386..0e10cdbf59 100755 --- a/src/main/target/BETAFLIGHTF4/target.c +++ b/src/main/target/BETAFLIGHTF4/target.c @@ -27,10 +27,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH3, PB8, TIM_USE_PPM, 0, 0), // PPM // Motors - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT D1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT D1_ST2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT D1_ST6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT D1_ST1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT D1_ST2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT D1_ST6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1 // LED strip DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // D1_ST0 diff --git a/src/main/target/BETAFPVF435/target.c b/src/main/target/BETAFPVF435/target.c index fc15230f19..f065744029 100644 --- a/src/main/target/BETAFPVF435/target.c +++ b/src/main/target/BETAFPVF435/target.c @@ -35,8 +35,8 @@ timerHardware_t timerHardware[] = { DEF_TIM(TMR2, CH4, PA3, TIM_USE_MOTOR, 0, 7), // TMR2_CH4 motor 3 DEF_TIM(TMR2, CH3, PA2, TIM_USE_MOTOR, 0, 6), // TMR2_CH3 motor 4 - DEF_TIM(TMR8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_ANY, 0, 4), // TMR8_CH3 motor 5 - DEF_TIM(TMR1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_ANY, 0, 5), // TMR1_CH3 motor 6 + DEF_TIM(TMR8, CH3, PC8, TIM_USE_OUTPUT_AUTO | TIM_USE_ANY, 0, 4), // TMR8_CH3 motor 5 + DEF_TIM(TMR1, CH1, PA8, TIM_USE_OUTPUT_AUTO | TIM_USE_ANY, 0, 5), // TMR1_CH3 motor 6 DEF_TIM(TMR4, CH1, PB6, TIM_USE_LED, 0, 0), // TMR4_CH1 LED_STRIP }; diff --git a/src/main/target/BETAFPVF722/target.c b/src/main/target/BETAFPVF722/target.c index 5a2adfe8f4..e24689c0ca 100755 --- a/src/main/target/BETAFPVF722/target.c +++ b/src/main/target/BETAFPVF722/target.c @@ -32,9 +32,9 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 0, 0), // S3 D(2, 4, 7) DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR, 0, 0), // S4 D(2, 7, 7) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 DMA1_ST2 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 DMA1_ST2 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 DMA2_ST6 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 DMA2_ST6 DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), //camera diff --git a/src/main/target/BLACKPILL_F411/target.c b/src/main/target/BLACKPILL_F411/target.c index ff8fd54475..d36b8c19c2 100644 --- a/src/main/target/BLACKPILL_F411/target.c +++ b/src/main/target/BLACKPILL_F411/target.c @@ -24,12 +24,12 @@ #include "drivers/pinio.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(1,4,5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(1,5,5) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 D(2,1,6) - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4 D(2,2,6) - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S5 D(2,6,6) - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(1,7,2) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(1,4,5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(1,5,5) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 D(2,1,6) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), // S4 D(2,2,6) + DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 1), // S5 D(2,6,6) + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(1,7,2) DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 pad - softserial_tx2 diff --git a/src/main/target/BLUEJAYF4/target.c b/src/main/target/BLUEJAYF4/target.c index ebdc83a979..0b968380cf 100644 --- a/src/main/target/BLUEJAYF4/target.c +++ b/src/main/target/BLUEJAYF4/target.c @@ -25,13 +25,13 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT - DMA1_ST2 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT - DMA1_ST4 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT - DMA1_ST1 - DEF_TIM(TIM9, CH2, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4_OUT - no DMA - //DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4_OUT - DMA1_ST3 (Could be DMA1_ST1 with dmaopt=0) - DEF_TIM(TIM3, CH4, PB0, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0 ), // S5_OUT - DMA1_ST2 - DEF_TIM(TIM3, CH3, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6_OUT - DMA1_ST7 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1_OUT - DMA1_ST2 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT - DMA1_ST4 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_OUT - DMA1_ST1 + DEF_TIM(TIM9, CH2, PA3, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4_OUT - no DMA + //DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S4_OUT - DMA1_ST3 (Could be DMA1_ST1 with dmaopt=0) + DEF_TIM(TIM3, CH4, PB0, TIM_USE_OUTPUT_AUTO | TIM_USE_LED, 0, 0 ), // S5_OUT - DMA1_ST2 + DEF_TIM(TIM3, CH3, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_OUT - DMA1_ST7 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/COLIBRI/target.c b/src/main/target/COLIBRI/target.c index 79760b4cf0..932188992b 100755 --- a/src/main/target/COLIBRI/target.c +++ b/src/main/target/COLIBRI/target.c @@ -33,14 +33,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // S7_IN DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // S8_IN - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT - DEF_TIM(TIM10, CH1, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7_OUT - DEF_TIM(TIM11, CH1, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8_OUT + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT + DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT + DEF_TIM(TIM12, CH1, PB14, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT + DEF_TIM(TIM10, CH1, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7_OUT + DEF_TIM(TIM11, CH1, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // S8_OUT DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0) }; diff --git a/src/main/target/DALRCF405/target.c b/src/main/target/DALRCF405/target.c index 037f6772ce..5b82d861e1 100644 --- a/src/main/target/DALRCF405/target.c +++ b/src/main/target/DALRCF405/target.c @@ -24,14 +24,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 (1,7) - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 (2,2) - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 (2,6) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4 (2,1) (2.3 2.6) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S5 (2,4) (2.2) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 (1,7) + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 (2,2) + DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 (2,6) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S4 (2,1) (2.3 2.6) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S5 (2,4) (2.2) DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // S6 (1,2) - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S7 (2,3) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 (2,7) + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 1), // S7 (2,3) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 (2,7) DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED STRIP(1,0) DEF_TIM(TIM2, CH1, PA5, TIM_USE_ANY, 0, 0), // FC CAM diff --git a/src/main/target/F4BY/target.c b/src/main/target/F4BY/target.c index b2594e54ca..37d9db8941 100644 --- a/src/main/target/F4BY/target.c +++ b/src/main/target/F4BY/target.c @@ -15,14 +15,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH2, PD13, TIM_USE_PWM, 0, 0), // S7_IN DEF_TIM(TIM4, CH1, PD12, TIM_USE_PWM, 0, 0), // S8_IN - DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT - DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT - DEF_TIM(TIM1, CH3, PE13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7_OUT - DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8_OUT + DEF_TIM(TIM2, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT + DEF_TIM(TIM2, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT + DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT + DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT + DEF_TIM(TIM1, CH3, PE13, TIM_USE_OUTPUT_AUTO, 0, 0), // S7_OUT + DEF_TIM(TIM1, CH4, PE14, TIM_USE_OUTPUT_AUTO, 0, 0), // S8_OUT DEF_TIM(TIM9, CH2, PE6, TIM_USE_ANY, 0, 0), // sonar echo if needed }; diff --git a/src/main/target/FF_F35_LIGHTNING/target.c b/src/main/target/FF_F35_LIGHTNING/target.c index 92e86f45b3..83d75497e4 100644 --- a/src/main/target/FF_F35_LIGHTNING/target.c +++ b/src/main/target/FF_F35_LIGHTNING/target.c @@ -23,12 +23,12 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 1, 0), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 1, 0), + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 1, 0), + DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 1, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0), DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), DEF_TIM(TIM5, CH4, PA3, TIM_USE_ANY, 0, 0), diff --git a/src/main/target/FF_FORTINIF4/target.c b/src/main/target/FF_FORTINIF4/target.c index 90ea1edcc3..5853bc3139 100644 --- a/src/main/target/FF_FORTINIF4/target.c +++ b/src/main/target/FF_FORTINIF4/target.c @@ -23,10 +23,10 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0 ), // S1_OUT - DMA1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0 ), // S2_OUT - DMA1_ST2 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1 ), // S3_OUT - DMA1_ST6 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0 ), // S4_OUT - DMA1_ST1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0 ), // S1_OUT - DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0 ), // S2_OUT - DMA1_ST2 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 1, 1 ), // S3_OUT - DMA1_ST6 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 1, 0 ), // S4_OUT - DMA1_ST1 DEF_TIM(TIM4, CH4, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED - DMA1_ST3 }; diff --git a/src/main/target/FF_PIKOF4/target.c b/src/main/target/FF_PIKOF4/target.c index 5a2de8b8cb..581dcd588e 100644 --- a/src/main/target/FF_PIKOF4/target.c +++ b/src/main/target/FF_PIKOF4/target.c @@ -26,17 +26,17 @@ timerHardware_t timerHardware[] = { #if defined(FF_PIKOF4OSD) - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM3, CH3, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM3, CH4, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM3, CH3, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM3, CH4, PB0, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM12, CH1, PB14, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0 ), #else - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), #endif DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0 ), }; diff --git a/src/main/target/FISHDRONEF4/target.c b/src/main/target/FISHDRONEF4/target.c index a096896656..b0aec49bc4 100644 --- a/src/main/target/FISHDRONEF4/target.c +++ b/src/main/target/FISHDRONEF4/target.c @@ -30,12 +30,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH4, PB11, TIM_USE_PWM, 0, 0 ), DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM, 0, 0 ), - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM12, CH1, PB14, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0 ), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0 ), }; diff --git a/src/main/target/FLYWOOF411/target.c b/src/main/target/FLYWOOF411/target.c index ca5b5abfde..965974162b 100644 --- a/src/main/target/FLYWOOF411/target.c +++ b/src/main/target/FLYWOOF411/target.c @@ -27,19 +27,19 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH1, PA2, TIM_USE_PPM, 0, 0), // PPM IN #ifdef FLYWOOF411_V2 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1 - D(2,1) - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - D(1,6) - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - D(1,1) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - D(1,5) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S1 - D(2,1) + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 - D(1,6) + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 - D(1,1) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 - D(1,5) DEF_TIM(TIM4, CH1, PB6, TIM_USE_ANY, 0, 0), // SOFTSERIAL_1_TX_PIN - D(1,0) DEF_TIM(TIM4, CH2, PB7, TIM_USE_ANY, 0, 0), // SOFTSERIAL_1_RX_PIN - D(1,3) DEF_TIM(TIM3, CH3, PB0, TIM_USE_ANY, 0, 0), // RSSI_ADC_CHANNEL 1-7 DEF_TIM(TIM3, CH1, PB4, TIM_USE_ANY, 0, 0), // 1-4 DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, 0, 0), // LED 1,2 #else - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1_OUT 2,1 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2_OUT 2,2 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT 2,6 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S1_OUT 2,1 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), // S2_OUT 2,2 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT 2,6 DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR , 0, 0), // S4_OUT 1,7 DEF_TIM(TIM3, CH4, PB1, TIM_USE_ANY, 0, 0), // RSSI 1,2 diff --git a/src/main/target/FLYWOOF745/target.c b/src/main/target/FLYWOOF745/target.c index ebc20d52ec..22f2d12a53 100644 --- a/src/main/target/FLYWOOF745/target.c +++ b/src/main/target/FLYWOOF745/target.c @@ -34,12 +34,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // M1 , DMA1_ST7 DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // M2 , DMA1_ST2 - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // M3 , DMA2_ST2 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // M4 , DMA2_ST4 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M5 , DMA2_ST7 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M6 , DMA1_ST1 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M7 , DMA1_ST4 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M8 , DMA1_ST5 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 2), // M3 , DMA2_ST2 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 1), // M4 , DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // M5 , DMA2_ST7 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // M6 , DMA1_ST1 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // M7 , DMA1_ST4 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // M8 , DMA1_ST5 DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_STRIP, DMA1_ST0 }; diff --git a/src/main/target/FLYWOOF7DUAL/target.c b/src/main/target/FLYWOOF7DUAL/target.c index 83326ea4b6..d9d5482e3a 100644 --- a/src/main/target/FLYWOOF7DUAL/target.c +++ b/src/main/target/FLYWOOF7DUAL/target.c @@ -40,12 +40,12 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_2, DEVHW_MPU6500, GYRO_2_SPI_BUS, GYRO timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH1, PC6, TIM_USE_PPM, 0, 0), // PPM&SBUS - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - D(1,2) - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - D(1,4) - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - D(1,6) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - D(1,5) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - D(2,4) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - D(2,1) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 - D(1,2) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 - D(1,4) + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 - D(1,6) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 - D(1,5) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 - D(2,4) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 - D(2,1) DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP(1,5) }; diff --git a/src/main/target/FOXEERH743/target.c b/src/main/target/FOXEERH743/target.c index 0d26747ae7..099dba8ded 100644 --- a/src/main/target/FOXEERH743/target.c +++ b/src/main/target/FOXEERH743/target.c @@ -28,10 +28,10 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 3), // S4 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 DEF_TIM(TIM4, CH1, PD12, TIM_USE_SERVO | TIM_USE_SERVO, 0, 4), // S5 DEF_TIM(TIM4, CH2, PD13, TIM_USE_SERVO | TIM_USE_SERVO, 0, 5), // S6 diff --git a/src/main/target/FRSKYF4/target.c b/src/main/target/FRSKYF4/target.c index 7d444a7174..cd83979c50 100755 --- a/src/main/target/FRSKYF4/target.c +++ b/src/main/target/FRSKYF4/target.c @@ -23,12 +23,12 @@ #include "drivers/pwm_mapping.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S1_OUT - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S2_OUT - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S3_OUT - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4_OUT - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S5_OUT - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S6_OUT + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0), // S1_OUT + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0), // S2_OUT + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 1, 0), // S3_OUT + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 1, 0), // S4_OUT + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 1, 0), // S5_OUT + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 1, 0), // S6_OUT DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip }; diff --git a/src/main/target/FRSKYPILOT/target.c b/src/main/target/FRSKYPILOT/target.c index 74f22eee6a..50b82d7687 100644 --- a/src/main/target/FRSKYPILOT/target.c +++ b/src/main/target/FRSKYPILOT/target.c @@ -30,21 +30,21 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM1, CH3, PE13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM1, CH3, PE13, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM1, CH4, PE14, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 #ifdef FRSKYPILOT_LED DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED | TIM_USE_LED, 0, 0), // S10 now LED, S11 & S12 UART 3 only #else - DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S11 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S12 + DEF_TIM(TIM2, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S11 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 0), // S12 #endif DEF_TIM(TIM5, CH1, PA0, TIM_USE_BEEPER, 0, 0), // beeper diff --git a/src/main/target/FURYF4OSD/target.c b/src/main/target/FURYF4OSD/target.c index 61791d0230..c820d0c378 100644 --- a/src/main/target/FURYF4OSD/target.c +++ b/src/main/target/FURYF4OSD/target.c @@ -24,10 +24,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH4, PC9, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S1_OUT - D(1, 6, 3) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT - D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT - D(1, 2, 5) - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4_OUT - D(1, 1, 3) + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S1_OUT - D(1, 6, 3) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT - D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_OUT - D(1, 2, 5) + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4_OUT - D(1, 1, 3) DEF_TIM(TIM2, CH3, PB10, TIM_USE_ANY, 0, 0), DEF_TIM(TIM2, CH4, PB11, TIM_USE_ANY, 0, 0), DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, 0, 0 ), // LED_STRIP - DMA1_ST2_CH6 diff --git a/src/main/target/GEPRCF405/target.c b/src/main/target/GEPRCF405/target.c index e8e94a18c6..68a900898c 100644 --- a/src/main/target/GEPRCF405/target.c +++ b/src/main/target/GEPRCF405/target.c @@ -31,12 +31,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), + DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 1), + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), }; diff --git a/src/main/target/GEPRCF722/target.c b/src/main/target/GEPRCF722/target.c index da376e545d..851ae376a5 100644 --- a/src/main/target/GEPRCF722/target.c +++ b/src/main/target/GEPRCF722/target.c @@ -29,12 +29,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), diff --git a/src/main/target/HAKRCF405V2/target.c b/src/main/target/HAKRCF405V2/target.c index 9a599d56ae..a44aabc014 100644 --- a/src/main/target/HAKRCF405V2/target.c +++ b/src/main/target/HAKRCF405V2/target.c @@ -22,14 +22,14 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1_OUT D2_ST4 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT D2_ST7 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3_OUT D2_ST1 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4_OUT D2_ST2 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT D2_ST6 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT D1_ST4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7_OUT D1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8_OUT D1_ST2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S1_OUT D2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT D2_ST7 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S3_OUT D2_ST1 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), // S4_OUT D2_ST2 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT D2_ST6 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT D1_ST4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S7_OUT D1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S8_OUT D1_ST2 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0), // D1_ST6 }; diff --git a/src/main/target/HAKRCF411D/target.c b/src/main/target/HAKRCF411D/target.c index 72253eb94a..1423d2d199 100644 --- a/src/main/target/HAKRCF411D/target.c +++ b/src/main/target/HAKRCF411D/target.c @@ -25,10 +25,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 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(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 DEF_TIM(TIM2, CH1, PA15, TIM_USE_ANY, 0, 0), // SOFTSERIAL_1_TX_PIN DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // SOFTSERIAL_1_RX_PIN diff --git a/src/main/target/HAKRCF722V2/target.c b/src/main/target/HAKRCF722V2/target.c index d423c1004b..f09341633a 100644 --- a/src/main/target/HAKRCF722V2/target.c +++ b/src/main/target/HAKRCF722V2/target.c @@ -33,14 +33,14 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, GYRO_SPI_BUS, GYRO1_CS_PIN, BUSDEV_REGISTER_SPI_TAG(busdev_bmi270_2, DEVHW_BMI270, GYRO_SPI_BUS, GYRO2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_BMI270_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), // S4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0), // 2812LED diff --git a/src/main/target/HAKRCKD722/target.c b/src/main/target/HAKRCKD722/target.c index 39d0d12404..16757ff641 100644 --- a/src/main/target/HAKRCKD722/target.c +++ b/src/main/target/HAKRCKD722/target.c @@ -32,14 +32,14 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU60 timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + 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(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/HGLRCF722/target.c b/src/main/target/HGLRCF722/target.c index 716a9e37d5..1ebbbf6337 100644 --- a/src/main/target/HGLRCF722/target.c +++ b/src/main/target/HGLRCF722/target.c @@ -37,14 +37,14 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 UP1-6 D(1, 0, 2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 UP1-6 D(1, 3, 2) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 UP1-2 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 UP1-2 D(1, 5, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 UP1-2 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 UP1-2 D(1, 2, 5) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 UP1-7 D(1, 6, 3) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 UP1-6 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 UP1-6 D(1, 3, 2) DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 6, 0) DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM, RX2 diff --git a/src/main/target/IFLIGHTF4_TWING/target.c b/src/main/target/IFLIGHTF4_TWING/target.c index ebb02721d4..87227cf3b0 100644 --- a/src/main/target/IFLIGHTF4_TWING/target.c +++ b/src/main/target/IFLIGHTF4_TWING/target.c @@ -33,10 +33,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM // Motors - DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT D2_ST6 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT D1_ST2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT D1_ST6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT D1_ST1 + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D2_ST6 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT D1_ST2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT D1_ST6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1 // LED strip DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // D1_ST0 diff --git a/src/main/target/IFLIGHT_BLITZ_F722/target.c b/src/main/target/IFLIGHT_BLITZ_F722/target.c index 736bc6b499..ac2af33d20 100644 --- a/src/main/target/IFLIGHT_BLITZ_F722/target.c +++ b/src/main/target/IFLIGHT_BLITZ_F722/target.c @@ -23,16 +23,16 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 DMA1_S2_CH5 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 DMA1_S7_CH5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 DMA1_S2_CH5 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 DMA1_S7_CH5 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 DMA2_S4_CH7 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 DMA2_S7_CH7 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 DMA1_S0_CH2 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 DMA1_S3_CH2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 DMA2_S4_CH7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 DMA2_S7_CH7 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 DMA1_S0_CH2 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 DMA1_S3_CH2 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 DMA1_S1_CH3 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S8 DMA1_S6_CH3 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 DMA1_S1_CH3 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 1), // S8 DMA1_S6_CH3 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // WS2812B }; diff --git a/src/main/target/IFLIGHT_BLITZ_F7_AIO/target.c b/src/main/target/IFLIGHT_BLITZ_F7_AIO/target.c index 4c244e27d2..54ba97a490 100644 --- a/src/main/target/IFLIGHT_BLITZ_F7_AIO/target.c +++ b/src/main/target/IFLIGHT_BLITZ_F7_AIO/target.c @@ -36,12 +36,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S2 DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // S3 DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S4 - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM1, CH3, PE13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM1, CH3, PE13, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM1, CH4, PE14, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 DEF_TIM(TIM8, CH4, PC9, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c b/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c index 2f002c6d6b..b4b6f6de0f 100644 --- a/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c +++ b/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c @@ -32,14 +32,14 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_P timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1 - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S1 + DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/IFLIGHT_JBF7PRO/target.c b/src/main/target/IFLIGHT_JBF7PRO/target.c index 9e97258451..676c3d6dae 100644 --- a/src/main/target/IFLIGHT_JBF7PRO/target.c +++ b/src/main/target/IFLIGHT_JBF7PRO/target.c @@ -27,14 +27,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S8 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 1), // S8 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/KAKUTEF4/target.c b/src/main/target/KAKUTEF4/target.c index c80cfb112f..bf58e5bdca 100755 --- a/src/main/target/KAKUTEF4/target.c +++ b/src/main/target/KAKUTEF4/target.c @@ -31,23 +31,23 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), // PPM IN - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT - DMA1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT - DMA1_ST2 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3_OUT - DMA1_ST6 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT - DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT - DMA1_ST2 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3_OUT - DMA1_ST6 #if !defined(KAKUTEF4V23) - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT - DMA1_ST1 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT - DMA1_ST1 #else - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT - DMA1_ST1 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT - DMA1_ST0 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT - DMA1_ST3 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT - DMA1_ST1 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT - DMA1_ST0 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT - DMA1_ST3 #endif #if defined(KAKUTEF4V2) || defined(KAKUTEF4V23) DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED_STRIP - DMA2_ST2 #else - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT - DMA1_ST2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S6_OUT - DMA2_ST4 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT - DMA1_ST2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S6_OUT - DMA2_ST4 DEF_TIM(TIM5, CH2, PA1, TIM_USE_LED, 0, 0), // LED_STRIP - DMA1_ST4 #endif }; diff --git a/src/main/target/KAKUTEF7/target.c b/src/main/target/KAKUTEF7/target.c index 4cfa725996..53ae9359de 100755 --- a/src/main/target/KAKUTEF7/target.c +++ b/src/main/target/KAKUTEF7/target.c @@ -31,12 +31,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M1 , DMA1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M2 , DMA1_ST2 - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // M3 , DMA2_ST2 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // M4 , DMA2_ST4 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M5 , DMA2_ST7 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // M6 , DMA1_ST1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // M1 , DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // M2 , DMA1_ST2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 2), // M3 , DMA2_ST2 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 1), // M4 , DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // M5 , DMA2_ST7 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // M6 , DMA1_ST1 DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_STRIP, DMA1_ST0 }; diff --git a/src/main/target/KAKUTEF7MINIV3/target.c b/src/main/target/KAKUTEF7MINIV3/target.c index 23815c6dc4..055cedc25e 100644 --- a/src/main/target/KAKUTEF7MINIV3/target.c +++ b/src/main/target/KAKUTEF7MINIV3/target.c @@ -31,11 +31,11 @@ #include "drivers/pwm_mapping.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 DEF_TIM(TIM4, CH2, PB7, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S6 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // RX2 diff --git a/src/main/target/KAKUTEH7/target.c b/src/main/target/KAKUTEH7/target.c index 1ea9cd3e68..4580912dd2 100644 --- a/src/main/target/KAKUTEH7/target.c +++ b/src/main/target/KAKUTEH7/target.c @@ -28,10 +28,10 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_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_SERVO | TIM_USE_SERVO, 0, 4), // S5 DEF_TIM(TIM5, CH3, PA2, TIM_USE_SERVO | TIM_USE_SERVO, 0, 5), // S6 diff --git a/src/main/target/KAKUTEH7WING/target.c b/src/main/target/KAKUTEH7WING/target.c index 193b621a31..c8235c85cd 100644 --- a/src/main/target/KAKUTEH7WING/target.c +++ b/src/main/target/KAKUTEH7WING/target.c @@ -32,20 +32,20 @@ BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS // BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - DEF_TIM(TIM1, CH3, PE13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 - DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 3), // S4 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 + DEF_TIM(TIM1, CH3, PE13, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM1, CH4, PE14, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 4), // S5 - DEF_TIM(TIM4, CH4, PD15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 DMA_NONE - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 5), // S7 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 6), // S8 + DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 DMA_NONE + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 5), // S7 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 6), // S8 - DEF_TIM(TIM15,CH1, PE5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 7), // S9 - DEF_TIM(TIM15,CH2, PE6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 DMA_NONE - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S11 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S12 + DEF_TIM(TIM15,CH1, PE5, TIM_USE_OUTPUT_AUTO, 0, 7), // S9 + DEF_TIM(TIM15,CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 DMA_NONE + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S11 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S12 DEF_TIM(TIM3, CH4, PB1, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S13 //DEF_TIM(TIM2, CH1, PA15, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S14 / LED_2812 diff --git a/src/main/target/MAMBAF405US/target.c b/src/main/target/MAMBAF405US/target.c index cdceba21e4..1781a047e3 100644 --- a/src/main/target/MAMBAF405US/target.c +++ b/src/main/target/MAMBAF405US/target.c @@ -28,15 +28,15 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN #ifdef MAMBAF405US_I2C - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S1 pin A9: DMA2 Stream 6 Channel 0 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S2 pin A8: DMA2 Stream 6 Channel 0 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3 pin C9: DMA2 Stream 7 Channel 7 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 pin C8: DMA2 Stream 2 Channel 0 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S1 pin A9: DMA2 Stream 6 Channel 0 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S2 pin A8: DMA2 Stream 6 Channel 0 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3 pin C9: DMA2 Stream 7 Channel 7 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S4 pin C8: DMA2 Stream 2 Channel 0 #else - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4_OUT – D(2, 2, 6) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3_OUT – D(2, 1, 6) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT – D(2, 7, 7) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT – D(2, 4, 7) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S4_OUT – D(2, 2, 6) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S3_OUT – D(2, 1, 6) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT – D(2, 7, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1_OUT – D(2, 4, 7) #endif DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) diff --git a/src/main/target/MAMBAF405_2022A/target.c b/src/main/target/MAMBAF405_2022A/target.c index 13396ecb26..d91361a263 100644 --- a/src/main/target/MAMBAF405_2022A/target.c +++ b/src/main/target/MAMBAF405_2022A/target.c @@ -25,12 +25,12 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S1 pin A9: DMA2 Stream 6 Channel 0 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S2 pin A8: DMA2 Stream 6 Channel 0 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3 pin C9: DMA2 Stream 7 Channel 7 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 pin C8: DMA2 Stream 2 Channel 0 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0 ), // S4 pin C8: DMA2 Stream 2 Channel 0 // used to be fw motor - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0 ), // S4 pin C8: DMA2 Stream 2 Channel 0 // used to be fw motor + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S1 pin A9: DMA2 Stream 6 Channel 0 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S2 pin A8: DMA2 Stream 6 Channel 0 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3 pin C9: DMA2 Stream 7 Channel 7 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S4 pin C8: DMA2 Stream 2 Channel 0 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0 ), // S4 pin C8: DMA2 Stream 2 Channel 0 // used to be fw motor + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0 ), // S4 pin C8: DMA2 Stream 2 Channel 0 // used to be fw motor DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; diff --git a/src/main/target/MAMBAF722/target.c b/src/main/target/MAMBAF722/target.c index cb1073af53..b97969e57b 100644 --- a/src/main/target/MAMBAF722/target.c +++ b/src/main/target/MAMBAF722/target.c @@ -27,10 +27,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT – D(2, 4, 7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT – D(2, 7, 7) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3_OUT – D(2, 1, 6) - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4_OUT – D(2, 2, 6) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1_OUT – D(2, 4, 7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT – D(2, 7, 7) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S3_OUT – D(2, 1, 6) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S4_OUT – D(2, 2, 6) DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; diff --git a/src/main/target/MAMBAF722_2022A/target.c b/src/main/target/MAMBAF722_2022A/target.c index f1e2f5e4db..9b51f13945 100644 --- a/src/main/target/MAMBAF722_2022A/target.c +++ b/src/main/target/MAMBAF722_2022A/target.c @@ -27,15 +27,15 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S3 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S8 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; diff --git a/src/main/target/MAMBAF722_WING/target.c b/src/main/target/MAMBAF722_WING/target.c index 4b0925d9fb..7ac29dbdc9 100644 --- a/src/main/target/MAMBAF722_WING/target.c +++ b/src/main/target/MAMBAF722_WING/target.c @@ -25,15 +25,15 @@ #include "drivers/bus.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S3 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S8 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; diff --git a/src/main/target/MAMBAF722_X8/target.c b/src/main/target/MAMBAF722_X8/target.c index f1e2f5e4db..9b51f13945 100644 --- a/src/main/target/MAMBAF722_X8/target.c +++ b/src/main/target/MAMBAF722_X8/target.c @@ -27,15 +27,15 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S3 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S8 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; diff --git a/src/main/target/MATEKF411/target.c b/src/main/target/MATEKF411/target.c index 2aae59cdf0..fb2ccde3f1 100755 --- a/src/main/target/MATEKF411/target.c +++ b/src/main/target/MATEKF411/target.c @@ -25,14 +25,14 @@ timerHardware_t timerHardware[] = { // DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(1,4,5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(1,5,5) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 D(1,0,2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 D(1,3,2) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(1,4,5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(1,5,5) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 D(1,0,2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 D(1,3,2) - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 D(1,6,3) - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(1,1,3) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 D(1,5,3) - clash with S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(1,6,3) + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(1,1,3) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(1,5,3) - clash with S2 DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), //softserial_tx2 - 2812LED TIM_USE_LED D(2,1,6) DEF_TIM(TIM5, CH1, PA0, TIM_USE_PPM, 0, 0), //use rssi pad for PPM/softserial_tx1 diff --git a/src/main/target/MATEKF411SE/target.c b/src/main/target/MATEKF411SE/target.c index c47706b051..caf6972b8f 100755 --- a/src/main/target/MATEKF411SE/target.c +++ b/src/main/target/MATEKF411SE/target.c @@ -24,13 +24,13 @@ #include "drivers/pinio.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(1,4,5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(1,5,5) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 D(2,1,6) - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4 D(2,2,6) - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S5 D(2,6,6) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(1,4,5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(1,5,5) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 D(2,1,6) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), // S4 D(2,2,6) + DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 1), // S5 D(2,6,6) #ifndef MATEKF411SE_SS2_CH6 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(1,7,2) + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(1,7,2) DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 pad - softserial_tx2 #else diff --git a/src/main/target/MATEKF411TE/target.c b/src/main/target/MATEKF411TE/target.c index 55c790c8ca..b873201652 100644 --- a/src/main/target/MATEKF411TE/target.c +++ b/src/main/target/MATEKF411TE/target.c @@ -25,12 +25,12 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(1,0,2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(1,3,6) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 D(1,7,5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 D(1,2,5) - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 D(1,4,5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(1,5,5) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(1,0,2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(1,3,6) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 D(1,7,5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 D(1,2,5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(1,4,5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(1,5,5) DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), //Softserial1_TX DEF_TIM(TIM5, CH2, PA1, TIM_USE_ANY, 0, 0), //Softserial1_RX diff --git a/src/main/target/MATEKF722PX/target.c b/src/main/target/MATEKF722PX/target.c index 22d8ffcac4..170b67d951 100755 --- a/src/main/target/MATEKF722PX/target.c +++ b/src/main/target/MATEKF722PX/target.c @@ -24,19 +24,19 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 UP2-1 D(2, 4, 7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 UP2-1 D(2, 7, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 UP2-1 D(2, 4, 7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 UP2-1 D(2, 7, 7) - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 UP1-2 D(1, 4, 5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 UP1-2 D(1, 5, 5) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP1-2 D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP1-2 D(1, 2, 5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 UP1-2 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 UP1-2 D(1, 5, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 UP1-2 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 UP1-2 D(1, 2, 5) - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 UP1-7 D(1, 1, 3) - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S8 UP1-7 D(1, 6, 3) + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 UP1-7 D(1, 1, 3) + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 1), // S8 UP1-7 D(1, 6, 3) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9 UP1-6 D(1, 0, 2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 UP1-6 D(1, 3, 2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 UP1-6 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 UP1-6 D(1, 3, 2) DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 3, 6) diff --git a/src/main/target/MATEKF765/target.c b/src/main/target/MATEKF765/target.c index 0754f8a864..712beb4c8c 100644 --- a/src/main/target/MATEKF765/target.c +++ b/src/main/target/MATEKF765/target.c @@ -34,21 +34,21 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu3, DEVHW_ICM42605, ICM42605_SPI_BUS, #endif timerHardware_t timerHardware[] = { - DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 UP(1,7), D(1,5,3) - DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 UP(1,7), D(1,6,3) + DEF_TIM(TIM2, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 UP(1,7), D(1,5,3) + DEF_TIM(TIM2, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 UP(1,7), D(1,6,3) - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 UP(1,0), D(1,0,6)* - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 UP(1,0), D(1,1,6) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP(1,2), D(1,7,5)** - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP(1,2), D(1,2,5) + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 UP(1,0), D(1,0,6)* + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 UP(1,0), D(1,1,6) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 UP(1,2), D(1,7,5)** + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 UP(1,2), D(1,2,5) - DEF_TIM(TIM4, CH1, PD12, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 UP(1,6), D(1,0,2)* - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 UP(1,6), D(1,3,2) - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9 UP(1,6), D(1,7,2)** - DEF_TIM(TIM4, CH4, PD15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 UP(1,6) + DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 UP(1,6), D(1,0,2)* + DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 UP(1,6), D(1,3,2) + DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 UP(1,6), D(1,7,2)** + DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 UP(1,6) - DEF_TIM(TIM9, CH1, PE5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S11 - DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S12 + DEF_TIM(TIM9, CH1, PE5, TIM_USE_OUTPUT_AUTO, 0, 0), // S11 + DEF_TIM(TIM9, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0), // S12 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED_2812 D(2,6,0) diff --git a/src/main/target/NEUTRONRCF435SE/target.c b/src/main/target/NEUTRONRCF435SE/target.c index 713139aa16..3a8848911f 100644 --- a/src/main/target/NEUTRONRCF435SE/target.c +++ b/src/main/target/NEUTRONRCF435SE/target.c @@ -30,15 +30,15 @@ timerHardware_t timerHardware[] = { DEF_TIM(TMR5, CH2, PA1, TIM_USE_ANY |TIM_USE_LED, 0,7), // PWM1 - LED MCO1 DMA1 CH2 DEF_TIM(TMR2, CH4, PA3, TIM_USE_ANY |TIM_USE_PPM, 0,6), // PWM2 - PPM DMA1 CH6 - DEF_TIM(TMR8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0,0), // motor1 DMA2 CH7 - DEF_TIM(TMR8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0,2), // motor2 DMA2 CH6 - DEF_TIM(TMR3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0,1), // motor3 DMA2 CH5 - DEF_TIM(TMR3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0,3), // motor4 DMA2 CH4 + DEF_TIM(TMR8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0,0), // motor1 DMA2 CH7 + DEF_TIM(TMR8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0,2), // motor2 DMA2 CH6 + DEF_TIM(TMR3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0,1), // motor3 DMA2 CH5 + DEF_TIM(TMR3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0,3), // motor4 DMA2 CH4 - DEF_TIM(TMR4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0,11), // PWM1 - OUT5 DMA1 CH7 - DEF_TIM(TMR4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0,10), // PWM2 - OUT6 DMA2 CH1 - DEF_TIM(TMR3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0,9), // PWM3 - OUT7 DMA2 CH2 - DEF_TIM(TMR3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0,8), // PWM4 - OUT8 DMA2 CH3 + DEF_TIM(TMR4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0,11), // PWM1 - OUT5 DMA1 CH7 + DEF_TIM(TMR4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0,10), // PWM2 - OUT6 DMA2 CH1 + DEF_TIM(TMR3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0,9), // PWM3 - OUT7 DMA2 CH2 + DEF_TIM(TMR3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0,8), // PWM4 - OUT8 DMA2 CH3 }; diff --git a/src/main/target/NEUTRONRCF435WING/target.c b/src/main/target/NEUTRONRCF435WING/target.c index 0220df8230..b1cd9031cc 100644 --- a/src/main/target/NEUTRONRCF435WING/target.c +++ b/src/main/target/NEUTRONRCF435WING/target.c @@ -28,15 +28,15 @@ timerHardware_t timerHardware[] = { DEF_TIM(TMR1, CH1, PA8, TIM_USE_ANY |TIM_USE_LED, 0,7), // PWM1 - LED MCO1 DMA1 CH2 - DEF_TIM(TMR4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0,0), // motor1 DMA2 CH7 - DEF_TIM(TMR1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0,2), // motor2 DMA2 CH6 - DEF_TIM(TMR2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0,1), // motor3 DMA2 CH5 - DEF_TIM(TMR3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0,3), // motor4 DMA2 CH4 + DEF_TIM(TMR4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0,0), // motor1 DMA2 CH7 + DEF_TIM(TMR1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0,2), // motor2 DMA2 CH6 + DEF_TIM(TMR2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0,1), // motor3 DMA2 CH5 + DEF_TIM(TMR3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0,3), // motor4 DMA2 CH4 - DEF_TIM(TMR4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0,10), // PWM1 - OUT5 DMA2 CH1 - DEF_TIM(TMR1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0,9), // PWM2 - OUT6 DMA2 CH2 - DEF_TIM(TMR3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0,8), // PWM3 - OUT7 DMA2 CH3 - DEF_TIM(TMR2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0,11), // PWM4 - OUT8 DMA1 CH7 + DEF_TIM(TMR4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0,10), // PWM1 - OUT5 DMA2 CH1 + DEF_TIM(TMR1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0,9), // PWM2 - OUT6 DMA2 CH2 + DEF_TIM(TMR3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0,8), // PWM3 - OUT7 DMA2 CH3 + DEF_TIM(TMR2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0,11), // PWM4 - OUT8 DMA1 CH7 }; diff --git a/src/main/target/NEUTRONRCH7BT/target.c b/src/main/target/NEUTRONRCH7BT/target.c index 74f2573486..d15f4c4a9b 100644 --- a/src/main/target/NEUTRONRCH7BT/target.c +++ b/src/main/target/NEUTRONRCH7BT/target.c @@ -27,15 +27,15 @@ #include "drivers/sensor.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 + 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(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 3), // S4 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 4), // S5 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 5), // S6 - DEF_TIM(TIM4, CH1, PD12, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 6), // S7 - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 7), // S8 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 }; diff --git a/src/main/target/NOX/target.c b/src/main/target/NOX/target.c index 2481dae52c..e2651956e1 100755 --- a/src/main/target/NOX/target.c +++ b/src/main/target/NOX/target.c @@ -27,10 +27,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH3, PB10, TIM_USE_PPM, 0, 0), //PPM DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 0, 0), //2812LED - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT - DEF_TIM(TIM1, CH1N, PA7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_OUT - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT + DEF_TIM(TIM1, CH1N, PA7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3_OUT + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT DEF_TIM(TIM9, CH1, PA2, TIM_USE_ANY, 0, 0), //UART2 TX DEF_TIM(TIM9, CH2, PA3, TIM_USE_ANY, 0, 0), //UART2 RX diff --git a/src/main/target/OMNIBUSF4/target.c b/src/main/target/OMNIBUSF4/target.c index a8a2124198..c639cff9b7 100644 --- a/src/main/target/OMNIBUSF4/target.c +++ b/src/main/target/OMNIBUSF4/target.c @@ -36,28 +36,28 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), // S5_IN // pad labelled CH5 on OMNIBUSF4PRO DEF_TIM(TIM8, CH4, PC9, TIM_USE_ANY, 0, 0), // S6_IN // pad labelled CH6 on OMNIBUSF4PRO - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT D1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT D1_ST2 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3_OUT D1_ST6 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT D1_ST1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT D1_ST2 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3_OUT D1_ST6 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1 // { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_MOTOR | TIM_USE_SERVO }, // MOTOR_3 #if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !(defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT #elif defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS) DEF_TIM(TIM5, CH2, PA1, TIM_USE_ANY, 0, 0), // S5_OUT SOFTSERIAL DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // S6_OUT SOFTSERIAL #elif defined(OMNIBUSF4V3_S6_SS) - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_OUT + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // S6_OUT SOFTSERIAL #elif defined(OMNIBUSF4PRO_LEDSTRIPM5) DEF_TIM(TIM5, CH2, PA1, TIM_USE_LED, 0, 0), // S5_OUT LED strip - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT #else - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0), // S5_OUT MOTOR, SERVO or LED - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO | TIM_USE_LED, 0, 0), // S5_OUT MOTOR, SERVO or LED + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT #endif #if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !defined(OMNIBUSF4PRO_LEDSTRIPM5) diff --git a/src/main/target/RADIX/target.c b/src/main/target/RADIX/target.c index 086d448030..db78409cda 100644 --- a/src/main/target/RADIX/target.c +++ b/src/main/target/RADIX/target.c @@ -26,12 +26,12 @@ /* TIMERS */ timerHardware_t timerHardware[] = { DEF_TIM(TIM12, CH1, PB14, TIM_USE_PPM, 0, 0), // PPM In - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), // Camera Control }; diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c index 913083c72d..d1203adadc 100644 --- a/src/main/target/REVO/target.c +++ b/src/main/target/REVO/target.c @@ -34,19 +34,19 @@ BUSDEV_REGISTER_I2C_TAG(busdev_mag3110, DEVHW_MAG3110, MAG_I2C_BUS_EXT, /* TIMERS */ timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1_OUT D1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2_OUT D1_ST2 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3_OUT D1_ST6 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_OUT D1_ST1 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_ANY, 0, 0), // S5_OUT / LED - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_OUT D1_ST2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT D1_ST2 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3_OUT D1_ST6 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO | TIM_USE_ANY, 0, 0), // S5_OUT / LED + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT D1_ST2 DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // PPM (5th pin on FlexiIO port) DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // S2_IN - DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3_IN - DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4_IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5_IN - DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6_IN + DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S3_IN + DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S4_IN + DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S5_IN + DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM | TIM_USE_OUTPUT_AUTO, 0, 0), // S6_IN }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SAGEATF4/target.c b/src/main/target/SAGEATF4/target.c index 63ab717851..4887541467 100644 --- a/src/main/target/SAGEATF4/target.c +++ b/src/main/target/SAGEATF4/target.c @@ -30,15 +30,15 @@ timerHardware_t timerHardware[] = { DEF_TIM(TMR2, CH3, PB10, TIM_USE_ANY | TIM_USE_LED, 0,5), // PWM1 - LED MCO1 DMA1 CH6 DEF_TIM(TMR2, CH4, PB11, TIM_USE_ANY | TIM_USE_BEEPER, 0,6), // PWM2 - BB DMA1 CH7 - DEF_TIM(TMR4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0,0), // motor1 DMA1 CH1 - DEF_TIM(TMR4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0,1), // motor2 DMA1 CH2 - DEF_TIM(TMR2, CH1, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0,2), // motor3 DMA1 CH3 - DEF_TIM(TMR2, CH2, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0,3), // motor4 DMA1 CH4 + DEF_TIM(TMR4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0,0), // motor1 DMA1 CH1 + DEF_TIM(TMR4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0,1), // motor2 DMA1 CH2 + DEF_TIM(TMR2, CH1, PB8, TIM_USE_OUTPUT_AUTO, 0,2), // motor3 DMA1 CH3 + DEF_TIM(TMR2, CH2, PB9, TIM_USE_OUTPUT_AUTO, 0,3), // motor4 DMA1 CH4 - DEF_TIM(TMR3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0,8), // PWM1 - OUT5 DMA2 CH2 DMA2_CHANNEL1->ADC - DEF_TIM(TMR3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0,9), // PWM2 - OUT6 DMA2 CH3 - DEF_TIM(TMR3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0,10), // PWM3 - OUT7 DMA2 CH4 - DEF_TIM(TMR3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0,11), // PWM4 - OUT8 DMA2 CH5 + DEF_TIM(TMR3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0,8), // PWM1 - OUT5 DMA2 CH2 DMA2_CHANNEL1->ADC + DEF_TIM(TMR3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0,9), // PWM2 - OUT6 DMA2 CH3 + DEF_TIM(TMR3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0,10), // PWM3 - OUT7 DMA2 CH4 + DEF_TIM(TMR3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0,11), // PWM4 - OUT8 DMA2 CH5 }; diff --git a/src/main/target/SKYSTARSH743HD/target.c b/src/main/target/SKYSTARSH743HD/target.c index 6fb3cfd27d..296fc51bd3 100644 --- a/src/main/target/SKYSTARSH743HD/target.c +++ b/src/main/target/SKYSTARSH743HD/target.c @@ -30,16 +30,16 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270_1, DEVHW_BMI270, IMU1_SPI_BUS, IMU1_CS BUSDEV_REGISTER_SPI_TAG(busdev_bmi270_2, DEVHW_BMI270, IMU2_SPI_BUS, IMU2_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU2_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 + 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(TIM4, CH1, PD12, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2), // S3 - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 3), // S4 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 4), // S5 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 5), // S6 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 6), // S7 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 7), // S8 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 }; diff --git a/src/main/target/SPARKY2/target.c b/src/main/target/SPARKY2/target.c index 881b7ddd5a..b4b4b29504 100644 --- a/src/main/target/SPARKY2/target.c +++ b/src/main/target/SPARKY2/target.c @@ -30,12 +30,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0 ), // S4_IN DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0 ), // S5_IN - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT - DEF_TIM(TIM9, CH2, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S4_OUT - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_OUT - GPIO_PartialRemap_TIM3 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6_OUT + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1_OUT + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT + DEF_TIM(TIM9, CH2, PA3, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_OUT + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4_OUT + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5_OUT - GPIO_PartialRemap_TIM3 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_OUT }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SPEEDYBEEF4/target.c b/src/main/target/SPEEDYBEEF4/target.c index c3c68ed9bc..b45c517bfa 100644 --- a/src/main/target/SPEEDYBEEF4/target.c +++ b/src/main/target/SPEEDYBEEF4/target.c @@ -26,14 +26,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 UP(1,2) - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 UP(2,1) - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 UP(2,1) - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 UP(2,1) + DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 UP(1,2) + DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 UP(2,1) + DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 UP(2,1) + DEF_TIM(TIM3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 UP(2,1) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP(1,7) // used to be fw motor - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP(2,5) // used to be fw motor - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 D(1,7)!S5 UP(2,6) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 UP(1,7) // used to be fw motor + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 UP(2,5) // used to be fw motor + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(1,7)!S5 UP(2,6) DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED D(1,0) UP(2,6) }; diff --git a/src/main/target/SPEEDYBEEF405MINI/target.c b/src/main/target/SPEEDYBEEF405MINI/target.c index ba27b5e3c3..0af028ffd0 100644 --- a/src/main/target/SPEEDYBEEF405MINI/target.c +++ b/src/main/target/SPEEDYBEEF405MINI/target.c @@ -33,8 +33,8 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4 #ifdef SPEEDYBEEF405MINI_6OUTPUTS - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // CAM_CTRL - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // LED + DEF_TIM(TIM12, CH1, PB14, TIM_USE_OUTPUT_AUTO, 1, 0), // CAM_CTRL + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // LED #else DEF_TIM(TIM12, CH1, PB14, TIM_USE_ANY, 1, 0), // CAM_CTRL DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED diff --git a/src/main/target/SPEEDYBEEF405V3/target.c b/src/main/target/SPEEDYBEEF405V3/target.c index a2f0859bd5..05c84f1c80 100644 --- a/src/main/target/SPEEDYBEEF405V3/target.c +++ b/src/main/target/SPEEDYBEEF405V3/target.c @@ -35,15 +35,15 @@ BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 DEF_TIM(TIM8, CH4, PC9, TIM_USE_LED, 0, 0), // LED }; diff --git a/src/main/target/SPEEDYBEEF7/target.c b/src/main/target/SPEEDYBEEF7/target.c index b7489c75bb..78821f5259 100644 --- a/src/main/target/SPEEDYBEEF7/target.c +++ b/src/main/target/SPEEDYBEEF7/target.c @@ -26,13 +26,13 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S5 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED | TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // LED/S6 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED | TIM_USE_OUTPUT_AUTO, 0, 0), // LED/S6 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SPEEDYBEEF7MINI/target.c b/src/main/target/SPEEDYBEEF7MINI/target.c index 14f10a79be..32b5792dda 100644 --- a/src/main/target/SPEEDYBEEF7MINI/target.c +++ b/src/main/target/SPEEDYBEEF7MINI/target.c @@ -33,16 +33,16 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, #endif timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 UP1-2 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 UP1-2 D(1, 5, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 UP1-2 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 UP1-2 D(1, 2, 5) - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 UP1-7 D(1, 6, 3) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 UP1-6 D(1, 0, 2) // used to be fw motor - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 UP1-6 D(1, 3, 2) // used to be fw motor + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 UP1-6 D(1, 0, 2) // used to be fw motor + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 UP1-6 D(1, 3, 2) // used to be fw motor DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED D(2, 6, 0) diff --git a/src/main/target/SPEEDYBEEF7V2/target.c b/src/main/target/SPEEDYBEEF7V2/target.c index b44fd0703d..0914224a05 100644 --- a/src/main/target/SPEEDYBEEF7V2/target.c +++ b/src/main/target/SPEEDYBEEF7V2/target.c @@ -29,10 +29,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 - DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 // used to be fw motor + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S1 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 + DEF_TIM(TIM3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 // used to be fw motor DEF_TIM(TIM8, CH2N, PB0, TIM_USE_LED, 0, 0), // LED diff --git a/src/main/target/SPEEDYBEEF7V3/target.c b/src/main/target/SPEEDYBEEF7V3/target.c index b716b7f5c7..5d5b064f81 100644 --- a/src/main/target/SPEEDYBEEF7V3/target.c +++ b/src/main/target/SPEEDYBEEF7V3/target.c @@ -33,14 +33,14 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU600 timerHardware_t timerHardware[] = { - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 Clash with S2, DSHOT does not work - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 Clash with S2, DSHOT does not work + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), // Camera Control diff --git a/src/main/target/TMOTORF7/target.c b/src/main/target/TMOTORF7/target.c index d50b3b9981..2f96517ba1 100644 --- a/src/main/target/TMOTORF7/target.c +++ b/src/main/target/TMOTORF7/target.c @@ -29,13 +29,13 @@ // BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 1), + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 1), + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), DEF_TIM(TIM2, CH1, PA15, TIM_USE_PPM, 0, 0), DEF_TIM(TIM11, CH1, PB9, TIM_USE_ANY, 0, 0), diff --git a/src/main/target/TMOTORF7V2/target.c b/src/main/target/TMOTORF7V2/target.c index d010b2c4b6..606ac8819d 100644 --- a/src/main/target/TMOTORF7V2/target.c +++ b/src/main/target/TMOTORF7V2/target.c @@ -26,14 +26,14 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED DEF_TIM(TIM2, CH2, PB3, TIM_USE_PWM | TIM_USE_SERVO, 0, 0), // "C.C" diff --git a/src/main/target/YUPIF4/target.c b/src/main/target/YUPIF4/target.c index a115a3cf44..310ab66b0a 100644 --- a/src/main/target/YUPIF4/target.c +++ b/src/main/target/YUPIF4/target.c @@ -26,20 +26,20 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH3, PC8, TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT - DMA1_ST2 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT - DMA1_ST4 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT - DMA1_ST1 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4_OUT - DMA1_ST6 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_OUT - DMA1_ST7 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1_OUT - DMA1_ST2 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT - DMA1_ST4 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_OUT - DMA1_ST1 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S4_OUT - DMA1_ST6 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5_OUT - DMA1_ST7 #if defined (YUPIF4R2) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0 ), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO | TIM_USE_LED, 0, 0 ), DEF_TIM(TIM12, CH1, PB14, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM OPT #elif (YUPIF4MINI) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0 ), DEF_TIM(TIM3, CH4, PC9, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM #else - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0 ), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO | TIM_USE_LED, 0, 0 ), DEF_TIM(TIM3, CH4, PC9, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM #endif }; diff --git a/src/main/target/YUPIF7/target.c b/src/main/target/YUPIF7/target.c index cddfeabda5..cd6a17ee68 100644 --- a/src/main/target/YUPIF7/target.c +++ b/src/main/target/YUPIF7/target.c @@ -25,12 +25,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH3, PC8, TIM_USE_PPM, 0, 1 ), // PPM IN - DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S1_OUT - DMA1_ST2 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT - DMA1_ST4 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S3_OUT - DMA1_ST1 - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S4_OUT - DMA1_ST6 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_OUT - DMA1_ST7 - LED Control - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0 ), // S6_OUT + DEF_TIM(TIM2, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1_OUT - DMA1_ST2 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT - DMA1_ST4 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_OUT - DMA1_ST1 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S4_OUT - DMA1_ST6 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5_OUT - DMA1_ST7 - LED Control + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO | TIM_USE_LED, 0, 0 ), // S6_OUT DEF_TIM(TIM4, CH2, PB7, TIM_USE_ANY, 0, 0 ), // ANY DEF_TIM(TIM12, CH1, PB14, TIM_USE_BEEPER, 0, 0 ), // BEEPER PWM }; diff --git a/src/main/target/ZEEZF7/target.c b/src/main/target/ZEEZF7/target.c index 2c57917515..f1f5356dcb 100755 --- a/src/main/target/ZEEZF7/target.c +++ b/src/main/target/ZEEZF7/target.c @@ -27,32 +27,32 @@ timerHardware_t timerHardware[] = { #ifdef ZEEZF7V3 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S5 - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 1), // S5 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 #endif #ifdef ZEEZF7V2 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 1), // S7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 #endif #ifdef ZEEZF7 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 #endif DEF_TIM(TIM1, CH2N, PB0, TIM_USE_LED , 0, 0), // LED STRIP From 6f0a472d057c667afeccccac8187d6f6a2c501ad Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 13:12:46 +0200 Subject: [PATCH 097/122] Some missed ones in the TIM_USE_OUTPUT_AUTO change --- src/main/target/ANYFCM7/target.c | 20 ++++++++++---------- src/main/target/AOCODARCF7DUAL/target.c | 8 ++++---- src/main/target/FLYWOOF405PRO/target.c | 16 ++++++++-------- src/main/target/FOXEERF405/target.c | 12 ++++++------ src/main/target/FOXEERF722DUAL/target.c | 14 +++++++------- src/main/target/FOXEERF722V4/target.c | 16 ++++++++-------- src/main/target/HAKRCF405D/target.c | 12 ++++++------ src/main/target/MATEKF405CAN/target.c | 16 ++++++++-------- src/main/target/MATEKF405SE/target.c | 18 +++++++++--------- src/main/target/MATEKF405TE/target.c | 22 +++++++++++----------- src/main/target/NEUTRONRCF435MINI/target.c | 8 ++++---- src/main/target/OMNIBUSF4/target.c | 2 +- src/main/target/OMNIBUSF7/target.c | 8 ++++---- src/main/target/SPEEDYBEEF405MINI/target.c | 8 ++++---- src/main/target/SPEEDYBEEF405WING/target.c | 14 +++++++------- 15 files changed, 97 insertions(+), 97 deletions(-) diff --git a/src/main/target/ANYFCM7/target.c b/src/main/target/ANYFCM7/target.c index cae2d80a7f..fb69d60a43 100644 --- a/src/main/target/ANYFCM7/target.c +++ b/src/main/target/ANYFCM7/target.c @@ -33,16 +33,16 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0 ), // S5_IN DMA2_ST4 DMA2_ST2 DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0 ), // S6_IN DMA2_ST7 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S10_OUT 1 DMA1_ST7 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S6_OUT 2 DMA1_ST1 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S5_OUT 3 DMA1_ST3 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S1_OUT 4 DMA1_ST7 DMA1_ST6 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S2_OUT DMA1_ST4 - DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // S3_OUT DMA2_ST6 DMA2_ST2 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO | TIM_USE_LED, 0, 0 ), // S4_OUT DMA1_ST5 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S7_OUT DMA1_ST2 - DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S8_OUT DMA2_ST6 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // S9_OUT DMA1_ST4 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S10_OUT 1 DMA1_ST7 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_OUT 2 DMA1_ST1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5_OUT 3 DMA1_ST3 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S1_OUT 4 DMA1_ST7 DMA1_ST6 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT DMA1_ST4 + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 1 ), // S3_OUT DMA2_ST6 DMA2_ST2 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO | TIM_USE_LED, 0, 0 ), // S4_OUT DMA1_ST5 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S7_OUT DMA1_ST2 + DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S8_OUT DMA2_ST6 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S9_OUT DMA1_ST4 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AOCODARCF7DUAL/target.c b/src/main/target/AOCODARCF7DUAL/target.c index 99494e94dd..d09fafeda2 100644 --- a/src/main/target/AOCODARCF7DUAL/target.c +++ b/src/main/target/AOCODARCF7DUAL/target.c @@ -37,10 +37,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 D(2, 4, 7) DEF_TIM(TIM3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 D(2, 7, 7) - DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MOTOR |TIM_USE_SERVO, 0, 0), // S5 D(1, 7, 5) - DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MOTOR |TIM_USE_SERVO, 0, 0), // S6 D(1, 2, 5) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR |TIM_USE_SERVO, 0, 0), // S7 D(1, 0, 2) - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR |TIM_USE_SERVO, 0, 0), // S8 D(1, 3, 2) + DEF_TIM(TIM8, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(1, 7, 5) + DEF_TIM(TIM8, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(1, 2, 5) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 D(1, 3, 2) DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 0, 0), // LED_TRIP }; diff --git a/src/main/target/FLYWOOF405PRO/target.c b/src/main/target/FLYWOOF405PRO/target.c index 7d818b2eca..f61d06ca0e 100644 --- a/src/main/target/FLYWOOF405PRO/target.c +++ b/src/main/target/FLYWOOF405PRO/target.c @@ -22,15 +22,15 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(1,3,2) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(1,0,2) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(1,3,2) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(1,0,2) - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 D(1,7,5) - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 D(1,2,5) - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 D(2,4,7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 D(1,7,5) + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 D(1,2,5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(2,4,7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 DEF_TIM(TIM1, CH2, PA9, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) diff --git a/src/main/target/FOXEERF405/target.c b/src/main/target/FOXEERF405/target.c index 9c48d9badc..1ad827bb5c 100644 --- a/src/main/target/FOXEERF405/target.c +++ b/src/main/target/FOXEERF405/target.c @@ -24,12 +24,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 (1,7) - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 (1,4) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 (2,4) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 (2,7) - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 (2,2) - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 (2,3) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 (1,7) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 (1,4) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 (2,4) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 (2,7) + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 (2,2) + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 (2,3) DEF_TIM(TIM1, CH3, PA10, TIM_USE_LED, 0, 0), // LED STRIP(2,6) diff --git a/src/main/target/FOXEERF722DUAL/target.c b/src/main/target/FOXEERF722DUAL/target.c index 588b926fc9..1933a5134e 100644 --- a/src/main/target/FOXEERF722DUAL/target.c +++ b/src/main/target/FOXEERF722DUAL/target.c @@ -31,16 +31,16 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1 - D(2, 1, 6) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), // S1 - D(2, 1, 6) #if defined(FOXEERF722V2) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - D(2, 1, 6) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 - D(2, 1, 6) #else - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 - D(2, 6, 0) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 - D(2, 6, 0) #endif - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - D(2, 7, 7) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - D(2, 4, 7) - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - D(1, 4, 5) - DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - D(1, 5, 5) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 - D(2, 7, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 - D(2, 4, 7) + DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 - D(1, 4, 5) + DEF_TIM(TIM3, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 - D(1, 5, 5) DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED STRIP(1,5) diff --git a/src/main/target/FOXEERF722V4/target.c b/src/main/target/FOXEERF722V4/target.c index 457e7acd4b..be84ee8b90 100644 --- a/src/main/target/FOXEERF722V4/target.c +++ b/src/main/target/FOXEERF722V4/target.c @@ -25,16 +25,16 @@ timerHardware_t timerHardware[] = { - DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S1 - D(2, 1, 6) - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - D(2, 1, 6) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 - D(2, 7, 7) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - D(2, 4, 7) + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 1), // S1 - D(2, 1, 6) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 - D(2, 1, 6) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 - D(2, 7, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 - D(2, 4, 7) #ifdef FOXEERF722V4_X8 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 #endif DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED STRIP(1,5) diff --git a/src/main/target/HAKRCF405D/target.c b/src/main/target/HAKRCF405D/target.c index 8d5505e121..664db47633 100644 --- a/src/main/target/HAKRCF405D/target.c +++ b/src/main/target/HAKRCF405D/target.c @@ -32,12 +32,12 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU600 timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM - DEF_TIM(TIM3, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S4 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM3, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 DEF_TIM(TIM4, CH1, PB8, TIM_USE_LED, 0, 0), // LED STRIP(2,6) diff --git a/src/main/target/MATEKF405CAN/target.c b/src/main/target/MATEKF405CAN/target.c index b303ac8c34..2ab40de1dc 100644 --- a/src/main/target/MATEKF405CAN/target.c +++ b/src/main/target/MATEKF405CAN/target.c @@ -22,15 +22,15 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // S1 D(2,2,7) - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // S2 D(2,3,7) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 1), // S3 D(2,4,7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4 D(2,7,7) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S5 D(1,7,5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S6 D(1,2,5) + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 1, 1), // S1 D(2,2,7) + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 1, 1), // S2 D(2,3,7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 1, 1), // S3 D(2,4,7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 1, 0), // S4 D(2,7,7) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0), // S5 D(1,7,5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0), // S6 D(1,2,5) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S7 D(1,0,2) // used to be fw motor - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S8 D(1,3,2) // used to be fw motor + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 1, 0), // S7 D(1,0,2) // used to be fw motor + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 1, 0), // S8 D(1,3,2) // used to be fw motor DEF_TIM(TIM1, CH1, PA8, TIM_USE_BEEPER, 0, 0), // BEEPER PWM diff --git a/src/main/target/MATEKF405SE/target.c b/src/main/target/MATEKF405SE/target.c index ad7431699e..ef6fceaca9 100644 --- a/src/main/target/MATEKF405SE/target.c +++ b/src/main/target/MATEKF405SE/target.c @@ -22,16 +22,16 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S1 D(1,3,2) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S2 D(1,0,2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 1, 0), // S1 D(1,3,2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 1, 0), // S2 D(1,0,2) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S3 D(1,7,5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4 D(1,2,5) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S5 D(2,4,7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S6 D(2,7,7) - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S7 - DEF_TIM(TIM12, CH2, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S8 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S9 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0), // S3 D(1,7,5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0), // S4 D(1,2,5) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 1, 0), // S5 D(2,4,7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 1, 0), // S6 D(2,7,7) + DEF_TIM(TIM12, CH1, PB14, TIM_USE_OUTPUT_AUTO, 1, 0), // S7 + DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S8 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 1, 0), // S9 DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) diff --git a/src/main/target/MATEKF405TE/target.c b/src/main/target/MATEKF405TE/target.c index dc97455388..79f6269a52 100644 --- a/src/main/target/MATEKF405TE/target.c +++ b/src/main/target/MATEKF405TE/target.c @@ -25,19 +25,19 @@ #include "drivers/timer_def_stm32f4xx.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S1 D(2,7,7) UP217 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S2 D(2,2,0) UP217 - DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S3 D(2,6,0) UP256 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1), // S4 D(2,1,6) UP256 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 D(2,7,7) UP217 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 D(2,2,0) UP217 + DEF_TIM(TIM1, CH3N, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 D(2,6,0) UP256 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S4 D(2,1,6) UP256 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S5 D(1,7,3) UP173 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S6 D(1,1,3) UP173 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S7 D(1,6,3) UP173 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S8 D(1,5,3) UP173 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 D(1,7,3) UP173 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 D(1,1,3) UP173 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 D(1,6,3) UP173 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 D(1,5,3) UP173 - DEF_TIM(TIM12, CH1, PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S9 DMA NONE - DEF_TIM(TIM13, CH1, PA6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S10 DMA NONE - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0), // S11 D(1,0,2) + DEF_TIM(TIM12, CH1, PB14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 DMA NONE + DEF_TIM(TIM13, CH1, PA6, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 DMA NONE + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S11 D(1,0,2) DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), // 2812LED D(1,2,5) DEF_TIM(TIM11, CH1, PB9, TIM_USE_BEEPER, 0, 0), // BEEPER PWM diff --git a/src/main/target/NEUTRONRCF435MINI/target.c b/src/main/target/NEUTRONRCF435MINI/target.c index a1bba9b765..472867af57 100644 --- a/src/main/target/NEUTRONRCF435MINI/target.c +++ b/src/main/target/NEUTRONRCF435MINI/target.c @@ -28,10 +28,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TMR1, CH1, PA8, TIM_USE_ANY |TIM_USE_LED, 0,7), // PWM1 - LED MCO1 DMA1 CH2 - DEF_TIM(TMR4, CH1, PB6, TIM_USE_MOTOR|TIM_USE_SERVO, 0,0), // motor1 DMA2 CH7 - DEF_TIM(TMR4, CH2, PB7, TIM_USE_MOTOR|TIM_USE_SERVO, 0,2), // motor2 DMA2 CH6 - DEF_TIM(TMR2, CH4, PA3, TIM_USE_MOTOR|TIM_USE_SERVO, 0,1), // motor3 DMA2 CH5 - DEF_TIM(TMR3, CH4, PB1, TIM_USE_MOTOR|TIM_USE_SERVO, 0,3), // motor4 DMA2 CH4 + DEF_TIM(TMR4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0,0), // motor1 DMA2 CH7 + DEF_TIM(TMR4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0,2), // motor2 DMA2 CH6 + DEF_TIM(TMR2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0,1), // motor3 DMA2 CH5 + DEF_TIM(TMR3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0,3), // motor4 DMA2 CH4 }; diff --git a/src/main/target/OMNIBUSF4/target.c b/src/main/target/OMNIBUSF4/target.c index c639cff9b7..81b30e11f2 100644 --- a/src/main/target/OMNIBUSF4/target.c +++ b/src/main/target/OMNIBUSF4/target.c @@ -41,7 +41,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3_OUT D1_ST6 DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1 - // { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_MOTOR | TIM_USE_SERVO }, // MOTOR_3 + // { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_OUTPUT_AUTO }, // MOTOR_3 #if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !(defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT diff --git a/src/main/target/OMNIBUSF7/target.c b/src/main/target/OMNIBUSF7/target.c index e6cf7c8282..75497fed8b 100644 --- a/src/main/target/OMNIBUSF7/target.c +++ b/src/main/target/OMNIBUSF7/target.c @@ -39,10 +39,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, 0, 0 ), // UART2_RX, joined with PE13 // DEF_TIM(TIM1, CH3, PE13, TIM_USE_NONE, 0, 0 ), // RC1 / PPM, unusable - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // M1 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 0 ), // M2 - DEF_TIM(TIM1, CH1, PE9, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 2 ), // M3 - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR | TIM_USE_SERVO, 0, 1 ), // M4 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // M1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // M2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 2 ), // M3 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 1 ), // M4 DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0 ), // LED }; diff --git a/src/main/target/SPEEDYBEEF405MINI/target.c b/src/main/target/SPEEDYBEEF405MINI/target.c index 0af028ffd0..3cc7fbbebb 100644 --- a/src/main/target/SPEEDYBEEF405MINI/target.c +++ b/src/main/target/SPEEDYBEEF405MINI/target.c @@ -27,10 +27,10 @@ #include "drivers/sensor.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S1 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S2 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S3 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 1, 0), // S1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 1, 0), // S2 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0), // S3 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0), // S4 #ifdef SPEEDYBEEF405MINI_6OUTPUTS DEF_TIM(TIM12, CH1, PB14, TIM_USE_OUTPUT_AUTO, 1, 0), // CAM_CTRL diff --git a/src/main/target/SPEEDYBEEF405WING/target.c b/src/main/target/SPEEDYBEEF405WING/target.c index 2d978e1977..6b3ed8a945 100644 --- a/src/main/target/SPEEDYBEEF405WING/target.c +++ b/src/main/target/SPEEDYBEEF405WING/target.c @@ -22,15 +22,15 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S1 D(1,3,2) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S2 D(1,0,2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 1, 0), // S1 D(1,3,2) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 1, 0), // S2 D(1,0,2) - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S3 D(1,7,5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S4 D(1,2,5) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S5 D(2,4,7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S6 D(2,7,7) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0), // S3 D(1,7,5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0), // S4 D(1,2,5) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 1, 0), // S5 D(2,4,7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 1, 0), // S6 D(2,7,7) - DEF_TIM(TIM8, CH2N,PB14, TIM_USE_MOTOR | TIM_USE_SERVO, 1, 0), // S7 + DEF_TIM(TIM8, CH2N,PB14, TIM_USE_OUTPUT_AUTO, 1, 0), // S7 DEF_TIM(TIM2, CH1, PA15, TIM_USE_SERVO | TIM_USE_SERVO, 1, 0), // S8 DEF_TIM(TIM2, CH3, PB10, TIM_USE_SERVO | TIM_USE_SERVO, 1, 0), // S9 DEF_TIM(TIM2, CH4, PB11, TIM_USE_SERVO | TIM_USE_SERVO, 1, 0), // S10 From bce3c9f4e7261b80f739684aea742b3027991017 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Mon, 25 Sep 2023 13:16:47 +0200 Subject: [PATCH 098/122] SERVO | SERVO or MOTOR | MOTOR to AUTO --- src/main/target/ANYFCF7/target.c | 4 ++-- src/main/target/AOCODARCH7DUAL/target.c | 4 ++-- src/main/target/AXISFLYINGF7PRO/target.c | 4 ++-- src/main/target/DALRCF405/target.c | 2 +- src/main/target/FLYWOOF745/target.c | 4 ++-- src/main/target/FOXEERH743/target.c | 12 ++++++------ src/main/target/KAKUTEF7MINIV3/target.c | 2 +- src/main/target/KAKUTEH7/target.c | 8 ++++---- src/main/target/KAKUTEH7WING/target.c | 4 ++-- src/main/target/SPEEDYBEEF405WING/target.c | 8 ++++---- 10 files changed, 26 insertions(+), 26 deletions(-) diff --git a/src/main/target/ANYFCF7/target.c b/src/main/target/ANYFCF7/target.c index 21c0acbfea..65f807d798 100644 --- a/src/main/target/ANYFCF7/target.c +++ b/src/main/target/ANYFCF7/target.c @@ -33,8 +33,8 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH3, PB8, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S10_OUT 1 DMA1_ST7 DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S6_OUT 2 DMA1_ST0 DEF_TIM(TIM4, CH4, PB9, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S5_OUT - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0 ), // S1_OUT 4 DMA1_ST1 DMA1_ST3 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0 ), // S2_OUT 3 DMA1_ST4 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S1_OUT 4 DMA1_ST1 DMA1_ST3 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S2_OUT 3 DMA1_ST4 DEF_TIM(TIM9, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S3_OUT DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S4_OUT DMA1_ST5 DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0 ), // S7_OUT DMA1_ST2 diff --git a/src/main/target/AOCODARCH7DUAL/target.c b/src/main/target/AOCODARCH7DUAL/target.c index 586f832648..85e8b00493 100644 --- a/src/main/target/AOCODARCH7DUAL/target.c +++ b/src/main/target/AOCODARCH7DUAL/target.c @@ -44,8 +44,8 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 DMA_NONE - DEF_TIM(TIM15, CH1, PE5, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S11 - DEF_TIM(TIM15, CH2, PE6, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S12 DMA_NONE + DEF_TIM(TIM15, CH1, PE5, TIM_USE_OUTPUT_AUTO, 0, 0), // S11 + DEF_TIM(TIM15, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0), // S12 DMA_NONE DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 DEF_TIM(TIM2, CH1, PA15, TIM_USE_BEEPER, 0, 0), // BEEPER PWM diff --git a/src/main/target/AXISFLYINGF7PRO/target.c b/src/main/target/AXISFLYINGF7PRO/target.c index 5b066ec2b8..8d4b966b69 100644 --- a/src/main/target/AXISFLYINGF7PRO/target.c +++ b/src/main/target/AXISFLYINGF7PRO/target.c @@ -23,8 +23,8 @@ #include "drivers/timer.h" timerHardware_t timerHardware[] = { - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // S1 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // S2 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S3 DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 diff --git a/src/main/target/DALRCF405/target.c b/src/main/target/DALRCF405/target.c index 5b82d861e1..e1cddea261 100644 --- a/src/main/target/DALRCF405/target.c +++ b/src/main/target/DALRCF405/target.c @@ -29,7 +29,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH3, PA10, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 (2,6) DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 1), // S4 (2,1) (2.3 2.6) DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 1), // S5 (2,4) (2.2) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // S6 (1,2) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 (1,2) DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 1), // S7 (2,3) DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 (2,7) DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED STRIP(1,0) diff --git a/src/main/target/FLYWOOF745/target.c b/src/main/target/FLYWOOF745/target.c index 22f2d12a53..879b66d01f 100644 --- a/src/main/target/FLYWOOF745/target.c +++ b/src/main/target/FLYWOOF745/target.c @@ -32,8 +32,8 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // M1 , DMA1_ST7 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_MOTOR, 0, 0), // M2 , DMA1_ST2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // M1 , DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // M2 , DMA1_ST2 DEF_TIM(TIM1, CH1, PE9, TIM_USE_OUTPUT_AUTO, 0, 2), // M3 , DMA2_ST2 DEF_TIM(TIM1, CH2, PE11, TIM_USE_OUTPUT_AUTO, 0, 1), // M4 , DMA2_ST4 DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // M5 , DMA2_ST7 diff --git a/src/main/target/FOXEERH743/target.c b/src/main/target/FOXEERH743/target.c index 099dba8ded..3ab6e19529 100644 --- a/src/main/target/FOXEERH743/target.c +++ b/src/main/target/FOXEERH743/target.c @@ -33,13 +33,13 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 - DEF_TIM(TIM4, CH1, PD12, TIM_USE_SERVO | TIM_USE_SERVO, 0, 4), // S5 - DEF_TIM(TIM4, CH2, PD13, TIM_USE_SERVO | TIM_USE_SERVO, 0, 5), // S6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_SERVO | TIM_USE_SERVO, 0, 6), // S7 // used to be fw motor - DEF_TIM(TIM8, CH4, PC9, TIM_USE_SERVO | TIM_USE_SERVO, 0, 7), // S8 // used to be fw motor + DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 // used to be fw motor + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 // used to be fw motor - DEF_TIM(TIM15, CH1, PE5, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S9 - DEF_TIM(TIM15, CH2, PE6, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S10 + DEF_TIM(TIM15, CH1, PE5, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 + DEF_TIM(TIM15, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 }; diff --git a/src/main/target/KAKUTEF7MINIV3/target.c b/src/main/target/KAKUTEF7MINIV3/target.c index 055cedc25e..095038960d 100644 --- a/src/main/target/KAKUTEF7MINIV3/target.c +++ b/src/main/target/KAKUTEF7MINIV3/target.c @@ -36,7 +36,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S6 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // RX2 }; diff --git a/src/main/target/KAKUTEH7/target.c b/src/main/target/KAKUTEH7/target.c index 4580912dd2..8851f95286 100644 --- a/src/main/target/KAKUTEH7/target.c +++ b/src/main/target/KAKUTEH7/target.c @@ -33,10 +33,10 @@ timerHardware_t timerHardware[] = { 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_SERVO | TIM_USE_SERVO, 0, 4), // S5 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_SERVO | TIM_USE_SERVO, 0, 5), // S6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_SERVO | TIM_USE_SERVO, 0, 6), // S7 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_SERVO | TIM_USE_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 }; diff --git a/src/main/target/KAKUTEH7WING/target.c b/src/main/target/KAKUTEH7WING/target.c index c8235c85cd..30b9a4f5de 100644 --- a/src/main/target/KAKUTEH7WING/target.c +++ b/src/main/target/KAKUTEH7WING/target.c @@ -47,8 +47,8 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S11 DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S12 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S13 - //DEF_TIM(TIM2, CH1, PA15, TIM_USE_SERVO | TIM_USE_SERVO, 0, 0), // S14 / LED_2812 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S13 + //DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // S14 / LED_2812 DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // S14 / LED_2812 diff --git a/src/main/target/SPEEDYBEEF405WING/target.c b/src/main/target/SPEEDYBEEF405WING/target.c index 6b3ed8a945..516f16bfb5 100644 --- a/src/main/target/SPEEDYBEEF405WING/target.c +++ b/src/main/target/SPEEDYBEEF405WING/target.c @@ -31,10 +31,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 1, 0), // S6 D(2,7,7) DEF_TIM(TIM8, CH2N,PB14, TIM_USE_OUTPUT_AUTO, 1, 0), // S7 - DEF_TIM(TIM2, CH1, PA15, TIM_USE_SERVO | TIM_USE_SERVO, 1, 0), // S8 - DEF_TIM(TIM2, CH3, PB10, TIM_USE_SERVO | TIM_USE_SERVO, 1, 0), // S9 - DEF_TIM(TIM2, CH4, PB11, TIM_USE_SERVO | TIM_USE_SERVO, 1, 0), // S10 - DEF_TIM(TIM1, CH3N,PB15, TIM_USE_SERVO | TIM_USE_SERVO, 1, 0), // S11 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 1, 0), // S8 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 1, 0), // S9 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 1, 0), // S10 + DEF_TIM(TIM1, CH3N,PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S11 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 softserial1_Tx From e108558601563fb1baa280a49786061facd9db84 Mon Sep 17 00:00:00 2001 From: shota Date: Tue, 26 Sep 2023 22:12:50 +0900 Subject: [PATCH 099/122] add MIXER_TRANSITION_ACTIVE OPERAND --- src/main/programming/logic_condition.c | 4 ++++ src/main/programming/logic_condition.h | 3 ++- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 6a08871508..d3b45453c9 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -776,6 +776,10 @@ static int logicConditionGetFlightOperandValue(int operand) { return currentMixerProfileIndex + 1; break; + case LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE: //0,1 + return isMixerTransitionMixing ? 1 : 0; + break; + case LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS: return getLoiterRadius(navConfig()->fw.loiter_radius); diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 446532fb29..941e47f8d0 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -135,7 +135,8 @@ 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 // TBD + LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE, //int // 39 + LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE, //0,1 // 40 } logicFlightOperands_e; typedef enum { From c4c4821250c32c82c17c12fb70d875ade0b33bcc Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 27 Sep 2023 14:53:39 +0200 Subject: [PATCH 100/122] Remove compatibility define, since all targets have been updated --- src/main/drivers/timer.h | 7 ------- 1 file changed, 7 deletions(-) diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index 12865fdc5d..a207aff0c5 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -119,13 +119,6 @@ typedef enum { TIM_USE_BEEPER = (1 << 25), } timerUsageFlag_e; - -// Compability -#define TIM_USE_MC_MOTOR TIM_USE_MOTOR -#define TIM_USE_MC_SERVO TIM_USE_SERVO -#define TIM_USE_FW_MOTOR TIM_USE_MOTOR -#define TIM_USE_FW_SERVO TIM_USE_SERVO - #define TIM_USE_OUTPUT_AUTO (TIM_USE_MOTOR | TIM_USE_SERVO) #define TIM_IS_MOTOR(flags) ((flags) & TIM_USE_MOTOR) From 970034faceeabbb1fdc369f9ac7a9cee0d341442 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 27 Sep 2023 22:13:27 +0200 Subject: [PATCH 101/122] For all my friends in the upside down. This should give you the option to pick South PAN SBAS #9315 I am not sure if it will make much of difference, as there is a single PRN on SPAN right now. --- src/main/fc/settings.yaml | 2 +- src/main/io/gps.h | 1 + src/main/io/gps_ublox.c | 1 + 3 files changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 2602868c4d..e764b08803 100755 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -47,7 +47,7 @@ tables: values: ["NMEA", "UBLOX", "UBLOX7", "MSP", "FAKE"] enum: gpsProvider_e - name: gps_sbas_mode - values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "NONE"] + values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "SPAN", "NONE"] enum: sbasMode_e - name: gps_dyn_model values: ["PEDESTRIAN", "AIR_1G", "AIR_4G"] diff --git a/src/main/io/gps.h b/src/main/io/gps.h index 99b6aafbdf..09b2725880 100755 --- a/src/main/io/gps.h +++ b/src/main/io/gps.h @@ -47,6 +47,7 @@ typedef enum { SBAS_WAAS, SBAS_MSAS, SBAS_GAGAN, + SBAS_SPAN, SBAS_NONE } sbasMode_e; diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 2baa97ce9b..d03c339077 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -69,6 +69,7 @@ static const uint32_t ubloxScanMode1[] = { (SBASMASK1_BITS(129) | SBASMASK1_BITS(137) | SBASMASK1_BITS(139)), // MSAS (SBASMASK1_BITS(127) | SBASMASK1_BITS(128) | SBASMASK1_BITS(132)), // GAGAN + (SBASMASK1_BITS(122)), // SPAN 0x00000000, // NONE }; From 56de8a4345a2122265ed516f3d6d9b5c6040d4f7 Mon Sep 17 00:00:00 2001 From: Andrey Akimov Date: Thu, 28 Sep 2023 07:28:55 +0300 Subject: [PATCH 102/122] DSHOT delay fix --- src/main/drivers/pwm_output.c | 18 ++++++++++++------ 1 file changed, 12 insertions(+), 6 deletions(-) diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index bf38ec9340..a0dac07309 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -419,7 +419,7 @@ static int getDShotCommandRepeats(dshotCommands_e cmd) { return repeats; } -static void executeDShotCommands(void){ +static bool executeDShotCommands(void){ timeUs_t tNow = micros(); @@ -432,16 +432,20 @@ static void executeDShotCommands(void){ currentExecutingCommand.cmd = cmd; currentExecutingCommand.remainingRepeats = getDShotCommandRepeats(cmd); } else { - return; + return true; } } - delayMicroseconds(DSHOT_COMMAND_DELAY_US); for (uint8_t i = 0; i < getMotorCount(); i++) { motors[i].requestTelemetry = true; motors[i].value = currentExecutingCommand.cmd; } - currentExecutingCommand.remainingRepeats--; - lastCommandSent = tNow; + if (tNow - lastCommandSent >= DSHOT_COMMAND_DELAY_US) { + currentExecutingCommand.remainingRepeats--; + lastCommandSent = tNow; + return true; + } else { + return false; + } } #endif @@ -464,7 +468,9 @@ void pwmCompleteMotorUpdate(void) { #ifdef USE_DSHOT if (isMotorProtocolDshot()) { - executeDShotCommands(); + if (!executeDShotCommands()) { + return; + } #ifdef USE_DSHOT_DMAR for (int index = 0; index < motorCount; index++) { From fa10eba91fc75843078d7d5b8e4a3a26a51b5e5f Mon Sep 17 00:00:00 2001 From: Andrey Akimov Date: Thu, 28 Sep 2023 10:05:53 +0300 Subject: [PATCH 103/122] post delay --- src/main/drivers/pwm_output.c | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index a0dac07309..d898b1595f 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -119,6 +119,7 @@ static bool pwmMotorsEnabled = true; static timeUs_t digitalMotorUpdateIntervalUs = 0; static timeUs_t digitalMotorLastUpdateUs; static timeUs_t lastCommandSent = 0; +static timeUs_t commandPostDelay = 0; static circularBuffer_t commandsCircularBuffer; static uint8_t commandsBuff[DHSOT_COMMAND_QUEUE_SIZE]; @@ -430,8 +431,16 @@ static bool executeDShotCommands(void){ dshotCommands_e cmd; circularBufferPopHead(&commandsCircularBuffer, (uint8_t *) &cmd); currentExecutingCommand.cmd = cmd; - currentExecutingCommand.remainingRepeats = getDShotCommandRepeats(cmd); + currentExecutingCommand.remainingRepeats = getDShotCommandRepeats(cmd); + commandPostDelay = DSHOT_COMMAND_INTERVAL_US; } else { + if (commandPostDelay) { + if (tNow - lastCommandSent < commandPostDelay) { + return false; + } + commandPostDelay = 0; + } + return true; } } From 9c633a816d3bdaa9e462453d5f133799b3f58a05 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 28 Sep 2023 16:09:44 +0100 Subject: [PATCH 104/122] [docs] modernise Serial and RX documents (#9322) --- docs/Rx.md | 29 ++++++++++++++++++++--------- docs/Serial.md | 5 ++--- 2 files changed, 22 insertions(+), 12 deletions(-) diff --git a/docs/Rx.md b/docs/Rx.md index ee600ce56c..ec34f4e6f9 100644 --- a/docs/Rx.md +++ b/docs/Rx.md @@ -2,10 +2,11 @@ A receiver is used to receive radio control signals from your transmitter and convert them into signals that the flight controller can understand. -There are 2 basic types of receivers: +There are a number of types of receivers: -1. PPM Receivers -2. Serial Receivers +* PPM Receivers (obsolete) +* Serial Receivers +* MSP RX ## PPM Receivers @@ -192,9 +193,19 @@ This command will put the receiver into bind mode without the need to reboot the bind_rx ``` -## MultiWii serial protocol (MSP) +## MultiWii serial protocol (MSP RX) -Allows you to use MSP commands as the RC input. Only 8 channel support to maintain compatibility with MSP. +Allows you to use MSP commands as the RC input. Up to 18 channels are supported. +Note: +* It is necessary to update `MSP_SET_RAW_RC` at 5Hz or faster. +* `MSP_SET_RAW_RC` uses the defined RC channel map +* `MSP_RC` returns `AERT` regardless of channel map +* You can combine "real" RC radio and MSP RX by compiling custom firmware with `USE_MSP_RC_OVERRIDE` defined. Then use `msp_override_channels` to set the channels to be overridden. +* The [wiki Remote Control and Management article](https://github.com/iNavFlight/inav/wiki/INAV-Remote-Management,-Control-and-Telemetry) provides more information, including links to 3rd party projects that exercise `MSP_SET_RAW_RC` and `USE_MSP_RC_OVERRIDE` + +## SIM (SITL) Joystick + +Enables the use of a joystick in the INAV SITL with a flight simulator. See the [SITL documentation](SITL/SITL). ## Configuration @@ -203,7 +214,7 @@ The receiver type can be set from the configurator or CLI. ``` # get receiver_type receiver_type = NONE -Allowed values: NONE, PPM, SERIAL, MSP, SPI, UIB +Allowed values: NONE, SERIAL, MSP, SIM (SITL) ``` ### RX signal-loss detection @@ -233,7 +244,7 @@ The highest channel value considered valid. e.g. PWM/PPM pulse length See the Serial chapter for some some RX configuration examples. To setup spectrum in the GUI: -1. Start on the "Ports" tab make sure that UART2 has serial RX. If not set the checkbox, save and reboot. +1. Start on the "Ports" tab make sure that teh required has serial RX. If not set the checkbox, save and reboot. 2. Move to the "Configuration" page and in the upper lefthand corner choose Serial RX as the receiver type. 3. Below that choose the type of serial receiver that you are using. Save and reboot. @@ -244,11 +255,11 @@ For Serial RX set the `receiver_type` and `serialrx_provider` setting as appropr ``` # get rec receiver_type = SERIAL -Allowed values: NONE, PPM, SERIAL, MSP, SPI, UIB +Allowed values: NONE, SERIAL, MSP, SIM (SITL) # get serialrx serialrx_provider = SBUS -Allowed values: SPEK1024, SPEK2048, SBUS, SUMD, IBUS, JETIEXBUS, CRSF, FPORT, SBUS_FAST, FPORT2, SRXL2 +Allowed values: SPEK1024, SPEK2048, SBUS, SUMD, IBUS, JETIEXBUS, CRSF, FPORT, SBUS_FAST, FPORT2, SRXL2, GHST, MAVLINK, FBUS ``` diff --git a/docs/Serial.md b/docs/Serial.md index 4f21b1f68b..4e5723e9ed 100644 --- a/docs/Serial.md +++ b/docs/Serial.md @@ -46,11 +46,11 @@ e.g. after configuring a port for GPS enable the GPS feature. * If SoftSerial is used, then all SoftSerial ports must use the same baudrate. * Softserial is limited to 19200 buad. * All telemetry systems except MSP will ignore any attempts to override the baudrate. -* MSP/CLI can be shared with EITHER Blackbox OR telemetry. In shared mode blackbox or telemetry will be output only when armed. +* MSP/CLI can be shared with EITHER Blackbox OR telemetry (LTM or MAVlink, not RX telemetry). In shared mode blackbox or telemetry will be output only when armed. * Smartport telemetry cannot be shared with MSP. * No other serial port sharing combinations are valid. * You can use as many different telemetry systems as you like at the same time. -* You can only use each telemetry system once. e.g. FrSky telemetry cannot be used on two port, but MSP Telemetry + FrSky on different ports is fine. +* You can only use each telemetry system once. e.g. FrSky telemetry cannot be used on two port, but LTN Telemetry and FrSky on two different ports is fine. ### Configuration via CLI @@ -89,4 +89,3 @@ The allowable baud rates are as follows: | 14 | 1500000 | | 15 | 2000000 | | 16 | 2470000 | - From 76be691baf0cff75778dece03a434af12f44a6da Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 29 Sep 2023 15:52:35 +0200 Subject: [PATCH 105/122] SpeedyBee F405 V4 for INAV 7 --- .../target/SPEEDYBEEF405V4/CMakeLists.txt | 1 + src/main/target/SPEEDYBEEF405V4/config.c | 39 ++++ src/main/target/SPEEDYBEEF405V4/target.c | 53 ++++++ src/main/target/SPEEDYBEEF405V4/target.h | 175 ++++++++++++++++++ 4 files changed, 268 insertions(+) create mode 100644 src/main/target/SPEEDYBEEF405V4/CMakeLists.txt create mode 100644 src/main/target/SPEEDYBEEF405V4/config.c create mode 100644 src/main/target/SPEEDYBEEF405V4/target.c create mode 100644 src/main/target/SPEEDYBEEF405V4/target.h diff --git a/src/main/target/SPEEDYBEEF405V4/CMakeLists.txt b/src/main/target/SPEEDYBEEF405V4/CMakeLists.txt new file mode 100644 index 0000000000..6e208a8373 --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V4/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(SPEEDYBEEF405V4) diff --git a/src/main/target/SPEEDYBEEF405V4/config.c b/src/main/target/SPEEDYBEEF405V4/config.c new file mode 100644 index 0000000000..a21244ed8b --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V4/config.c @@ -0,0 +1,39 @@ +/* + * 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 "fc/fc_msp_box.h" +#include "io/piniobox.h" +#include "io/serial.h" + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BAUD_115200; + + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].functionMask = FUNCTION_ESCSERIAL; + + pinioBoxConfigMutable()->permanentId[0] = BOXARM; +} diff --git a/src/main/target/SPEEDYBEEF405V4/target.c b/src/main/target/SPEEDYBEEF405V4/target.c new file mode 100644 index 0000000000..2d398bd1bb --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V4/target.c @@ -0,0 +1,53 @@ +/* + * 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" + +BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 1, 0), // S1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 1, 0), // S2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 1, 0), // S3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 1, 0), // S4 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 1, 0), // S5 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 1, 0), // S6 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 1, 0), // S7 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 1, 0), // S8 + + DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S9 + DEF_TIM(TIM12, CH1, PB14, TIM_USE_OUTPUT_AUTO, 1, 0), // S10 + + 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/SPEEDYBEEF405V4/target.h b/src/main/target/SPEEDYBEEF405V4/target.h new file mode 100644 index 0000000000..8f333db3c2 --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V4/target.h @@ -0,0 +1,175 @@ +/* + * 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 "SB44" +#define USBD_PRODUCT_STRING "SpeedyBeeF405V4" + +/*** Indicators ***/ +#define LED0 PC13 //Blue + +#define BEEPER PC15 +#define BEEPER_INVERTED + +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PB11 +#define PINIO1_FLAGS PINIO_FLAGS_INVERTED + +// *************** UART ***************************** +#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 + +// Internally routed to Bluetooth +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 // Not broken out +#define UART5_RX_PIN PD2 //ESC TLM + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_SOFTSERIAL1 +#define SOFTSERIAL_1_TX_PIN PA2 +#define SOFTSERIAL_1_RX_PIN PA2 + +#define SERIAL_PORT_COUNT 8 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** 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_ICM42605 +#define IMU_ICM42605_ALIGN CW90_DEG +#define ICM42605_CS_PIN PA4 +#define ICM42605_SPI_BUS BUS_SPI1 + +// *************** I2C(Baro & I2C) ************************** +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#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 + +#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_RANGEFINDER +#define TEMPERATURE_I2C_BUS BUS_I2C1 +#define PITOT_I2C_BUS BUS_I2C1 +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** Internal SD card ************************** +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#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 + +// *************** OSD ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PC3 + +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** ADC ***************************** + +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC5 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +// *************** LED ***************************** +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_BLACKBOX | FEATURE_TELEMETRY) +#define CURRENT_METER_SCALE 400 + +#define USE_DSHOT +#define USE_SERIALSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define MAX_PWM_OUTPUT_PORTS 10 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) From 542b5d4ba6417b71b235839debccea8d188634e5 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 29 Sep 2023 20:46:20 +0200 Subject: [PATCH 106/122] S11 shares a timer with led --- src/main/target/SPEEDYBEEF405WING/target.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/target/SPEEDYBEEF405WING/target.c b/src/main/target/SPEEDYBEEF405WING/target.c index 516f16bfb5..504379b9ff 100644 --- a/src/main/target/SPEEDYBEEF405WING/target.c +++ b/src/main/target/SPEEDYBEEF405WING/target.c @@ -34,7 +34,8 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 1, 0), // S8 DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 1, 0), // S9 DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 1, 0), // S10 - DEF_TIM(TIM1, CH3N,PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S11 + //DEF_TIM(TIM1, CH3N,PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S11 + DEF_TIM(TIM12, CH2,PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S11 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 softserial1_Tx From 07666be41960dd5e20cbac4f48351fed8b7c37af Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 29 Sep 2023 23:06:42 +0200 Subject: [PATCH 107/122] Remove commented out line --- src/main/target/SPEEDYBEEF405WING/target.c | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/target/SPEEDYBEEF405WING/target.c b/src/main/target/SPEEDYBEEF405WING/target.c index 504379b9ff..5f44b19754 100644 --- a/src/main/target/SPEEDYBEEF405WING/target.c +++ b/src/main/target/SPEEDYBEEF405WING/target.c @@ -34,7 +34,6 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 1, 0), // S8 DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 1, 0), // S9 DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 1, 0), // S10 - //DEF_TIM(TIM1, CH3N,PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S11 DEF_TIM(TIM12, CH2,PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S11 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) From 2bee6f3655908f84b113c99dd3794a947e6ec6d2 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Fri, 29 Sep 2023 23:19:48 +0200 Subject: [PATCH 108/122] formatting --- src/main/target/SPEEDYBEEF405WING/target.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/SPEEDYBEEF405WING/target.c b/src/main/target/SPEEDYBEEF405WING/target.c index 5f44b19754..c6141b9a73 100644 --- a/src/main/target/SPEEDYBEEF405WING/target.c +++ b/src/main/target/SPEEDYBEEF405WING/target.c @@ -30,11 +30,11 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 1, 0), // S5 D(2,4,7) DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 1, 0), // S6 D(2,7,7) - DEF_TIM(TIM8, CH2N,PB14, TIM_USE_OUTPUT_AUTO, 1, 0), // S7 + DEF_TIM(TIM8, CH2N, PB14, TIM_USE_OUTPUT_AUTO, 1, 0), // S7 DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 1, 0), // S8 DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 1, 0), // S9 DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 1, 0), // S10 - DEF_TIM(TIM12, CH2,PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S11 + DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S11 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 softserial1_Tx From 235d3b0c2bd9a85b40d7346dc7a1b7da28bf50aa Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 30 Sep 2023 12:54:04 +0200 Subject: [PATCH 109/122] TIM12 ha no dma --- src/main/target/SPEEDYBEEF405WING/target.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/SPEEDYBEEF405WING/target.c b/src/main/target/SPEEDYBEEF405WING/target.c index c6141b9a73..aaab610a81 100644 --- a/src/main/target/SPEEDYBEEF405WING/target.c +++ b/src/main/target/SPEEDYBEEF405WING/target.c @@ -34,7 +34,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 1, 0), // S8 DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 1, 0), // S9 DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 1, 0), // S10 - DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S11 + DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), // S11 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 softserial1_Tx From 45e85a28959af3fb56ecffa23293cdbd6122f03a Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sat, 30 Sep 2023 13:04:54 +0200 Subject: [PATCH 110/122] Leave as is --- src/main/target/SPEEDYBEEF405WING/target.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/SPEEDYBEEF405WING/target.c b/src/main/target/SPEEDYBEEF405WING/target.c index aaab610a81..c6141b9a73 100644 --- a/src/main/target/SPEEDYBEEF405WING/target.c +++ b/src/main/target/SPEEDYBEEF405WING/target.c @@ -34,7 +34,7 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 1, 0), // S8 DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 1, 0), // S9 DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 1, 0), // S10 - DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 0, 0), // S11 + DEF_TIM(TIM12, CH2, PB15, TIM_USE_OUTPUT_AUTO, 1, 0), // S11 DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), //2812LED D(1,5,3) DEF_TIM(TIM5, CH3, PA2, TIM_USE_ANY, 0, 0), //TX2 softserial1_Tx From ed415c8a2510a694c2c586fa11dd7c30c7b80fa0 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 1 Oct 2023 10:17:22 +0100 Subject: [PATCH 111/122] 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 c1847b353a0c6129a3a0eca087971747314d9ed5 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 1 Oct 2023 17:06:54 +0100 Subject: [PATCH 112/122] 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 ef7fa53a9464436e4d87d86091cbd3b824f02300 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 2 Oct 2023 20:50:47 +0200 Subject: [PATCH 113/122] Add Rate Dynamics to MSP --- src/main/fc/fc_msp.c | 36 +++++++++++++++++++++++++++++ src/main/msp/msp_protocol_v2_inav.h | 2 ++ 2 files changed, 38 insertions(+) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 8b62fdba39..192a2af314 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1582,6 +1582,21 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF break; #endif +#ifdef USE_RATE_DYNAMICS + + case MSP2_INAV_RATE_DYNAMICS: + { + sbufWriteU8(dst, currentControlRateProfile->rateDynamics.sensitivityCenter); + sbufWriteU8(dst, currentControlRateProfile->rateDynamics.sensitivityEnd); + sbufWriteU8(dst, currentControlRateProfile->rateDynamics.correctionCenter); + sbufWriteU8(dst, currentControlRateProfile->rateDynamics.correctionEnd); + sbufWriteU8(dst, currentControlRateProfile->rateDynamics.weightCenter); + sbufWriteU8(dst, currentControlRateProfile->rateDynamics.weightEnd); + } + break; + +#endif + default: return false; } @@ -3040,6 +3055,27 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) break; #endif +#ifdef USE_RATE_DYNAMICS + + case MSP2_INAV_SET_RATE_DYNAMICS: + + if (dataSize == 8) { + ((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.sensitivityCenter = sbufReadU8(src); + ((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.sensitivityEnd = sbufReadU8(src); + ((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.correctionCenter = sbufReadU8(src); + ((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.correctionEnd = sbufReadU8(src); + ((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.weightCenter = sbufReadU8(src); + ((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.weightEnd = sbufReadU8(src); + + } 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..9cf1881c73 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_RATE_DYNAMICS 0x2060 +#define MSP2_INAV_SET_RATE_DYNAMICS 0x2061 From 42f53ac2f2854b362b9507cd3c2f6223a7f8ca92 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 3 Oct 2023 10:15:18 +0200 Subject: [PATCH 114/122] Remove info about F3 mcus --- docs/Temperature sensors.md | 17 ----------------- 1 file changed, 17 deletions(-) diff --git a/docs/Temperature sensors.md b/docs/Temperature sensors.md index 384be48eb3..fb28465e05 100644 --- a/docs/Temperature sensors.md +++ b/docs/Temperature sensors.md @@ -89,23 +89,6 @@ To change for example the configuration of the fourth sensor to label `BATT`, mi `temp_sensor 3 2 7d01186838f2ff28 5 450 0 BATT` -## Building a custom firmware with temperature sensor support (F3 only) - -This needs to be added in the `target.h` file: - -``` -#define USE_TEMPERATURE_SENSOR -#define TEMPERATURE_I2C_BUS BUS_I2Cx // replace x with the index of the I²C bus the temperature sensors will be connected to - -// for LM75 sensors support -#define USE_TEMPERATURE_LM75 - -// for DS18B20 sensors -#define USE_1WIRE -#define USE_1WIRE_DS2482 -#define USE_TEMPERATURE_DS18B20 -``` - ## Configuring the way OSD temperature labels are displayed You can use the `osd_temp_label_align` setting to chose how the labels for the temperature sensor's values are displayed. Possible alignment values are `LEFT` and `RIGHT`. From 5c6b8a67d64cfa806ca3f1e3ae789adf47f0c3dd Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 3 Oct 2023 15:52:27 +0200 Subject: [PATCH 115/122] review changes --- src/main/fc/fc_msp.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 192a2af314..2b2d4a8437 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1586,10 +1586,10 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF case MSP2_INAV_RATE_DYNAMICS: { - sbufWriteU8(dst, currentControlRateProfile->rateDynamics.sensitivityCenter); - sbufWriteU8(dst, currentControlRateProfile->rateDynamics.sensitivityEnd); - sbufWriteU8(dst, currentControlRateProfile->rateDynamics.correctionCenter); - sbufWriteU8(dst, currentControlRateProfile->rateDynamics.correctionEnd); + sbufWriteU8(dst, currentControlRateProfile->rateDynamics.sensitivityCenter); + sbufWriteU8(dst, currentControlRateProfile->rateDynamics.sensitivityEnd); + sbufWriteU8(dst, currentControlRateProfile->rateDynamics.correctionCenter); + sbufWriteU8(dst, currentControlRateProfile->rateDynamics.correctionEnd); sbufWriteU8(dst, currentControlRateProfile->rateDynamics.weightCenter); sbufWriteU8(dst, currentControlRateProfile->rateDynamics.weightEnd); } From f74b0188669b58ee1686e7bf8647a575f153bcb3 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 3 Oct 2023 19:18:24 +0200 Subject: [PATCH 116/122] Update PR testing Documentation --- docs/development/How to test a pull request.md | 15 ++++----------- .../assets/pr_testing/actions_summary.png | Bin 12158 -> 0 bytes .../assets/pr_testing/artifact_listing.png | Bin 72315 -> 0 bytes .../assets/pr_testing/artifacts_download.png | Bin 0 -> 100463 bytes .../assets/pr_testing/build_firmware.png | Bin 32828 -> 0 bytes 5 files changed, 4 insertions(+), 11 deletions(-) delete mode 100644 docs/development/assets/pr_testing/actions_summary.png delete mode 100644 docs/development/assets/pr_testing/artifact_listing.png create mode 100644 docs/development/assets/pr_testing/artifacts_download.png delete mode 100644 docs/development/assets/pr_testing/build_firmware.png diff --git a/docs/development/How to test a pull request.md b/docs/development/How to test a pull request.md index cb7abc57a4..44a8507fcf 100644 --- a/docs/development/How to test a pull request.md +++ b/docs/development/How to test a pull request.md @@ -31,18 +31,11 @@ Once you find the one you are looking for, go ahead an open it! Click on the ``Checks`` tab -Click on ``Build firmware``, it should take you to the ``Actions`` tab. -![Search results](assets/pr_testing/build_firmware.png) +Click on the down arrow next to the number of artifacts +![Search_results](assets/pt_testing/artifacts_download.png) -You should see a summary with a column saying ``Artifacts`` and a number. Click on the number to be taken to the list of artifacts. - -![Search results](assets/pr_testing/actions_summary.png) - -On the ``Artifacts`` list, there should be an artifact without SITL in its name. - -![Search results](assets/pr_testing/artifact_listing.png) - - Click on it to download the zip file containing pre-compiled firmware images for all INAV official targets. Extract all files and select the firmware for your target using the configurator by clicking on ``Load Firmware [Local]`` button. Don't forget to use the ``Full chip erase`` option, as there are no guarantees the firmware will be compatible with your existing settings. +You should see a list of files. The one without SITL in the name, the biggest one, will be a zip file with all official target .hex files. Click on it to download it to your computer. +Extract all files and select the firmware for your target using the configurator by clicking on ``Load Firmware [Local]`` button. Don't forget to use the ``Full chip erase`` option, as there are no guarantees the firmware will be compatible with your existing settings. # I have flashed the new firmware, what should I do next? diff --git a/docs/development/assets/pr_testing/actions_summary.png b/docs/development/assets/pr_testing/actions_summary.png deleted file mode 100644 index 88673a49bee0fbdcdbc16481fab2147a1244f56d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 12158 zcmb`tWmJ@5_cw|K5|Rqi(hAbuq9ENd(hZVB_b>`dhk$e`-3UXcLpRc$(ltZO3^g+^ zKJPi-&N~0K-uL-(@3{B1uDI{DuN}WgEe*vd1T+LVI5 zWqCP0KeOW%ke~ic_MUr=J*IV>yV2@dg_hBVft7Ix6*uxpA*G^(SibEvmrJFT%S-yY z626+rqGU=VvLXQo!lVZ1d`2WMKYgqN8*X$@Mxp_Y4qr{IGC%7Zu?>YcPD{qC;nSL91Jm~_6$@4YzD*vv=b7?yhQtf~5KfMSIcmK=r%XS+m;!#sk!Fgl|5pjL z{r4Td;db&p`DgXt+voqq5&c(&J`izVm1ZkHX%aiTa?^t^^p?-Acr|0r%Q6irjirEP z^*D9Iu$PA3CW7bqRJD08=FG2E3nd1=gATUR2tCiX_?iKqt=pm;pCEE$TIohVjY-@lYHkZlRA2Ge!tD zP0a)Cek`yqvnRwkkh{K77CmaVx_J8ZF~g^gSBEv!^qG)^mHXlTIW+L!(%)tUe)ojC zy=Isv`+SeWo5M(9@hYI|;Q9BIZz6)B(d(AKahLJ3-#_xFkZQthf;=So{p)*sC;hyh zGBTWQ$KUby1JoO%VH^s^t{OiJ#fP{rU#@`#7iTT z-2ylD&xY#t^##nQ5G&@|myhV0hJn$H_0PBxUJtUc+(av4^>in9Q6`)mR@+kMReCd&^s~%{3 zo0Al9S>-HQZsQ`0q(mR}9;NDc%^E4E>qS0{R%m(F`XMjS^4XZOuf*?P#l$sfMO88+ zabMw=qaJXY-13L{{i&WY#!l`{u^-1sor9k1xx-zYoyc;HSE|J+d)Qr7PUby@-llul z^jX<20k2LK<=3^MaTv+d=SUV$=k2d-n+$qG0$Z#?Pj!!uoSK69y9KUh{GdD*d75j)~IC{m>m| z9^~=PYRbUDh;aU}1$?bfzN9W6r<1JNUez87Sh2DBy=s`LCbu;^`l;T@=bRv;=yq!0 zjT(|@g2tU-VbErlU?{oV`H`#r*_mVred?=u2RoK2wG+gV=@d0z3e^H3O7B?{D%mtr zr^y^i$!nIT^)q$NQt$J@V)VW5_J_m0M13~#xg~RZW0|?H*6^f}4FS||i-%6X5%x zVGg%wRB{5^QX4+|q5D`xy^5hBSh0M1 z!mAv9omnKz%IPKsstvM^g4_>`ejBaR5Q-h*<19 zeh7`_)|Ac7`QI5%XLJX`cPBQH~QeWW<$+{g&{WMk?@dS(*g5}`aKwR(&62!WgO!^8Hp#oDXxdc=-`d$mV|Quf}Tyn4H> zSqG`mT{R+x%`!ex^Hd+Zx9-a6hOq=4-igAqQ5Wnrfdy=~zt_Hg+^PKE`;(uHbc*Zv zNG&0mEDe|dT9=YT;`5xHN{LwKTAB8h&S!-oWn$axq6HW=&b+Oxr%lhYEA^H7ind!O zgtFW2`TrI(%Iow|g;NGEo$4{G?)bz^r zogHLk;&C=5!<4+OOt&RlZCf+<6>K2Qmi@WuZ<&y@4+X$eSv5yKl>&(@ucOV;$-Yf; zRIfofd#8$HI){T8F3AM>ba;5DiW;`6jPC=Rv1j~jVZ8%D=v6(!Ir%4-4p#Jbc|Ix= zjL?6(QcfQ~_^GpHh4fML3Y?<8CD)_DDsoy$jVatiPb<#EmfI~lyqD}6D7!6 zB0KulmzX0x1l#6c$8$`h6O(!?ro1nk)Pk=*Du4X&m|ld~{Q!}yIRb+aG z3@(~sa=*W-<<*hSG+;mQIgxBx)hJmHb?=3kEssSbW$T7`s1fUb9G4S|-dcurVUlJt zmo;KfN)+X1m5nSE`=yesCN zs52>+bh!IutUzX-dWuc`D|PA82@x|wmER$V`x7(?(+6^!$QE(Vm&R4gGb==Rxl6`G z1WZNn_U@5n6LrI-_=F54rlRHP`v!r6s5zG?c56I^jD&_QJujOnpR1lm>UAP3M#Bj^ z#tYU}xm5J}6CFYsp%mY1{&S0%Lk9jlc?sh|8nGjHb2sB?en+uTBj?R9I{H8l7QI)k z)PnCdPm^h$#)Ni>Gc$)qto+J1U+4#TA*2eTgeIkg^butxwhDgj-=L+$pcANl3xW}33bPMXj6nj!ta97WVezk z_tF;&zn`e$;8-+KzZ(BfCL=cb|C_A*S0eGd4gM!Z8vBqx?mxFQ9tbo1yC!SbHO)^! zz~83+OqlIJbvi@$E+ZjgEN1e%%XpR-tU0m*F@bl95^DrFLbf-2%nC0ix>+T zxOmDES|X_(s*!ykhmS66a(yG~oL!^IVrc8t*P0%H)jj)XI1hxcvwYo4Ew?g<*dF8j z=JSdQ35WD+q>1e_lQ9JyMU|hlI9;*m>o0+)>dsNTCjrgJjogx)y_OhFN=t& zwnu(znh;3a0c0KCSumfP;eBq6di1W$#woQbr0SY&4B&6^F%%Cp`m@RJDhD8e>X@9k zJYQ_3TIGHUn3Y>5@C+SJVAP!3R;Hoigo(MB3BLnI8tlHRhts><=OnG^R^+hyCpr&&o_OdV>k6-6FUJ zO;!CaB1Vd6^1v}uEt4fj`Qi>WYr`YfVEF42=a_{m(v^!?r=0ku?12u82vg&R72cqb zaHuzO9-kTKL(o!otNH%O(Y`Cl^3c@0Z5yDehja$}fQJRa^CmOMi_jUTPMzkK%XI8* z@PvA<3AP>Bc{>CPybcV!LBS5kmwj#oY9z*GiDa)Rq)d!!{(hX>nK@W1KWvE?N!4tm zOlz)tEv7g#H)WFQcU`=`9&-oi-WG4L_@K^u8X06p+S9Vp|>J8^g%6`%PiUv)QjfY;r(Ew(^0>W zTk7j#M8+eo?sIlVK3J%qwmgAa?r zjpu+sVjq}z6A%U+!E`)GHTSPq>QSaFUfL&N&`9=v0t){9>qkR2X`^fr)mJ zcXZn5^z89B5D0MI*9^U{0?pdCTCEODpI^5;K`(9n+8B?@J7>b$d?>0f?Z|7Z&2u&O z>~GMqzDE(SLPAI-YSy$FOK7JkBP*wyZ8XL^rzd(y)>2*Rti<6a_Ac4gwcO2Bnv)#e z?5IbNh`uGU2l$sVR)q54^C|l-kVWXa;=dbB!$GP&%on67^Z;7s?Ak^gsE9LI%zMln)<{ z98espVV8j< zSiVkz3CVO|QVy%?wQ)_ErK2P`=S2d-wc;w%@q15%CKiVoAflDd~ z;DTY@T$nG#KIG>p?eTDrV_s*wM*~*bLAR*Av_*d8W`>UxpP{Ha$V{FpTVG)(JmpdR zAZ;DZY*7^5L;K0dsnB&x(!uCp$1h{k7964U{yUUGS?v)k39x@%>a4{PGi{aaU8um} z_AY_$lO6%|xb}S8?S-tv2Pf{UhWe$8-5pX2(EF@LLZYY;E09Ef@y=LJ2OA@iGMq19 zq-ju>AT_mOaVlwlVQQ(faksub+o?0a=}-{se~B8uMKLzq79yznGo3Ik=ty)XqhH5u z4izUX@G6yr3cS%mMSDn0KM&%Ape(STL-B5Uu^sN?DhYZQsA9BMYoXWTWGy@P@&3nG zt@;dhp0G-nBdy$s?$YK(vC2dJ2C=@KRpYga*7%MXv7PM|cIHyZP>#H5BeP#eOdf?p%T*8JR2|ix&|65Q;fI`+j3Wkbvv#nTpp(oPtu6ann0>I zT_zA3v}wP@YKyu4yzHm_I!rT8wl?O|8FgXs@T^!U+eS-U1=o#_snYB;z#? z&&EB!IP=Kg)U?LS&+YMW6d!+1!jAM7snC@0OTs;yA1~(h@5&4}jIr%``cpW~@2mXW z7DwX6b6=op>6-VrS-Go<*VWV?r&-~Lplc?klmAL(Fer?*7~+wSg!Gnzr1XLe<;rhQX8t}pu3 z*G#Wx4rQAz4^Wk@=rDRsX*eTlxn}z`x1$4ys_9sr6Tl;m+}rpA<;b~iR^q&#uVa+* zYB&y#q&F_#0>QZ}+XDug z^|RUCPe9YYngIZ7#8KPNs>1R{NKIAC(a-Dm!k@gQJ9)Bt$CiF5)>oM>$zNNghtW$v zS!L7K4_i8Pl8E!E9|o4U1zwLbsB=%59Q%SXZOtV*vZd^~rst5#&L<+-?12Vwx6w0U z%!BVL^+qynKL;c=|Ew%%vG^9$m?me|^gcZMl7y|RJB5c9Dbk24O;L4>wq^$1{e}{z zTQXlOso6!)axjT6t+D74Dvc zE1!b_#Ku~piaFd3!;Oh~PcNa8V4(To`K@sg-B>Rov2+s;$lDea1sA;t>rq)hv3P*ha4~+(R3c%%sgKGnQLceTE9}hIq)c! zuIs8V?qFS9LN+Fnh<}Q+eWz@fcJ304Y|vi@i$d(XGIhun(ipj^ufWH@;5 zJgVEt6^u*}lQJuNa(uit2Z6bn!+uJGOUiGd9kZjnQb_bohu2DyQ!4$(pbNal(N*%@gM$oN*~q;_HWYSZA#sMhf1{sv^O1x(vFq0_4XUVZ!g*vRsAGfmJK%Rbu6j5^~S zDE<6K*9Dwjm4l3{bczb$nDMf(mf?6I(q5<1=WLmk!W`%Wx5#WaLpEEkUigO`C-*@< zik4BN%Oxo>`$7YZ79|!aAiSQix%w0lKdreRfsQIs2D9~7)y_I|A3_Li&Ai-?^UmPp zS~qdm$%EsvVo4gRV)`>w_w@8g)iP#er-?qO$IVC?kN!fai3-U2?EH}3%2_Jk7L7e%F7A z#`uS?NaM8xUL%nw(uoVG-OxY@vmhUA)owuW&H37_v)|P|UVNj>`DKQrDi#r@I2Y`% z+Ux5hbNU;|09yYH3_k7*Y+YOKgneN5ywvKv#IA-?-`&M{jJHNYyu_C%x^r!$Qb}uuAkxX9{Z{IaqPL?ti6vHAMSq`N zKs&cd3gpwLE8>x~c6pNb0S+oc-E~Ylw|D8H}}6c`446+9}UfW^!8&mD{r4 zC;v1Y2$4A_!xe1FI&Qt1aXXaSe-?a#$IuMf<)xsI+7o?24Qw;GVW7_R%sHc~mFDKY z5|xQs2vW7yRm~4t(kU{;h`PXkAepCD6ZU83J`6e0PU|P|VFN1T7_g>lGs2@D{n=!_ zTWS*A8!@wK4Mxy+&pGxSyq-%vjHbpnV)`7Xw)r>w<9b5u;>Uw^=wR`)$r3P!+Gf5n z^_wr&{kZ&GcCp5{wJMxd&o#JrE2$M|%PyGK`8C~GpKK+JZ*RPojogox!f>t_C#^;v ztt~(IQ89AMZMkzk_ukU=s?V@(I6RG)nPBm**Q;m|9&Z2s{HdTySFZa=lv{eaYA#sKAX|qWNC*u#lk|WOIHhB{4MXwHU!F037RYzO3WG87Q{~R(p>S8~ z+M+ba2AaCa{Z;kGo%G<|;rFOn^3!6lVAh{i6LX^=m!@BH{I&-MUk)Ygo>uZyE-cPZ z&#q?UGn6acH8F?nO^=tD^W!=c#F{*n(GD>ooZ}~H#lG^XiE%}VYfC?d{%{i@Ed3sf zgH^6Ac~Q!|%G^ihGo$J4d$}^E>{ctksxN@#u?Z#(It|5zAf&GQS!w(v`zh?+BNBrW zimWC0=7$x5V=d@m7x`OB`$-4!g>`85{(BxWza;P8OQ{<*BLP56MU}^Mg5rJgP&_a- z(3A^%$JF~WNnYZMRyOXPm{yq@7&E?kvpwyR!_~A9n5crElZU)U4!k)DKB4#Jr;p(6 zjWh<+q$+Wo$cRm>7}(1|_+9*C8BLWy9%Z{yz*so}P_P61R=KF&?kjECqhwcgG+SpC z3yN2ado)w234M!G#XD+3CZjM_@1nj%;K|C-p|n%kTJbe5CF&W+*&mU*b(5cH5#)dF zh;0{DNnhJ*5+n*iFZl~QeiKO2-X;ji-yeX1XKrqjs$IY>Hw#1RYpqV!r)>amO-JF` zDtcV{Y^fjIkKw>Zxb-wE+YEzVdGiQ(A17O zb}L;G%5#Xen^R$j+}hLzBi22W?}H}H+Z$CU5{Rm?$z0b+YHanh3~R#|3p)BB%dled zQ)9IpJ}A{+bau2O4~yU_oPR`AMzoTr#TXW@H6k!LShiUohIC$t#*~iga|AEuM))je zd(XZj%MtFK?R}y-0&z{5?T=d4e|ykQSA$mafUle3@B@{ijfY#iQvMj<#lgc`4@t(T zeMd7-@N_-XEzaZ(UB;9+Bq}w(vHQXOIc~a52dJfNsH%8;MG}{eprJhHUk^G5?}ZJP z+Fpt>W`q~aH7XK6L3x6f@ip+sY1-E1CaawV-bPfJ*7sfAM^nbam-epgvg-EFhtY#x z=JweLR}yph{HKoi7h9b!uiD1G{h8Dd@Jnm%0+ZjBRgjJ-G+We~7mGa;x{*7*J1KY+ z;Kr=u#@q0s{>Rh+PmQWL#gmN(Q=0m+=xfa1epEZMuVZBG`Wn-)tJ&VU8g$WXFPO;~ z=yX%`P7~dPtQwbUI|^HKF*#jEowx?Lso$jZ6SrNrcK0Lc{LpXK4i$;%rGqd2&}KS{ zMi(S9rpX9HL&4kp`$M5Kk!rc7ugw#RCNDIv0{a^R->&>cTc{V+NHvA6AFDR3%S{2V zbpcW_xeeOB%B9ATY1@Z~NT%dnXNV_ALFR<~bJ397I`o}KEoWnJYPMkDge)6cOJ%E9 z{y^sw`mbxLd`?OOFh6RyU3yU3ovruly=wvAf>!Owy_;=4Rtkp)EiOH#YtLKOnb>g# zXvn{m;`i<3g%Dll-o-U9<|(cR3~Em_h??7!)WhibGlvt6zP(Gv>IJI6N&BjkCC2W|8IBzwxQhaovp=3mJ3RO{;1h?v9>T|$Y_eK%5Rv#!D0Ub3O?3SoKRTT># z_!!JidzV0Tmep?^q8NtS{F|_dZak7sjL}YYp0gzQ#?kZGleV+I)wP?E(GWdfdpJym z>4ua8!DpG#jkkMCt(jmC z4l17~IsbK0z0UZAO*Z1+{w@K4^R|L1w2M4^lR~VIaFM&n4*QL1 zk6=R`Q{88vMxBeHZXIk-j#pGkyL6wCpU$!b=wD*nX zC}S77#*_6gm-Xp~R6~eg%tEqH4Fcd+JTR4xt=O^9ySsMuRd5*TV`l1e^%y9x8i#Bi zg;ack&-;7E(5%eun^_ZRWMn1R42S3Weoi+NKEoG$Dz)a@A@TH)jc#;!90Jw8uyzMa zG6gR+dV+_icxO^kz-oswqpLrnz^i!U>LstW>>0M`U_>`e>YQ;+961yX7N7Jy^4l4p zt)>^p^iAXg%}ygV`!Gsb;H=!db*AUQ&DDmj&XeQSgN*tOm#^16G~$VaOB9Il&x2nx z(Vu@=jCsIZRLyV&o}kJ&4!Tn1*%%Mzo{lzVlpe^8oa;NjU%i!YA8433RCb)J9Unu` z;@(A}%N(~)^}{$wrTm`RNGGk|`4c*ruFW`FcbsH|LAHQvES+t{L|YfabStP5ce;uo zINu0=-6rZqT|EQo!6mtNf64{CP7j9zHuOk8Ca1Xq`t;d{)9`h({q6U*Lh!Jf(#`SB ziR)NELkxjkmG1}@)KJ+Dpjs1XXp*I*`c3&3A&cRjGe=d4$L3T*GEbh8Qj%bB z+QHqIoe(AShY@L^=&pH947#dV{LV{Jc_WVw9%Wp6d?7_@$N^u&$Q(vqT4|`|fJG4PGL1dn_R9>>zfR z(j1+qBhB8i*bo_d_;*(WDX;9o1~Y()7fXS97N{rhCS<#NT$%X0nr( z#ov-nw3&yhunxm2qG}PtKptacItO6obgwoKk815KUAA1*j>tptW|$5b{o&y{yR7LFE6j-=JY4~;Db_v=QoB^nUFhs^ z3Venbo6t4?Z`x7G=Ryk*%(V48K=ep)saG?nKh{5S{i}ldfyf`FRkgD|Tv>~6@nfyN zP|m}~dYEHr5(wn7LY&Tc6=6J?UU|7Lhdir&4-8KWScr8r{;uzwa3j&Qq*m}Z?1WzT{O9dl;7hA z6Mj1%x20@g=VqGKY;*$1?hY}3d~POLB7OJ^wJfiRigd{0(8(GG(b^Df2`xIrUS079 z1uv}(i-152@7CJRof=n!uwm)LsX>m2)M{Szt+y|w#%f(tiS_Y;=wVJ!IcV4TrUe_Y z_4`?FlM(ACYx(~E-%=umhiD&qn4W=o5ok{2@CmN3fe7we)C1uSRPpHA7gs+eO}GBB zm!%@XPtQRDN@LbomzN8?x_+Cz~Znav$#0tUU$ z(|h0EL^M!a7M;=_SiKY8fPI#4N4KFQbTxZu8?u9I-6LB#h9Y*yD)*IW6lx@ldWh}Dm@!gmkROH7H+eK7ryBt$SF zA`W8}@MqdVcsMR4qbJv{A7Ayr_^gZc&K=e4Yl63G?RQPl7u$>&L{_=EVH12%6FoI2 z8#LJFfW7%ESY&eX`MjtTTOt0{x;nUjZ3VRv4L;{3%+0tNEUv;%H&lbSlNA}-&Q+s( z4ki=}6A}X={kpg>#ooor?3#{EQ`EfIg1@+HJK5skXyo4kA0MJaNgAK3VGu_oSl6-s z)(&{{fu@E{Wpni} z_qKJ*cR{y-bEcTs!|Jx}165vLI&g0*c22g_eniyHbF2k4XM9g7nZK~^{V44|Z zRu(!;?60!YCV$H}slFY?_OG$b8G^TQR71h8(V`^(h*{)vGsc0o>Z%7>h&}7-GN$bG zJUU2cYzB@UE$n8WgLz()5=Qj;jcu^{X~OGZCEPMs_96UMu`+>DDBf6;ypyJ#yDoE% zhBo|1w&!Zk-3?4e_V)Fu{*kfay{xo}-L}Ky-F85GXEGsK_nMxzZeB;z`rUvr4F~v- zSO&q9yOoSdW2OK0X_EKI_T)~ieZ#$Lzw=dOh5ZMz{9Eb24ruG%c#^>MVa$~`0|;D7SBuP8~9JFC+!5)%R2gF@yn&+jH#UHb=e z|80p@T5dW`Vt@9u1GYI#z>D6iBMBz@H|+jxm(U&gAHd)L2WRyvOBjiL;M`wy#0#^S Q_&1fZf`)w6TZ@qY1w2O&fB*mh diff --git a/docs/development/assets/pr_testing/artifact_listing.png b/docs/development/assets/pr_testing/artifact_listing.png deleted file mode 100644 index 083e73060f8007e8295f369977c23790bcc5b79d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 72315 zcmdqJ1yEdF*DlyG2*DBv5Ih73!GpWIzd?fscbCQ?AwY0l~8r zzw>{$?%b*W-kGYY*;RD+={oGQW$nG6^{i)g@IQ)Dn9qowfj}Tk8EJ845a@9S2=tKs z=|kWf_toke;O&8vvXm&OVt`~5xOi+Pq96hSRYjs-8$1E7(d?x)oj@S0U-y3xI_-*# zL7=;Q8F3L+H@%%%G#yp7dDMg6HNTC@;4fHTuna{*7EshhQ?lL`J<$wFXne^e@jLeL zoL{^ZJKKaQc{*3L=@a_#Cv&Q#$AO}T&xzi>k2O@G^M9TD+W*ad(;3;PS17NB-W{CT z2(qoGdG4`-pRNy1IbWt?8iGK=e7HJkT{Zsxk1}oa9UNHP2fFDOYG#G`e~M`R%yZEtOve`xsi zQTF~OwdQX$53&kh!yu0zie(1}7Y7$ZKMOM64}~8LYe@#Q;eLGeDk&x9WOF2F?E&!h z0`nK3eh<3rV6Czix=mzi4f84jogY$E? zUjc9l%0f`&J@(7!7bY){yTA4&{2B)usxhFZ0xtYu&!Hjr)c^xP0NnTIlONOnsCQ3+ z$NVYI(HY6@!YS6N71ZPR`q_>gzt5Z8_q@Ji)9b1KO8e zP!L#f>m^n;HJ^-+kMC9QJps|D8T8eOM^4#(vNiai`Qu;X>pUb|Of$;n>H0ki9Fz=u zKeX||=;kvD??c_AA@b26<9-4x5)y&Fo#Y42H^-Y;f17hKWX_z&?#N1ZU9an_q(b_L zRBJS(;3pWCM|7pjHXP12-g-$VgI!DV>h=^dUyx^_lWmayX5o>Rn zsfXY))ElUpA{c@LD_JXuD=V&;gV|+526wpbUJ#wCPo~6|GU+y(o0)MLjmz6&uOS=# zkE*K+3zY0EoBx{8M)|0itN^Yz<+>01NH)rvdVS8`gjUMxvCHm+)my)l44#oWgWnLC z9)ChiPvY0RtNE7OD}6x)omS^Vom))-0f80+R|RUbfiyyP^MyXmn)AO4&2LUtAa7?o z=j3-eX5WbtME!Ss{4P{fj)>68H%jtBD89G%x&2zP%1X5JN>>R-=_X2`Ce%yfG8k98 z!CM+hQYUJ&wtRSac(H?IRx~!v=4!>r)XDC&;?x;4$RXv@>e5Jv! zgvTgz&F;vSQKKhMp4?oX`1;%;4YtRJ`>}t9;4#B)JBY=^#i($)tKvrKH6V)Vm!nTT zQJXb!ah_ulVAE*0++MqDZb2{bUl#cxr=RJMl_|=?Y^%*qfX`PH%q&TiOlmgo*J|1e6ci2 zu3&H>$KD`dfxNSbR0C%$67J{caJdx*W+tuUi}g%23``451rl;^)yer4$+7UXkwS|P z^vJb-;${BJj&R~a#q=DBH2r)WF|pi&xyrxIX^ZiYE*`ObxzfLHr!%kbx<4+EvcBA% zmP%!@Gd=ibC}db|U$Dd|%V+Xbx7F=%BCJR$ec z(a!*6i{Nb%K8ySe)H^>v(OeQ2-3dJxDj6S-$3EYKt0b>^4VObf`SL3W+pKPf#B*6P zJ_5_g)KU^ymP2TAU=x`Ts+bzuVY1r1;PvUGxU`3^^zKwr!@wy8Ixj8i^uYuZnU{P} zvotxeXs@$@&6gHyMAGP2!}+&k(D<*Ip$GObL3d@87>~sLZ;!GUDn})X>n- zQWiy$I7$ZOgqZT~=TkG6U!C#d;>Mmc!~O|Zb??!lcISLes8d7Pp<5v`G$te@? zsXY++xU^~54Sn{zLQhA8aWg<0bu`!CG2SIvFq88deEUy= z_j!x@Ayx1@yP162-O(ASf{HJenAoq&OOJprZAVvTGY$K`IXMp#nOce)>kMu#)A?M7 zFhL;f_|8W<))p~U&SzE`YUQ{jH=>+m(mctjbzn3`1Mip&Mx(p;g$x7vBR0tKfb-xc zb7cyFRu(FDXUz?5or^~~7r=oC%F^AUFqy?W)pt<4$#`GoX7E~O^hQtW-o_a8NJa;y z<6SiNhEz3@lao20pPaD!&O5ufJPE|k>W}&zyI-L%)c$Mvcypxm%NOMcvV3B#H|y}> zVRyd?Y|sICx#72(ciGA*D>E4y`5GP zmFNUJdJ>_8QUjS4reKa4zCTs3$Fu_C0>;?KaDwR=6E%S&!7?pUN?|u(ARz9PQi=i1 zde5}>JfA=!hXQtYd$mdKOEm?TOSH7KEJMNcSW7lLf3~-`XKQOqT0u8Ob++EB-C!Hx zKqg=}$FKGKy;Ei~*HBDHHxb_LQE$0+!&gy*5v{~rNuHSFlkHV~YN{g4TU8@UA}wvt zD|q{9!QBJU#t(I&^$v-+o~83R<%&E=sFa(hZ{Z{0Ow^MR$ZMs9sUReYbEBPLw`6a3 zkHM>B8IUHGxuysR-YQ-wKJ0vcwuSP|Tri*85Tdtb%~fGZLthu#$8?&MoUEy=1D}}W zHXkbqPvwl3TDiN?Pp{q^Ahj8EWT1{G$%A~D=YTwkt%;h2ogekmWTw%@-Y8m`i+<^t zH%<%?#VwRdKgZG5*2cxnu7n+sTTSfE!t_r>u=p;jy1h7X4zchtDWcaSr>4BnK*G$p z$BmQ|0;(D5m9(tXk>sq4+y==W@=byPnJ}95@5;kJ6}owxnKA<~aN~a#-2CTJN2a;Z*NOZ%l6Hr0iOLvcg%v(8%p! zC%ZS*fo2r?%u&gQY;F8U`|}9&+*6wMA`&64ZR9)s<`)1oTPz?`#=*->2Zn$>9smrjG(6C;NotY242|rCZvtK2D*-euI&CW~GsQO*A_bNM7UH3WoR`Z{S-c zM=gv);}?Ggp+RUAGNtKKAOw(?}(=J_k4+j+j|d-Rg<@Ox&l&Ybsh0!?G( zEItVd$+`7aNN8xclcL^(%w3eF7g%td(>!0g4{q?ocI($~`C84Vw|7cf1zV~)6-~s- z3UDmFWj`1p$W@XF8WwlE9`oi$EUW5QMICC@bcd#Msz*2Qy{Y)7AU!1m&WWYI-LVZR z!>kB3B&O#>5q}(kXIZji<;Wx;$Rg;X?~z^ZxsdWLt0~U|x%aiR{#cjof>SksfsdMk zLQZn7>y>_HXVT++lPMehFngytiX%&xlH1|>oXN-eG3X6Pvco+a56pPf1HWNs6f{$1v&etvb&y^ku zGgCkF2(z1vHMPqgUS9OJ{wn!xCgIXPSlzhT>LztbCg(jPunkg4ET^dSuyP{CsVclo z+!_1p%hHI?>d%aj>NXUIRNe8W?SV}F3qjy#Hah3(Du{2Nn2D53?GDoMpV!CE3Rsw} zRBO)lO7~3-v~z16wb>AA4$$E!RR`~!Gt#%cPy+Dh0eeu~Z{P^;61vS5DTd1DOJdfY z^|+Y)vp?fSr4=iZbUfJ{7+JH=+sT|1GQ zd>38eT{CeG8FC+aFU}p%IP#l_;pRsop^>3RGiyQOHi*omG)LBk1#6LJY~A-N??`^M zRoH_^jr8NqPFovWoNC$&@JB8UGmi&z6Ph^~+wYNA8mE}-lB-C6{GCpP!2AzCVdX{H zm&FC{C6js!LeY0zVi6q}8K!L^z|LC5hm%~yY zalI&IxCvhutKX69;g({3^I1@PJg-vu2aP-fM{Sm+h^t#~iF+iU0{YX?-UO%U{2>Q} zE-hPPz{tfEOYdD@zo$n|MKS``L1 z)>_N-4@4cX4Pe@9<8#Ezxdb!t39^0{iYFH-p>fptdGB44*#gcjNLY?ufaIc%FyEbz z10y_cmoe&y7WK@2x1j37=pjT@YW`b*lefRn>_}4qjGa(dxMSSOs1cT0p4&-398Byb zF=Nc%kMkyG0J%)j?t`et0e_8hy68K>44KYMtEP!66*X^7`koZG@@QCuZMNxMJc&?W zdq}AoGyU~fIiL~zGtZSD3J96vba6SERGlHOISy z4NSDJ)!R+k$+Go|-zkP*=ulY+nCV#bg>>Ff!n$JAIWxip(ixZ;spHq!_2n0nbvD%` zkT0uc^F>qQpKl6nmpg0S?*#TEglh-y6dr<(g+oe8nw$4R>1Z0cqs>rJQ3VmuB|}$e zN?PkfK?LS+N|HS4YbqXK{6Mo00H$Hcf4013B>nIn4}pqA?t3v=o}$eT*ew8cpWJg0 zDzqgfdvg{7rhh#7W^7SefdAMVpKWr;#nILKLv}beC;5_tJf0n0$rhKXsjAHuHGe*p z0c!ArJxaed^*09$koOCr{{79W*~|3zm4iUeFMz84l#MsQgZ`8uiF?z!FIl0${Qmj$ zKcPHs6+0N7VqvD3OE}FM4*gy=_;EYHK9LPucm`B*3%#$wZ+z06PX46IZR>S2TCI^F z$2)H4&jS4??@wkA}559U~tJu~d9cH=p;A3g5UthsHn6iCMw)mRSK6CLL)AFA%g3ah0jn49Qmtz>Q5l49?iK@}5ULyQfN8u}shZkNl z^tv!n&%4Sg`J;q4g`b$UZ&~RkRWydTEm}SCl)m=AMQG~6M#s&j^g_{1=Luqo zye)-CXj261L~s*P6*(7sxUa)a<|8(huFeBxJr3`Tyojt4stF1lfAkAIdI@&g_@}R= zV;NwrunTG4Z%M`4jBvnfk_;_&?bs%j*jECw)t!QpJTYGKrfv~!&_TvIXKb=gfQ`3> zV*F8eO+dhtOq=Vl<7yYh z>(bVr*sZ_RG&S{i^-z-U-rT;_4-$V186b1r?dnMHE@Z7yGD*Nr7VsS3@Pu)aeg6Fl z;`VB_N@e8$hV}c`8o6Xybp_xrIR28`(pQbw#NaZ1u zCVl8dr~y4T_!aW&-sXmP@J{=TlZWGUBecB-738_(>e6dn-WY>8hE9mQfycBek@LjzN$}ws)^BA>o z*tWUwJW_1coCK$TfcV7Ia+#0x?ASUU47jcW8mOfDnDQ9np}QT|;OikgLtG8E&vnri z*<|jow1{KMcIge*b(bYVtxp0_oKb<3%PmZ^a&k;HrUd@f^rsGY8T^>tblNx;zuz|I zd{RZNAT~3L?Q&9xWuTS4sY*B6V1R5U(bKaSJleM*W}s~l6Oz*194blyF-t*%oz0|$`AmZ;d&`&I)MOH8Z_Nx!X%V|jr(ccaWAGfNEn6iOo4p;HM`#Ow|+j651hK7nhM zfbPcbbRGi0#}lX{P>#tO-V~eoTvO(9Rja8`7`gYo5LKvoOk!hZv>1RY9xNl>55hyg zRqDP|yUM~*!=oc5-Ia=Ymy>1k(plk+P0DcR#S3jo<F;<-2kCmTOnsO&wW$8ZbhIiZ8{JPPlfRwb(zS{42GWNEURe8$!H3EM?*RuC& zYA^q2bPHV8-qPX`u2XUW+LiiUq<3BS49BYB#B>UKyQ7$VZ(Rr2)w#w@%cLJl9HvHY zJgZHCNli!(3R=gl%3GyOXsJ3oM~jPQSU^iNPLNkD>+)J2fh{e3-2=&d%v?fuzq{oH z5eZ6XyI1)K*QGyxuw#Qjq%Fg(-?};yC|AGXzi5ArJiVJV=h%R%bCYm?Piy+1F6q?Y z_-opegE@ncWSXC0XeNiv7t}ULzcTyDsF3LsbDh6^ZT!IaKIcwQ{!!=C(_#LH_`u+? z_rJ)!z)i@JaLxhkPPLkwolb&MHYMhCVYk)>KeX>KC^rK_@ks?-8DI+pIB5FsXuAc| zk^2YsMn*=^HFR|RmFu{xZfKhVfGn_CDyB+Eb@5(F8X(Hf~wER=0rXd=Sfrorw%S zhy6pot*@R}9=4qULw$LVC1(Zzjx)g`9y6xF5%uyluB zs!d;^R^y%y5$ZHfnOmDNuF(uobTF9f$oV^Q+&v85Xe9zS9Hq>*zCw%krK%g9;iz;6 zD}PpK;AQZf>+r9v=}J<>GH<4`jUZ34-4%o!+&b?mbMVNCf=9Xq^_-dOLidOK!yX}( zR_9)mkMFEqxS=Q<+qJ$2fi}7UcKK0_U;%Dj3Q6YJki9_Lj(YSLQy$Yj{5I2vlTFAq zK~_su2Z!P4JSweG_>aa$tBDFiLZam4VPAY|obFz_}khZ*lbiA4eo?>}vCtR$)m}~=KQ(a@aB1YKkQI^J~;n`yQ<@4Vs+&Q@2+Cvft)4JU) z4h^AS|DjJ~1J5D$#b=sboNP9Ps;jF#Cz4tDyyo7CnjL-$hE`$2+ZngG9laR z3f;RK`(Au#L`uJQgJSCK=qYx?&DnA!KmpH_2w2+K+zcRI0Jgm%myyQFu{FD4r2#=< z`1rlS=Akfz<;b=l<2;^*H9Ph zCiL&XzY$a!3{1`TRJ5Cs^S+rE$0NC9gc4j6?F`2ZADfeSJMW zJx9K`$@naNXPqMzx^1k+-^_dBXltJWWX`RF5iNbsz5n}t{+oyN)I(I{P3YFIy!n1>TnILX5m7fLA?sz=^=O5@7zfEN&@<40K#6k18acv z(Mhm-5A?MO+EiIl=NPqmJ5Gu^B2E%F3*iDWO`2;w5w}t+4rn;9MZ$n z)V!PR^rOXNqLVK!iS0%w<}vTiU_x_Ev9?yKnwlbSKC*=l)QtnpDr(f~V8`+|Ca>vp zGP=nB2Y{)!f}>(Rfz6)mV;fr&FpadR#OuN=XmiHzSgKa*2pWCTYzN!Pz?Lmk3!wLj zqa7r&`O5x+C{#tc7gv<^1lyaNy6@<6+_89!)YLTacY6A+7q`WNrD9^9`COPRWPK){ z^R(-&x3NV3FbCC@%fNi{P!JfkA@`jX$&c*-S9iMxJikQ^Y+e#w2g7uSdN&nNRr~#p z#S?OVu7u+f4?I|3K><_Yh9@j6Y-@j9V|JtOXxs)-V|A9AeFsePN^+A^W;&k|U9_9K zd%*QFxii}z7vj5^7(k%jAZ$`Bjd^A*H$oPvKB#CZEO*PSxmrz!(V*e@!U2jrHI<8< zeRN`CP>WBe*SDJjD~DrF6Zq|lXDWP+s&U^LB3*J6!}YOfd#D( zR8S8;Q2*$Ng;=~2D&87z8gO}s7uwF=UR6WPX?=b$Jw5%VqSR7B!Npsw&ArzlSY2KH z66KP8B)T_|85lQA@;Srmv?`;{>FN50l^Pu;NJX(aA0z=-4#ayLak^sI_l`HPpY{Ws zwHb$$KUE0{+0rK@{Czm`uxR*IV!ct^a*9-a961SME9IlQ;yWPD#8jstKBt(CrrgC~a9T!FJr=@Id z4K6L6$MZmiGF%tE3}8MtqVrx(V0jF8>$zq%O>JgBc#}Mm zRKdaCK52K`%FK)=TKWwor4XN6l&xtJ_zu@)%eVlL2LzA5ZE9J)O9LMx>;RrvT(VWn zaCACF%goGdpOEeN1hd|D&hexNuek{`StzXtroGQ=%b$6(_tEk?QU9Io9EpI(aat2n zGLlfmCD(Go_pXK4Jbx>!4wps|=M*=iyZb|G2Y|Qk2RU(g(~k4oTeTzs&QFsmFW5&2 zVYYP54$WTxQrF06*&7uLgVgeBfbRt`X66XSWO4%<64!qVWIv{>OSLd{E9!qhYg+XH`Q}acdkO zR^}U9<+Q+U5rE#pgW1{Zo}l0*GX6&2BIaLzP!vcGReX~qN-#~n4N z=-b68Xy6)a;QG>xZ2+!*+w}A8&nr`+EqGQCeVAg#T_fFk&FuG?pE=cE{?+k~tayM8 zP|d!71qrLA8vTor08Izo(**aW`Tvwz{O^+(|DUcf@Bcx+{eI3i$Vk7&p}a-$U&kgr zP4V9pM;EiAytzf;y=-2|p4ZPbR_IK{PBAH;SAwl6_Y15FG-HE=_y6!Sz+8Be>MQ8< zrwKZfa`$RAD5Z`$Uv6M|c^u?w>wX<5xJL;0g$&E4BZTUom#~X(6~d)I5}GAFP7QJy z%(O;Y$8&OWL#c4?EeP$(e!Al-mBSeo;hG$9}}y< z{cn{U82{ns)U)Suq!R4*kr4~CwRN>@Ph>JOxNT<|utSz$EoV_tNnZ=RP6M8xJNoq8 z7|-k7dpUoF7Fh%%&y|US!*@xRUAtoE89iM#<$(yFb>DWKw8=#0ArupL4P#*tS&jSb8!A{qsr(B z0n_&el7|;=rwWS~csqbu=nc8kWFs4~jj=1^uqEsF7;hn9I)49Em5A>gRUKTP7 zz^sk{3J@y@>~{ZKgN?OyNGKDDjO^v|*}R$H&2f>GDNci<~mMn<*6o5NZFZ(|U?Nntg4_D9_0M`rfDk>;A9&rOse%N;Z%3TTaBg83#mWR##nA%AK%!f7>eKi;L4VoO6X7b%uzj`wy&U&R+jOt^H=;>U~{RD=x~G@=;5R=!~PHaX@lF z0bo9~D?d>Lvw?T7Kid2xQv)<7R9`r1Hk?sEf&4N=UT17_#1sI>#XF;QLJ^TcMI7xj zu2H*dD{zfG_?BniY{(m#CyA&ah5uXd%We2e_r$+;AD%B~xtOd<$FX4~ z{Dn6KCS>SYm60(Qkb`d|*iBekQerO2cY1ot3_Zqi@4TCBs<|1HJ;$mFe0UrK1bXD& z!>@uBnLlBG4$chDzwMVvg}qwSD_`kkHUdLoCPv2zHsl>X@gMBPx+nh0xN$ry*oZV7 zq2oQ9#a~#=Ayb|!Zx&MtFT1hnLhkl*Py>E%M%j6`zgtXEsj86l6+jD^Zw(q48>{*@ zK({(DQ}%HHP~ft7hmSz`rpFym{qV1S30g2v)&Ag;c&$gmWtC8ODMShIgYD8+6gzUj zoe|fs)l{7Xj^f5bLJK3>&9c;Rggv+BpV;2HrWO!sDmD-`8*y;7~8-J1h+Vh4ogL@U*|{pK4v=g7B`WOxfp$I zdjNmvsT(S_R=!YLu6IhJFZKE~scnb+IwJIj23u7>t7q~u_zC*BJ)Y>VFAoXAhz(>L zKp=Ak{h>AaH~p~O#DxL%%2glbRY>?+41NV-L(0n;mzqn)M^z`dMpGL|63tCa z^6kE3r|nIy_9mVj9|vOFv1kqel#GoHV!MVqvA5K!By~VrO-)l-S=o8<%hs~v=Bnq} zo|+Ei(?}vSk^_y64H@W(X);kU%nv9jRBo2RLe*mZ{hjBEwM(JwRVlpSjz%dIqV3t@ za;W!NMFrG8Yb2~aG<`Jj$9p_9LY*Tt&l}5DAC;c`8 z_~#0iw`~x<-#nk%uVw0~2Fjqi+TKAgk`RI{X5Bk1AKTDCwW?GX>E18G4m@19q>UIa zb!MnxHmc;|Y~gWu>&WtyFH#w3IyL`X)cLWxmH_>>8rQqYC}WWVlrP{k5FAp)QVNLyh}X}7Ji`P zGp*3eA0D_F_Tci8meWnG0IDP|JTBnu^EUYL5Kz=GGw8hUDoNiLk^gV*$>Kz_{GFgT zG&6I5XR0LfS5PeA6%yd-zTQ0Wy$PLnxM-UT3y<)_4IN7aIPTK$+DzWC^WRidGpQGC2%64ucKd`Y!h6rrM4Iub{QeZ z%X_Aq`CO(WCi!FH;u21E^^KM*eak7$C|U}A&eG4ql1p|&%GES9^qbv=NBgY9YS%d!vdoom!92R10|d=jIz*EG~2_Xli-INaJw9%Jza%=Z2oR#HGdQpc^1Cp*#n| zcoC}WS}6YrKtc)r$l9;^(wPSg@)|}^H`>qvwN2DZoM^k-bb#%f`)a86eo9le3X}u&vP&- z8)8@Kf=npYs2J+E>AGGNznS%za9Fm`Vm zW|4c$L4iVV<^aW8z8({l{tu&o_a~&(RgCXt`gW%!yLmOI?uLz7KdIcqo|c$e$TK3? z-qc4Yh3Ih=4Xzu#XPDaj34C!6eAqVaHSWAR*!tIzJd=+$v9@mA z|Nc2!%x2!5W=UEZhtVdnt?ecvQizkCRfqU8@|1w+fnSFCmrz`HS9|+~nq7J(rniGU z?oWU?-8U(2X}QVRTTK8{poX!T*{1PUB9GN7#3xRJ6A8lDOyl5rv%!~aqGr*JiZMjq zD-10k-mf*aD+OOf822FR)VO>g1R>?!XQlA_P-Whbm*tS5#!+3_aaV_bxY!dE1syW( zsk|nvPWSq)=uU>Gr`6Q@YduVf>a|;yj;n>tNW`}PLr_-o?e}h_!LwJAUtpdv@>%Hq z7v<&scSoiD79G##r5=Y>v-5BYW>#>)k6TJFrvpm8B0u7dNeJbw0vpZPVhwpRCZZ-ORfz2fZ}@$XpB!9R@}mtv04 zFJA39o&r48t7R6=iYgh#%iYzP*gmzi9_y$5sLRmn;xyYzCP za6rv#wo}EB*d|G-S&CE2i|X;PUGFw&ewl|oM%@aBR3Fs(A#U~p`n!oZSHk>gZCa^D zQN1w`Y0fm5M(G&qt25gPxtzgX*lrfNh0^^g-x=wV2dE%EO}#zG5U%hhenAep2vwCw!YbyTqG8vKjKS* z#;d-=*lpArtUD#Q1%H3*=|D z`_XucPYBvLJbo-`Q?V!eUnCH$>PZK3R%M%PntalAn+_vO9RX=YA0q=D{k_d!2B&vo za2i_r@_DX-$Erk6j^-_cB3`5(3Fy=3CAUw!S{v8RMsED@e#M4BTkce_&)8uZSW3y8 z8BM#cQBjN0?HXvZyN_enQFIez@=kEu=gdbrFmYNFmj9}9Oyd99y4lq?dlbrr8b)Yf zJ7l)-4b2vpCX8%da1$*uI1+=iIJ#u#31}$dhf#({pGh9F5iPPw!RKfHtoKjzLy#?g zdUe{@QFJbuoYnnz=<5N4;oF1ipDwYTG8P1F4VR7bgdOWuHPw_Yxl=|b_RZL)chLwE z(U@$Nz{qa zlX!GORFzcI;|CyfeG4DkAMGJpwgnpFvwU?X8b^_Po_C*6CSHh!k8!U*V3+YJjMnF) z!+vn%uQfd|tDhO8S~+X>ByYyAxZ<6F%dv0MwU;TVEpF{zc_N$}Uh<$8Pc<}eP+3RVF?gpbB_sV zj&>FnzMCO5bado1oQ|HITXQ{+v@dFQ@Hf35uv@QxaW`uiga@OqX9ZIbY{Xl8-I2O& zmnY<4Jh1r-fU7wmB)aJ@#^{IDEFdy8muDk!`<%|ZdG6&e!36eHcm)(;-5@$nH_OOufsvi1KlxYyNy^496}G1IF$8}K9yV^RSIg#U4eCFB11R2o z>nj(^eFG1t>>|jh4Jx<%ze1?KQK#yCtbDy*IHPpB%fZRHMi0oYfpTm}Bq~c89X%_{ z0>o!$Wj)2L#DD}JK)x-X^4_PUP)c1LpV31Ya79xEXG<4mnD2Mj>Sda+eIR?Pyt+Ow zFK^@LlUotE8XykY{x=3^X70}uKyAr^QSeJ1Vo9kWQ(hS~7eo^BI%QyBO(#l~o(JyEZIhqfVuy zqCyDx4W<7YVFw%zZ?r>Qreb4-1DKdV86I^o31O>2*h}ykjxtJ9}Jl! zkZPgd;=?``5f~VXppMtn;pgerIflQ7Hp=KDpzQgiG*X5B4yYL!EX(0hQNR?D+s^4| zXsjRRt-r*^)>^&|`>(_tF^qWZ{W72#S1a8TINbp;F(YO^)73WG+Xk`!nYy{3n~m_l zF-B;X$^5m0MbJvc5>r3ddx8czdbU*{T5HR~FexIX;Z30XnM}c=FfY&Tsy@;@(BO1u z&S~-5J@)o(#d630lzBPu)}gPciFS%j*-AlQXQuK+V!FR1z(d2h>PzE6wuKXq@y-B2 zt*EEteK{kfet*r-<2jH4lD$W!z|nkpvX4izLVZVD1gW4oq(Wm(UGCP9GAD_cwAZ+K zy$g6KI6|40xW%fLL!Ew)UD$nnf1er(2(+O~Fm`ywu&Jx54Tp_mb+q@NAw6&ECc1us zPj?6&;p5@qVb;~1`0nv&`8xr`n>**rr|0)lUx2!Y0B-z$l`QeK_qn}Tx5FZ@Xi+iS zUl9J6?UNC0QLOIH+m5JG_HL?+X<*OeilJ5aK?Eb){x#z-(@iX7d(`S;8HVjt+tl{C_s zj`$Fft6r|Bz=nZaOJ}|@lud=jfANTKtVETr9I7VZcChdSo!|(sz|D=HWfd(wLOtHv z@$z^xH6(SpqX}C1=>el*5&=HbD`OK0wv-hhAhx~6sG<_4%% zio84@C@!wJWnkKa=Z6|^18M=LH0B*(Yfz|_G4CI92NIxs?x_7-slk{vQ3Vv0r&1dcibd;3MJWrQ1raKK; zHZ4By%T6OH6(DT_h@wtUP03KjbaizB>Y}_go%|r>3SnJ21Sx{mWAublMyPY;DEXuxS92qa}h^32ALNx!uvxv9}ky z-j^;V+P{^u)t2c~{l64A#1Yuzv;Va54+1UR3S$i6l=&!?jMuenY4b3e3gfkhi!y+R*@xxPPUS%=ZlhB%4YKpxrg zZAeYydb=Jh94^l{H8!`Byc7?eKK=RS$w;B+jq_SxeL4BRaD?BSoKxq-TW^L-3|$I* z0A94d4Y?*x1j}q!Ox&|+`vDP<`)8E^u>ZzfIrb89f|tD7@C?sowI`78ED1$&Lbzek z)?Zmq1G%kGy=nPn$8u@^PcA@~2C<<)6u-7}ts&$7<;nKS#lNBchd`~)kyu(lq)-^| z{uPKH*6}3#D_WT4{qLe?;e86N#!X~g+)C1WY%LIWQs=ZlH!W?Z9mexvpeDD;`xI}# zIZE?vNa#m~(*tZBdAVEB&!~=}R5A5r-P;y*>f(air{sf-3#IA(GE;Q}4Y}w24vQT? z_N2#3T3=pxDCs6XBHzyK*a~hvm%y3z3ys3pTs&|4IumS{zIlCVpfTlC|Hl*DT1?+SZOYN+?HCmsoQhx1 z{j{_Vw_GXv%F<(nAFK(UsL)spCgp% zjM>Lx-W>?TJE-^GWcv-G_x&c5%K?|4t<Ab83~;j%k1x3wfTtek6GnNVB8i z4I|AcB7NpgkvX*VTCSm80@cGlGeEhxY+VSd5R97ersT1o9tH)V!8j%(v~!QFY9QZ) zzN?Q*xDGIUq$3p*YH|26p+_nvpH^FN3CA))9JL9p+sb{dz&-D__GtxFn4g)dHQaB= z#ycr9Dg4v3Wzm9YUG?8D>7=WM7~lVlgdECzoEemr+<-c#3+daF8&@$m#d5I%>6Jk& zEtL>qT4w%M2f{1K9q$S64_%U853A<44ZNP<_(?ozs@Yf1s52oeUM7^8FZZ?Q#{4lU z{ehx)lHhcSz5Zt?xk-FYZ$j1nKoCTv%TYxLi_(m6S$uCYCw*$?%B*kZ=1a;_V}#;y z0=PFaxV$EIhCSyk^Wq5uXLkEovyI-0NxKg|T#RBQEv+L=2Opdv@NLLO^IQk|3}C1K z{HVe$gOWm~A{qN549aJEt3M>kds=@-SwoBR>jn=*kj3uCifc?kOSBV??<#p1WEJ)bBs-Q24A>P<~CkuX@(C4%C{U`fw(!zMjqINo>_ z=#w^}t6=c6IX)ux6y>r#?-UfxfVzil=Bp8q~u;T0(N%##fV|+k+?am-EH&d!kqs+z8XU2el z((yqpX!LX1MMxN@h{E1*QN&#_Bpr9XIvuE)fO|CoUJ~Yg&Vt*4Xoq%s6D?xde}K8c{BWsUP!1HuRy%v zn}B*}<|-WxXZ=4GKLjQ_129#lEpv<$c(DxhU&6~CGY!gi#n`jNb=~qX&Bv4%PR4l0 z5mr+RX&!a$BJ6Hyt`8E@BNz4R zc%xIY@G^D;`xWA}NX7MjaaeB=J4RD?$`1v3Ta;$9frRb+?sX7kR8lmBgV1xsZ7K38 zjJicR=`Y4I6jQ$wub-4@)wobHomt9wCtfBuPh(FOt#XIAmS<$%MA-H4dtoIjkM94Me#>H0RxtNxL6shvzD8SEC@@m98DT;_NC8%M(M0B#o6 z3R?M3Z{g3eJceCa+@pI;;_$l~rKQZr*~1moEm=HYcA|xzd$ovv&MXQ0RJLyWEj~Q3 z1{?uPO=_7et^Rl_v0|<;&zP8RcmYOCDCaeasJ-NlX^HA#oo1N&a-Wx!30cn(albUU z1P2UcZX7E3EH}OF3EQm=R&MbpnM)jqSl!*Oe*ZbWUTOuu8cdDYDT{l%J9;g3zg>gw zw+H@Lj~G#H0j~!5#ROMUt_WkLJ2#JrNNo40$K5eM??`#Y>7p!kPHd@b@o1GP*TQQ7 zt}dv7C1KB}w8=)iO*DZNm$%=i?^Pj-;wjSANyJ#6fVl#)IS{AAB#g_4Qpuc_PZnYA zm(6hPgRVcs@}ZGyLY#I`b`mc6lDCdlaHTr@rOQlcaz4S?^cT0+n9hQW)p2Q=MUv(g zgC?3mPK_Ok^qm1-P#fD1EI%S^6f%3@ahMM>D7zI>@o_xYxb~uS*Q*@jQNg1>V-Zac z?c~@_B`6Z@rzE*9kWU%aQlp836Qr)f3~^W8WgK+SAXP5B78*sc(0Jv97r2+#)g6=?rOrSeAs9AWl5@bFIRPV6#gHlyWkOnP22k7uAEr$2|? zm5I4|?d6z8q_?lvUaOh(siVbaNmiBwI)M(iZwCLpX=O)5U=<6Ol)Im(Rine~xM&qL z8;(E|6=UqJ3ZE<{CJ*Wde6@s+7dx;L0*Ijl%U`5Wx%bUZ`GZ0I}-0@a^@r6=~+IXq` z60m$3;tYNK?t*5?T6^uw`lg-a_;wlMoN1eho7{fzb`__f10&aXEi1jL1iyY!@IS|H z!uIDq3H0H$@U>v|ON9l)`PSTMQpKY@pXY<$h4nk3)*(Iz6&JFkt2h8DZv;L&R*(#%2l%V^iB~Ev6NHZ0%Bkfwqacdkx|D@kr0lT}j zQ6pPz`IwPP=NLUWBv?sNagaybzW!ZU>bHCuFG~snmFZ>_CwEw~;-jum{p=o5LRc-D`mmMrZ4c)31TGu!`{+V$buEF4g~oy0;FCGF2PKm_~-1YYyD z^~;7J4F5unT}`y&fYK6lU9*K(7)3H6T!59u%8-djrOtT{Xy7ybUQUPtTU76aY%F%~*@>BCUf09A#jKa@uY+?7!eY)|MMdDPCDcfmDX+_8}1a{ z7a%3t7?Ng&ZB`Pk_P0fx2^?yRw6W6D&|?$_?b7fkiF_{i$j=e$uajcqy*!K_y1mj# zUY&=ku@|X0=xD3nlz{1O9QCCK6}`|8+{~#pf3zw^3NhHJ9OXlV1`*5kmteG7{G;CD z7}vUF+uj^4xa^ewI6xGyQdjn&4D5=dx#P$4+)AzYs#o*kD4k76LXw)6t0mt6F2TO7 zIV}>gL;@n5JmR8aqsg7F%8IJznCs831A+vv$eecewxFl$Aq6orb+I9+^OTb9*3aE<) z*w!K$7ZMFHH-8ceC$ZiN<1$uNJOS6&c*4~w5dPYA^2L3JMN^EF#H!jQR`5b1v!i#$ z%vb5eTE>vM9;TZ_S-iC_;1Ka`w#wEk_$HWwYXIrpPF=?j42 z|6V@+weN=9=>F6K?Hi?JqqOM{x-|764E5#E6<%{4S+FXZNz$5|@FYfwe6uFuJ|4{#?TW zu-C+Se2{PBySiT3Dl1<)3o;}nzG%HYkq*OpxZbO{RkMyBFv0?pK{AZ`v)g1jxqLd@ zd@Nn@Y&)R_#zyYh5tewfW6?6AO8Yn^maKzM4Veqszf>6A++^N&u}9~)p)RtvR-()p>oWzi zx?$@W5eE=wYS}oS_q6U+pHN`@cqQif>UMSs&?I11$ zn)czE<+ot-yd%x3jNr2pa_2MtEH$zR>IsanD#t9Ai!bh{y#KiGEfM?+Zzv%Git^wk z&yh5tnLPZQVgCB+TUfJJP+aLgJ@tHZ?b-Y0{vaeo0<6R3Tm^UNR@w}1xa}7>B7#Ek zwn^5j;#AdURAmsuR$wt|-Ju^h@})fs2{pp_m4tj4n&Nkc`5lWqcY2Rba1Doq5+POx zvYl3~^*es{*F|Ut-*q(H?VG0f0oH~0)t^&p@B8PguH0O4B3_pt-X}(Ua~ekCU~bNr zSp3>!~v1aAd@nJEko-H*lHD zkB{#%ZyDefJ;9K}9-;c>yd2X0;~{CCA2VvLooTtM45JIfF%edIus2s;+^A~)6qVE8 zUiQ8ap^)l(7lxXP6SmN_K!TqDZL00WeRGg4QQSU{?267IaECgI$rBlC#cI-tE zWOt-=uQjM!ksgT>TWcfCqb|ITk*T7hU{_Za31&5S^i-YzAZDxItS#-y>1qEd;ArAo zs6Waj;O1h(j#Z&-jwa|oBp)Q&WsJiCn@ESo<2|R@rd80Diqg5sFK~NDyFy2=mMMMY z<{m;BW^PB3RD0OiL`4#2jjDpVRd50;bIo<6T7{$J;-LmsZ&f0ZjY2xNwb{N|74Ucm z>50#hEo_eOY1ziIzf4chPzqiURrFz?K5;*CHorCbxpvP`XGNags+=Z~to_+{J-frf zCh|Qrd7TDaebQi!qSm9eXz5ZYO}i5kpD-3KFSOZ?o;#!pnk6dqC|Wn5HFgi05ZAGA zCB^+tQ~t}>SYi5DaIC|GmnbHB$lD9X@8g7GA0i|Se)M%Na2PPT?uK4GnrfVk{&d-w zO@3`l{7c#8OkR~-e=9_z#?B9{hI5tmz{4DRVEn$Y^kzM7hJeVrqO5gja_q;*h}p)j zs&wLW=$kVV2;$ao(8HcyU|`_Q>dbvI*@2c^Av{XpTMiNmvr>T=0$vh<@sBc3K4ABD z&()Wms}a^^onz9QC#`h=RYs4P-Nik#5Srcqyy=ScU5<}<5`%9sAly27x53huuQTY5 zu~=l>#bykp=d6aHGl^}M1;P4x@Uo`bV184AdL>J=fEFg}nCOOFv-s6K#>l{CoNH5SI3q=!J9+RwM=! zo4dU%f#6etfLy(<^7#2KJKMT6hhF@FV>F7-+e*Y%{_yJG7T)=wO!P7@u;jItI=(#r+M`pK@82!&2e_fvvYHW5t0~nnhYS!N)Z)+bxJ+VeRRQj_Eg_~ z-#|?B(rDDMJaf3h(y`KDS$q0vIFDz=uGipfqgHfkp^;VVXZ7(c&>CHl z_P!6;9P6a6xS9&7agx~`N18#dRM8I)NIw{9WWC%;<+8R*Z*nj^VaDI1%>8rYTwQ|z%?=NIyRfZem(fP_n2~ z(Wi6JLT$Bdr79cCEFJ0Mp&)b6Ta`z|ru>B=uXw|2o@U}jpGbWss=Eixx^*g2dqel_ z^SGdd`3D1HO)K`z_O+n$*J%x@@TCzFuOtZrrvk|>Z$f9>r`<+LwSYkQqag(#^0Fz= z`_K|)f1T;Q!39%(^Au8OQK5c4j0j(!KR0(engnr3m=v)h^P+s2GFCcM=LrT4UvdpP zep2t#FLL;{Mlv@=^3~sFQddIqlUN~&4%|=h)WNt3TLxd#vn;~fZ8fayYU)2~NH-2@ z2ed`0LUU4jy7QLUQM8a&Gr{In!)jw0J*=$rL-IAu{hhD9=q6SJo9r%MS*e|4f;-NyVoB494F>NgHxQ59|}tvEU=iVE*ua8>RxHGI^Y&SJiUb9lJ_;ODscb8u*w z-<~;cxNc+I`^JZw=fT2`Y3O%f7=W+Kzfh}&YEpE*q(3mL^M+_CAtZ#)7#0z&5p7c% zSez)4akGFP5jV$;%= zT(H~xxT3xgl7xp3IsKW51dl|q!ASRB0D&J;KRq*(T=A&Zd4dv@+_8kyGb1u_B3(10 zAh0Us{$|MK3o93c*3b7%HwSJ%hhl*Q*ODZ=S?}Z$eeLq z{y3b@S#N3C#_h8I-om0$d$HZu7rXm)Lu!Q+tI?~lv#=rE#tK)3CySsrn;wgn7t$L`HRU|pZ(AkM@s{@6*Ocv-Mqkd@< z`oZ90ztLr5cU*p$klTe0;D$#A(J^m@GWlnkHUOH!*|`>%XcY5tNydpTc^U-!?4bx?L zxy+|UsGJld){yrmj^^_xBh4cI z?K)bXo*%nEK7@rz0pZP%ILa}k3=tRd=D5$%!jlsd(Vb&Ryn@Sq+BWnJ@ozPO=BH6v z+6IxkL@}^8F}e0=c+Z?PW+;5e-KdsF$4ntF2{Y*T3nKrFY$zPz*?=VXKC^1xpM(<0WwapuOQDXoXQ;sXGc|4_2uAbY<|MBo%oQE0EP$e<5}k&RwmH5d`2try&msM>t6{+v z*+-Rk6$|Jn8>#WO#$>~-1vna$t0QO&PqBCsY$gKxsI1h%1ICrT!`EIqYwgL>(5=dV zM$e?m#;@_47Pv(Hd#c6xP9~pPoh5JIMA|Ap^m-iV-!C_MVvVC(aQa%W=k3Ggt>o<~ zUm9X=?4tlsv1S|FN0+V_4UskV!1`*)LBeaBb!^dms%dJi*g)5*mdO05HPS>CqbI;a z-i}o3Ks?eZb-C55a|OEAU#XE-;Ch-)P#SgHJJVcYHVTI9hG)^G3b?3vH#7|+@+wHM zKXW4buVyCt)e*84F2`cOxlTJi81WKUwBBF0lP%U&RZ;&Na$5+d;|(%0IR}qxB(xis z*W<@Xc3m+AuD37G!R#chaA0tOOp4HB$}nk(;Q>0kJIVMXOYaxr&5hlxvb=X%?DZ6X z=cV7q0WpRIn^MZY5ZK7o;kCnC2Z6Q@?-R(IcKh1;T#Wi<4so-MZ8V<`M<<)XiZx!t z{njM9x%2^E1iXF<`#24Jl*OD9h|;$_9mBG8=p#JB#cp&Fvls`0r<$j!otYBf-X>_P z5#uw>vh(Qsei-~ZW`BOq2r9Q~Bd^QJ&&QEvQEv6_>pr6pUjg63+Da=nE<@c)P;VS6WQDZ1k=}$-)&zsRDQ6s6)Ccm!xh&S-IqEf) zxcj*Q1qIOmOhhC~?qRNM6rcsXy|=cvw*dg$b1}Vfoel{6_@bg&8d-^0nyvCob$3nV zfpbnK`eoWg$Z^L2j!}!!szgExWkcBLHURurMMH}xU zdfKPnNq7!p@ej~cP<0E{e|t&P_F|2QaGUevb9E^Vi@YNV&l~fK-gVVjZ0UWhw$@_+ z6&LtI$DdSV46CKT-csp*YQ;qL`UcL@BGxR5j{SVC(j5vlOy39Ut2HcXcr*r^hgf-I zZ@HXr>ONdN^$0()P@C79$2stxK9FW4SMM&N`*Ba2>Md^79CXwqtaNYD0+VzCtS>GL z?D*f|Nz)kP5Q_bw!|z2R2Qci-UpO$%=6(yd?@)GGPgqe zF0EYT5H+BQqVG7h(M`?QdfJ$N80cX!NKoIBei-7b`<%RQcXo<5HYh2z-ZT=m(8UxR zzEDD#h6QGc*b{VN@LAX;pKSq2g}s%V{L@nNG0WG`f>F9$dmq};s4j$l-^7k5qH1ET z(eRepuR<&NH4b>?brLzS5z)ZvY$eNKA~_r6Ipl?>uf6Qtu%coRQrCUUK#R?1#pOsM6(d;NYmq!FV6W304O zyUqG`k+fp79T9l=u`8lb1IffumE01&2VHw1-IJ_O*Sj95^0B|boS9zE{yi(fNUoD8 zV{Ot&3`Iz?@lyFOykAKuh@W1FTQN?Jk2fn!82q3DJO&ue*jA=EI5-5da!`-mqG>%( z>(LI_(T9-YqVi0x^CC#w(1M%IQaQzNAWQ}u+!-WD0^^w{_c9GcB{eC!NJ>zt|2xhb!cr^$x;OCSp0hz6m zqN3~~emHoTy+;*8gW&1KmPhw_1QS-Li?MBgJ5n zlxkMjWRT&zn)YIk*qf5wbD9> z-$={hBO-iF{MecI&;xeuj>J=6?cS?n&*>s4^<9`(EY-&S5LSeC*9IivtZU!6KhN`0 zRw#y+KyC;0JrFrhX8q(q$;O>Gau0Z{;$WV0=m9SF1;Iy?MA~&$1bv|vlFs*g^TvXj z)SkGw9|u!4IP$3E_jyI-%RRRO|Hkceg zqq14PMEkk=(t8#0T}Mx|q--muL5pnQGvqQWwA z0XGRxau#Fv$RI!7xXYifoi5SF2kapIvep4P*EZ!@rlXBfmW2Cw-ny=z_LSWB03VS+V% ztTWOxK@!<=(ua1g@>+nzy#%Iec($_rj2Gq!k2a7_?B+z0b$?cXyqYWZDS}FGoXJON zvdl4KPk{!r`XQC|k0`?qwGhKzN7d4zcn@!PNGnph1`H-u#2<26KiL@c@bKsisy7qG z=XNPAv-Ujwe)=?T*B#Ka&@s}oFz;KAg2l^$`(j2DxAAo9!=a6d$)a6_VC{2Ylj?A` zJz7}6*GTg=7-%Ny+2^IXmqy5I@BIWhs+x3{25%vzj0Mw&Xa`fE-}pOPYLbh&L6`^X z?q8VURUTZrlrxqndA#)yE}1DXm!VWntyzh<6oT3o!&D7AT7|q28eMz(eT6m+S2!S0 zTmHS_^p_8|RX79;B(Fo~6Ge_Rm(<|ozJDBT`yO)utyGOUPP|B6&|ogNPke{wNe78f zZ`1Q0jkiJXmA|2>aa{{ke$iaH^fbPGGlnV62JEQW*GA`z-_aJ2RcKUQq4_pq@!OCN zIW|V+J8VG;;9h6`-wpB!w|#s?z!l%+N9FtB;R)@37(s*%v#?1ATql8ttZO1#T4T z#{32%8X6j#DEz-D{4+8Z4(96fWB(|v&w)K-IFDI@R>)r(ggtR5rAR(ushY6x3|&%5 zYA5e7b4%k1Bj+;*s$x{I9 z-)%gY-~kgO-gnru!SL9V%gg*oEgND~XlR}8m)MnGtp-~)$6@P!3WvjK3rQ4Kf(_{t zgA?)2v)0n?2^1Yq_X6aaarUjj&q*&5!wPuZcEhwbL5#T6+@vcuDfxX7+V@IHEBge| zn^k1CJCwXJYp8)KgRUSo32@E!(%f559VZ$*D55r|cu5&huYTf-dLFIhzEPJG0TLSz z!AxW+o!vPaP+nhB&^4qg9L@aSmRlt6>P?DAZ*FY#O-nr)jU-q%vn{(R6eRkbmsjC? ze`VVC_vGI9q{j#4$t(W!8kb@UyqB>Y2UntHg{}QFl~z;FsrV%DSiW;RWkpc1o5?d+ z64Lb3>)|X*4D4;VH>(eMlx+C(W>5`AM!ota&oNv87k;rJOh=so6;C{d7IV08skywE z9qH7rHr1=r+Jn6w&Odr}z8L*IQus~y$*WzF2^H-6pT4u$OMNQk-<61=TJ<46KiyC% zOug0OL3h%ZQ!@#TPlKu&J!l)wzoqB-mdKRS$PD#)d9dJ}0uQn>UBfkBq?)I+&JPmH zue2{3;oZ&v`rg2!Uk3oBQIjriJ&xqCOr6`+U5`$Dui(eHSN>O8To5jL*XxY$?Q-sI zTK5``S%>B1Jl}0^B(=-R9WLo{EDY|AiW9Xu9gjVTwp2TxnrMF3r<6-4->2elM?7Zk+#U*7#pHUkDlD=`8y1%t8I1%Uh`Lg zo?4~N?}V3I$MzRDU@LJ%6P+l&?+=QX3K;k%0kQSU2T_a&Oejt4B=&SPBs{g>YPkG4 zRb*fG6OPd#b3FMS4a%^w6EK*9I?dYD_<5(!C!k$vZ+L3fpWLDcvBdkZ*Or*2Uc~B( zcr%7$UP9Ww@oAtp>A=7g8z{~5Cj~}>4>hfKdUf`z+;?(gn?ku#M?0D-D`TM02d}-d z5%xtp9G1Ym3_|y=i=DzaWVW)NZc;&$WohXi4zRBxCN2?cGsg zBw8^PfzIiyFoyB%l3q0n`F?D2xI`&4RGt-VpC5+`n%*T2CtCU{Ww6Y8SnFtHjf{W5 zPz3}dNWgs8Pa6}J^mBJ)-bLZU7 z^i7T0jx!J)>cnsMRLLeSDteAz1m3X!++N$pB5a@fj8{TEbl^ra@%1t;#Ir;1_#As^ zQ^aOb5KkF1a$}Y5%GP~7l&c63~w&ZJN=Njl2)fN1;@ zqZvGtIMVi>1oz3Zd?9BZ`M}@6Mm^@E|3`t)rUvTl$-g9lxA_i9eKhf7E_5dw^&7-b zJZ#WH7JqaxoOVJ9O%bDrURtJmQ>}L|)UYwzp%Xnr&{nJGfVojfF$v67U}Eq~8xIR5 z7Y!jHRI|EO%B=F0RbIp zn4wMIgkI5xB4m@4E3DUXaK-QklT%x~V?R(Z*4+=Rj4TwIL_@|tXk>C4FBgGcM-j~s z@+4`AR_kUG;Kh8KZX_~z*i7r>bwD;_`DE{_KTcG>m+xNO8Xy&ycf0jP{IHz7S+p?! z=Oww7smskm(9UpTH^h<>S1| z_PNKa**W*1q`gU(Q5?VY=|5ycfTZL}@Lv?XzOEqV)}D8RO2g80(uI`nOS7V{t7Goa zXzVu~yac9ZHTlW;RtvI1>h2>ueB^`-Z+t%a1->xxmXOrh$Y=u3O;Xg`V9?lLu3~|n z@X-Ai1XeV80EI{>By~Ag<$U3wuP!qxK*E_`uz)TK)X;SvokCyGUMqDh{fxci+?&6` z`7kNDChie5$_i-Hvz`GR9sw%i$B%fTFu8cf^H_KXUIzmIW~SKxO**KU-$xnfBM_u4 zuZm<6{F{Les_Zr+fYuy13Mjvi!tI@~lsUYo67WwS53~QzGD3}?CO4#VdT(>tCDz(x zfl7AHMhPy@mc{FvUS`Oe15&}q7Z3hyIELhx$5xt-pPF*V{}#Y7W;xFP3;7G1yJg{V zKy%gy^mXFAJtHC_c7Fc(R;|E;bxgv@s9s41m>yO?wm32yZPGNV4i6tk8J@Mf6O)i2 z8b%mxdUsnOe?h}>F$kaziGv&6-J+sc3}5-kQA5CTMGZw9dhahEaqr0drbxUC0QX)X z`u+L;B{viwHrB{wKOyN`m1G;WIQ*fnuPVtdPK zkTMlxe0;RHiOW=)ZCO4Zb|BIBO91&~9af~BFySNQ_kGCijl|GyP#}*WR!^Qk2iK_RG6c+x(Gcs{d|zqF=d~z~;XX7J{0uQ&Q4AoXg z@cGiSvKY}3^fXZ~53kRiPCx&e-K%)uUbV)%M$xI7lAIWS zWm(`;r{k7SwkSQ|8+94WlVmTpd4%WaSH1qZSpIk@9xa663LXAb3voa!dk{N7$B>zB z#Nc6$tv8=nVXc=s78#d2{=MOu{BZKIm_(l!e>)1hZFxz_soR(%paL$l_m$Y++T#`% z7dIU~TsYnQL1B8F!Fv;z{GQB^Oj8(btBQfLfD#A;7Rs57>tC zyhT`ERhwR90tu6}Gj@9*0}V_ID=hFt0^>R{JnV0x@O=?|RlTp~NQ|s?+3D)YOz}!l6_&@g?dh{I1#keegjyP(Z*6 z)eOHPH!UqL&Pn-snz_R3*0)?|a@gqIoXCTR@Z9S!ibZv$|EPX})~}!&sj+=9sPbyJ zBZ54V6RO2TdERVnY^>*7Ow7#1?OJ-yYcGcQUjhNuJ?19<`%AJvZQ>_9UVu|-u6?1P zNGx%@EU+9~4wWr`k`?$xZR!h#++vB3sbrlK8XMh#e2KR=@6ZxEferx~nQ&^OEihUt z7oVu;YfI+1m_+|y9Z8Re;TJpbtNc&siN46Q5HxySfdOOHuN8XAL7c~ON*Vo-8R>65 z(d5rTN8G!wAw@eCV|uF7$co0l>nPd#vuuDT?D4f7@xMqynyX5Ymd@vWU9h^@U|;^& z=MKZ(3X97LB>>^`AT4 z$4oiiJQdx>GPB%>QKy`MjaMZu*UcyBSM2fAGyUc@RR3RyamX$5*;tDJ0h7~lPEiU3 z+tgHZ0%*7BsjE|&8+N=$J)WIGrjJX?;IRJ$@WVXunW=mkJZ6v69RL3?jSe{imP1)t zS(`jGXjJew@WbotUu6vupZxlj{LZk))qKfzsWI*`Z@=^SO}BL(=dR{R zVgPXk>^hU@Lry&vX`wdh3#LmT5bBeWU$5ODij7SeQQnE8Rm_I33+~Tk~VEWI^C@Hj_J8yY2`TaIn_5 zCV43HNU8t_x2tz=o5|HFm z1!N}+5lL95Q%+vyBDwpCm6dbqL@Wzn}iJ?^r-f+3xs-{Z_o zS$SMsEJE{jLYVs)}V;{%TLEkO-Ls=uUNM=wUhr$j+fz1*t7G0Oad6Ot3&A?WRfGh6#2 zd0IJTUpeKyT=6IYaQ?E@C>1*pu-n{35+K50LieUC+S=|3LA%q_tq8& zMDn@}^hh388%daqQ+%1^e}Mqx!0QT21^5K~+1;VCz}rU19#`}q|7$sC;5_^S_c#;h zNroY>8&j5>)7dt#&R{#&JD__^hU5DW1MQu3dEj#eP#y;WKWQT6=g;Cn!2|6-_Izfm z41YzFcr}9l_GNCf310%!@3IQ>$b0?WM_{(OqG~;3m6iCGu!(bEM>?Mq_R+^mgpyM$ z)&S8edB5MEX|U#rm+1+8%xuP;IWbnmPZ*M9X9os~-A?^|oS(A~?x?lbw$)b<(Oaj> zpeo3B*+BCI%i>n3;wq*kQ_WIzz1rsCcpj#07Lp#Xv**Q)u#1mnBhyd)Mf_*K%xuF< zjLlBdM*)6$2S%Mu280}n13PW(M^aSRQBhG)ZXmOkudLj|>08hGe6^@o#{6SwVvN!v zvyaNn)4;?KHp13ucfdMCLl(HZeB=(MUzibj#7bL_Iba+6-|6$oI!_gjc(VcfTe|$o zS^k&9Q?AxBr`FSlajWLXa`5*-FwK~qZ|n~_ij(qu zn(FTLo^9*?P85d$iQ=v6>vBZIW}iC`BEhUAJ@<|Gv#xE9TVq4?KpZ7n7Pv(`CL{YI zjV|D3L?r*;1FZWxK3Pl5<17d>=eF_PjYVF9b5oQ(LBp7WFnF4R2ue6EK@^KYq zBINFQI(h})j;w(_I-cfwcN$*6fdU!+4q82qa2qGYN1{OLYn?ZhP7U&NM-6YYoeg*nKXCH(QJ$I=m{@XeL$sc;$rz! zJuBVu=}Z3l&EZz%qZ(NHLmHA3hzOrxEsG{d=S0Pp2wcR-iIB9x=%ytVmgUz@E8ZTg zL){p%vY1m)KlLMSUg<;-5j_AWD3%!k<5MD$zYI+RX1zxrq?wpjZe_2ge{7+Gn$niS zEWi|xUwYuA2dy7Hf*(6--1>;SA~-6G&)LH2M<%!H;VXQO?YjuP z_S;?BLUE#vl4A*INtejqqdjt#JjDNj;U;ECK^ZaembqfJWx{&FDtxg(==|hOl0r2( zSD&ne?jQ^M5ZQU5sNFg2syoSwbq!x*8OkYIwZ5#rb{{KvFf>^RmKw7OR;*_F$=ExM zed)vX)ZQNmdrUl3e*Q|jZfA6DI|@7i5v_o*uXauo8#NXY1;tc{+mo`Jj{dZQ zVy_eX2+A(CCW!$QudBi%#p{_a;Q@E|xwDbW*1g0F{}$Lf3~OVn#3lXmz)aizMZ8{T z`-tQ&y6j{}o6E@=iZO(74-<-P*U@R85~-#F*U??)GhVpLprm}U>)5b#sE3R$g{yRD zJ-b-Ake`5t4}F!68O!~RyM9&*iwH`FCe$~{uo3+wzewZyeHK6pf_;(u6o{E z-9NB2d8=(RI=qE3D}m$|nnBxYI;7<3MU535#X)N$%cUn?jT?}oySz$}&1q8;@yp@O zTT50QR5EE>p6MF+OuW7=(T@4+Irk4?NCC_t@XtNqp*x z^NLQ1$&@RO0e~Hw>7cN;ZV7NVcZw-V*s()cwKY&2zF5hn+cD(2*3z?YsZl_tL1=hX z_WZ`10+6(N7RA0Ldvrl}sr>~o(>8PkLg3PSAPz#*cW?f*$Z7pB$7``Oys7@tTh|El?Bf+?$tT*bhsm;GQ}x`rb- zmqP2a;yR_jLw$y1RCvDuKeYq>P*RCT?~zkgMHt16=B4PjRPX({1cFE(pJx|w#11+V z4=Tj{Gp)N-?j+pf4LA0`V;lE2!D7zLp?kl|nZxxO+NJeCpX6SiBQIohw;F3e52Kxd zpPduE)kNpjMPzV?{|Mu0!v%Rw&6d=C-E$b;fN(ETARMlZUTU)P68bC&LxjEiCr-A; z`u)pm$E;{do4qVDe*Uouf~uM?NZuG=gFu`OoYEq{QTmy2MR|?)GfuO0eFjlj(cBA# zwrSJPMvxwvwQrvlJ$A+b_NpChz}Y^#&f+snC@n2LC_x2JKtQ0>;I%V`F_;)*;dRF^ zTyiCm6W91goD(jQi(zqsb%v43+c!*6x329w_i9uL5^NrZnvYK+txSl`o9NO={y|ka zE33M(Po9-g0G?DcDbi2pyiUofBvFmpz(Y$S-QmrK1>x`A&;p;MJ1&vu!+NH+c@99O z8fp~QcYk8kRBSZxoh-6k{Q69_^R;aLj+M?zYd>&1kv@gFD7|@GET{JXuCfB4y@rx- zw7T>PA`mYUu74$NHzZmQ7O89Di+t`iCz63&VIL;I<9B=GBS^ZO5`+&YI`mf6P0v_K zH)Da=6)l`!b1r%1+4hMh;rfr|CB%T`Qg1G$jS`z zQjNykeOlEWocnY~JpC_mkh-Rl^#_=C`2ArGcW9=wxtC;+%=7DgX?N<@5?}Rqj7`mQ zo_utXcXNI(>?!ueKai^IxF4FD3uW%jHcd-^Zs`gqrCljQUTOd{QONfPx2RR*!49dt zkVkuWQu>_UN24jCiiDq@z!eO8$?}_wfZMsLIWqO|v<=qv-J7BZOy|PFWB?4WK^|mB5R2$?k<92hJX%oit~?lU;|qxje1%?fYL0V%ofSYIT>9RYm@{QRv6gn* zQ=OGZXUJ`xGjT{9bdg_et?8|UNmMBm9ByMBUuh0Ml``)z8B#t9?toC* zXo!i+#TdOyF2z$9K|A*kO z1hyGHJ^LC=zI<5}@UavDUQkAoza!IoTWXWBb9DvVS_9;&iCB8f!{hE+7PMbOrn|%T zESp#;lES>YBA@Ofnid6--P~zwT;5@}eKE|jvn>x%%1o%tk6`pwPFodbn3GWKZB5ny z$E_E?IUUk)fKX{C#-5&*I?Zg2(9=*}+C#ZZz^ul?AGahNd+LG zaY>QEZDK=pmc6%rPfr0R{{ixU#-$gFb#lwnMT2u`VIxlsw`D4GpVf6=bA#lzaznOy zh~?|3-)kgSg)y3wqRtIK-lg1b-LTxO(fvu>sL!>Q$d(m2xEptEr9_-!W35x#zA}5W zFa~iNzX0aeI=qh0k`DD+^wgnTm@&++(0UW&(LH8t@08om)G_?^Td% z5#}oX2sngi=89KZ1i@TWI)xMZ%yp*>_v^#&>yp2_ zY*))7q+Q8;peX^af$~eiJ6jm(=AMd)z1u=q5h5Ea0owUrZ2YgnBPnjksiTO*x28BC zudI=k{tk`@MFVg=d;VYH_&EY%)vFhB8?%}lJ2B&GReIJTV|hr!jA2H~I%Jv+^xkvY z&>otwIFLx~oP&deuBh@Z&r}ap`9@%Z8j!CsD>RmQ>%l|J;bjb0R^?mc3}@~uXS_Jt zm&mKgrobO;`r%6j*_=!7NRKs0?iBge!8~(j>XNy6SE7i`hb)DCw9Kv-C?Rij>%wCr zSlFtNW?a0ur;}8vdC^<5Cq2z^D20%E^87_H`VTww6?bDt*j6*CfU zvc0)X?X^17x7@u&e}V9gYMtlOYA)nh7Eg4mxpg!p@xl`l#yVr>PFa7Nv$2uJAaOvN z8D!tHS?cT&F_~vuRP>E)chK&a>^^5XSW*>dxqpE3`$EZ>m{#e!-V!{a#IWhCHNn#? zGj7#%nrO}070HVM?E0?XmMXu4F3EmCpVP~jpXuGCM?^x>KwIV|d8<1Rdw^|K__dXTj~o#=Z=RihFDWxvlT$MZ+4^2Ne4Po{;o-NoGK|tYO>`XzjnbKHf(wJ8vOBOl`80t^QVW8EKX%wyG>1aj?7eCz zx$$vhzEi?7uv}^AYb}-(%*i?5%CUgx(%8O-pp5m%{6bzZ9iQ=TaQ{kP?`8aC4zXD` zv)*&Ew0>5nRtPcm&|-~4Nh}3xtKBcHGKtgm!;oBCt=>9Enz#9i_VrJNBcyrq#!rfw z#h;@+Q(srS6GHuUq|#btu3rUl==m`j_JF92HfPL$Ozty0JJ#RU_K5cMMMcQ7axXD1 zWvqBLLE)%x&EDL&YjC+c*LWa(%Yp;?iNNUQThc`E8hpZ-@cfvUp*GR!qTbgj{P^fD z`WwdA&Gg2b*IZTE$#f;=i!t7V1rhcJX~np}9~Ef5<+ruLDqt#f*HuG8mK&WF7u$#P?QpK#43ft4_*VQ$^N@ zxsAKnj+mX0MRH&Px#tJiomx6j!>oJ3TNI}q^r9Q?2{|2|j5$Q2WJr)MKs#xgrqM!K zNsW-7J~lrX?|in$+SGX^gE_~J>X3K9I3l7wXXB>*5nj^b6;I+m>EzJn?Zen zi+WlCq7sd&Ck<5%#5N^Kpjl5V6!1~W9DY{oLm8**Ze{Zu2{m!gA$Aq#6-%veZGGrv z8<>yx(CrWAeRg+w_-ddfK3I;xe-DrGwVmO|r}wCjH>c$l&|;w0l29VnYy)c+JyO34 zd3UCM`x<=rq2GAJIg^wlT8)j^Z+Ai6dm-UmC+d3dkGZa=R_Q*O(0z8%{Il>`pmQPI z*j}}^ihX>!c^D8;6;%35p}CM-rSFK=0e+PA%9QH4Seb+2GX_!Ui>0mHOJ`gy4llKy z9&!(Z`dXSK&cOB`pPn;(anK^#-1-KZl|)mM&3&df8LTM_p+QagrB987#d3MBOqbD; z+KKHO6=OxPQQ=OX>i$f-5n_WLD|1d5I7`&krBvHl){Mw+SRs_Xvzi9%dbLi0h>xW* z{ZJ@x7Y37b?x%UU=z4{e+V2%r#|kXj`4(AyMNcE=gGL%!#Cu(9?VE_R`&5nTk!ANs;kJE#-}`BuoSe*d+jzeTFTlmDX&%xxmmT%!wAI*)i9)ep_tizE z3-cNFFOECHL6|V3-xdb_ZVu_=ScjfW1RpqR0gX%9O?9Wf+1MUgkmW|BOD>~l>gdxs zi5UUZeV!^Sq;kKo-+F}Gnz!7j;6~{9=)GbIWDo1g-}+1+ZQzs|kL#re`|%CfmXoBz zmQ@`z%YS>yyP~aRsn3TtV>>gDh0@Z{9C0*0Zvel}OmLU;c?K=SYsz}FfKwHdFl_TM z@6m{$Um#uw@pSx?4Qf;@@-OpTj(p}bpC=yL;lwvKxER~9ASfMGo7NDbj}Pb+I(7c& z6e2$9G>lJ5oNAs08k^fk=kYMi;4ar$;PI2uYEjL8Mwtv9pSy#MY-TVc)_407)=or( zjf>bw*Apxqb`xp~GJGWTB4~aO+vw+Rf8dO=8O@H`J{8p5FiPtx>R{>51fCzhGJyhx z3gsrMHGEHT5#?N0*lM;kOj&&k1eTdBnWL|*JD!ckAdX0%m1E0Bb6*^Dn-ZcMLL*Pm zT;T+-owp+${RsqJ!UuO3v0Cd#Dc-6OA05&|lqD4jWl8*-@C%onLG*$m_LKTydp35% z$`;~;`?9CYjK9~(T!od(SSPpNr|5@=vMNeE^&TRl0U<_TwnQrbzTWanEZSHzQ};1Q zHLR&J`&IJbC2}~u5n-QUJDnzSrGY7=fA34HVnShGDo{ak&=SQRyq$+sEWp62`}n=q zm?-Gnm&t-To|o+nyL9J+m1*VS27Pk*nNGCa53+mrtjF!7nOx+c-$aYb-{!ldsA%k3 zT2fPTjDWC*o1;@uQgS6JonO{_Co2J!9RGdYc<>Omn<;X?+t#VMXlo;ha`(lh4f@!gVI+ohFKk6TlAN3E#6akLT11uLJb=!-(dmR3rNheF1P>&5Kujo=| zywyfrU@4WC^XXG{gmZkpWZGO>PU6UJ2Ev~VR&2F2c`u4T+s`(%G4vX^$W=oDzrkHh z@ef3e7A(DQ(Zi*eH=Pbokyfs$ST=BOrdintUEI`hAc^dtDt;3f>8MF7S)WmKP}c&K zD`P?Bt;1R(usu}5_ALe^X9tgp={cFXH7-;rHr{h0Q~^JRXFhuLB^|A6;> z9iW~125on%J-hJ2V}sA^qzA{cDlDilY(@!?8_r)>FDD*OoINzu8O4a7TGVKN6k+-% zNViFp`07TmWurZ(3>gL>gA3as#Hm34CQ`=Eo^%))dA^2_fcjtOPC%>zXZ_n6U3$WC zyr7q^OQP*~=W`oNmvpwlW)hlQc#JaVXO}uqZoNLT=Ab*rg_^?5)oSr5!iCGl7qyRE z`xkKmT415#gbV+mtJQiPaCM64qwiS~yZmb|exm*!XA0n-+k~_vV3i_NHrFKopv0?^ zKx>f@;c()mOjNB%e7yGNKYhq5&W@DXA&3f3;#1CIIjMV%qUu>d8mBZ|?_O z9t-IazAf(n&#f2eqA&{>{-rGYnmqh=`3_}Zp!`?^`1|dh-yJxV7x4d$ySI#r^Lw)e zNeCec0fGk)?(P(p5Ineh2=49$M3CT8xD>(N-3jjQ8r-D{_j$>$@Bhy2?z>jsSv?%wt z4*RE*UVjx^%W(k1`T$pw10Lzzj2zKmEwZE#;%jXouG~$fD!3LC6B5F9mcIr%B~Vh2 z3$FG8lz?f5eRPbc%a2GladBgC_N5-Ey*K_++fK!;!?K7jPe1=-uTEf<2Z-d8a`!o8 za}8QD(eu|!l9LT{E~^e-U){w!QZos*FD|AS0W!OBNvS@oM%1a+{W&-1cS>&elYc({ z8!zJP&&z?#qYsCHH@0|7uKHv%uOg)S6A~33Zzzn?mb5(h=!iuG1?vh+ z3Bu;=XLGC>!6O*?gwEr-v;Y9!^vulsQPCZ7uQ37-m+G|Lnj?mzcsYQndN{Gj#=)^B zL-{WUaPH>`f1mw-P8Qpo{PRcu)v!;!E$N`+zpGFG-+2nYK56)rol!usznlt4(l0C| zPtSv~Jlf_S?8cCZepJpLG57pukUXgV(#VqfRk$t9 zYHM|s5;{A95;ZXv)V1KG)2ag*;PUx_7$;_z4N?S8|KQO6hY^QrI{+g!uS@2M6Z=LwOwFRyn_( zxcMIIb<&+h9Muriz`5M2v%p+5V5EM?{a-K%{4ZA4+A+lNz*0c22ilgQH-xG8u+!-P zOcWGvjKmkqZfmGj+dx_3_m8C}b4>n#Gc3?XMDqfoQJpW$@<%62d`fu9Sgz#XdpQdR z(nz_@63I97e^|5Y_?Q3n<&{d3y7(Z3S~Fsl6#VZ4jtD=HFZk1c?4} z(71+m`YMubxSTreqH^hqvSI6#jtyMaU65yi!sht}1A~Kv1O&T#d*=7eJKMVe1!L@! zx~7K4_TG-VYLy13pX~wVh7kkPmmeCU;{W*dJ&xG_%Um?oVb79g=(BoiYU=!g9}%2% zWRHCyckLZ$T+tJqt+M1qf9wUq2w~MLx?zj3=Ta(s0v*3MvkVBf))X_?n60~MyA=Vy z!EAj0ms&WSzyM()LvO#OSg6v+s4eFMuGq)l{ZOu6DGLZd+bez`;Kqh*v>)xV#HrQ zBt}p(po~4O5-Ezz&V6a|M5`k!LdJ*O#@Fd3-Euu`;wxR$`Zwz+%^%DuxQ?l^X_ZHD zHWe)B*)aibU$SZG;1fhyRG;MrbkMLP)X{}^LH=^hozHR@2nV6KT03e7MJEr6W8Y`d zNN(+?!vtt(a`3#okWmR#0M`}39%Y%OC9?s4GXs6io42$jLscSbs!Mt?oP=(v%nP(= z3Z02ZmlQ9`D|X*6>u#ix+n*WT9XIa9W1!zYq~3qHZ>Udlwh0fZXn9 zdxH2}fa`F_`|hSf{l+`w{=1;O0Gry3nA_zDS%$IIV}yo)Foz#p?BcbZP12C#fvP7E zjjOfxNonT@xn!hmIkl+hpsTX-8zQmL<-1MoVxMxcu&}TKp@)UJE`IV`;yN8U%O}5@ z-mdL_Xy)hRgLQ7E@H+>A1yyv~@Q$AJD$s10pNl@e%podPQ}oBlZ_<-pj+LLQQ3!{s zas;GwTD%20DB9b;M_yg+u=I|He7!n3xH(&_c4mN6{_R|)XSOGu`-ka6(Ito7&(>1? zvJK7|ho9hdgQFm??XEi=Jf&y1WVs)DNi}4XIiwA z3JfEOcK9y)OByi=~rgs$OCu2kQLEV^lga1waFN8N^bPEA;i4-*cs5g zPmTLZ^1XHz~zAPN{Jg-wa zqHQjg8md?&H+8R*+OK8E9k&?jwd-2fW%gW-A5StmAtrXcp&(Cig1{k(jBb@&t|5h{lh?_p%uEb zPKGAgFO^KQaY9K}3UM0Xy`z*!^HS!U!YY0#Czp*t(dW?c{92D1DFkhLajd<4z!A@!ycrljI)r^mGKZrxCh0gF$r{q9QOq4Yy;$Exhu9O(k@W$ zNbV+7FEw1XfHh~Aip>Zk+1cj(#P6A6P&4UOHneR0w(jkZ>Dv@=6yvar-f!!-33#L( z&Q@xN@`>Ve@;_JRP$@Nu|v3CrxddN_eaR`){oX~$p!kFeHs}8y7 z>NX=G6xtzMZ9`9sv?7yuQ=3dAmUEe2al>9xme){RJ%3FR8hmWXQlS-jUrobz(8jf3 zJST;iad(Mpr8JTIid%drMMQ3u&(*IniWsTWn?eYT@8#%tD! z#q+$Hp`x9-wl;)_TlnsoCuZ8s?RFj*3*l>k7(_GjnOJW_xYL_>uG#V*p;?COcB7fi zl~&cYmzQJZ?C_Y_`Ca3L{ch2Ki%mQrC{#*jch(vm%~&R$8OBS3cXoveGsrdK6G-<1 zBdjiXaeJ~ZhSJKqI`RgcJIXA$qV3fcJs`jZlcM&SwJeyqFNarlGQb&n{j(}O4K2pD z2><*>T@#2byY#Z@*;u;loYhfJ>KQa8x$#D)y~t*cz4rHk4ttf7bI|ju_a1B?5w$jP zC?g8i^{W^??{>&AK*9X(C|}Ceq~mqPz1xmoHZFkIWrAJqgQkE(JuD~KK_xzl;Cdcf zLGEDx<@tdWV;s%R7A%zl)6?8fQkIEAL_WJO+_Im%4F0>?>L0U zOtI%%^5-Cxi6v}nltbjzNEvi}ueT)XH@ma@W>c~2V!Qg05Zq|vd2}NHP>C zQP4+3IJQgVwO>7Kx=}0Elhrf&fxQ#fq9LM%aTV@puBk^<^mDljw;wGFiGNsX&gJKw zJdgIkGIp9U_4scdC)F;J#ig;aC{cGyXVmXJq-*pitEf+V(?bk());kbV(>H5go>?P z%=3ezUOF8PH=9SpKNS!3MaS9ymfpX7rOv(nhYq9cs4uEYr_>;iJKBE!Lz%XtkNPCW zjc@V5oW4_`%0<(WK4Hhf&;B)wAns9(nM&uEFn_@W`mDqTGh!I8#Njfsbf_D2|K$f5 zMTY7|o1}cy9dx#GsoadB>XvIQ<{n*-FhTh0(*H5D5@Y`LD;tMRkCW#}Agzn4Y(LNK zy@7!;L-Fv7(}@0^qaO_$z%0GmYLX6nXuKUCmW=f6T9=2AdYvk6?2OM>+caHT`l(zS z?FWzor1GeyhdX$`Zi7p`;Qi&^``Z#jU@e4I1o!*YSY0`F20cMUKIQ^G0x7E5&glhY zFa6m!2lK3p3be7$JBqAdzkN^kUa$BI=v%c`zueeb&Qoer-*O)vUDejmRU=B9_Z~i$ zsCK3j_EAJiZ!BHDYG7}6Lf>mACmEFoN7>t9I6e_8N`Ddv$zQ$he&+H8Yh^OnB{uKM zt&4$0(H@*f;VFSseLhI!8qfaZbyHN6Et^p8 zXbN2$Njt$~UPsrgaXGNX!P9qJ>GUs_0Y>|yt>Tfdk5BU1AdgMBuv`$bj{t9HcR*v$ zbGoR$2V+yn^Gy8dTPP;~PcD#QHmW1hrsP&58+o1;MooC`c1OdZA5(v_(7Z8+Mjx`E|V@Felq1-j~0d zOYSD(^j7B)5Gp;VrnrNbz>d?+g338%4?7@zJrYc8PEUXhO(Pe9H~UUZ$=tx;Jwb#? z@G=-e)JEzV9=#=olw+Twi|V-aEd71`QY~%E%lpvb00m00^1z)*2FK~t7WT=>_JVWp zU{7Y4)yFaHt)f*1EpFz4A1IQP4cuYboZ;8#Kb9*@df13u=CGH)!gTZt_=R0Q^wfV~ z-j3a(9Ed0Fx2Xzsn}XkND9;iW2*yC(Ok3gER9~al8xK&BQ!so_Qq!W6*Ny+Jo=A=z zeu5r~W|PKqKAnB|xzy@)oL8`GM|CX}0+SLzdT&xcjw?dHSG*! z;U*B!AIKd`K65kj_6E5e(DS*MR~GKu+1t0Z2-}o#xSYn*FoLwabF_n+O^2bxOdz%V zNlGa=S4Xp;C*c0*F?04-=oX_n``5dNaN&D5;3CJGfr&6DC`5I*P!TL22#7(*{?zAp zU+q|Ia2drVQlgA8!ZUB(l6QE)7eOSaecQ>2LltT$>ntU1R-!%b*CD2XJi>qa$9pJX^`q~d*f5hnSFLGJCD32h12?>RHD_gi+r@DgOj#YEt-ys8yYK$rn4$a|meX89!TMzY#HFtpk>N5VKY^{D5Rj$SmiLh%}0BcTAqG!ESyNE(N zEI++iCzg!>py_0=iLLT2fHoM{$;)iEvsbEAE7bedhS#vDGMa4k`mFEgonCyJZE={g zJO9Ceo)aaICwvbHTRb3xb~Y)CI>*gk=9qIwi-+KqrBw>BxQIKV|4_s+>A1czhWB@c zZN`O8hF%^RxFH{0?OSjPXb`db?=7mt?Q{N|*i5Dz=nuV-Ls4gz+w%OPTDQUmD6X|S zW46#2t~6OZ`cE7@t|@_Bltl}1ue;e8V^s%c`LF{r?@;37ypjq;o;Mv<%tOrj**Q(D z_N&5eZQ1=ssZ82x+S+@t!YvMxO@X*tV<0|)pQU^;F!(+EjWTuhW;J+Ed3tt+n`eKw zOtE;e-nF1!>8$XymU{UYUFH*WaRP{_WF*m0$%d$04^J(+5!<(Y z@P{JyB+ox9k~KMvJah!e8FuWBwcYn9l!xC2RP^z4-6lfG6PRLp%YSXU0l(3bcc!xGqpkX|p9&6^Sh$>|TPd}C4xcqg@A z1~}XMlS)}bi?UzFVmNWy=9+LUXN&&vAB-f~cO>BI+-uJsX4OK7RaCKCY;3c6p1R&6 z|7E$P@dUG8EWxm2Ml2lusWGt22hLHE^< zHN}gEQ>n$No=XMcUa4ym;Y>H{SX!N|bg4eY0@l0J6=9N;{A6u)0a6BG`sXrJ5)Ef+ScTLGngb$hYCr(D{!K3u(dn||r5M8IV zM6bAzFe^#RRWm$h{XFd1L2sSv@4{;P1TFzSzfpgp*qb88WwZWv6(@Q~7Due>RX=md5T z8@`f>DosrSyA% zJi?FM?)M&e@v!k;$z~~A08-4fhhG!w<-Pfh=8ePbqCHLyGv)_}PTi}xQox#zE#qBT#qkj>W z+{da4(H>DPn86udlv+kW7c$uFW;WLVPfAKktLd#iwNayAd55YIL%o(=YKDCU9%J}4 zw08Kbhl0E}U@LJelGu3O6&Xq|?&+vlZIRX+2Xld(SpvX1SDQ61;m1LwP)6Umfq zM0Pcf$$<~vKRibe@%&6gXM1lT@Fcs06coSNb+tQQMnx&Fch&3%l-{c)#EXrG>{=WS zXZipZ*-1bS*XQ;g#I&5i^&o|Rw6h{$HA5j9AjEbJTS#7DuGTHqZSdHs39dv!5NViV zoqHI?pm5orqw<1FHP2|Ri#YJ|z0@aSH+s=xU*gqoEEeU0yG{gBbFeavl1Il8{yN%v zU-^amO_0ZIMZrFH&B$`@u<}Bj*LZG_jSRtwu@ZOQi{yn%WZ&G?D2Lf@;#ZW)kn`x+ z7?Vynz8CTQ&MWnA`FS1dTWIEEx=#sqdP$@3YpNrNZ5W-<2kDrY<|`OSCc`MXj1S8% zaaq_L4UDL7>_hCLeRS0D`5HMHyr;IG6y5yT7BFSw;gw>guQi|}SS&DW7br#riYDZS zmQ+CIv^Vds0#9a;+$wV%qIU92or>Ox?>GIvr1aQBcu6IMk#rs*?U3imE#_t~^CV`A zN@Azpu73@(LwqW`Aey-G(b1azq9l~-Ex_biNWEd6#Ct8#k%xupT_L$TiVhrhQ=($H1@w@7h3}87}{PxOxWcTV{`P-_2+w z0++#|gzAM_lli?7{}vz6h~2AP4BnS^_PR^kVCMd+5beiSI32T>I^c|b&#az2|%$x?Vunz1uK#(-j*3FF{&H)g_U(gl#R}X<_4K6 zlk>_8M{K;hQaK^X3^k+f0al&P9IB+TGnN<~tC;-wH6yERWaAoN@BX*emDdqegnQgjQ zH}r*1z(-KV7vRd@%U~Bmd zs@JKW4Z{x*_QRc=7L67m*fQxjy}#x)ted6rc-2Qpzv;`B1CUHSXnU)U2cPT>)Sk+q z%8^SU*GI>RJMQ!pVV{t4PrMsxQ8C8{VR)SvCd?5qU7_z&w9lpmRLwos(HCizm1lQd z%0sRJsn73tegjE(BT^%Q*z!u&gX480UCy?@`m%oGOwNf|K3dU~be8MD5wg6&% z#f3F(LbHjWCWeeQSvj%imnirbN)}-WP`w#Ta4MOB9HJhfm4hG&MdDf!;TQe|cefsL z7hM-U1<4UWwRt#I*yoR@3+_*)yhiT>j~4Gclc99WaN)HT*eQp6(gP=8m4L1{spEBP zU!!h1l&SjqWVbNEYyZIfcXWnCP>F8SRFh|o3Do&&r~yM>=x(B<?H!apsD63X+1@?N*<6)o$*llcGY~)w!+rDoebx+xk^rSUl(4>sxpd4s5{k9n(Ymxw{0Mu*ptGf84=a{8?ajfaOCuX!*`WWKn zu%%urZM6O3sWvk4j*6~y?nWbBrkk8DdEgPeTd1orIs&e9@=yh*oiVE0Mc3)f?5OE- zdEv>aiF-}U!;nE+M~Cyn#l_hvZg>+doNoO%rNPxxKKY{(gS9~)Fd2qZ1m_orY}O6K zN9q0DAAX>}IzM_4Fh=!>YDGGc+P@v%N{!pel8ACc=6&6m*?hX_x;#n`1OVONZ^OOv zRlH2ZyH3`2)@T7?f|H|;j*{m4M4wtoM5SAPhTwg2)NMri?r<99sCIJ{gs(TP!p1(D zQ%XMJ??a>qLmh3FlBf)MJH73?fgn{yFlR}`pM z?kv!TLAU2L3%Jezb9mWP<;EuX&x{Sqd}ptW+s;gtuq*+iXF zzs`61nDj9F^B0aeIM1pR=zK3g0n z!ePnR%JdhmY3$BgrK>-5Vbqo3@{`$M_{svL2R ziBO!IwB97JgvCh#eP;KA8Qv1c-oIJ`GY*`2ct<-4#Rh)&?ET0>rRe-isR~BK6o1g> z?|48bkGW1Nnt+dwiyJa99NrwA8u??JM5B&5l;*3AVXM+u?`7ePA! zSU;zx7;Cqx7OENkyVg0QnDO4%!!!5}<|F)=&K2}@X{fJjCYd;mHctWeBJjO?Nh%tt z-u;egjkom(#qpoDEYk344W=&NLzgELG#tL1yi* z6Y}5={`iOZ{9$UPU4HJbO)F{OQL|hOvSycsh1l@-i77Je1gU(_>`FNC>0Zjhj)HuM zMv1HquGGdvFqRxDT1tMpE_n@XjAnLx)UqMyO*JHOP2w?S-hA-{L8rlc&!CGNK%hXQ|7X_8tr=4Lv&I!VlLREB1# zk~x1+Q#v>CC3$IJr@@nZdI0%KKX4v+HW#tvV;dZJy!#(=1zGg{uB)v zeoLmztUrA!In{-u?@T&vsWSto^_8y8(fS$PSnx_#%s-#;-l%t8BCOFRq7mB`5AsDU zJ7_;W^zRG(dhafGN#IV^{xjfeED_hJkU@nlMb|5~9AiRoVth7A5t|YR4$}T8WWxm_ z8=v*!E_zZ+GY|y$S^;guBEjPP+fghy&DgKk{S^}h>_s%2_mjgf+4XLwR+gLMCXS@j zFT*judA^DS)JXtIkrFaPynO?UL6RwTl2pB1laETX`RWT|A^D#-Eb7|@itc#7HavO! z+qt&3w(mBJWesk?MvDCNhwYaLQx6{93!CWKZ*QG%MH%*sL| z?PT}hJ=RaHcyQ61lkzb&fa#NEH3TYU>h1nEicRfT@(XpKTsZH~vzub3B@FGMNlsZ_ ztMh7W_XUQBks(UbKoLiB3O=;q|M4ERXsEC65)%oVJkGDxb##WNisVDQz8{)V{c{6L z&Ie?{l4B1qK`$g3R-s67coGZ<2yf3=EW~MDTrSQNcK6t{#;UX)qqamJ3kEDGJ$H#l ze=Z7#`e=~JOdypU<{=fXo;pLh;pTM*_J|k4#ZNKy1|cUb1OzSiu1Pco)k_!}skb zjXB*c`TCdABzyw!R7EVPXBf-jOc@1i?O8_qy!1X60scFP^v4fRYDoMy)6?G>OI?a1 z0r3R*7~Wa2m?HLJEL*OCk7ig00}@eiQPPZYZ;w&Yq(k-LiTZ>^v>$$f;hLkf;B!hP z@mdso@r0diVzIqXE5bd2I;g-O(93U>yh4>}DcX9!kA;izM}j5rrZuH(X=Qdn2>D^V zc2A>l=6&61Sa5$KmfTF$O3I9V>ibp#swB1c5%bOj@VAr#n=_6&b2hybI78 z$6jHI2A6|A9H=31tnk*_Xg72%?xbn#^B>Pb)cSFd+Vm*E z85}%Fymn&5TVhGol+SteFy|F0%QNN&+-yl5*eK=UG%GA_?$9M9o^C_)rE24EB&cPv zqC+hBho1l~UIbT!ze^=|J112S%FVQz;_7pAkRB5=+4!|p*YkV`o@xwuqKZG}JF7g8 zgvLTRsRJSqdx3RO*}2%-MID;|*>HW~Wmr3r;8t;j`c$Mvnx{wz`to;JFxv6HSX+!* z6~~loe8!q@jdE~-WLH#Ay813=hQhlMHIiW|y&mqj+)V5z&j>f4VYZBHdQi$L;vC!x zI3#AQN#b=IV40LKug4lxLi)a+l6(~M-heBZv&e{hDngrmZ$1LJd+60G2h~P;v6Wc2 za}YTVSwnfu?W7yhGx$vs2Q!@(wLwLun(DFpK%4o3wI)%8M~>1U^2Gc{cL;aAdUjNS zvI+MDZ@KQ{R)qQnC@}kV0MG|3D(<(qR<1Tuz0{N)+lvEqod%GXZI+q6;Jw$^{@kyD z1Esv6LD%(PV^KM(n=X`$0UC5Puo5Q&m8+=63xLkv#I1frT$ttYPgvWd|FVpueT(Oq zVW3(E{UR$* z`KqiCfDnhKPY5%k{+@Kr_s};0B$}==Nj0bHrq~{Of&IdBPmD3($p`IoU9;(q(+>#~ zkuvGK4jE9vZ+q1-Pe?FrXxcSid4`_be(B4q=q7|E#d(yc<_`^9YtXu2E(hnTbR=FKrLdi=-=+`oa4BLOu_5oI#5=< z0C&v3)nun)|6Y2<@(Ko|p>bubExRWUz7KF`?;+}JAMWFI5;Zxcu>n9^irub!CNG#xCGCYeQwiO(XUVzLyU@3Mvq$Zyjei)m_ih+>(9Foa{tR zb4L;hUs~?rV(&7QWyqAj^8Iq*4x^J1yjrz>)+B!E-^C4TQGzqTgq{lBt$%rTk@+Qj?1&A{hDGgl)t! z6Y5Ie8Js`ETb^O+r00gQKP{U$PNM_%4(ou&u{{Veb+VD`aKj*cCMB1|c5`lQ`wDYY zo@A{ppfb|1v7HC)4NRFzHB_0Zu3P;Y1i9vSh9ySy%Dl$gHy2bj5HD=e-+bxPFm1Ms zP^=^scc+NcNE$W7+}&3!LI~}5_H>D@9X4D>B^uTzK1@;gMV<701^Rx|S;YZ+N6{Ng z{JQIKou3g2Q&R;~7YPqoKWOg&dZCEtDt?XiM&SzO3ky|{p~mo!>t|Dt*uC3=%PBrS=g~L%%hK0i_U?VEB_sF0WX;=YR zM$Y$naKj{$9DYmpuFYBzSLU3+MZ~xx&7IC{KG~H`$~h@~uFjNDtGQJttRE(*fdb_0 z+e$nX-<7}AnfkKkrw`t)34Ty2hhySNnrk>kJTH`n*fWe+U|%_Tn3`x|BxxWOJF0c| z&KT`6%1FajnuFo#PSty3AREzpe>365AR!<_5%L1vrZ~Htwx&~PrZxmo(=ucE`0VZP z*p9=c_kr#e;`Uy7yC|LeKpjgfaoOL58PI!~uG;#D65tXIE_44+QcVG>x7F;z-Xc2( z(FtLYxKhF==3*E+MicEt%^5Oj*#z5W>o0BgzX;cJ6UfFWn02!{zs~S{EoJ=vR{7g) z@~5V~QOjRU!!j>M2qQs4-t!K^fulb)9mIm0GG^p@T2aL!PaRI>+QNE5k7dlt;vCHN z@&+cD@|5wYuLpJ8om+?IooJ=$Dbx5LqaqtyL=WCN_a(*3prC#R4)-sz2Dfj0GICrW zXPmztU`gv%ODh+h>(t)_u*gD{p!j>!Q*_kpV@i-PmMZYPGcS zxK>)Z=*GKuWs+cWC0QdO8n|mdo@&6We^nEC49*a~3VrBs%Y3<>yWpm}LP{}GKvnCnsc zJnm=1UGyW=c-Zu#*WL3|NZ?Hi|A@E60|`l!U%2zp=gIe;W!d*8g4W0gBTHvT^GV=? z*$Ntfvbxb9*E_Axl7F=-IFeyHoX@Zy@W}pMAY}R|U0|bjmyJ$z8>@Ul;{mXqc4j8~ z(hZT}yE9c3bS|We8N=(%#0^e`Lh4>Jp1~xD2qWJAFow4+ZT?vD@POim7d+$-=hKuS zgN*#n+jk#YB!r!Dgr-u|{^5JKwx{(LN`6mYUzFf~F_36A`@3t5&7syzNneXwTL%m_ z*Tlb)?zcWG|8%~V*6w+NlBq;TCzrrqw7orggtosGEPM53tt%CWX6ZF*)`9{HbVE$CB|XNAs~D3to*YMCpPW;p9xYSjib z4-F83Oitb8(E$Q_!68W$OuVsQ9dp2IrWaN?)ZQ9!1$hO7kf<^nC1C9PTK-Fsh62K@5fJ(ex~dbRvCv9Od%Q;9Sjrb-kA#QMqNfyx5Qgf-TCMt@{G-Xz7 zGdL*dahj_@3%1s41rqmTi>~e3wk>x)Y)9yCS^uc)^a2S}@4JmSDV9do+sG9sSHLWl z&p|Z<20ov?5WZ}knu?vem(@TiY;S9OmcqYrFk}Bg@ymRt%k_XdUNek;aWU#4J1d3H z(WK`OS+jD^F&Br)(Efah?Fu?vmXQ0H>u+z5N7%!nQ;?n0veL=WQK<4=+%Xm?2)(R+`qeKs|OcfurVd27?F_&hskvuJdjf3IbX8 zMb|8Q1cQ$NQAlhjOgA^Tu|+0228Q`^_mjc;B$npO^o)$P6Ft540411Z=T?FG=s)t^ z$8R{oqH)!_4BxX@-<>VwmnS7ARq6~U>*f{Cl~5=B-=O*TpQUOB9IsFFV*1rbp0*e2 zR-CT~VlCFYIC|dNYdM=j|5JEgR~&`uO5JKd>ey9U9$Hyb*EuoGI3+ zE4Od=2UKxSI@<%#0C(Qg?b-2Ll}7V+|2ER~yUtbhyF2}qt9)y``NF~nVm=4o!$+}Y zfbJJ>pIKPaBv#|Z?0wQ7b2O0y6cje-Nx&%s<3ioxgK5+`6jRHbLQ*F~DWK^HcQ@&* zv3y93BxU*rh{8TvLrV+F$Q6GgB?JS=QooRfrieiVP!cIUaSo0e+hw87?yV-D`-;Ls ztJc;hqof^;CpK%o!wm&j4CXj+K@vtQ9o6l*Ny{3W#qz2H0f%)-En|O{mQO7X8*ps> zXmk1GSe}J#Y9BKDJK3d1@AaiqP z0qGW-J1&4@vTHMS_b5EQ;49eR>H|rcJnoxs&PZP+U(A6dM8W{B$(M`3br)&a~ z^f{9aJK)9VGgef+JDMTk<>jTTOU$&)7L10=%{^5);+xsg;o81z?$+sbxl-q7x+5g| z5ER(ETq8dt>sI5xNx=3XeHf~kA@1%Wr0r7x&Ft%iP>%z?%0P45#+Q&Dw8zqQZ|b^O zQKtI6*<15zAa%m^p!WCIFXtv-L!C=~XKHyC0DO9^_a_VRm^ea;imXfKy9iq_ zu&tJ-?|mL_wDMHyh3PuiME`c?tE+aVfC)cplnNi^fO)Is582{w!ww^6>n^*k6|!L5 z(WmXt{GOo_@kXq-A}$}%h+!HQ>o+U`p0NoPCNNYe?AYx(A%|(eJAeH*VCVf5{2vgi zG|hhXVjTe6qwE-C$CHq#tGBSM+UoB&pIjaXMs9C+cY(xbVKj2{VEV`R=X|eMYur(m z-E{d6rQpgMHQZrPZzEU%Eo)NQ&%v*iIdb?D~y(cH3y z*>8benHZEGOEXakS5iu2zzhb1b5!(O?w3!UyeqfR=8J%rSQYu;Bb8{;7ta3!U#=b`p?vF@) ziMg7ZnyCNlQQ@HVd1l=?cL`x0HotCnZ?sp0gRjNz3Eaw8{|z(MWm}$tWpso;w!6Q>qaRbL|Ac z89)?UX?b^ZPOa}rAVgO~7ssMct?$#6yBT~T5)KtCC@v*^1w7l%mXi;Fmk?|M>i*{F zuM-I`AAb+Dk=Or(#0Usx6#w7<&P=$YB8q!!!&)Zv^cT*E3kim0&Blhc+$rAp z=Q{f$abu4@Qc~dd>E=k{4eh(4+{(hjJb+YNIcwb^q?mM$9dkSwM%*V82)Cx2;2V}6 z0I7T!2AlcFtrD5m=N#N38bR0f>g7_1KUyZP2r$@;SBst|0@AQ(8%3eVbqDzpmozpE z{AztQbo>!9oR-fP+y5!XD6#wuC&VXh6p&duPKk}Rqp|-5BK+w^&a=KZq^wlQ#5IY0QoPc~xfyHQogn%O>D0D!%3`3aplmTCuWg5A(DVz8E4ixu@Pq~8L&}6u8nO-)Zeu1C zCmPoXVe~rOzv*p9{$ef*q!xoNsi$!{-NMj5<)cE7gps^}AHfkU5bYAbEmo5)=cK1MlBvtl!1SA1QIBl$uwF%m?F24T(&aPE+4)E? zqJLzU*kxIqW|5@NJS5p=h2W6=AoJU(HyDMR&O!x=kYY>j9StnG;e(#0MEq$NL=f+t+nsyJdr2i>*o9JUjV`rO6cYsBW&u%{+MNW zQli#ZOE>wdI(g9yM!8{6e#Tu=LR$8#RIPk8-RD+u zu40VZ$7Y+@xOPrZk0VNtXxMREQrkD7O|amKx?=9gq+x;cI}(LMSzX36)CYmoo6lk< zDt5(D^P|grUp-B;pL;mO<@LM{8#HFAct^&2@l1QXe=^QC`83W+WOz(pdiWz}h%D^%a{t zasn(;C}ZYcbrPC62@b`lvBxcAdMm4F!s|Mpa66;IcLO1x9&@WhKtT7~B&T{A%A8tv z23@ET&7n@xblM%c@$(M%-lYc@f{LC3A?^|Yf4Lql);OG5z{vrW+x527X&mol)lBS` zdy$B5i%$v_a)-8I8#F=++4)0QPY;kjR7B?9xt*{Tv$HI{i(u^I?cy35bJk9HPq4ez zXA+lPPn#gJb-$k^PB*;XSNO>tAFr?@ti;Y(6b*`raZ}8w*^fjRYaxnX!-U-+RTs30 zKlGV$`R2arcD=V&pg7wME7VU`JMN9`3?xq}zb<$RBiwPnvzY;hkbuQem(C{vQK!4? z2uR=W_Ip}8lLQ~OutERa5zm% zagVx|O+lP-IVn2vQj-3=nDQ2(oKGogfc1nc^7%<;_9MVB9E4@-@BerWUtlxEi+iw{ zh3^F6AU;R?WBFJZBwZd{Qip!sTuwGuV^E)_z=--&d;Tr!_YZ&obEnHw>#Eq4%x-z4 zPeU(^yAzA)|A^bOW7fQDO3Qh2xKAq=CHm^iAljSYw#FF_vtUQaCl^I_H0CeNzj9SM z-`Ojv>O91^%2|;E^2N>P7Xp;xFS zRLq?&1E|~_(|BN6_c%FhfBvCi{`=o_O6MI;`C?gB6)Fn)as|tSTj2LQ2-C$_c%ioI z{yVbRkDBGOQ5K>}^ZJ=o=IsG`-VLffWb2eSuU?6V5{MPpaCjarP;`ewOkAOpPY?#C zwI@J8cEHr@By@f)9J2bG6kQGmBV+l$s(bICD7$T67ez!xKmkF?ND>eb$yq>hXvrBQ z=bR;}NKO(YLxUhl&N)lYIcI1xP0loMC;IKR*IMV>=kBxX)UCSwqh%E(FE!`vcaHIU zo^jLi+4r2702!=S*7}Su7`i>ZF(#lx!8yoj6(mNh-V7(-0L8oE-TNWrqE$imHVI`u zXkm$(wH1Zw*#`j?Fmjt?ut7f&_nL3?(;ibEJfX)Hb+yxsG<7kw#ip@$6XJt`*{f>X zJuFY+k%4x%h4OYQ0a%J;yR}IrOj=zX0{4DI<4OYYF- zN0{3=0myV`z-g8E%!egiqRZV#@G(2psGqYy4JIBdU7+1yC4N#KITtnMbl-?pHmw*s zlu6r3%_@xOB3(B6f6iq2i#>Q51Q+_NiD^opOiLX9}$8y0b<#_&wh}K?Z6$Xp& zFZLDGFd$-;+3Aq%jyxfMb)l@Xo!JT z&ar}wphmG~#l!~xS`^doE|R61$u}Mcox9p50q=Nv`B}Isyl2O?v5|hKjVF1TCZM&Y_^KNCZPdtYx& zq(Yq+rz`EyR#2SzPil4o8N;L7Ds1|KJxBFF2Yc-B)}gx)jn_kmzviQ}27dNBGqeDm z+th8P8TqB8=c>_4>n;OhV;v?c4i2pJ$ViB9r;!zQeGGh*TD2coL1GD%OPqElh1IRa z!W6w`j`w?TQN7UsjHIp5y#0con_99w^7ejw$ajUK2UB zU%vh*&T#8S_l~!*LCN=~n=BybC;)8d!_Gm_H1JB#0E}zZI1lrPPxvKu9iSUy_x$<7%5Ym9#J+K~Me&5+L<(S;#=X zoCxHSm_j0z922Yf2O@CQ6tq1#uLn!zy!fXk#9hmZQQo6+aopp&53ZH~9`H<4JQ>MV zKl&C;i;7On;}GZX(Ama+krN!;1IDeJJVTmiTsl5o(l#=nL|iQKxo?3xb)6K%)8p4E zNMc&=$2^+L=-~TU-|S}pW-|DQ9WDCBX@E%Vl;n6w zPjBz`mWrx2qY+zxB5_}ec#ceV=4g?oB0A$zSgHqttUL4jN|NQ^t4G7uHCaFDq78xo zOtfY!73Pd_BEyMRDV9S}W#VixvNcjPa&Y>#!#E!hZt>S_M7QOS^AlJTF6TR&GASS% zq1S18POg4NHao-bW(?Rc4h@7%Zn}69T?e{GEGMs?{^`w8)the_drYXz_{|afIQ1v> z<%u+TwcOIHn3ZjecDnwIwIB_^s&5}&lz1={isgMTvj)0Lk7 zeo%F<8?Ok9;uQIY7;at}TLR(~_;_hH4AudVil&wp81!}SMi88KOQL+c93cVVi$p+p5kjFWNC zPtCkvK``l;2-7z=J&f{D9kyQRt3hvg)?jUVE#&0gYpd-?A~rv5G?lQ6zC~BOn39Hd zeRH{5B;Jbu{|u%w+=Bi0U@CN%OQBr;7s^`QjDZwbcJlIZ|AE7m5OiHGn#%Ip9TyJ) zb4f>fVztdjb76*M4h$mvBI804I|nn%ZBWhg7F;kpxXq{bVX7d7dv|oo>RP+|0{QMk z4#f}qQwa&$o@WMwXp9d%n-B5rMEGYo z1)C546?1M}6t<`+zT-y)+-|3@&W;&1D&AZ@JLx-_B>;8(xrTv(usiLQ`8~yjWt;_` z{3bWWvY zgCb^v?!~1R^hj3cFFxXD5|*BfMpl@4-Qg}=McFOJ-+YgvKaF%SR5eK3fBk#%YV_2` z0_zdpV(--?h|-<*`Yl0+j7d*o0^ljdkrkqAnk!;guO(ksuC3Lv$gMOxLTH(VsQUf$ zMVia$Cunh3;E~)kz z@oeup5we;NztEne0UAd@%f+%8(4OJU;c06?t9n~Ub6UviCX1Hix3<7;1p(ISDm_ta zv37UNC{R5Wx7->m?K(Ar{!n};2TJ z_4>ay_POx3vEKvzgvaC}3AFTy3#;X%ufCSJm~0FyYk9wEgT19b zNKC;=+4V|{KLA&$smZ25zW6%e0tE3P&ApGOUx}g4HRH@p;bqcI%l%q;7$%uaM-YI6 zBF%HJ`A%ju_K6YSzY|^B&ik<1Y2D)Eq{sesTWvwR+QbygD;Ay1>yt%EHdEuPM#QJj zzoHpszecOP8hY$u6F9z!ck!0$yntX5+vPs}msyG{m1FhZps?V10457tX%X~T#L*8L zJ;W;yN$b%Zdh4gT_rx={x9F7g*bCHLx++jKO9M3brV|g*cjvJUJ+{JqT9kvor0D|? zbKdX=7RKO5MU&Utp-uS0e9*%O5eF6AFZTV!_H_<209fHRt%zqSqpQC5rOK8>Irk;o zQ}nLaOB9?f8eibc#6@lx^=yw!uy-0YRhKi}im&T$A@vhK6_r4vTPjSBF1z|*sW>6s zBdwNa)SIWE1UK?z9tSZS42Pn%_ikdS#|uii*1x+k1klA2$DT<*)!T1Q!Y!o>T(({E z`HtN~NO;S(A|S?3n$p~^D)&n=1>UA3=-3>^Pq}|kLnf!D>Yw4qB}UL4m^o5@tk-gM zJpPtNmuG2-4#D0_H`T~gjtYN1>% z3gyNTOQ(X<(9`tVH6W$3FRL$T^@9-+5`Khwf8;&ULa{CwYX@B%7ZQ1$iDS z(LS%{SNq*gLQ*1RebTtgE{e7MEj`j3ZhbxAG_+ds2Mpt6eaLqUe{t;vj$?L(iasph`!iAj&{$i3q#NGMHmky`+bFe)nwl2dWJHwiIF7Q$qwaLXR@>4mJo@LrQ9wH;vTO(H7m6BcIKi=5c1~ta(JR3 zm^6??y1)+JJi}-lUCaRm;y(Yx1tMYU7i^(!3EJjm-@`9?wypO+dGG65&dvN#V|Jaq z;0y@VP@yJClLbj-!>4(RL*dfv=g|@jWfF=~GP)d_MeqGj7Fo|aX(y$C%}a%Z?Xpy% z2}&bf5cl8;^FgZ`U&m~F2eU3XbfA%MNJ%YDcZ>yN{DU4K_2;SDm+A=#dx4Aue7J4C zF?>T4k1;KYk|2@DJQvlmZr>fvCH!aRPuUua(Vf(aQ|DNywxNiKLfW>DHsR$tyO0nb zgWKiqf>3^siAG=VPutF6lO4}TcJRp&zg;JoZKZ4&BHQ3_jfsZl`t0SzeAuwa5eVTQ z9|t=vh0a}zK_vN|LM~^65!zBgb95e)1d~7ZNZb=UuC__Z3asYpNNPw9q#beRe8z^^ z+qHFsgfvw&b;ogKvC*YbFNI00o7o^W)ckb1 z#j1{z@l^p>fBIm|5gw!FdCzR!&Q~%pl(`A%{owx_(MH3bpz|AOvj9XL-|GaT4=UNY zn)MztSx@N9Of9W*rNI64z821FE3G%w0@QLmfCWEv-BDFnw~{h~8uE7+dW#+)BTXBS zBe3;^coKvKw;5k&2|eqO4TfYIaGr|1^=+S~+={E;(stPoC;v4#aqA)&l;WdMUAU$W zB1{y$wW)<;;}oVzZ?f02hFl*+2ObC#evQIjU>K%l#&s?BG`%lI_guIt;y;9KkL?^5 zKIu(Mx-5O(<41YhH-)Lujv=yC81g?d#V3`4SV+W%OH1Vz zA$!lraui{!hO2nWuXIluDsVh3ncK*$g$%K{2b3x2ViT2r4&O^~OC7U#(63G-QS)AY z6t%9`QO!U{%ktBAIZ{U`9<*pUVw)|rZE*M<7AdGEd;4I{(R#+v3gh9$7%yWu8id7ERUk@vo zLp4b~7SsGgL);F>v^_d{&q?Yfp-st+!1izrFP~$}vC{bbhW`z1SEuE4#lY0;m1VB) z9VAR-w0(ZZ+OqTRprF;Zp*C57+pW&|`)j*jvR+$*i{+_<5-xCZ^rI?-kU)SWUK3>aZ~JRE%W*BdctO^ksNd3krdMOch=Cc)t;(er zENDiJ9)JcTcon2=|4~6K?q!tBG3I^DLw8dfA33_OQfPr}7tmOWNUBbX&$KR|_li|m z16X!CA}Yr?qP@59dj(ITAKtCI#dFUxFtSZ5Lm-^i_X{VwvqeG2k#kT?_m7^Z+dMq_ zk1r05{~|BNF?e=)tCbS}8N7suQFW}Y8zq&!y2uO%$2Gl{>QEH8&^f!o3f&HDjVa+*1za7YkrXt7>Ev2TL~z z@>yLkk%XrRomuE!9K$mp(2a>yqXxv;`5YC}$JjjW`lLtohbS{cR3xrjg+R{K#wfkk zK}G;D0PQxYgvr}yB!R34KY zQjOj`mg)OVo%5gc2x&^6u(L=XGW|QLnVo`i@RL!I;o%28Ny8NoQwQbG-MvIP_set7 zq4ljsch}=2o|Lu0ACjllJ9*;Ll=%iwkF4Cx%i?3m)h@1kd_=L+&USBES=f$n7=+As zXS#OEb&(=m%_Pv!0Y2$4Dai<*EOz>%sF2LF7Mi5;f4e`l&}0(NHXvdlxKF^Daz%IC zgbDb?uj&dfq9cN{=Cb3|+OF5a$nkoiJ5%}E`}@l^p zJ5fG;0#lQzdrptRavpj|cHan}^_p<-u6XAIpU2#`$mMT;^=@^l-G#6iz*=b0hg7#Z zgZH4UYJ!4Bsws`H>tnqQU{F=iA)#k)0%ykUG5I*c@%?bMKtge`T!kkC&l`}NIOMQa z$C4_Kj0i-Z&t%m)T=64@eAE}_8%dnt?RK`d9|p#p`jZ6=3=9ej3ju*ASrxCtcm8VI z7x{u)&B3j;NiS#kaxH9;XsUe3eZ@cc?4$m0+(uj*v1_;MVsi*lE}v$UTj6H}d#b^W zI;7zGVq;?i2x`$?VUKOSl^L`rc3aMc1sa`Bl^w$)I_@87Bco!ZU380t!@#RAKgq>e z_3fdqm9X)%0bi0R1fp1sB96sne_p_=9N}a)kvU|~?n`)atZo&Sf7`6FcnRv>*w&`g zpZwrp8x!ecoxAIa^!~AopY{j%B&)i*x|tclO`W?a^IGZ_(ln~#q?*s;fboQM(N2aY zJ(~Hd+pLpZZ1{Jrx$*DiilcpM2$^x*mc-9eG^-#&AN@Hz9cxl3o@7I#v+YO$IcGnU zQtkxR|1^tRdACb>SaBhlpHM^g0`hr&t97S2UJbhaQ+R+V=Tu^suC6zhbrV$8U}jSI zZ00He@zQTP@y0u?+>?IB?f6p34dtV2FQYK=4%r~M^|DcLg{~zm+a;hptS8Lo;9~b2 zwa$IbtY2igmF+w_Nl)T@tjpqUV`(>bk=`D`^H#*H9BXf?6G5?ouwF-KsOf!F-&0gn zd13E_w+7XigVWX7hQ3Evb(%V`xV6pw4@a*Orc_nI0^yB>cNfG%3`=ey?UHu*X;P29 z5YNl?qjTyXslz6I-wLQY>qM_Ia?gjI|bK7S?<2A1! zgw*)>)~2pg_|whdfJCZ&eJ=nPD&l|ga%#SN=7X{#J#eSOS4vc3aj-0)=nHnaY4?Yq zwp;=SgFWiuDJGfU5r`{d1vA6G;2v3x;d?Du{t<7V598$Br^y-JB$y_sv=%r0B-i9u zaaZ>fEjQIAVMo{pE;RysDz<*(IQP$Kwnpi4W;Dm*ube6T$!ecy^UhG!B&OET*kWov z88{ZjMM6-<1x0>IKXq#14>1lYD{!MTNxo-Q`Rpd?(10vl$YegrQLYmbvengNXZiV^ zzUY<1)cD@d&S32|IGgR$v4$24Tj#i+)a;(&?kwuGQ#uo>##QWc*(M%AS%%{8ZBu*- zBYe^+&SJu_6f1SIF@HY$R9wxUd&~I^3m%RCWLGJ8RGGFY1vhsAyAla?nU7GZid<+ zx#!44qokkJ&M^5qjW)j{g}Y3nQ_|wHSK>xsGmN85mP#wNJT}vzPa*)MYhkvO5-Zy; z^h-LMOiHE`5I?=ey%mGrEJnxRjxW9xkM$$c%dYK=Mk2;B6qW#K5vNX`5(jRBfkC~1 z9w$5q3R1seZy=j+5FS$&Vua2(_;Ddbu2afLz`@4y^@W19U@4b&ib3-dd8+8{lZVWF zd<~k-KbK>r6Pi_AHm3a^{)l>9<@@91QQEikuMnfY97UYC2*q35WH(6^V>KG-HT zl&T&mAbc^L4qd+x%E$=H2$!7=-A0<`w&CsmXOk@=B$4~r$9UWVo*;ApCpCb z3jRsxOx1)A8(Z0OoNBJDTlv>dw5a+-4Ve?><-LwdiQER4Q9~D8PKasmr)3YUPwCd0 zQdAZ?KDA+J5zF`@q+yiL7}jX*k5`rAmX%Uxg!nX*WzEGUj8E-9q9Q-Pp#){54lh_) z**_d@9pzV4B;=|?pI+RV8Ibs6Z{bt~oe56*nLVdRUzHTpl$6w>ZlKP2tDlQ<7Dk2H zzWIF$5aq|IFQoz#R|u-3xAhe>8JV6NIaxt7XScB$N0wYV0)L=6U>3rjyxh~O5y=}2 zNa%3kN#Itbv7NJW>;Dl8_K~lVt>(9sXEYx&<<=T?0_j+$S%1@?C%O&rkDri#%>~DB*gV&sE_QW7h}z)wYR?DOTrFO?9!%69 z0Y&Gj@DZAJ2f4546|?CtyS}{^B5p?tkA(O3&g%Z|g5=2ha{gj33iP{RBswTGlE2vT z8CLlDoX-{~wtJtGnaF31Bt#hH`H8oWTu{&7yRPt?(8|LiyDmV=6#>&qx!CxW$2gN+ zADqEMIoO*$zhYP7=lvW}Nb1ynf*<9fPVF^L{qlK3s20}ACvLskrs7I>jH>~gVt0`M z@5IXDUA%->`~ue`bv?iYErNPh#kI!Z#apko=P(|`VYxe7BklV=P4Ilp@rrCqBbDmw zj>|rlCi5REpy}leVZVMbl^qx%dY-$&7JSEo;XYB1X0}MuJX`g;x13sEBRh+3S>IEm zLZVtcn9^60?W!+nJ|vc2xZ8m9uRITeqVc@ zrn-vXSFq*9^!Om*O&#LxncH$n`u|~2&Tt8TG|7GOHe)@M5}Q%Q^}S2X*ggE&r~heT zR@N6bvoSl|@81|4-OPql z2zfmpd~!^NC$vxDiFNfkdUajX+Kwk`#X=o-ZQzj^Ckzq3&|6|%Z|`^%z*b7=FBBA= zJzF}eoUbpN4Bfzc z<#P;bs;WI`_ohpYc3xhqMnzSeJ|3{MW2mpM%5fs5vm~ z4*v?tcyHfg0;1$rMy`fpFndOAq*rAQoXps>GW2=RRRx|0YGq2^Oovwo6r2m$)cf(0 z_HJzR7;G_wVEkqni|~zLx!oirgj^HAb}>M)tWGr}LyI;j$+)D$MaW9e^HPi~7En z(T=#isg;goKSA(bee2*)fW%I`TWWWdou%*9TbWCunGxbm?6~$CCz;k{<>On1&gwFd zn93~YhJao^CR(Uw=>g7(&||;atIQK4@6kDS5HZ31eQIce(68g@bqy6yJ)*eJ)YKA` z^aDfA=BMCOKOlUn+H?IrWWu1W=1{&V12ALQqZ>k;tx9s(msvN%g(0Ztg+3}%)`JM6 z4C2MxUdA7}FIr#OxoK8rgwvIsGOma;W!WwnQNWbL=?kY`KC2GY>3lHyg@={i{7B2P zVrwtxr!c2m2^J$NsgIPJ)D&W$XmmS)iR|*k-tI@dS*L zzmNE-{G8jvMuGN(=y5>zZhk=Jj`#~(m}%V6ceLndMl*(EQ_|vR|75Di0$Z45ZLt_cUYnZ6nxv8D>1{XUl z(Iz;}r=d@tFRouhh=(ukBJCmx-r$(r!g7lNeSEGS2s;YO@I_Ga0IjpVh%^ch#v8Gz zc$xU0EB3DIPTn-kIn^Wpq+$5@Co0+5Lm{b^$?SHo<+WPNu*7*zeY<{8Q9Nb%D65su z#uH53=Qms<^uu7wl=p`)Du}y1#V}=k6@u|yA+f(D+(w7EX~Id^5>_>}vd@|lpG&D^#x3oNY_hS@=OWPqaDJi{7fNf^cuP~RpO1|4c*w&QE$1rNEi8>PtcL( z8~;fvk$~=Pb#R?A`A^1m!Ot9ghY+ zz(D>|wpHDq=Wk;BI+Hy5?Z~nSufpvy3p!*T3WP0l(2s&K<7=vP4KCN3$Mr6m)EAi> zh-n{hUFyAB9SPwa&P}0!nG9e0xs{#CSh#uDzhkl_Y0e6A$?rXJ76(3+SjAvdL>%jK zqdMUXKHwD~L$HY5qx`)H(l?^$&3f=h_!VZ%T|0k}C z9kaC>NJ#kF;%@~Mq-Ts3&B?Ak9~Hucw=WxOtw3sv@a7euBHmKlrp=fh>MCACI_tZM zob%h!8|{Z-m5g>IYoUKOZtWy!<%7)|<8Y9djoNOOB5ioPp7D5CP5^NMN{BBgsgG47^Mc;}jeTjtg=Y(f4 zbkEbp?#IAhGSJ?m)rY!EMI0T#S(d5V7LA!=Ud>#iGnqz zJdTh3Wzps;WuOr~F-6cUkH2S>{>5_upZ@q1!1g8jUiGOpGS#SLyelsH7wY zz^i^iV@-_Lt?ZY|JAt9%AiMpc?$^7>xjWabs}(P>>K0ZbH>lD@&aL?^;Qqtwpo}{) z5&F=M$D+_vjLT%`+w2sTg~GF*88_=40`Rha_a^IlMO*Czf6k~@kPs0hiuv%tkCJ#5L(oZ$QTWUT2ZjmA63lD)1Fn@~qfO`xyKPS1=|9H!%Xv zR&KW?q{nzN!&$AF;nPcWmx}41 ziSOC*S19A_A?J+f?yoY!e!<*OxR(Yd9P(nGt?qPsaAz&%OEYj&0PlHHDT~U=0<8@e z+S8ltN3h4-{wt3K%G_hjJYzB0#uI^nX0(cvDfG40Rr!&1mhIX`-ka_I*W)HRw_2!k znsJDug4cnVXV`*4xF1=?3E{tT?`A2jkA8W~I9@`T;Ob_exCfMZ&qUA~*u=B0Rovti zXgxZU3fNElgT4oZMydtRHj90;)Y6uJZSv@ezxs?`x)|m$gui#08x?P+m}{qQ+=O8( z2=r)H-MFGh#9X?2b&quucz@kqsVq#)qu!5@?tT2NxhIpF zT~pS;tjmK(-MPHEmP(4e^f|5e<%D?5{nzzhG~^|}$O(pB+5T9%OsuT=?poukVm=-C z0{0+M=O55CrRmc`iV~)EKNH`05xY408AmLUR;R4+hc(fzRz!*s*rGeWBQC<`e2!o5 zauxd*axk_Y!ijl5suw9L66U$~W_Xd;qSxHMDtskq6#51`#im8sTZ8|{dxd#;gaU6= z>uJAe5G>zv-|7+Os5>%}v-NM*{5O70iLB^hKD4A@MBg_~h_}|e%u?t&57Ys*Rc%iZ9LLQej zM{y|af5To+U6%1>#Gt!=*MhlbDdFVIo5eqO44L2l0z^RpjB`Vh@X$Gz&v0R!Dqjng zA14RW>YRZy-6}E9SI-?$uqHZ@Rq2FQPtT=}j$Fv84Af-ay)c(W@p zAO4=PLg|Nrt`v%-$txCI zIFwJq-w~~{jTvVu{yodRkvbRR!F*zHMo^)mrTXYhfmAa-dRAu!-Kdoke)gHKRY*P8 z;Lhz&BAG>zen*hyM-^nugNXNw7r)bY+?yWb>16 z;1Xhn0BlOy8QXji3{H(SYCSJ?I3hag^&1xa=0n9BoMr7kZXZYOFTFkyAaPvi$MV25 zTcKs5yk~csfYZeW)P0276h}?g^r%g0I=T>Xn$W13F6i4-CEPThuI~1TW*wIWn{Ph) zuZS#4MI1P&m8jgUZ69l<`N}@Y9pl|xcD!i9rCz0(D7AhjVD#x&gjck3e$Dwv#@m(iE|;cjgo0hN{?-pS{`u(5xCVgAm6V2jga3E z?|>BlPo5k#Gn($A83&uipwhKR{W~bHBILKH~`y@A(Xnc^A@Xn@^ttd^tWPrDQrU zS2J3oZi2gh1m+k9it3_WzyB9Nz$QL*<)O#wb4*4l{>QkLy79?LA8+5CiD=K7w*s$U zUH?l2dQs`0BG6M(*Lc`=i^G`!b2Cx()tD-uD!7YT{ z-genghwbUJm7aKDfF2@Q0~kKKcnU?}UmW_!>dwFL^|uf;V_EmhWrXCI1ZzoqVZ`y) zi<0l&jylO+Uda*j8BM;Ph&@p?2Yvv_AAb?l8R;-R-CZaNV0Npp({!H!b$igyb9%P- zBG({>EF?rwr<@K9NP8&(R@=?jHtmwwgyv)bkIV7U&@z;+&rMFk%zmpi&K)ZeC7%&- z<%>)Wfl}pPdha_$zwIZI&Oy~v=zvI@d+-v+Lgzv>t0iQTUeeQXYiK0w?u4q3JeyJ+ z|7JPEPf5u?W^6`CLpo3y+;>8I9T= z656%^HG9Ncd0XQBRJTod`I#mde!`))e*l)))CN(^ku)2py0OYrdgdE#Z8-ATdNPav zVZIyy4Ix~(zP8@ogaJx2qi9h0SJk-95T9QFpf5 zgH0{dUql1zt>5oFM8jh+pDTldjv5Ar*X#$n$YwE*9gr&R;=5F!buY@=II&PKzfw3H z>Q52Ms68waM)i7e)%Ww~8m6w#Lt@(vg?07`)wWQQozdEhO{QfRm)39I?tEC zw;azqplJp0$;}LPbBuY@|$^eVh%VswJ!Q@2FGx=)QY3gj>e097bz(z0m)nYb}Qn& zSP}`7=}r5O!ZqTwt^6!6`Tg8%Edcu$1Dn6x$F6!%9e#czn9W_poxfaY@Bkw90lg&B z7QMER@aqT`sar&R(`UdTz@ex%*+0{%ZPD~p^Lwg6Tb=v5o=hkqr(kcZ)y-@?@EP86 zBiUz5N11K0@~GTTJU{fMbQs$dOQP5-VuI9h4#Vu5&*NLEO=c_YR`CVVAb;Xq{%=d% zj3`2|Bqh5de%!U=>!1#QFNBr=1RIeXyl)1L4OfogQyHhHH79+Z;V|a+^B=*Em~|<) z`L#MT(*2F_YOgIjE*lw@>+9O-)|Wl^tqZo74MKzI2BMODm6a7dv}+V#Oc;gJyNLG0 z4E2PK4b%N^&4&9UCNc8S44Mp@HDZg;%Ok36mnCL;xYXXqGz#4vyHd^OXuPZGZq%D_ zR(#wi;5D8RPt0w5cwV~cbr-X&w3LX|G}6lpS-ifbMHnW^Gu+|NLaJN5Dq|)Aok#V>158N^1iF%&J`7R_QJPvcTwRM;VK9($@o?}fp?G11cflsC|1)8nN@ya&-ior0U?`qQ0(&FOxJr(3PHt?HL!g>=e z#Jew+Fuj)Dtj5IOOK<0%%TdyAYE&ejAFM$287EfqD~&>v`gjhy*Qi_VH)j)J;^E9@ zS!O<%M$iNr8+*jk28n3E#Cxf_#I=*zh%V2yk>W7~3R>Cn@(s0c!R`Iz_eO~Whl`a) zg+RIeUqPbcoPQ1y-4EwqS5iM(8%V9ItBY+IQo|*BX>LC5JQVa#Mh2ZG4k_|~^)Z;N zNPvKa$N4agnVA_L9v(Y8yWCI#5@Z0<0$SkPqq!Fq8Bj9z8_J!cY_EDU$nDXL>Fu*; zs*WW%M}}>k8|18MS6M#NX$aOS$3jY`@s{O*c+Xi1JQ3TKWx8lo4Eq@1TFTd|Wr&1Y ztzq!m!rDO)>C&jK%KgGojsl%eT&;EI_wo4=HNYlqn2>$o+nAXf37;aCd6HXKGeX>b zEQH|U3yZL~gQsg~y8X$GUcL`AGc#$HeX^94wez#{HwT8^KT&mcy$DeX4s2%G0hXPp zs3;*Hj=|TyB%j35a-9_Iz=yCM_z*TTD-8{KDzG1Ob(@F6F$zrjh8+jB4S^StgVnBh z?f48Aut+lpMh^i$qH{}yxZ{gbB0iM+JWzsijlz0`i{L0MPDUva`?*-bL(LkFy`|86&1$yk7MH`A0ee&=mfX6! z+3&2OqBoCSAyh8hsh2)PD*jFASHj&IwsF`89ucXPLBoem#Kc9$kLh1Y{c)lHN#wi; z{HH`tTnoE%Yts^lg!wpso*@J^(@RT~_{1&zhXNEg0;rM@U-;@p49QcsBg~MB_-$(F&AZ z(th0u46;9WuYZC^XKH4)X*p_QW@_>Ti3JW``-r&Nt_E&=R`dCW|Fe|M(Ahu|#p}fX zC1oRVyA@ix(mRe|qc+-^ok_H?AfF3-4i&_ht8^_tX%?p_9mMU~m@M5aiPo9~Z6GiK z(YEd~N@KyNL>kK<2Hq%#*et#WPkw1uuob*i2HC?wcj<_(Wur)=cJy`qkq+ZqNlR^^ zCV8e+Qx4Q*2n^BM@Zpn@D0&zwlfedyZFRded3nfm!yJR=VEsW_&-P5U1(#FEhn?%X z-p+H5y}2}1`|gXxYWu4l&-&?ec)1(1t_;A_KAI6gO!wRFSh{MZ%^#o3uR1oN%g zR*=JG!I?$uy2Z5PkIn5^a&E7>-xBbks#^7bo1Jm9QjZT)5tI3Ojn83CIy07oO^w5D zHCy8jl$Z6M)$JbghV9-dyN_r#_lM-q~ob`Z+VtSvDnEv5q&{_pRZ~{o>X0BRD@` zjanfw4Js<;lNFy3r>C_@{WY7)`3_GUQ>L`&gg!ySFSKIwN0umyuWkE!T!B^YFw= z*%(MyXP$vk(&gQbKP$XTqj&N=7H^H^nX>p`ir?(o)4-Uu9~4;_3Rz$hTVX#TkZA}d z-9f6TXUHC@eOt@z)SBvavzoOEaK`OZ;(hXq{x zjkXo<%8>%pE+DLt)i*nkBM6?x8a?H8{lzAN9AjLH_uz$ zd8i>lu9@hqsqv*OMDtE;9O_gH^Z8~D3=!T-PiE$sKI zDK;T8f9Wdb>PRrtRFz-)O_N$qUi~PeY_Sy#ELV7vHqW;=(d-^90|2{(k`Z&W51? diff --git a/docs/development/assets/pr_testing/artifacts_download.png b/docs/development/assets/pr_testing/artifacts_download.png new file mode 100644 index 0000000000000000000000000000000000000000..4b6a13f5f08c6e994ebcc79017821a0f4c1fc7b9 GIT binary patch literal 100463 zcmeFYbx>Q~_dZ&jqNTVOX(^>xafhOX;#yovad!z?+)9hISa5gu;O-8=9fCuUgusu! z@8>Ib=FZ%i``7*Bu9-~coY~oD@3q%i^5j_&DoV1rSQJ>#o;}0;Bqycz>=_E=*)wDV zO!TKa^4q(KPhUtbYO)`nm5)&!JYAq#NGM7?dsY>PeQ$#Hbp6~>?u*N_XC$xxevm$? zF`hkp_L%ocNXG?&F zr*$4x9x5sXs1n|%ZS&%Cm~`J~6xmzW(*7)do z?=UDOr2Z8=$&!cH^#2M*r*V4tKQhqCp~Lj=O=k|Axrl%7QsD%<{nya${~5Z_2H{Ot z!l0!U^Yr%YTI@xmh>=0`oRh`K5RnkQ5@MnxC%2k_Ko6N_)syGaiLRAU{(bbdaf9)S z0hWqn5M|eBH*Qmt7Y7k>R^}^OX=!vftp2U-+z>4YDyg=1V@nGiI}?6HGCQ3%)^c(7 zRWs@Ko&v-$(@#EjBmq4wEp7c^=gTp-_&@W0Rd#E)@#jQfJ%uPo}t0Kbst4bkf;Dkzss z2R6S-G6EJQ&&!r-n~%(=2YRnCSqFwA-d-1!Sq1!~m_pteejUp-$g+QAg|{tg!A1hAa&0Nnp>CC zCJn~oUY*=yf(_^HnA z@idvPrT4dG+7*Wu;$Q^!?2X%aOfWkA+qZH6Z7p#9@wU|=76ksUVI5K;I=aKtTrlbA zWZZBTyLq0^F#sRQFa6=vARThi-|qV9L+&(jkNC<;DbX0K-Y-!Ojg4x^%HY{I;#`y0BTt&PoVFG)T zZe6KUHoPA`&#&^Zewin`Q2Cwez)3{ZSOi=;adsw=VzLfpNhW~gQt9k9uSPJfrA0Z2 z0fV#9VktYK!~p@irtMY;@4E_~C_lL3gAb%9f(LT}F}YVX&iOd0y1%$U$~Lt+A9>7X zCmh_uhn%CEB~AD5+mj8WFWF$4P!@>}f4C_!JA4C}shC)E!|FU9b_b@av3k3C(T2FHUR{Ghm-zgFroREZ#i-$F8z%6mu@|%dd~a>g|Nq zou|y9>Bl`>kP0`qFnE)gBcukD+1j6rd(5;M;nSa~&7iykSaN!=mlP*4E!fF!#?+qn z@Mcb~bEm0gtvgng!132E-^QOP&s(^xQ?T~IpNy_P&hbr`xS!AJK6FZS^1B~Z!p79x z<_!v!GVPU659oDBrOpghBU&T+w}4xz?YQgiCeJg{F3mpSes`{udBiyFr3R$ZcPK6< zEiG&4FP{+`K6*3#9Bp@i_`Qs5g_#arPIKm(qwME?374h&Fkaqs-_YLMtYP6rA*-hP z&%2WilM=2GCE)9Ohy+As{926?uDols*eQ~4WdOMQG)jf-x5>5&Z;L@PKI=zZ( zY`l0)WP*OhCxY`xB4J5y9v`#lG@yg{P@bm8G_J`>3H!sI+2BMuc3=5S8(lc2122Yv zE#yOJw(D2mVnA(T9DPMs0U&V)QrgZEA3I{S#K1YJAvcc%8*}KY^TFo6aSv|c&aV_t z+1-BmwcMxZ=bB15`mUe{ulyx-FjsR!Kqp|r5DQm7_w<{AK;%f`6pXRINIg|bd~NeF zfD%SOG>>aIwMiCv@x#SWL~U+F#;^W^rdBr^$MPh2$U9Bq0uCp*@!Ww}y8a0qF~Mi3 z{PLn}HgaCzkJA7cM*K7GF*91_09+xvmo*ySkk1}V3P87e9NT|e7PWBl#m2B}XG`G+ zc-@RBnvCvLud3~0vw`mJbZ|g5dC@R!S-90u)kyn`iV9|Rbh>B* zgM8qgU3P*FjUdB*SmMG~c8I7c$-~W|r|X4FJaRLUzHn-QMupb?^rDfjHB;kuzu75J z&q=F9LN}S9k!gr@OzlUbu^ScrQb_m8BJM*5+r(}Gz33Yx=Av`{CT|QS{y#6xcUoIp ze`qL)8?LxjSY@(N3At<7Uu4_0xL>?7jB+9-_X2-*z2c&`>rcJ4GFsddeqYzO;9=M~ zGKO?E^KEk|grD)-li7CQud>>AEZ_;;S|C1cD}eM95gOY(R4$^vMBQD&0a26T%JP!U zefSb4c9SjIn43w*Jt6WA^g2KF25I>VJ@quW!vTNN4eA&Qv;Pfg&_T!T8~d>Q1KA&r zzKUpDpND{=^k5W=mK%vE1@H^N#Y;Ar?5p>sgvhNZPVJY$`!tMb%RYRYpCd^xy1OPT zHH|El03m7mZoK=k_iTts9V|g*9$>W62HJp7Es2Ghn&Y4lRZJI{uF;(RD~+YWlB2?{%z>HOBrL$_S40BUy#^zFNs)1O2AHuYUkUPPjQ*^6&=z#i+(d!yRt4cj zuCV}YpV>;}y7Px8a#LcdS;iyNz#macgP_*Twnkjin^W1(DcC=QQ?jif5@#;sA5*y5 zf8DQ>TP`fq4w8kVA5(U0?dzr~IZL>At8hnC;MjR94g2A z`{4VGq=NDI+>~vczKz5p`flW_WBkQT^5BV~Ud-fS$oWC^7tf0(i?d~soAqNtX)U1o zTc;PG$33ghi*C|>1%pB%#LA)}dl_&t|K=sbVna%)c^e+w8AW;Rh=w}7hNI<`!;*{i zRK$xnd`_XfkKA+Zju;}>?gH?+H}lZ3>*qZhu}zbPDM4f**)dIF;7DiHX&EL z>L>P6dn91*L?{#fpiVV_j&q!!W6?pNe_Kvl?JkDA5=!}_nFkMT$@tc_SsURVp}%&m zw$P5e2RcDQ%*iHrAzWEv(}rZ*{f$uF4sw*NM%gE*Jy9Dox54q%#A8!FdnoMm?8@YM zrtP8IEIUzW?rd*ie&MaFV;J8g8*+u% zScO8lbdA2_-lFDPex`-8f3Ld?v^hdfd#o;KwI9Pc2|Ag_<3GRQOmnpf%+C=^Dwy8| zAn{ev3?6>$U#lqZ*L(Zkupeiq<^zPE{LZW|D@sA|3LDPgH2Ib26A;3S6LeDIzZF14 zV<{vS^P}$~9UD8Q%Ru#3-NS3K=L*&fC&1;qjUfvww-A*$qBS*~5_}NFkY%&_0nVgE zmOLUaHrg_7vqf=X-=M@-C2nSK<|WW9zI;)$D_}duc|50aUw=pRp;+to@W+v=E+r9B zX?t~gjk+0B^Nz-b=1uZk!SOAYk!(~Xb!0e?nlV7)DC!ya$=WBFULsK?@c?p&vaX8FmkmeMo)h{ zRMp_}rM{h`fhRtT#m6CZ@qEY85)-!8tHr{h*S zbS6^y3AY0r-cR=4N{Lm%+kLQpw%0yPRJJuzawy+p+bOcH!>Vem-SPQ56`93B9^AR% zJ!I{s*C6Dt2G?3LvnZ7F4uwupCvWmfrlY*H83hys1W@Z5v76N}q^x9kcE>*HmAAf4 z3PFjG=W%xM@IQDgK4O}#^=fQAb|}@Y${wjaca(aq@GTv)&&YpgO$)^x{qV2$To{;IR05%Hqe2uLp^1_ zS7e|n1^baqZsyfm4d*hzb}(;`PRKn2wzRCZ{!>Smwh=v|1ur-^QwnyFFg>7wJb%!Et)X~&% zy7r=3-|SXqXLAI$zORDab6V2EP1&(0yG64V41?+D>~#;(N>VU%BrSlD!ohcX~eQ^D-Btxu{I(#4kY=Yi}ud zWFGCzB5=ITLl(?L+awLp2J9lWFstw-&CmW*RmBU~xeXUqgcyrsW%BTZo2SpnEl!sN z$=b95avwja{MPEORLzJZB1+A6v1-B=2_8lr=yf%P2@~ZelYRxu;R*O=%_e#bGsrE) z1}L~UzvcGepXb&YcldxV_P|dohS2!%{vM>4r(AtDIhF2g_N^~G_574ptheP6{_OPe zjCOe=^?B+$@-&5DLzrKDIcdJ%CEe=%rt~sU-A^w*p=hFOq`Ha=6nwd9Wl`Z;5F^H*Z#N*C}n&SDxeM zj=Oj~1dU%uS)V=`0tf)YV#4Nrdj*L&5c6YDgp)kLS1oQgYRDVumQgfqF<0NIcd!+= zbE*7O@ar8=hDA-_T7Ak+eyuM0!Jr(LRuT19eMPv$q!Ctpy$uWP9+v--xsR`~VzlUTFjgj3 zf1*K?+bQHI;H{?~Ye?cQ0S#)*#)k{G)R4=aUhqc&NVtNNDSlVW0o4wGIsf=~qHp7z zHOEZPlXr;G<>PN@Nh1ILjq)Mv5q|f|v|2jZ2$x{)J!W&1!r5v?)j$nhp-ugU!N^L= zv$h2Hy1)&~!{bO~AE{t>jl=*0U#;n+?UnNP-Ed{m&>L;pEwy~-Q#o4)(mi3aDN`p; zsP2&~0oam3)aOFe7sP-xC@sj187Ec4VdRw}dHE0`yS9kj<}I#mE`|oYM`s6BJriR8 zrV!}+j6#|>c@N^egQ~^)P_z7ST_TTq^w-l!)l(v0Sw?Ye(?OPR4*5+)e&B51HUw8l zJBp%)`TPVF2v&d9I*d&>%kYisg=r$KVeIEq47NrKhBOEbgHDDLHKena7=6)3V? zKTcOWpPUs~b!_{cJ6ff` zxRxsb$zY<(k(}A5WKBWaZfgHNxP+R%&JK)}3~{2J`R`imr^vhk>gH3KCGpKGCJS(T zV1bE;SMHvvG^_rf@~GLC_o_iD%wK{=4M3R#$fR5zXY2R_daw6(zTrz)B|$tUZ!QCL z!oA1*F1t|D$W>7&7(fu;$a$@Oq{paBNV?|rRIL*##HjCM&`9i!p?`gtqKSyuHP4@G zXJ7@7kWMHNhNVjrSQ>buTQS9L{riYh*#V0w{$drpHV+{`)JUx}(TB3H!5XgMgZ-jH23^FJfnv zwe~V;phAi7{%mT>Cz5I@Le5Lj_`R)P&A5AhDbdTD)^N#8kQdt$pG&a%wK*g8O5n_U z+U?qt$U9`2ZFqDj%gkOQC<)GTw_Q;_{6S>S1i?YY1_p?rX?)qfYfdD3&(Ri@BVr zvDoYY*7fuM4%7T!xYiRgCM`Cnqy*(!C533JimgDsR*F#J*8jN6Y?~~Z$!{hSNVU3A zhL4B1RfeXBA$8z6=32{Es-(Z`)bdKh_#@ngN%jRKFqFR}e{tK6>07hQf+}Jz> z(WW{7^E>pAy)2=gMgBj?XkDI6r?-p@g>aiN#N5r%!-LNYF~lHBIIV)v{PI7LU1T-X zTjav|Vtw}{E4GMMxUF>?`toVQ>1K$p>mgaOa*tox`~QIoNh6pH+fmu^l^Yuy3(XFB zt7uFCJ>Hr!pSMm9*~Gw~pMX<*1^A0!{%8IA=b?A--{a>;spg$B2(bv zgk}qZgX-TZLa#6SLa_JZ(-ZSzS%Fq7!4#;&5W|kXfkR={lCFL|3zz>|DK162f29Gv zjR(H+cR8e%)G$hCmrIo&Kz59if1zGR`Ce&B)6KiDs>fdv@^`hWR5>r*#>a+|=9Y{^j?&~qWX|+{%dVVgZ59!ky1f$TpX=%-m|&?2A#txo@LvxO>Q<=%9ZAiGtK9@ zF@?1K2U3j}SrGXzR69GR$RAMt7yEjWS*QOei2Hw;!~Z|@|CI(tc<|?-HK6{BEeofM z&)j%y-ZTu(xQ9$q_06=jr*TQsKgi}l@u)Gd=K>@MJsYQwE6NtvfGF8%tQqB_oc&#k zvy)AO1+P{{ku<@2e1#0HsqgIv2v7g+=U%>7V`Ar^z~n^sf51!uvY0Wkg~E2WWWPCN zDz7Xdp%iHtO4z$tv#!<(u{)7R@pnrEmdC~#m~>zbq*S-mR_NH zSRt?UN`@;9Xv@BH4qD2TY(%$`joXmV5S&84i&@I_35&(FTX?atsx&Zf^l>?akiYKn z*`|7lXSW6fsUiP(GT*?38_Pag=0wKQrF{K`#tfmn4lIXO6<#AerTu zKXGEQa3-AYm@@jwW%WfQ3Q(WrO0!Vt8Vr-B@rJh+`~A=Uu)?|Jmx(DuGPj)m?{}W0s zW(@fyGEtbu95ZI`=%KkLcTqh&PGw;WAV<*N8?b&M{d06$ zx+j9_!)#DpKF~Xe4>nuw*Bt&`{WaaX*j;`OzOe%pGqY}d`9hG%p{sz)zSE~4v2(L4 z#dBK$0tTzb7_6t&Qi_R)kyY3_9;FDw{O~t>SJ4)(d-oQ~w1aFyXema0$<$pQ`!FtV zlJ&gpvK_doxR^X-e{*7x#+7z8$H5`9^5ATRx=H7@5QP2~JBOb3tFDR!ER!%e zf!|u`YBM;OQ+1BT=s6zwVquNgBU2!9CcaK!Mq8brXiL6yA5V=cix@jBcvps@?`p3$ zps$%_$>oNO-Y8|(YXMr93fv(dOKYDr{@h*`*IL??d~LF_AM92&&Qfi()}{kUO7 zNud2u`d5wR?^1)HLkWWcd@Y2ucd62+uA@5mbBTzn&flMIx3gdRf`d8*XEp3lA+UU) z$@CI|CEcl`6T>^qEzxqZxT!{EPXhe!Cw-^D()Yx2?&51q{aIUq>}PjNEQkCMthQ$3 z+fvp2{j?wi2oM?LH0KabVUUuAFi_{584tL{b=bTSnN#RlVQTx15wun5(tEn#{zjeJ zCcXXUv+yj4u65ddv!8vQeh{y-vVHG!D}N@PT0P)9us-n-4wGTvba5uVLzliHBlkZU- z+tXC?d$iYTnRTsV8a+9+sMSRavLq)v>z-BFfZp+`kaDB#Ii4kJ@@o`Icmg>s%VXI` zckW5J%O$yU_`iBm5*x>C>L#&8RS z8z7$lldToIkd+$Aa^JO_t#tnU`62lM-{gVS7B_W3m3)~ZC%yqm`(@57=QoP5?*8B3 zzhm1UVnT520UV_vENQ9H~wL~vzK2_(yfE%m|Mx*TJ^=;%h6*;_HoD%F=J7M4ZY2} zxT`Ch_(+nbT%mCr)W9dRqJ}`ApI2+)mg=vGFtqG;Hd{I#_WZF-O9Mh)?`(AYf#))x2RZMt zkd|;8S?m!E1Jvq=A*fje&iDZa_O(QLnCzYZ^om#$tF{sGd%RLzUSyL@uNFStxT(oM zJ?TB2PIz|!GhyG#nZucq? z5dBaFx^qVyr;?rEJgXZ#$nCI{)U~nmhrgS7L%z|Md+bEG0n-Q&bYLpp{CM}Q)2=$nLb69DoQG( zC7Go}0tL0GqC`Psk9KX9aO}XR>Q1G1?=W*fX6mts-!$V=4wEhR5p zOyWda?&5mXB{NL&WTYD0%uom;`qsj=Y~m>l^h~xv4?c=;!+8&1oKpvWI)`aJAD&+~ z@m2`5Y4>B#trgGpjn2b`iwM9K$gSk;PEvA`Q_4bsUEAo^jVh)^Og}`E{ko8!Ox+>P z_VIvxgks{0lFjZ45mvcqXE>QBpW(wXhhN5lY8_(b%Fn88*l6qx;LX5CcdSb$tk6-^mkRNUeswla-aWs+T`Sr@H2a>rb+h!nEv`Z;_hsUTF8(K8CV3S#9L2{eCod6ZwP& zK^gAlZ@QtDjNcNjI2~N^Bp{1G)4{DN?!!i`CgCvJ464XoHsWN8#bA4=?fKe)oTts3+(L%!k@zsja+^<{H4FxjVtPysxt!iQ5^tt!8F40R^ z)?hR~$7vFlymA~73&W)MWaTB?Z9*?wqPxac?RT?(T zd~e4nNxH#Cr$2y{acgJ555Tr|qteSSr9Lf37Gica?xl_0qh*2~TWK37s+TREbgGJZ zk1mcd4QK`}Ut+P4Id#vqy!ZrvJbv3Urc8 zbv-<4+u)R`)+7tR8sn>BXqS{kR^dihSSRFEvDYFPgJ6v#a0WG49=s{t+9HUae8Hkr z-<%a^_Bo&y^eX|el4V2dC2D4W6urwQ65@gXr@~BfnPY3^>Bxyqfwn1dBKtUNJz=re zqtctZ4tR85R>ZQCy7v1sst!(~$2*ufq;$u+6jE6Xl)TzqGBnpTKmVzaNOy>!GyKun~W^mB3f`bsn3L zLw6Npij(g#cahVd#s~KMI_^WXzm;1eY`MYrb1ofB^o$&xBmqw+Y;(HBn^+sfzHrZG z4|Z5s7BD6+lR4T?(YBp> zk>W)1a9lDx(WeXIBwI3v8t9%v@MN6|Q?Q$dHs7`b9RJPgB`%)jD3@;4!o?CR*_HCA z2qy_k{Hy2Oa)D5!5s(+-!|CbQ9hAhAiLl?-_Y`T&8H$pwWFo2nyTP;F%f^a7YPv;( zVi9%9F`c=O}3kC)|!ChWT~%+S~4*&8-8 zf63^!yZ!cmL>;;3ER;tIv)kQjXLl#Y5X^6%SI9UmvqPK>)ih+KQxw``uC)dl#XSS_= zyIUCdA$!5(9c^8>k15Z*vc>?r4J$nl?1bWoi z%{JP|KkiTeo*S7#sIe)HP)B|N9UeQXf3)rAyyae12NgaH z4>DTNf`MNwdF1#ScEJe#oOWK%(9B*AJqib*xKZ}iNC&nA(l>I$O*75{dSYJz0<51d z5%Z|N2Awdmnxj|MqkC}U#k)hXv^VotFVa5nZkAL5lbZ#;F>m~-sN((7Cb6?jp8jpt zUh{S-R}aAcP{XFF7Ezu0qF&&2=d`^4R)%zn`8Edql|ig#Sla>>2##qXK8uoXUh&C4E0o!jr)9uvx6|& zt@$+)(^;VD?=Wd#TZD)IQZ$3w#0mI7=`)4K^qaH4<>gVyQ(UlTs$c)Z_~;xgXfQ&` zPi|Cgy>w)-aFL*nCSm;knlT~ajtC9i%rxJewjCymk)2xb0fQ3+q7_#0Qn>?sc6z2w zHiOko|C0qLXeE1o-6-lvFL90p)PBXRWs#Ef`KnD6pW))2K?{YCujk(8;cPkQ@Y#cp zv^(ZZ;_>Y!ka%8d0#J)D8}%7-6xP9eIBY#-H<>KFhhyYfuVtjw!RpOrxS}%X+-}j7 zhIBleO#I>!U@qBvAeZ6bBxyaj3&wZwz)?3sNuCEq#Enom*V>EDWiUU7NrFZ5+ly1{ zSKvHz#nSU365USoOw`+3H?fbYk$%=)qiffA84u0xj+qzaz%Nw;W%dcTRGPgSy1vB_ zeEZzH!><>-#zde|lp7$=l{Dbq!=6FHo0oTmR0h@Wy>^E_!3E z`<=yE=^+#iQUb2j=ej!H#*d*RY4KQc&cVXOQn637T#D{CF!{3Z2yW47Wg#%n`1*sN z$-ZysG-=DRov6~Ig)m1~|OUwD0)`m6zE_nD5}x3_qy-Ml~dt-u}@*Z=|Xnz6Z_`LdE4aM1;Tu+Yu$>_31~ZtI!$_X zm7jLy#%Ut|mYN#4@LhE(PT#_!I)`8`W`vMmhsP6rm~~h?y)br7yEfea8&j-C5y+K# z$t_muIu=-2Xq{ zR@8^vE|RrpB(01r4y_Jb(T_KTUJ=q09Ddbpe6tTNS(S&e3F%YWEcSaC6u>vhM?_TK zp1ujTQ2y*!LaRFf+}>QiKleOVJJ`D^8A72s_Rf@^KOvEXk14L3jRd|q3snQ+cEy-HgUongj{eQS(PP|_wWt9 zqc+A-xpJj)*&%a1$`F@OlMWHj+xpe;sUEYN?50~c1>Zj@NcETEI`eNEDWUw$r-g!J zT4QG;Yf-phJC>Mv>a`fVMGB(t?jLQ^cVcw^I~|=5id$MxgKBEc3X;eEW1+7Tl+XFpv%vs!k3{sB63m=Em9kGS&?HOOdiqZ>p`te*sI}&D?uS zDSSoNPqntt8?b`A&Mk{h2p}0czSrBrN16(5(pyQ@IYwsJl$sFu>N`7(D=HqU91K0Y zhT0c=NWv4fH;Q?pkYKh98KMJSlg!@R4Ki>6^D;|B^vZZ?N44^5Pk&UB8Dhh-uBwh} zp}~dO@A2Be_i9uvZA^s?Ti)$L|EsyS-=7~PZOW;^{XXd3ubl|}{=h}*(?>PM%4mZ1 zEUs)Z`OVY2s;q12fusOTCthIvxQTzQT!{pxgKo{vnSh7LSpqCkFvC)^^5|1^$~SZnrKc!=B#PZ)>dyB9iRD zMJvDUI<3sBy$fyEcIt6Sor+R4i>M>mzEPU8>(QX0F-Ke%J=iaV#F)e6AD@?0*E$N- zRL(mzH7GLsQ9QaHnr*B)BYl8+|pjkV&~oIUJ{!WuM|3{snNiSm+^KAO(P z4y1kF@j=3sU$Xwod~Z%7E7g{~9<1Q-cKswaR*!e%t3|m|v6#Hvf90iK?I>Hr9Cc=D zStqDpyan4R`}7)NNokt2QAStBX?)SK zzGqhkCo08llv`DZhMP)HZD-u#w$w|>lBDbt#g|G{Re2U@Txf^sL24pF8uAW$iC%w= zxFn>rIYvpJ?Lh4_>4ZE$leVmr>(RhKU;cf@bo%YCEqBAE0s0Exc{ux+LfEUTPyN;* zU)CH1y`_I6*D5SL4sK&Le=PBrKLyI*8vx6`LYN)`Kn_@mHp!M3_{M{Ws5>a!QWX}D z9nr3E59Q=pZYtIv!BI};4nNV*FgiZ@6F6yF+m;&j-exsDh`vOnf0v`@PV^VAC5 zPhW2~IJ9>wfg_=IKTqe0MUZhFl|(}stTbCUez{6NY(b2AGk9i7OzK*S|1y)RxzHiJ zx-aymbbbAzu02I~3Rbo7=gZph8xX%#d|kTgPJemYG}k`38*Dr=N_!LT?6lg5c4tS`_rr0d6u^G2Msg7h8I{pMjS#QgG9dPU;VkY)?Tywpp1*2 zacLEC*6xoTub#HBI2c{fb&DuZ3)~;wrrD$ojG8z^dOdDD@gko1j_goA8 z1Rq7jA4$q?mP@h+*bc2ehlr3FlNW1hc9AQxe4IdJ@f^e{N?9tpmS3Wi;E;@x2Q%S; zMe1V5X2}!tZ$#xpht$L1o=(66nY}TxTS=pSEVkqKHyh)XBQq9>M5S(CXCAdxHU}`E zjwkmQ0IS_}`80=z_;H=6Q49UqQ}vhS-fg7p8#Qa8@Qxe4%t6V{Q)=qAEm(f4t!(@` zvsyjJct&G6Ie|S^^t@5!&~o6$CRENN2YPt! zow_lcMjgd90xH2L4>xt0r*KH+)ad^RNN&F5m+S$aVxmI6p)$hb8 z85LBSWNCF7EGw};A;n#&4UZ%H+dZ=w`DBT%daGTVTdzA6f+vl(8d_M!XAXo`V;;-& z!sDhtKy+RS($;|9ADHPT(67FM$^MgiXi=fV5+%w#u49`cPS`9B=ij8Zoaf1!qk7@AtiAER>M~>a)WF41 zHwQ(@$MEVE^@#SS)6^CcS$`jbEr!LT6h!d|6G23rv~g)Xx5U+6*sd03ek9NCljgNmw9=(<2uITg^oY9bXCB zY2XRbHnc|^HY;Z9-O{fvesR8(qV!@~1z$6){(fP#)2EKAJL*R%X0IROaB>(BT7HdX zSP=q0pGFahq9mO;f}@Y$TdwkNlib7G6!~-PzyE`|Gr%>%#{aDvAgq7*tTAKgXh;dI z8N{{r!DZLs{U%=Gy|%G4%Cu>5#Sb~}{4T%8`xORSwb7a_b) z5+0tw2usZ`iKKS?&3MO*Wxr_P^(U3;C|-Y=Q#}2~ZCI`)z`iql1^LvNv3AVVGpzP6 zZWOZaW&IaBCAlUH?$m;zQBj8dzq)fj+ojv%2$5hvK*_b{P0h}pkB@YK=JQA}nq}sn z@|OLA+r1gpqm_%eR>eodIzpj1Su?ouV?104BpA4k;b}iB4Xx8D*CM+=&)7t?+HN6H z30INP;$w#taFU)!@sVISKxN-2DSJ^F^(Am;?-H%jHni7aF~uEs*K4xu*j2ffERaCX z=cfrLSW2&v2TRPal<`f%fj|4Ca-6Yg5bR@#OAXluVdM3Q%LABHH+Z5Al5V#j$Em)i z2?TWS4e@^4PfiT@C96c2C1`Ox)Sd$ko*#8NGbN>tW(J?hI!St)qoLh?dfa;@B7N+# zy1GqrnwKfUS-uol!|NdSu$1&HSdS|@gO^5CbZ(s7`SDDh$t0l`G=1|BSvR{s{5>0PzJ zoGw?#WNex|aloY6Z>TR@w3`!#wl%I{)1H8@yT(EAQqTTjRL3ssw%z21o?2ESX{Xfl z{s!9O(?b%(5t?U}!>7#m6p21}KPzUUwIPycXVL4RQ+_t{N2^{o89zYTus0U`9- zd+bzRa}ZaPw)!GUV(?Gw&Hgn${$O&EXwfoox)cViM!5a)^4nG)- z0B_HBW693$_jKBC=%;EfXOxLjy7Y;1dp2icdvC872`q&y(G3?>dhKhd0-h)nw+E{~ z4^PXT6wVLLe1_Tv^P{{72}#r5mJ?^kwBn9~Rt&wiEH7M4&M>9J49%S2S7DB)ZTLgo z!5-25nRr>4@61|;AbzhaqRnq^*b{Oq_0@b9g#MCMpnHLT$aV!f0Thjs0+hot{{Hg(e=&1P(f?_7 zkdoRqCM*4?ZIOULfD9e-*O@#CUTCM_Q;2$!_+XR&YG(ZZ>QI@dwmIJ73Y$c|-(lR1 z-2w~5N=Ql^hiSR-V-tb~iNK0W9BGPI6)z|N1d(cyDxLzgUgu3yKXR1*)7J}?E<=aV zi{IEn&M#(K}l!$ZcGX-P8Rtus$MHFti-K z`%d`l>8QB7Ym#8-lZKzS!uC*pMzfBQoRo1$)=Yw>WX|BCPJyL%Im`L4b~Tb0 zSaog=w^8Eg0)5d}B*HD0UFO~}K#W8Gdm5}3R7iU;%KF@>EI>Av(ZK0r;o(*e~8Ku^HGEy{%_h3-6_T7U{4 zo!3v6@VQp$WTLTAvcxS=X81(&V2O(&(wKv&L+1y!q-wd~HLPzdp&Uc_dRV*6*ns=Z z9*^)-BZb?ixnd$-L0KtR>S@8IkC0tf^9O^c4aN2w4}{UNs}D6A0Y$)P{CSXBsNYet z){gaAwh!;*q0p?N=~@IpPD*N?R#krQh@j(H09A%uj1JWXQa=DgcYhOXpkBxTP621t45^I z;5R6x=;nzVoLxhuE7}p0Ez16GBXyd2KcVP^l38|}`RzH)BaWi@+9YrOs=QECy?7Q@ zbQ*q`(Un%~y>>~qv$v-Vulfr2$Tq2k`+k6^uXOgF=}v4QVtYK5p~zoC$l zJ&j>SVFk-J$u3gdL;Il++-id|)W`d?4A;SF)-cm-RT4VyK_G2`U+Ad^yGp-`qSbwx z>RYrUY1l`%Xhf5;HvxXkQJCMczSFl;fv+|*_(So8GlYE6sWxcb2Qmd|*CE&4|ne32Xf2??03wrV^c$CqU zu-eewZF~KJB30#HZQQ>*vK6^jh_anjD@XU=xiCLkXeTEpKj6hxOZZ-YEYvl-LM_x_ zr}fPpchUFy!q(=|dK#pZ9_9bk0|$qVcd?i~gec;(B?Wu9(5pOp4>4J8Qx?b4`4q(f zbO|32VL8fDgthxTFISMsiV4451XzHC93cqh%`7Iv4m0Jp0D(BMK&vgG?s4h#?}b#^ zV5aQmk$mn_T-pAjUmUF_1eC}B$ zdQ#eV&|cR(!FtSrN3Px1cXh^CGm1SvoId~yKEOE*HCOH{nU3GiR7~n#7K=~49+bX( zZ^oL4?IMep&CJj~5^$T4d>bVTf8{flB!4d1Ehk3whNeFjx8&@m`FP=H0*1l%+mRGe zR0+4YlDhDhFD{`F&&O#o$9HSK-7_+}tfvjdZ@6ml(bu44CsgYdu~qEX(v zXE6`}T)8zU>w|6su7%b^1Y*#Q>G+cW^*e~S7@O@AYnIrvtN_5LG5;o=u9`;ypS?c@ zxDuqDgpj47Jp`*fu*ffrqPT68Fw+iijR}JY$FEwHsr9H8IZpaK&cTup$E(Hki~H@3 z1D*x0Eq~7@MHIJYnBtLol>>Fi$vXS(^$OqFWCP`op3Dl8TRQ%CI9X%Y?UIWx>=-D! z#zX!@FC_-li2268_Gjx~1^76ATk}4;yHjuVQi=QcXh^mYf}yxW#aBiVoHIc;fPJDg zZ!h+y!7%*H$343@S6OvlF!}>)iBNsXMxSKMX_N1;ZJz^uibMN-2fFqgXKi>KGU1p0c zl9hr%z!n9o~m9aQ=kxL%08FDm%3qvn$hWqD9 z+oU1Khp#f!E0k@maYcPO8_5}Ys3`K#;* zv}kLOXsbAKnY{5Kk@lTP7tWSAAp=T6F;LKB;57Mb4|^#yk6;<7M1eTFc{9BT8*nvx zhXwytnRxmD7N8`;(^?;!==cuDs6tu2AIr~@`_g2Y#t|K|`hXV3^ZLN>%c;ICeADG< zPN;MLWuy$>{~_-!gW8H3w%r<5ptxIsQrrp@cXuZ^#ogVDySr;}cY>AT?(R--mtbG| zyzl$XIWuSGn>lm-onM<_k~K+Yubr&5@9Vmw`f~?kw{NLsID?R-u{TRJocX+q!EW~I zhP{=~IQs{YeJy^xll>Ety2Yb`-Vdfj7TOA0x3o)5$*Tshy;@x)DSDR6QGKDW)>Er1 z2;1<~!)^YDx7Rh>p&Wb_ET=oub$992T`Uf5Q9ZN7itx;1T2i!^0|5P=^aKg|r`sQ+ z3%7tCqL!WhXeAJf)Ds2P!0RJgd9*3kd3}|j?v?Fs-}&Dk_0|eP8rjqx`QbBF?cOP` zeg!6~Ty)Ln)-9(+RiRFdlCJ&|^6b%gk#et^kL*#U2Q|)fUWBJlbqzXl89+l(Xe!hR z*M}VTr`k+TVwC|()t@6|)7)l#ZuJB_uFvYrkIv=aGsK6`AS8U;5zF=~^G`bqp~>6+;pZ>5ZX? zjljMx>u#WsZ3_x+%;g$+;SONQm2!S;fFFCH#QT6n%(cjkq($CCa+%VY#hk)?j)0+K z;Fs6L_r8@vft=qRBVE1Y9JlHEs!JPn>M_+Qf89svahHDJa)Ar-{b@Ps_5GHvk~4Sc zfClF=N}6pIg>04wK_6aV2sdtU=1Ho(y4pNw8|TYtThBF}Y>tuHUx<4d+;AU{oB>9^ z5pB+b=e0oOmm))tL%Q)=i~fe4R-$d%tfeI6<&f2G_6scJ& zy2(GPUB3zw0r=1=VuXteNH}F+n~y|l`0moHgnf#XCY95{Jh)0nO!3zwdR2W(dE5Bv zR3ysBJ!ic)-D5y=`CpIR5q45sUGV+M0YJ-NI3karp#wr$MTU68CjGgxQ;E?Z@}|Sg zE61y3?VbGy9k#^&>(kBys$Bdgnc9&XYMJp$rl>;V8`@s0S|iu$$}>AEC7PgipV_99S1D)`rqW4z&GLp-e3*Y?chNs8Uvu<)C+#-xT8&UNf zcCe8Z*v9_qxAEnT92xOq{k*yRe!|yIYe4(A_$8A7OR6uYdVssvoeG%2(Ey zDVQ?kzNpXuGDd=BLlLa`F0LD`O?^1!5tM&g6Jn=zAAdUo-2fbN{nCew{BhGy$X(Mr z4w2^rK3Q+aH>K(3w9uuQko**QNMS@{YL!5Nu)^_h4)S~!UsM7t^0RQpPx;Q0o6PqB=M^nwy6 znxy{VCmDi;&$_kTy9cSw#n|1n6_jT!9V9Yatt*$eSEk~-$u9ABPN!1f7aF=XPr+Ah z{tGl7uDXw84h6NQ*HUy#&hS(2g7AoCR1$IXmd&XX2)z>ZbNiV+*yh;=oyYP<<;oA; zrbmQ4+$C&(KO5}1Gp^L3h_h&;O01DxG=<)3;m0AQuBFJ`@5UY7s1GTY65p059e;#8OmQqsjvue zKL=-QC4c1VFNCEs=S3xcFCV~V0O}PGAIRyc4X9L1mh(bZ?_-^wgM0X8mtYNYPGp_^ zid}~wrfftJrS<)WMus@M*~?_-3(n#RyA5tTiBHUV0gVl4kuEIXx5aiOtrlyDxZ|%2 zUzpy_e7_5{8C-MAO@Kppt&W{uu-B&hEKsh`!dw>QK51)E{g^no@gfgnKKJnq<7^<{ zCB29IQNbS6vO5j0@8dp{KR7m;+*#@>Kc za>}tSHBpWP09{L0fF#oGSCNx0{BO&4aQoL}MnWQS{!qLC|6Q;}4smVz*+th8g)$iv zBlVbKaGu%+XOOOY5n*zS){K3klTnZtA^n;Mp}EOW@8T}@DE_kcFk@(Y7;WZmh7mDS zq}wOQ{#!BH1x&(}39O=@g0P0eqts@58h6W{g9SSP8clg%okKBpL#Fb+q1(0F;8^tFfocAF3;l3KfCv10ZZ++z~=+ zFtkx;Rx9^DuL5CVj*m}>HVxy4*IOk8W$5YpXeh5=QhZZ) z!SVWRfSx^Glg%4Ve2EyTlQB|VP1uI$otzo#d)xTr`m3(X3A&vb#MreK9Gr001Me#j zr18!p#>w~XjqrW`O>Y7$@|V7U+m2c9Km`NU+Sm`{l3TDgs@*>4d`s6f@+BI{Aqh^N zE?-S`W%>@HIBl}^p~Dn6{P&Qj9FiQ&(}{# zsQ3I+EsL7^(R^X*pTWxO-ka@ilxQXEOj%q#|*+t;%hT5B`cal^i%hqsEl`a!jSdq zixz8{DuR7W)Ziw z){U1Nj}23H-<9qDPN4?4<6&L7M-=i?en8NS)$!+d?$iGEbG6|Czc8QF#53UL_02Y* z_BryDw5_}Hy;mDj-vdG6yX)TShr9FolHBQ#;Rc;L)aEM;Ixg*Tb{h3Aq3WN9t_z=T zT=-+yNZta;VYXS6mw$Y9d`o#SImI&G-riu50JCCe?7xP31MhTt94Q*PPxy1D&DT6M z*;;P9YsBI5EJuH|zpRiN7kZs$>oGgd59OK;qu(LfP~?%io>GALWH(A!F^@;_`Y zc=tVxCa%+20^y~W(+*R#k2q4y0w%qdts;?Wyem>v6~lDE)0R08b--zi4;3^a72rNHF)jlzF0(ps;;uYn_$fv?p3-IfiP;-EPm3vh)KJAMG&JbhqEK9LmhONV2c3w2ByC*22_s`+bwP zcWE)4f+_JBcwgw{?;*7CQ#b^!=vPe$nw*B`<;npqTCs_=%)&+8Kr@Aw)I9Anz@Hwh zRI}HDlgOI+ZS34OlSNuyiasMGwz@qj>}IJo4m2I_aG){7MI}|NXAk}Ldi`7JxFBWD zxbC@fdUWDFFlFP)4L#BL$mx}w@WxjrTaE6ido}}TOYG>;b zy_&ag>CYE^Pf8DfZ)^{S-8|Z%+|`jPIsl4eJC+eb?T`7aI-jnZ0IrO*Aa^~HFaaHd zmIj!KM2r%|I9im=8i+EozpbLKy4i11*NN^H0cr)nK z;;)7|Nk0%N$>XEa^jx^VYB|3NXy4<#mdjmWN7BbK(+2 z1ddj_JkeWY+-bXgiHhgCNp^T-q-_>zkwFH z3>>DX1MxeW@hblY0JkBqA`KHYp6xJqf*$nq z(-D?=aA(%@-b<51mT@k_;m^u$5Fs*;ri)0+(pkC0>t$4*A1F71)8E^{+E4vNlX8Bk zw*mPXjnH5jmKgq+80Ng8W3g`Hs>N}9Imr0{i39tATmT}9!4%DiQ}OvSfwy*4 zOU>MmSS%+vfT3*ZOR?=Vf$&FUj%LF+(Oia>Q@(KAC>FBxz;Z(xvL9h@@omTWm>eZ!<=Q18XbU=jx`ZTj_X>l3nYyw|Dwn)a$#;np57} zfp@eGB>r|I!^M?NO5YrBg>KeEvo4@QxN2?7%DKyolDQ|18%}K z^$N_KO>LWIbtE+Pe0_=b6xmQh)|CB7Ch`t6PR3#>?>CZU%++Z`GHNrDm~T|$iFg0? z@_2oii%|JzHz56(dPE_$%Y``CZx+wz=QF}-LR)|4R-3j zXk$D}2cACBmLbqaFM9&D;YNr2O)a>A@k4Nf$n18^p7%oTQpAyp0skt+X-NErQgWpc ze=61c@IfltW18TA*ZpHAb)v3@X=hZtbCpI=7x?-kPKNYKiB*6yo<4iQ*qGvUUHMEY z_*-FP)-`9J(}nyqV%Iqh!mR89OiaFdg`RxLVQ`tf*k?`7c&rtW%L6LiSH_ro-c2#Dx%uMouLqghNA|$Ut zMq}FD>U+Zr(ljJ=M;Pv&YUYyS!@=}%ZqmGdWzq{Uq5r)1U4gk~t$aGE+cf1gXWh|( z(1K4J^B-sc#$C1Xy&y0Pc`8<$;5InjvWwRQc{I#WQ{(4(A>5X&rucP5DjxLDU$NtY zWb}`iIRQnawi0`OklXPe;u>F0*{rhWZOER{@;lp|jGG{3JePw^eN^lEZdD~JjTHC$ zp{&HcfBOt4x5soRz1~P)B>{4aXR@Z7dtapHwh#B;LQ>j9{-U^t^4}2JxR;YGcdn46 z^Q&z(qykOlSDD*S#@;bf&!qWoceOnE@=k4cO>8}VV^gj?_M2iStm@a->O4BpS_6|W z=1?a8{b=3a6^Yl3BCKNeSo}`0?@6ZYF{_0mQ@RwQxhqN{U|u1xJ&@m z3#LeLCz(yL0bKy2HJlSX+osj1U}j91c%CiQU!BC$v#E-(Oi2#Ueur!*r2Exk&-gyF4`^e>Tzlg87E?``d1v?Nr(w$3(P>GGvxIuH>s`oIxJYthy72-M!;@Xn-uPXOKF~fewVt35n%1(Ibp;JlBhj%4>x_(eg+zs zQQ(Z90`$_T7GMr`9Xa&&)v+81}nn_2dM!ORIM=L(Okm&`sT6ruO&p zYx-N+YpaKg5RLVcvYI<)fO}Ci)Gv~PY4Pir+eOjto3wDI)2zwtS)&ViB49@`hmCHf z3-2%Xw6EpSXxDGLQe9kuH&iP#0o120V0p5FWSg5b#7jA$U=aP4)4Ey5-re@?<*l+! zrlwxV`KY0B$KDh!l9+?hz=@!Qs@#+gvKfhaFnTj? zWpuri@qBtsU_Oo$x3lbGVlyNTf5-m_lUavu#{+@-rxqW>33eT2xueOan=WlurN()V z3zl=sN8B@$s=i5mCGjh=?!AJ^lQm>-(dG#JZ-J?Im_ddtpW2KzrAE;z zmM}shuUwK66|1S&mRsE%Uo^gf(+d_t+b$D6QfhM9rC|GMlS8G78B!hn~Nyz^wK< zafU9DW(PIgwNaeHsn8*tdx|z&d!p8xEwXw}GwzO)M@)>cmJ6lw3`?6#Z73+MzyA)@%)e7KFF2w^=r?#Cq6#bY5 zSjLqSrv@5aPj+UStD*L;mwK#vMD|Co9x*ST-mAqJ$v`%4j;i~zzE=^@f5e4ZD3z0@ zXtAfl7)tMn#Pwwc8PQ%2XYM9SysLaZs(X3&xE%K5m%mL{^*<<7oE2L4Z z*P5n<_qLka?>hbN(?@kbVv;N6-#Wsld)fH(@x?o-B60(@{r>M+{Oc-kYh%kI%L@k( zm{{hLkztQ1%|_Ao{Ys%MQ54|zvSSM2*FkCs{so|2mnC zgYO7GfXmTm&nr(9#+vA5d^qHP*zLK$*lXrD7Rs)oG|9@edZIOfgi_mz=fvF=I#8M=0-g0~2!GA+>dsA}{2QjEx^ z^wk%?_(vnW?ecrrX6(=l_RZC_4vLA&JAw#=Zq42*ZxWLBH{$)VCuG``%D?L~L&jwX zO90YUXrM@M-4o-ydO4;b&ChJv^Ya$^RkY`DlFt;*-3AB6k>8?{;?Py}twzJG#t zP?x?c+>^f?apqUQe&44>DZ* znG2tWqEzILwVrFX8Wq8O*W$lJ6uro1R#TIEkK*bFJ$r6~f9 zstOYUL%9So3~VExG7_zSRsCeyD?&HZDQ=yvqdqQ9j0eYgf|@=^J}H+KrmUkFPoU)= zRhR5DexRChngeIkvrx&5tAv-G?04b$#N3*`5d}EtFuB1wFLlz>4gEV!yD{Y+~i z0?y88i}GP(*bz163ywRRcwrKDqop{NkZ_`Rf{zO$LmD8+TEQnQwMbw%@mxJnG{-k= zuXLDnvcg>p{6^SINxjtdS8Qyu4%U^zaXc%fDTGQ8MYR08jYI^SDlodIHbT@ce!tq1 zDCn;LTPD8-Ix5W2+=ZdNf&9?*mH*TL0UPZO#^=0BCs*kiLQTIpy|>?Uc$#MUpj_as z+gN1$67?84*k8MHvebUW!Df?Hc%WaC!%dChmSV2cJOsa7( zR)SX5Zgzl}?%TKF0dcn$Pb2SlGzE;fu4NR8{f~xcw|@p=npT)&A7e#Qs6WGcnR7yNX-rY>Cv=Ky=5W ziQU2VG>u)!w3VbH$5J}G5|FLebZ6yh+@7#4`Y4uWx-2W~&IVIOe+xogM3Sx0#o`NHjA&!QPe?3A)9tC%0r`CGVtAZHmL_UD;leh{8ixc1KM|I)UYnu&m_Po|Vl>DgLCxIUp|pvgz5J{?c=P5)*8~mXB<+1)pw5 z>9JzRBIJ4ne<%6g%g?@?+bCGt)dfiVTRQBO*)BCo_*x6Dtk2v~y;-<(Xx!;Lh|TtG2;qZaKML zguEBtQ*%uCVnctB=HkiHsDqrOu?bxn1R28(LdT zuJrQ^(XuN@dcBlwcdgfcv>gX0Lx!t`X42T>xSx*y^9fVCI0I3aD(1fW>Vlc z@J$ICn@H7P3k#*`B(ZNgbjn3%yC$vOLbVgaMOj~+@D~x@i%KrmuOtsportrdr~ID3 zKyHvBky3TxMUTiSWyrarYg59~^{O6F^;mECQDiDRGlqYu1PWKCEJ;@9yw(NLw6GPS zU#6=_GcKX1BFBmfw`Q%Y?kJl<|#VarmAvR zF~1o8lJ1R2>8E0;zM@u?lu2Q+;odM%{d!_!vDMl!Dfqk-(jaquwGa+HGq;Qfx_ z244D?E@VoUIf2D$>a*)H`@x<@&8PWtPLI_qs(qf^ZUl7)-x9`r0SbkmRb!pJL%M~?@- zkx$-7$C)iSql$g8rs#+fih0uQJpnftm{!}Ekw%^WJmqW6sF)RAv1^*H7x{pW9`Wnq zFgR}KiM;L}7YR&(|0|*C0Mh4h3bSEzzdfaqu=gl_*NG4SMX)FCkmB1KA>J8INu5$o zE6Kwn1=d`|(DXdf%To&7gmSa1pdrqRMNkW6b&snO7xm3~5I0G?{5rsZFW}4vow0#0 z z_B~|v5jDF_So7@J@!_~Set>$|^~=iZYLuHfCusGR@GPAReXVehY0T1y04NsnFYT=9 ziw&+CW4d}3XEq*vN3BCO!foAj*hCN0hW+~fST>vU$FVsZcP?W;bQ#chhs$dDA-KhO z=cH4|qB3=PFAF!sj2hR@+?PO18eG~JdU?nIcQEa417>i~xlM)mujUp@a4QOb*Z=!+ zuWzM*Z2<6%;WY<56;&tV@!G+VX7zIR%7llSjpc{}%4{^NJ88zq)f$R;;;6X>asZMF{rz$n7qCbQv#E;Ldrueyop-wJ)<9WR zXVVb-mgYCQN9X2H28W#EBsA};H?CVp^AsBH+qo&mU%xO`pyCqHulG%5Fh_F8{X1{O zPY4@pZnQS%b_uMj5rFdtWblry5F+P9LP$i&`rjEmAnl`MgEf=Ev{veVu@SA;3U5%y znkFss;vPwFGMmocrDMK4ZB((u3`)*V9LB&zRuAlDBiQveTT-7>A2A|FYZcQC3x=Hj ztwOq8v(>G=tuMChrkIBq(7WF$scjE8s+HlTS}#OCTotVNrcMqa#hA0iS}*k2nKT`k z<}F@a#0Za~c1h3~+#JG;Lw&$*c)5^+ecwZWIPVjQ^1AG|Q!07|3I&UnYRO3|KU>kD8u?A5DSEMs@%sqE)!D#_iu6A;OgCc_?OKd@tg^8dy71OoQ9`50Z`u zI(YEPeFu&rmh5b%NDQBvf_&pNqc%`OW;VS2NnHB2;sJp?Z_F>C{4CZt<>_aB#<^na zO63%B)^9F-w1hgI)FU&?IvUwPlb0*C{#mLVbG@k36|^W8*R6^3WP{?Qi0FUOxvK-V z#jGk(fqLTUJCf*b>z6IUW&~e4b!+>Xe*AOUF2gNJ>dNvbNjg{dw-3EU4~QGyuhMA@ z^TP#gEuXJDA2DbdjQ;QzB0?lbNRvAPENRAz6IEK7=+D1UR~~8JB}@l3w4eI#?qLnc zq}lWy!CRWovFvd`C9i*mtUN{VFlxLn0az~frhwp{#da$axm`$ZP-1q!MA~Y;)gHQa z=S0Jn)H2>$DZ(=gis2Xv$*dcmC_rkMC1SX~Z+}8V?S`k&%+I}ed?lZ`DSqBZc7mQi zvI)*3aV0Cp?9r>as`RFf%@S4m6YO4f0Jz^vR0l1|iT-a*eN)Yac+;~!7u9i;wmGmAh`K&$TEWQuSfTOs_)tXexyTuV-6TmoH1WRZI$$-& zON;T5^LBRIvBS+r$0>pGZiulFyGCoK%A0Z&bWhqU?<`&nEq_{Z`fPEbz|oL>*XGFh z;iS6AOPkOs!>jd?puKTV`c_BdUkLULO^V6NftmOHN51-b5)X~3y!zVxCUe|vowD%) z7+wPx-iSP<4?pggU$~i;^fcGKcz-l-JxI9EJqv+P;;DP`RWIp zd;aIPeCQzG^Q75+Pii4|B*i&nZJx;o#Z$*yo087_VXBvC(?oYM-qza>PG<`$KHuB! zH0g@NcTIJb^ycJwrbP71*JHaSv#v9)H8WBZI7xqbqe3%3mZ%d<~mM?i`f`KCFCl4AY*Az;_ zlm$XoX&EEbh%#s3I0Vv4h4U&7EIGG0>tJS-e*a{~sorI{{xKB_O6%fXSAUis62*GJ zLU|>Hd%Pd_{d7EW{?@j~w?v9X}Vh}RXT)BQm3xmmNampl6AF>Elx z^pBhoyC(mqRTq>ZQ8TpWD{DHglae_;u*c3e-ls7(tI-CATHQK^>__amAW?P);lfKm zHRwBaWH1?~(aN2fnoi$NVo61Kw72pQh>DcmdCnvPjXf$(%exwp;`k@ru~0x*-sI2P zM#HV}u=opK>F(B+)v$LuiP4DpfiIWF)x*`&7~PO#LtUZ!PzLM`G!g2jv>UfuozoKe zZqSw&aTT46!Ume+oReS-=L;I1FT!O?eq1cj&s4#(A=JX(&XxRXg0BBQB1UKJ;4+M6 zbN396(sbk%zr<_XeSJD=JIs{c5QoPL3-puBGW@fnVq!*7XL*iWCVG3s$^`CA-sf3Y z5odXQIeaA1#+l99f=y`tTTOJJGp3qxx#>7m*ZZm5&?+Gd0+A!%2v&D`IM-xUWG`jx_UJCPDr9J_fC~Tf zkNxUR-!&{>d60g0(1sP}`&_R)>v~H74alP}%+%^-)3Ey{wo0z9)oj#jl1*X*x0_&( z{K4G$a}VWMB?~zJ13Tad>lQ)6OKe)Rry2e|mxs7av5vvb`O0tM;@vIL9EC=?QmiwR z@V|?J!tWztT1QLD-7=?de-HRPT3}WnA}tb;{I~r&9|Y8#+Z+q~8mqcZl(NW zW6Ag_6&ayo2Ry-_gpQ3;mK2f0)Ha~($~E49iJ|kk2BEUy&F%Bg=kI-7PD8TF+~HZ;cR>8@r*GxO`>KLB8am z_6I^|y8l9y=8PNhD>5+r+O$%+GXr$CFgHIH$bDX4%Y2M%i|S=L9Hb2tV}v=N7Nu&> zgdSUwCja~0O7GuiRib30 zWJkQ1>xY?XnKvOJEa$@T8S#4WYeY#=uPlkFDZtGQBz&+#38eiPU#%^ejoA(*-E^w| z0dI;yAMii@onS--#G}W>WmiR0l=1R)cABAL`u9p-(iu}irww+F2K3+%hVG13QvAJ` zNuju0tdK2kUkE>V$UHVQ^w6XCU%B5fMOkMA`t9s2?GbK%xo{z8+?@zM)WZoPX8vc; zE*CL$*v4~CE}3a0o6eR9AftzxmvwCay@)u~{5jXDRKlsoZ_~LF5zzUuK=2R2GfFzl zmTiE@Injr)QcaUVzsGL>!{cdCKooJ->d|zh$&kYvph%Td$A92FwXn|Wr5G+9%m4eo z|IN4mPno?bXthDqk!8N+cwZkfR~8NrPy5#XKCG!Jj#&f#?aUP(GPK1K`zs?O3MXgU zg93N4`4Qo|GB(TRZxlySN7!Qo+*0dyTAHpzwPc$beK2)?Qg z^Th9zSN`vT{2_M#2Ks9{4^Br@?M-L3{=)zE&ROOZ^%|#(+$W}_X^BOLfY_ga?^6#c+)gXqwA zsFHzOu|N*n{N?cWqU+*tlmK;ilOB!rGh#qQc{$|l2(^pSC*>%m;yntKh|2ym_;caa zNlgo!Zrc~gV^4YaIx+et zr90N+JMzEW$_bsh>Qa{F78b;pqXf#AY&_XSQxc<@t1wa5j0Okc z8?~oMS}hgSir&Y43|zgHUhgBmc$OO;2iMeu(m0zMI9&+`=)O#@@WN)y69p5$!V~>K z&EgrBZ+bLc__bCW-Uc1Duy2Pyh!v^2O#8Aq*?T0<)Ru(k=1MWAV0dx1FG(RK#+~A`H$EA?_B$u_T06Z z*epl;^9d5t9MRuu4Bh?-hWWD@_FgE^)pt`QH)(R(Q@x}2ccRLItMbpBR1Bd0_@`o> z&qP+%R>uL0R|lUgk!5+g=UFM2BC-#*4YQT&Ny{*iTdP$-RR8^!T*6Rv|6be+H-vbW(iAn?LPi7!?A^0z2RSp>(4 zfD4uP!zfE6EG8D_SH`Xzg>T+un51lMIzFms(9@-M3wvjgdsl$hW{*<6=G6mvwwhsO z#+eB}=;;qFB{B{MMqDiYDWR(`s|`OUZw7!EGYx9{S-Bs1+vcNInAo^O{~qZ9iWhi+ zs5M@jAtHI)=sZ8)@#3!5Z2vZz2;^*OO*;io7ItP!htViC?kG^ZT^zHb20$8xTBPS} zPcJ#hK|XU9L!i$44!2r8)NS_mu#J0_%H_)1yUERygjU6;07`B_)@I?>K6LE5V`FJ|r^!atxV&K{vRWFoA`yLGjogCL z`->DW<3)6s9zg|U5mVyL*NsK0Z6X=QhO7LS-(n-n64cJow;ne%4W70ksuUwiA3 z6)W0Cp5cFp8QoED-omtUC*uY?d{9zSnss&7>(ujI{bBiTnSySB^7?+I0a?aMp2P(B zV$caWAc@6Q*)(x!(%HfEzcLmCmbRx3{OM^wib=ZQyEe)Q0d>&iQ&%_5+azNC% zs~q1)Qkml!q#}P$=JNm&_Wo1HfDvj9lJKWjHynAFE3vbw>dVp4w_m_EY>0l$_BEx6 zz8lNT`M!{^F^i8mKgRikYNbWjDfkra`Mz4;jFL$CyF*y(T>NdEo5i{??q+%BV!2Ws zgLc%-VJO8hL~iDCyQbgd06XtF-g)H;WBQh^gcpKB5N?CaOG-h)`Ig{tNAlddo9cvI zkqLI?lI$Y))#J)3&e03oc;le*-Z)u(x)tPzX@%*@_lKtHvXK#oGYzeWa;U5(Vv_8{ zY?@b?I()wgWhHruX|9SrUz_r2@>Y!=S8l|V&(O#$l>1HJN-gnu^b%|P%@GW*=VH&e z5VL)FnX@(@l=>599Z^%_*Kls3P-pXGPjxy`v)IHO{(F z8DM=W5K)2(?)AhLzf%D+W24}T@%VG@coZaAevUqWh4ZamiKdrypA`MlpO~gRDfO99 zn#JPpq{&s~;VF6)5rLZi*pP~mdvL)4{mkT={7}pB-RXcJm<|th4i8u#0Nc!WxUl$c z0dc@ieM}~T<~iYi=R{XDjvo^jr4#FE5%HV_C3 zNVOFMBPe5*2n&}xd7OoHN2o+3IsFcMGRiSa0F2(B3f3aSTBh9434U4)MDOyn1R?)v z2;ov#r;Y2e&hRkk2Bw`c+q(y|PGT3dMHttX5fwcyK3*3?>5731UN|vGX0Wz#a@dT0dbBQ^3h~%{QL|yg zp?^x;&$keujd>z(+UOl!xxI6N-Ge@0*5H>+Nv#jjayiO(@P zn7E*nF-T(E%DFBNt2dPg+%CD`YbQsJo=8)?7|Rl-59koFo;}Nzi(vdi=t0a%#!38PQlq8Xd~CU^L@J$~!%}}# z>Mxj=wwAsXvSdSSDzZ?li8P->1Rm@wijN+8=Bfr*iqd%wor_^yBRtWZ3-@(Rn0B-%e z6_#VdpRX5UmsbN;5R8pyXNh4qNP$*0l{>z*E+NCoS^%$-0QqjeZSsDzIR1FDZ?leO zjNlH}a12?+!!!A)UX$eOcwW-RR`JAJ@3@t`2vSDiopG7*V}WBEnN{+<>m$he3RL~- zK|H@_mKz4@9==I(bgXau3_y}&)C=jLL?^ZQ4EWC20;72xX*bLhgn`hsLE7x?egu0y zi3)!E*4w9&XS{4t6eF}@63TOr-1%nB7A-Y!AV;0`OasIB7!_=wR;*(63~_u+Wd`o3 zM8Pe)o|XBu1wyl^<90614POpozh}8NJf@)060sO$W3#l zE1l;XeVJNCo9h7I-uvLI>h7TCHylTgN2%hqMmPE*kIKx2X2;SsRZ{+~^->Ic^P9!D zr{b%|g~Yc8wpl3H5e~?P8Hd(z&s1LOS<;d^S&kjX}eB4=831~ z^+?J$cGI8~!32+%AXXqfPW%k1HGfGwz1|n(ZJ36j&~&B|1gf#$ilj1QwHaHX{ zFNAavis$K#Ow=XxMia0Zx(lbv5f&z0a&g0|rQf8LJFoKG*n-mlwv&Ap;gOBvhmX+xBs${iS{>DC#XLRJ8zN5@8+;aQa)^_Fx**{fYu$(huqrp! zLU98DnBqsS`C!cp^*ff78sD=3b+AdY-1-xo){jDg^#wSh`o!zR*C|O{bTfff{(#GM z`)j^h!`jW57gT2)clYG{`umQaNkcSwIWM%YEtS+>RaSpjC1);& z`s&zyw0T2Ht1;!IUuh5y%l~9Q@fA(%Jh)kKKO7AFT1h$A2NvDM_NrY-KtpO2?!=*ot*FlNg!o}(le?*?eTse&S*NtgZ5J~m|>$9HWkja1W* zJrgHSs$)5e$t2}eT`6I-8PTM*Dh{*k;HbQ5doP;-k`@&j#OP&0IfE_T@r zPdDbK@0#nq3p(0B6?JLv8@y~UVmmn3{r(-#-RtiN(a4l+^y;73IrJeMU-(+MVVL@(i2ZMG zfc_p6M4Z&<4=xf3|HlMkpAYppxMAaBhEe_)#=P;Uj>{fsjn|Kep($#dbPcUs{UR~6 z_QoHtGC$O=Im5$Oc_isax&0a$4|k%U`u^vgtRm0$xQ5=q)olM2$A?R=+{&^HzRVjO zGynv5OnF*bXq)=cHcWe0V&FF$bcs+Yav!W^c&&)ag*jsqDO_v<`qAiARz?GsNXQA7 z4hw^J*r%|Z%7OY1XFcDgmrs0NDbp=lvp9h-j!am*?8up$29xCkhx$8YAFT^gci6Hj z+D^H);WBj2p=`@kA(~UjM^r_jeUO1XQvNr;??7mo))2vk5NUgLDk_vvYG;TE9kGSK{8YBN$l1(`Lv9OD5oLFbd zZM%o)2aI`$cHNaDNNy9E^jb3g9CRnpHKYDKK4jE||3yhJeA&e!<*}IZ#Ab2px=H%> z{+^qnAacRvkN;;}R(2XB6ba9AOs^+fnwT`bXZO&KF!KXV)2g$ah7lfHp%gn6Y{7q0 zCUKoOJ%hZSy0*x4-zNtCF0|1ao$}QoOt$zg$6aj5FozuJvgi-F-6gMTHw!j8?P;}J zbZJ#Wz*vRN*yMN&g{lU!SS+6ZUhiTgIJrq62>9T`Nizjp6gMxfCXtbu)z$6bGYl7< zL5L*AmotEz_ms>0_Pu6`6bgzeWA=7?%iz8Z40JtJCHmiPW_pFAPyVC`xnaL@Wu{~b7}1i#|m8^6ALcr z8i3EhIi6RWYSU{=;df27yX8W5wQoNZ{P@x`_OcCPH3FC#@ieP=RsCO!h(^5@p~gXT z|FZuN2(caX!(hnxgo63|;Q7nUvaFs!Dg=!tyCi#-nPMR{SYx|wNp#_sx_N)7qPdfm ztB%+OtwF3&&cu(83Fy;ft1H0DYF*0ytXuT-?45l>Vm6Nw9b}ijTn;i!_d6 z7YIl8ARE3nC-_NUf{ARq_eG!@j(Q8zq9`h;oUW5px5?q-;hx{JTTfLF`jhT%^!hE| zz6GEPc?VxxueF4DsP2h$E2uW0$B0^O|BLam!6PnLV}S!3f=Bb6_(9L*)v=Gm_7Lfz zTzcUCa;2b$9>tCK(bl;|*B;a6l+o%3Ni%cxCgzn2dWJ@U@J0o+jL^v0ybt=FzpJ7v zK7g60INU{&L7rbK6foU_k%?&h^f^M=kCyzy95&yOa_xA2-OjeJzSkVZkg&^;T9&>n+K z1_kn`pK@8QTb!?>40~4Dkv~xRMx-!5G)sIj*jy%H%z=Cui=`}NDWeDl06yH> zqqp={3<`n)q^n`H8bN+x5LCI;myqtF?VT^hZZ<($TJrk$T(9YTdj3Y~-X2U%Twb@! zIk}FC>mk)f-Oxk>y0J}l_*b^Gq%BkJu*Ij{I`w34>c~wQLJ8qgiMEpyBSR(sFz8kG zV&8~_Ed1#Qi0$ncYwbAP7-#w8*a}Y77~xJ;ODvW|D6L(O_hc; z`>kPqK(&E)p!)isBho5Jt4=2`dlr$Z^|3eRTIjt$5;(qI;Y4-p%cMzM9ma)f9KE%& z)>s`nDzZ1$Uwm-R3Y^X_d?xZKL~A8fbGrGS<*cBU{-Kz49C4pM!BwZRgbB7uWzoaU zFsj6Pp>9lz&Yp3Zm9ggoki>oXHLdB)H4DgADANdkt2oK=x=9QB1BJTcQKQt z(0cnQ7SORKJI>7OI|`%7bkZ4!r*38**qrDr(2pJ{+qYZ6YRJ0zNDF zjUMF0Fy+H%y0Ynxk`{08ZD`ZR$NbI9T+`)z_jSaY1E+|K33bW1gQC$+mTo2(3k1Xwx-cGNQ0 z>8DI1gsyG2f=VKq6fz-%FX#L%qk6Rut6c^t;sl$@?g9v1tKYS!lr3*#O)dee!{mCS zBjqb>CdF2Suwqz}ywn3^bp*&1D?VN|0<;Fqz$nicA#ZsF zSNgaQQ1j)R8ca|n+qf8YP$sEsF^cqI6(yz2`vyr~61n@TADDV`2`;-h@N@<#92Jb@ z#nDZiT%Xg}Y~QY*Q`}p&7Fzt%0u4~vGe9uSzRrBSY2_FAzxc#-6Q6b`X8ZLO=ql3xm6%G%r5J<#C;-5=(1SF>O zX%FRc5}d~EBX6-WRf7o`Ij3j%heN9^lk?EVMN|d22L`})1)u-NwIb7v+ObyFHT_L1 zN=eXCRsV}_k=MUddgMje>@s_AR+y0Y22Qtr%sct%bKiU+;$C=8OQxQngpP0DTBRpj zhv!K3gP&%ere*QVd`MaegTNjVQ8hu+FOy+cUr_V}T%fT@t$eK>#k9PJNw$-1=Vu|H#P z9NMohR}!wuMY(F#k;Ivd{)Xz7xe_^Xl}zOP+_<1!Zn{F%b_g5* z+<7N#|G~v&hgY}Pq%2Xdb@&cuiZex<;`8r-e8ebj1a7BFU0<0#ZvVLVB;<6$DG|Cx zGCW&)S7VJR6Pqk}M*seE#Ll-YdpsUMx2t?iPrTu;VU(k&Z*hV_9VM~iTvh`6rgn=T zk(|Z`SNu9EAPg1XZFuSKY+^5h22G}a0*;n<;qHhyak!dpf->vgMNr3)H6ch;-7}uk z^;}Si<9g=xD7^Lcs)6h57GxQW0I~#}CWqJepo1C|_~B~Jr0eN{&PeLF$b=d;|D&s3 zL0h9&7(t&ym~n$Y_)=Pcpa^3AEkpgt$M;lz^@zApMSsB~G0QE+?*R!Ve&Ag%kl*h6 zD&L9cC&|YF;@?mAWcp5@MTSaW`@vjva~z$!LZI_If7|DM`c8_8!yqr4KaU$ISEGCp z3WzweGa3Bp6GTp%OG7T@0vcb1wq57?JjF-B(TO)7M%zFn{PW#pS!$0a9~S1a}(J@2ACBdms+U%we1xwEd)@R+xb8j;XZtCL%h8?jxAa zw%1_SU+|KrhFr#XTY^Xbi!Cd`b#PcpD+V@$2?rLAS6V8LC zW4WZqoG9ReeaIj8oPFE&T6r}F8fT=O82T_{R--OahmK;69p#pTg#vzSt!t!u^wL2Z z#h zXou=3m|zsi45pQIm7J<1{$*9QU6(uehTWS>PJ5TxxU+TOW0>G$LZnWHZH#rja=a_<)?R5*z?W97^ z^9KuDXY&VY)h77(*{68DK@;iHcdY|eJxa_1F>w&t3jOfEK7ZLZ<%VRavIyLzgsfJb zD0~W=hQ4MA7Al$zM7+fgRd)}4S*ymDoB~pOI+J=l8*u9SB?6tthuVx!2unV)g#DIO8r4_w^JpenA3)W)Nz)VQ3Wu!SHR6h2lUJut&X|k z-Buk`BJZsK zE>@c4A*pTHblNbdA&H^odQtiF#cG?QAe;_Qr<}rr6UW^Bf_z7UN;R6_bJ24wQAi;) zJYAVWl8#f${Nx|x1n%mZxr6SKbhMhVQCkds_Wp-@aK@HhjF1hFQqZ+t$enAXz6N(5 zB?uT)|AR0DLgU-8B~lfPC4&mPm_(0c3^|VxN7mo}C~6s)n0#<{Nr9WJ;k@qHd5k!# zZl2?qV@mHx{SWkDEe9}CT3_eFS`BRAR;{=;lInwo!528Gxln6I!S!VI4QExho<2T( zBP0F>yBZ~5gh;P(nf`t+lQhy1=Pavs^{bw>7yb@YR1$8_FoJFnbzA1hI7=~S@=|!o zjvu!<3)6!hv$cDSSUat0IrBypO|XoDzDgus`|^Gb!+Oygyr8@}`7c;9$3ey<7-lkSfHg{QgFj|96$!`n=^DhwfOdmfs-IG9r^ z3MavGg@FitgTQR?d?>X0z!copj$X9b0(}`C98MOgC4FgW8VCet-s6Ef=h1|NwSDz0 zp{CYt)x6NqP0B7;D#RuoTL0xtWvEcl!I^*J}oUQD@*?9UZ+Y>5~Z-f^?cYWtvKCH&26eMu&_j`M54mx_x#_%(=2%(&m7c^pg5LJxS*e^pM>kV zxMY*65fs2P5Mt+j`~JU5+hY20#PiiVXy#Z_(7+3^?i; z6Ew7pk|H94P{UeaZ0a+~HpUD6&%yWM1I!FB6N&$?R~mZyu(pB^KghW8La$LsNhzWw zNv}_X^0vOHC#UYJN)n99$}OPP7}rg*AocxoL}ObkD9Kt!?aX2%W8qc;kox9vF)m); z|AI$B>J33Ww6-%p{C4{9wMc!^Wl%wAZ$p0)M7L0@?-dml`#utvxLp=^fVQ9k-v1N` zy%gi**-%qu&|m|<1U>&T%DZM7e1L-UKZOimT(V1c{rT$xqYb@V%uT)O6JW;YFp@V; zhbt6+JCg{0bMf^m<{?C>^>gTV%xJ0sQ8Tw<*wh_a^?j}0EW6MrRi1I$VyNzV>KgvP zH4thgNJ&N2Gqe=f(ak20iH=1SP3Hous>WO<_~7|<5&4(o#|Na4fTb@WDo`b0!x*3) zdt>^QMnD~2juz45|CE8^dNGe(yl)PzL^VIWP%C*~KRMYl#4OOR3DL1 z#2nvPvoV{kKNP_w#%n4Tnc2QYHUD3-KN1^;I`xk0s(M zdtO#M{e8cMz8&60{aFNtK(P!H3wJ=qY3|#9KV)c|FCG#c&I!_7@HANRGMipM(k)l> zHN5jHNe=}Dp?VRYDD>hZZCCmKJ~H(4TOD&_pS}tNp}W}lW)BrF!Sdn|C&fE$^rQUjgOI5pEbGWV;j#O=F+3VG!N_=Uhp#NfVqB zaH?FRgD0Vz7jr+%Ge_#*vx7dOeZBGP&5XJOU&&eN2!4_Eusr>qudXStst~tQ`R43W zpOBLfne1|?tgW19-{pNgQ^>{2$~MmtYMc?+y39=^=qqf{AQkDxdM3F$z$~@o;W2$@ zuOm07oMKq>{C}*|XGeFa&|(T;IR^+jQ45&N<%tmsdm!6Y%{XznpV9C4mX?MO3=%`f zARu3gLWok<*AFi!Aa9#w(ZXzsbgS>*NFLnl?D4H5YP&S*B9-{}*-N(ZczxO1@6W1h zIQXSdiT^%S3su-?;VOJxl!@lU-0*vTkQ!1nK%;EtD-=I-IoWeM+icOgH~vje>R|$; zwifMGdoPgPjW+Q=#dn-qL>!@lZMK(WZ14Qq&+zbn z8C!rMMgljK2jd+o_jZQCQsO%oVE+gsLCD9!=nl>Mu2q&iwbB~x)+2lVt1Z)6xAPe} z;2_k7*f}Yr;)eXXeendm?^XQRk&gJjf4KlWrhx{;;!FqKmMUMh1d~fc;kRw;!ktYq zd3ZM#GSj$_DVM1g)2Y(Rv9rZ_-JFz^T1Y?0861qvaAKTerG5m5t3)n4FqGM@l-uC) zU!8vXW_5$LkY$!2Lz=-NJ%f)SIlRT-5wLmTxnJBAQs}^9vkG@2Uf! zHy>uAyE2^qD9HOIFr?mR^{JtBzlnoOx{A5=So0$s>~1NrUkq1zXr+Y+=rIye&;2YKG z{<=M!st|nWA8bmjCjRyQ7t`#(PbPzQljULPf}d8&+W6SmK(hj&)6Je!-H$QD4<8`F zoT$>{d?~q4Lp~SMnm zWEF3831`EfPcoJWws3~V;v;B|G*?u`IKLgYPz1OYa6jD#kAToyW59PE*ZpSjti}Zr z34$vuD*DLWbrnZ-oTv!ga?ou>0~E+#E#Mk$b$z|8(92-H7_3^GXxPZgU%daDGwPWV z8jR4)o-(v-LuGt2zH;^LsZ6g1$?|M+E1$v zmPoUCJ)oX2A;yB3xN*v?02>AIDRd!rwBi}(6}kSy&){|!Bs?~Eekz3ylx=i$ma-{! z4R85$PPMZ&qZ&3OQ&bH!_p@2pwl<#d*cb`3U{#eP#_C;6$G!^GiDi6wO!eo6UNL`FO)xqbcY z8;DTFJ`Oei;v+^_?CU}5p zw}*=5WVXu7`F)aP@|{BIX|v+nU$FdNU%9;?@O1POtmAbQVSh~5s4D5{=!C(s*($oK z(Wt3_7}5Z38(>M74P~Q22$__Vb-V}(ufK?Y&4LgM3%pwCRN|||PPXCg{vi#`aN3$B z)Aogc_ZV1&ab!$T*97-*l2|VxH(XLD(abTgnuHxl-x&GJ~J+xx9>hqogf zY=v{hQIUWb7rXZePO7DvJ)QG zVh&l=Vqqwj%Wf79?Za^a(Qd?huE^6GAOFy`%T^e!4d1BNK|&TWqDlj> zJGb*5{HO*@RJCpkj(I40z3No~Xu}5XKr)&js7`|anub$})M zMaSDAYxUu#Bg~JfoS0u?a8W*~VeC%wF_YOHc^>@0z2O?q-Ycmnd<(szPbCw$vG zJnWK4m~_hurZ#48{Bxrvyu|L`i`5VRUYD$98{A|>!N;ezLi1=I2MLJ{cQUM@MFS6o z?W8ZItHViJID zl~0!~i%;rM$J--TO*SiRPkufN;*4x>%B1N|(FkaOIpFI+XG>#b+|XXRnur)5V*zBR>TCx& zB0@&nb;%$+TGRV#n&&GuHR82jT4(cWs}B6Dp(tqfDLFMY@L7t3*bENY4=0Qsnux==8wlm^0Qc3CWs9Q%i;$=P-j zeJ!nQ2Nha2emP-MA-;Vi5^&ZAs^xcihC^Kd+|XD&Mxz^sro~|0+#ll^VNRIT#{Fe= zcr2Fi1%)QieBF^W<8(_>reh8Uu3Vu}yQ(csirF2z?QPJo;ihmFzZ25jkI4k!W0O2U ztdwbIAD=PCC!5=Sc{On_oSN~J{Q`8bcG17p(`R;`DcIF$=LbecJ9Hx2Hij`U+ZpWzyDZKoay!w!wRIeE7xG8rj}}c;AyTpovYIh4-PJ( z9M5QYS2$=G^d1Iogdo7$yzn-I^_*8ehu>gOX6mB?u}U7F2Z8%^?VIqmC^R=f9VUzI z9v%|b;byyAfplrqVxwcoV!a|cjR8@EI6NS|p$0e5hBXw4FoJ0ZKr>X7s`9n3NV9>^ zUMKojP$;?B2BO}n(PNIE<1S;=bcaJgx^YTcS_Bd$1|lx->*agmxLMO!>B=6lGAa&@ zeuJN$PTkbur$k&%^}avgP)TBAvpdMoP3TNaclOw-Bc`Ft8%TKk>N%t_bL373NY*lh z%sYiwAI-TNl`aKO+D00`DE@ADlgC8D+~@U9L8>yizKTko|c zT`LF^46=HJ4>Z-S*?VDcSNSlCxu{CLmaZv`r|387 zMVjW;8ikMXtY1zhy+wW3?vx!cG2njf%1Pw@c)XqNkw|2Q&orgNuk8e5N)=Jw~<#u0s`f1p5aEM`Saf z`(2tuVJAd_q{1yOkrX3*`Gv7Q9Is4BD~TD__)Vdl6H2ET-Z3fWa%lOQmLiB?P~EK3 zl6NcTc%AF6Qj(f4_aJ$~?OSqhoinL*l8uaNHtb{m*;7 z7W;%X`}QXsBz!@n;vK%n!PDC9P3ErPl-z3J-@{70u4gn7Bq{roSv4oHyJJsuYrguG_)j238%O~RwxX5A<;}RchH;v+M zs#04y1Aqg_E`F&hK3`=2Zw}=-Iksj zy^ahO=)0w6&gYoS$rOF&<$l-3-8uK?>Bdf4|8kMoOomr zWs?*Q+DD-gIab7N=~UGbE6>D|CJ_Ux!*xf*0txLPkgV3{I$~_%p!6jJW+Q%&yJJ3K zU3-qFr%~5iOwpeR9DN~2IW8{>1zT$(CBy^J&FNnaH*{EcXY(#vDOt;V3&-`zf;Gyq zNL^pe%IL(2r_M0YTik6-^ahMCAcXra6o@OXvR*T&aw8~#XI>kXWMt~JYg0)TFpiT-ro@9=mCV8lX7y=j zr@~t`tG}u7gS(#Z8V02TXi1#so%tp8!)m*4UgzA7;tcxA!760Q8v@<$0$k75flNq# zWqjda$wOfv`|(Q}cqE{`HMnqf&5Uf)3Y^YnvDe{ouqV^D!OLWb^OyLMOe&zsC1I?h zdqd_;w^uuxAeIOyRiR$sy58-;_3+l%BI()N9tW}L2Bt^FMkI)Ks{1Or+pjTf)K(CH z)%HKRbyL4pow-&D@pz+@?PoQsoVI&r771Ysm)!_QjNt${r2_T^dq<#2RYTSKxPc`u z?4ghQ0fO`~V>7(?W#FkX=B@Ro2993NoVhnx$(UT4?l&8N_OGuFT~q<(_0bSJaI5o9 ztvq3-k@Fggb}PtYcvw0KI~hxIt)y)yk(}WTB;dtAp<)B#NGgpC)Yp%>%Hie3ZSZ{@ z@VWdGlZ}=}%-dt+J5<)eUR_#}h3RDuyZSj`=+B*&;3IiAb;1U34xKV%SyfH4>1-S^ zFJ((<7GD(dW-VsOxZCjLh~}f#V~X5gB_9vt+d)!gb!8f2#yLT&ot!y$*7=2eIb40L z{dCd*kfD20spv(cRf8Fzs9${Y3xLn`o1SlNdGSfOXD&@nk`(G#eMDTG3W*JPaiTs& zC7=p(NCHnqxkQ$>zAhm%DTtA9X*Un#pAg`vU3S5p)26utw()yBJsON7ruwMKqRM1g zzYpW)dgD9q;u7^rzTT#L?HyK$f}z5mO{hVKjk~mYMTnmczDhE8UTr>ndm{IKJf|3w zuIz?jTrwNb^(jZWcE7&tvvvD{Ic-Ydl zaL=FPGZF*8UIOR|Ka|~UeY*Ca>yUYJa%D9Cv6J2nkqBQ`+UpQe=I`*hOt2DNT5fmS z)!CtbemJG3mkaj;`}cM@bTdx<(gvTmXg>m5Zq~~re6O~8W{swfF{!UtD{DvnXx6Do z{U`wvvM_S`m74WYodJ0?dXYXd>RJ)bwcgdxw3(i7UB%LJ4Y}!g#Wy*i573g@3RorBHI_;~r;iHRu$n~1dPYg!C?xmFpUc}XJn zv?MxfqdbMQpHqn(WZ`6=k(Jxck7Q(J2T@cU{r7VNh6rl`ls2!HwkJcE-4qBzkz2s4 zK3%U^dO>UYP*|OBE*=RQ0?lm*Wz9;GKEGtEFOJd(VRw4pD!1E69^b$m!#o-}xpe zj$83$01JtT{Ud-%sK}u6XN&l1_x<3Q=dRFO?~;vXL1UFT&hjSIktO1B6qfv*lpXY# z)=Ar!&3)1imwG0w{NJu^Dok!O6<_?)A4cMry02qpMV-eZN+(%P+>$u2Kj`AEziT|v zp!O3AK9x`_bfIS_pmOmuw?71a!}r`g;oz+bXx-B4@66sT=bnIBsZL*63tzZFX`H`3 zj0ro~*cincy}%>fbgH8At^QDSlxLsNNhC{*=e`C#kez2`;0oWySCM={xi21M;0XqT zo@)I~-5xjIY*zI8L*Z#&!B0rcet4b2G zTbh&Vl+xATD+^S~Wx&c|@UI1d{ED*BFJM0+-P44Bz{p!L{F~xn!^0ZKY|cjw zv)Q^>QUOYf4>P1ufCd$G6=`YtGf(mCCa7Cz}>W%Lj`JK z?ybLbXm5t(WH-tWNZp>K4h!?UVRN`kxe?2FN?U=;Re8sY2l@dp!*srW`8Bs@$bfIU zLgijqClRc#(fCzW2edew*Kvflv&$CV5VJ32(n!0Zan;Q3H<8J-%3$l zUe4|E9Nn%NFe~9-aM>hn&R!8rU9fBI@TIVBojnzDz4<~i)eXYfz&Z3At8N*^xhwg3 zcBowZP6LIA$86Ilp4;^*4|1U#6yLD&Blfd#4Uj7^bxL)E20qU)vqz+!TC5oqi%~cf zGZ6Lm%=Kd;hoZKNXWGmpJNS9&u~yi`^TSTxsr|P(>h&(XO5}`Hiw8*Np8k5b_ul7m z9mgn!--*8s@1LB#`Xbzk`Q$3&C?h@WH*LFS<}rM){wg`QxmA8tu|)0}XjHd)$`B`Y zBb@sJBWH}htvZ~PN8NsZL{Tj>C&;dm^`J6=(W^%2F;`-zCsB6X>PQCL;clByoil-M zUB387eT@}Cb}9L`K$z@`O2I&6PE$orp!hiMbZL}n_hXY|tV5do+IV zg*{UK)0U(sBEr}h2sl{+egx_57d}{-1RXouWUGSDU1bHK-d~jk#@k#h_OZBD8{|VY z=zJ6Z7JAghXm00c{fwq%X8yFs>F~!e%;(PHdji~6S?Q;yvq2sDIiww5@4w$!N9{A! zcPlo>65P-EMp8*J9@M43I`{LKM?B`#L{#*(Jd*mR^vRC)Hu};33zu zz&TKRKys&0;!sE8O(o+923x^u!gxor$`^w!Ag$XzHdEZCG}Oww+Ov9)Z_mHKV{F18 zdw-H%_L2KZV`(#VvxrQ(Zq({uR>opFw`fowmPxg^@5LAV*gtZ6jZv+7;_uvDbL{_m zDpegDimC0y46&p-wKvhoS*nHn zfMzmJrqSYcNejNBqLZcH0~dJAW7f@%B*zq2s4O1*RPRuUIq?YDOaBVmvzP_AP{^m3-fo^k|p)@hT zJn0{RutPSr0nukc_a&ynOy`Jdptn38u>x6>1RSbwUZ*g!KtSN10_{c4@|fJIMW8;B_$Ps z6rI}b>zvEOIBj}4mzH8KH&X~{lRk6jiy}16SSOk0=rB8v{f*r3SfZfqdTt^0GcrM6 zR%T_mhn9ZgV~?a)8+q~wODZSFClxBeRQ8LA9MvHokuHi*B+{6brOlsw7hdn8F58vD z@9^9z`I0RR(HD0NT7O$(pExHurl&EDEXrDM7o}>#7H{QU{CG(z1CL1Gzqix?6-SvK zA*#Fbdux`9hUh+6@l)PMI_mnAVe9UFwntw# zqi#_{1m7Oo zX%;lKG8G#p!y>Q>im7oWYCFeXfS9r**WAy|5ZT?n7HM)6i^}3E;-)eU9@IV`U#W$q z51(8AgvKdGH`rI3UM}y`%pJ&BHO271t(ZA#sxg~7hF8M%W;Uzo8`Wt4NDJMI4R`QW z6I&8BSUX-*z^2ojcUkyCh$%4;Ql^|s@2&J>GJ~3avW$?=j@razXODZ^K$Lw=$NJ%m z9gV!*^b-mmtNLW9XqWw+?OMG`^Q-l=J8#S4=LlyZsD#M|x~O66i;oAb3rWBYV8LMy zHTL$_XEOG@;=5Mu+>A^OO$BNo{olJj`h<@o(uVDq;%um%H)uy z^)LlD4~~El?!fI_g&Y4r!TX2i0%s9}d}GTU8pF5K)pCKsI1;KGSc+!b%^2d2fJE$N zO5x!Vm)brdUQ&m;%H)E(*+h9a-SxY!q79V2b1b`D0!u>u3#+hBbA_La=GhnBY!3vRID zBIR^MPwNZ#VV4W_m4F#aG{lk!GU(lu<8J%b=Lq?>LL2n-kqIze`E5IE)QMs3Meu%j3Htgm^~oF^mRYWljYndt_*DF5{h(cx8ACV zlWIle+5Jn*aR~S*C+2Jh3BTf0$j%=i)4R0Uqp_A;dKZs2hxD?-@_l~!bF29b5RcOY zD=}#`Tr?DISrlFqzU~q-yjRJCTvwG{+DB!lahuq!sq}&an;wD~@LZbzQ3KLA3NPT} zVVA@RnlH}Ptsg<#vWvRxnKmx8!O5^DsdvvhD~!>i3P>aMbQ59?FD0v$gVZ`Y6W8Qf z?va{nc`?V42n1VSD-H}aOIm8vU?iUvhum3El zq&eM`ww4`ABhPc+KbFGf1gj*F^^;~4*g$>8z2Ck@Mgh@XKgbIT3(bEMlwFf9ci_G~ zEeV~iTCXKMn2{yY zg)i-Sfq5ulJo1-9;qn0KoF{(r^Q<25f?PUDOu*FA63K7wPJ2otpyb5FIrHH+=c%_X zWSfr&WYuC259+79_T%8o4uk@sDBG78ZRGg^Rwwd0RxMixYaw`uJqP!jW1^9KmV7IP zjyN1%I+t27b!z<79n$gi33|j&GtKnxS$~RivL5+;-7R~*gvY-tvdC?Bl$2av>&kC* zeIl{4+D5Qg%LdJ~O=R$qLSui)`(%Z2BB^31B>X?ET~at&<7k$YJ=80-ul6#}&Uo?+ zg>AZDWcfFJ(9yAD%I7S0oB1x@uh8f7FX|PM8H^HkIaZqtI8n!nSW2^?kno1qF4@Pw zvTn}v+}tj$`&WzMC(n7fT>eG?29)jB72xbKQ_3ybKlQ9wxz-31ecS}n`e7- zV{A+&DBjj>I)k%0^u?x{6oE5K)q3=oHdUTNhlaIxl4DpO0NUrrQj5c4%8aJZkZMhLxbzg@j1eyzuSkH2{~|8(>4YB^t8nIGaUCdyH2h8I#| zSBPpHhC)1}_5%lD;G{K86e^Z>qT!s?P+0h_JvjmczhF8mGaH$JO-6E`X6`G6?)=Nc z-DmSG=7_=@1PRwU&r@bWBSQ*BXTqfb3%jlk=RaFexMmM@+O+8#!f(BeLyB#!Ls01c z>kit)$cB2`f6_@qUI-n0KPv=?%xQ%)m$XXRT#t6Ykqs#a&|aAO12`3x$JX^NT(N># zzrXxoY#f=QjHEC4OTMe}fksX?^c=}9)4!4*j;Bo$_6tzD)VclTrU=&Xru06; zY2l*rWv@UOi+?IRMU1G-Ik0_Kt;MYZjnDfo9NOEF|GB-TTG9zF-XL<$B$R4Eq3P4I z1?%q4XGay@QbsRCuwbS7%gK)YiHYWp@F3^rRwu|)^)@}~>i{ryoh}yEMh9)IsF>FD zbfNN70t-6)nZjzOU!eioB>!87PK6(l2dw*q*ch_A54KJ!4&)gjKOgFVa!X9m-IhE; z`yXLrjgKHU9dL}%`dHkEbNz}6KCmyGbuzCiQ2#Bec*F10=*5ANA3zi&AY zn0E%`XeV^P(bgK^j9DB8y0^@H5ctA;|3tA=dHJQ$I-3T$MaE3%c!q;LTJ>H-RH9cZaL~<1U(};Ovy7E2VteF?;8FU~MFmW9@5{h*36i?!a3NUtB8Eh(XYN+SeQfu#BBTsm2 z`bW)KD2_P4+Yefj{~ex0t)w01nMfRF#1G1A3M2n~5|Ko;jT!*KOiUyWZJtM0_%j>- zd%I9F>PC{!D~r$pfS=v58oJ4elaG#ml#gIue0&=Y&U=A?OUysTC9b{>VR zHp=dQ(^yJSI~ZaX*N0vXFud?%@W_8S2Y-eL0+^=rd19kUhm(AV<$PHV)V9 z*l!Q&zjt!e=fzhdv)P~|DqrA`I?qsG^qtR+$=l`TqEhoX`f5)zIx4%rerx7tC`6Ji zE${krov(W<_UXa+c!|@(|)7WW$Ac&NRfWbexHz`m=u~2HatbCtbi;JXN7OP@l z;%6Ml^C-eWft0B3yB1!-QHs1_gg#u^cG>A$4sh*yrQP_tF_ym(OOt%f9~uo zMiy>h_R*q3`fIc;wSGJ>NkaSibWeM}%RqM!$KS{OA{p+Qh&bkJ@%cP5pozhD`62DC z+6klGE~D_RDMTe3NAa_qX5Q2=ZG9OZ$wVy64@lDqw=xI+i`(*0`drv`|HvVm7Wzu^ z@o}7tm860Bae9~IFV^LZp$49Pu<*4q=!DKXr2=1)ucp3YvxN8ANbfh5`%P`bZT_2U z%^u_H!QuWe(}h{cTV+aaL6JJX&4ta4gyRg3=bg*`;w+({ z1`DOJblD@&p48?_-I8MJ)7~e!jYeLC!?V_!$p*6Z8shoh8s54y2Kigp_&H};`U}w_ z|CfbBj`em2%|dlw>a}oDZk?#5hoq^AZl^HN~NnfkaHCbm@J4qN-I{q&He(v8SK5loZ=f?V+EDq!z|y>x~{$D85fC&MRww z>^dIm_cwI3wV1fLhTIiMcnPTWsSq~JxP&jus0oTo*O?aO2HG25fIPgU7Kg{H=*^H! zx;%HgHM$*)%3j(osZPR!ZM+Wb(j0LGC0+pkCq8{iWsBiIWD)i!2ug!#0@>8ry8Dk2 zHysUDu!IEO2i-bdk_5@c7guT}N@>*%qybj|qEmTt$K^lUpiRC@*+QpFCO=e<4Zk?4 z!8LvfW^Jq3yV6`goJ+vld+0=gQNr5P=_Z(UJ}&yN;1gJAEBmY5^{o*E!wVL+eilHR z=ixlE<}lJ&vUpEBSF+2PFnJjOiIBG-@YesG8@EpyKpBJ2CkpqWHdEk}oDf9%Lh3Q{ z0$)K6Dso+GhL_RyV>X#~(MNj8Yff|^oCG;&xpQE#a^HEYN&D?ETIl=kOKzb{>%>tE zMa)WpJ#CF1E`?Tn>w2AC(pj%!=vZh(9IPKpIhuU+j(QNk)2M3)?SSRRrqhys6cg~g z!*p8kjy0+5bfYWH_b&>m;1`MZ!3a#L0qh%e&Co#Mg#ufKrY^pO$z!lU?1=G;D{;)bH|q@yz83HMDaI$emMR zuKoEKk<9lqex*PP#&WCNZAX+e)@=V6DrLr%$aO2o5XI*6fYwfLv^c#Wiwwp}dbRvD zhQzWY`Kmfe#O9LFDlQxh+;Zzqk~=o5!jZfiPkR$i8Y;H%J!+Kk84=W{@$ACqby8GE z>+5ff(=$K(oxdNxr&@SDHY$s4nODz;qSxOhH?UJûr7gv)HZs;1mpAq|6A?3Yy znmwalCG5NUV<$wr!OZoM!KOMZ^#j(&23H5VrwkJ$G3TbUtJ zjNnF25~VXxFXHoA%g0TiFz%#!Qukzj!fc|v5uI78+k+7X_0CC2(qY9nF&({^*! zwR5u|M)2i_QvB)c_IiW$pS5Pv5doPK@q;nL_N0r$irT;o(bb*5Ff;pN_y?ySqWKl*!SgqAo*C+VTAy^?cH}q1Rc#(e}unK%V~?GVF{#&5{G%?1V>- z7gXGON(9@cVLybyGVqEG#Ug%kX1y#IwQMJw~JLBI!uub$NWw5Dn^H`9kAK zUW_A&`0u5b&PnHoz2mCwi*5*IGL@Ft;0zz|j6pC3$(?1gwaMW$`9l4nq?U&`P!fp~ z+*H^fd~-a9A{QV~A?-Ee7KTrMzSg2L-X@QUHx3?Rl?GcU`q?boC9m?d&F$pRdY{13 zi!|l~9d~Vq_}wHUu@HyMBH~sDPn`&VRc#RWSobJ~N0X@P+rT>5y zYF}M7)K`2_mXYN;Zt6G<(!`4%BvX>b(iPNs&53L}!(jsK+4TE2`Hjc3D5Gs+_d#T= z6jsnh`aE}|QCANsBH~Wuu$5x`rUww^M5Yryp98(W3Q&YMxY^ItQ`{a(Dk6VClQF#> zpn@cBILZ+8T;hpommSms(jMNQTD9E|MrQ^3KtP8l$5on@v|}N$5KHRuOY`}>9uC&t z7~S4*{sqwvd($R1*qOQq{2-omw3KNj;w%TGCdXo9u2dN~)Ya=LQo);(1zL)ND@}Nm zQi@2M$+Q|$2nQ}5I~3vjbt**+ET4}%P)4w4rg!R%$#?_}UTdgKcSz{yMAG*^ai6Yq zdkcm|PI8Qg{_q^lemF2O#y~hAWf1fg1ff!hhV4#AL*Vk}Lc{{j!r}}6<`7^+)95um zHw%Z>i(1*RgOD$5aEqMNgOYjLMf_Wy}I}H_2-=osC$5&r2Agj)bnv=Jn63z>@JII1# z@Iv&xt>jfiC%I184ZQ8-IQbv<{erW&JYVZQE4B6keR_|a6upu$lI19?*Lr#IpS5Ga zb2^NV2X36WFg9_be@H8uk?9?i+$`f_U_^%H5`WXXZG3HBYnAUUE54}Ne6qJ*Saet^ z;;^971UCxTXr+JQ7la)9%;Yrc?)Y{$?3{CFe8L`Y8WT_FxQ-w5&C%s#q5lUxqA76E z=<7geyLs2LTeV8l8H+C;IV1>q-Phdv_Kl|f@~g+eh46jo-T7zQ?= zmG}DfdE~7C`s2A)6JbZb5qIe*pX*LF26RT7i)cfE_EMG<_PR8f&1ucR`Be2`O$B%3 z;0u5I--(JPeHR;|?R$N`ZaY#p@m#i}j+&!P@ z+-SdAt5g`v35I$Yw@L*B8;*}k*V1|k3!^4g=?18n+a^YxO%9VndcWNagnz+WcEm`> zV6*CGh7JobzdP%Q-R$ECK4Vc!A5f>1@|r+1WAN7=De2GnE+wPTRP~(gK)~ZFVGp2y zH%>!&A_yWvV$XS)x5VSz8xAZCZL{1IX?dQ4Au_y4HW=DX5=tLZDftP+Z9I}kemG6` zm9TmhCkq_h_HAmn0rsq6n9PnXMopdekQUMB_~XNcY?7)Jq$YZMx|uu-p8t)M+0mbN z(Duv9LfL$%Wy%A1g3E8$;OtHcRU|(YvGjW~Vnn)%%UJ0|`D%Iz^fDE^5H~6Mlh10? zbah10Bs0*vNgE!GhoK>E+H2EvuHHxUqJzptrA)7Y3Q_sHSn&E#DE?U1(NIgBx#=#X z8kgcyY`+AWNPtUaszmwb_ z>gD+p^HZvNdTiY@m!k{4UiZa<71i8 z*-@s>;6^jczQaDlZ2`9#%EieeNT1H?#tn8@@%7gN;BG0pW;0ayOQ&izuP*#7Ikah2 zuK6B0luu77CCQ!0g(iTqk8eKo9!4hAUJ6!O%#$WgVnm+BE_ASSsLl}N&Su|nUNz?w&ck*m^L>F zy5YOU%~vp%1Qy&qnD77_mQC34v@v@aPkM$_AFv8K>?o2sr%&Suzo$P~s>2SB!H>#s zJXO-vB)-CdqS1Jv3Q-^L`r4r&5i@0YRuv|fZtN;1jyjagDso?v*t>W$1v2zLWFNf+{N=-xXO>gQak*HdU z(et$ej@3-$efgtSd*l;?y&pe2EcR!JJ(k1|TGwaKbdo*(ri~xh}Vb!ZQ@*|^sH!-sGVD!C{z(CB2UgJ&Gux;tXDLEgUP zD&q(P^Ib4D6=+2KquEUP8N*+q*h7Y8wDl_jEEMXuRyq2pWVJkFu`Efk5V4ntkF#_LI z_UZ<^{9e&87NFuA-_(N0s#i^V5YLS4q?zA1_NvhDRG8n?9@gXZjefUp*E%-Q@38Mm z3MndcbF;sd4|0daU-%X=94KeuhCRRL*@|>jS1W$b$)&DI-(RpRW>4`6F!AW+ZosdB zj#?zw577QAovy;^W+iT(;{yc_U(?;MOLt0G{$)M8C ziip#bvnCETvdZ-Ymq=Uxi2gjoA{ROxEDc(^vU^9=wipu!ROCq*1Z*gpwfm|l>S_kc z308{Mw4DJ-d!x}vGY}=MMD&nxsp%(in*e=DdcZixwv`j%MbRJ;*VB2GB`o5A{)QadcNoawBl&F6>g+20VGSs|+$wF;EA$OxKmfokF#xT^ZvHP@A4`PYQmZlqXd2 zJ^}p)CDS!`8vbIP3jc-N6G72&g@cl%S6AJ|Bjd>?hK0e2L8N765#nd1_$h~dIXl)r z_0VK%S&wIO!wCw$L1Uk2y8#~E9(NpV)@zjrCkWUi_zSUedhuOeoFVJ%yJ+ z!TzXsb}n$~_vZr`05-d5t{XDb>z`qC6rI)8m42D@ebym3XT~5zlWy#}BUk-ql#?O5 z^-rC)K(M8|OD^ys7rh>PM4Bp@SDE<_5<{MgFGacs%R3f4Z0G>TK%2 zqs+K5``5&&bajci>^u_|z%Q?}u!=#>mO#vK=~1*+`4tHXN%%OBY-evLlpWiV=MR{6 z;7DH8CE>ZT`B5H6TjAUWju5w`l0zY!b3fM|Ax6!d0lRf{6fAd@mCq}qvIj@6~+H=Yo=}Twi+2FZy?u z)&GiTo}+6XD!)x;mFn;=CQjkc(D0k`<2GI!`V+fLAI^Rxv-o%x{~2S^vCwzE1$o%p zo-NXZ%$U`~bD>y1ef47WTC)tSXHV#_UfSi?HVive<6;ja6Rr5nvc0(@31CsOC&U1=3*BKtlooEs z(B7~i_?m`IzIg~21JPOk&Ka?jEAz!0eu~O95xtn07}SRc4|$nSf$_EedRjffwR0p% zc(GQ5jj+W*9cnh#_fU^{_05oKYHAJIVf*ud;1alw5s5rxua{>Ol#Q71X(!!bsWP=< zboCl}NF;d4q5C~%pNxG~a|WW;^znyW2zFL3=_rDgrhJ%?U}7>djGv^=Y`>qyf(LO4 z{t--!=VZDhCSp=yLcQkZig2H|m63*RohnuqD~&pIvf^eSAR$RA8ZyatcFtc)+xE17 zXCCn23T|17Juh91jGH#Lgy~I#=jW}FXM^b;7s+VxI?#vNkN9kX8zUNuSN55(b@dtI z6UrBCN)~paganLkT_XtqpuoLmmkRTJO^j0Ta1iI1@Z>ITuEZ4;L#a4bNm#%3azNoL z<=t-*r&u4DWAm0SK)H4FFv&tFiI$_!k_#AH(WU;7;l#_!Yzl7cWKBlD0Zevaj@Qxl zhzEafI?83&yUCxwzP|@=v+sH3^|~O_f9ns5^Aqv~gR;NUpZZS^%O4EmC(P8^a3w zNH`}aG&)*bUcFJ*{J%{@m1~?En~@QQRz^bGaAK@MG3C|Z6eZMTp;JRUr&$9HXhrU2 zLi#Cbtk;WTA!azCc<+W(>U`&Zbf)i94p|TaZ$w?8?v1}$Z z)C4}X%*@D}N?G6aHM603-1^s4e+==LH;RH;Rq_RDOH*T%t%lhDI(;7uuc;>uB<@kvz3H;3I-d zVM~rD)T}s=5sH7Ez1Mm{8epwBHj(7fa6I{udy%`ibnEWtKT`}2+5<#~NB1nw6sZx3 zXb?J5jW;);oug=muxmzLfCCpu0GM~h`6j#bQ!8gTAZe$%-;QWCTu)J3k%eKb%sJVv zIl=X3k-5pc<_f!WELXJ$DL4B-dBd&G-xh|+qWkf9yDN269bn6iu}52#P0WLhj$mn_ zz*Br!w@VI1x&FGJd|KLdZB^4&ylwE%5~Hv(%=t$xBbz5=hDc+r_*=Acq${xUmoaT_ z@q)-9w(SB`5*N~5PqGotxlzL(ra;Mu@G{v^qx4ol5SA4@;J+0Ng4S$!xDN_M7uYuuUw)rwC9q>z)D1AhYTJrfm7#Y> zPcp*MsMa*c!Q5Yz8N)N>udE|=6Uks@`X^ZGrx2D9m2NwQ(}IN5C&$0RMtCq_1#ioJ zHo;bJ5_w3{ZFrzAbLE87WN2vbwq@rx|Qy z71Yl&BU0i!zRd%@&pzjbJl^-818l!?Wlf7^OV+7-v{67C(euo%Ai~ zRvKbUH5mg-D@}h4m-@h%X~AvEjQ+F9UN(Hyz3M~>mtC~Bc|Zek9)_~ZL2p@C9NtIr zd16;1+~5-Acg;w>ILG37B#ldIRd^s?DhK`;v;9vmNHO9`{OK6qOuPHmbjlC;@Cxgv znQEA1zrBm<pnP|2_>h&k~Y$cA@TKhTCS0gsqFS=hO{W zkkKqj@6@UC@fw59oZ69t`+v5?vt56ZbLCRCaq3p3!d)oO%Z&K-T^iYyy)Uim4sJul zjSl0t#Z#pW4kr%pq#@un!&yk?)@`a>_6%c>38%prs)So3jM*~8833E%Z>%V{hfs!k zy|o>Ryy>rQ`{@z?_F|z}0zV&v&%rR8YyTH87Dad3C?)uv6{%S?dAoVUYlkC*;bL58 z?mwoO)Xz_~A)NrdCUN&>+Pno@XY5}_DbQdo_bzPO(sKXbGiC+V3?(Ll#7Zd09RTe3ISDvR!`-+S_K*fLYwvOR2*Z4oXVVh+M@tzX>?WPARFHkhr*mJ~cOnLz? zI(D#+sKk}dfNr8@x|U)rmELScF|7;?Q!H&5QA_z#;taUeWX>yvOWHhaE}x07(&9v60Hi=TaPk3nBme;yYs;ezmW-#ton3n zK8U!8hY^h7=JY^2zTg4KpFv8vcnTv;t$h+$Pr+b2%N; z&1yr5IM}E?@Lk(VFwCdKe-hcf3k#OV^*aA&0~Vib*1ON(n8ooVO=Dr)pNAd0!~1`$lq? z5EzzH8q?Epw;FNos~OV)MzsWwr7@WuVE_>RMKp-cryq>bY&k_&(E1J|Czr{{9gR931x5Z-74sQ!HU% z?BwOvq9rrv#rc4t$f6tPM1C_x3MOYK+$sFl9P{P+d3F_oz=^bwm}GDNL<8?I61kPM zcdum$D<-g&f4|u}D$=|@%p|)FW-_xRS=d(u#Epz!(zSt(QuWll|L_o$NEf5|+y8C* z#^iMGa9Ajp5gsG>CDuJcwi|;*TJ}(7(@|YYyOkRGd&j zft!RQT7eyb;UYd-+HY%J!G#)C`Ugu5w4YvHREfYR!`_h)ZCx{MRj6(GGVWgOdtO5p z^$TI~*nK&s?fHTwE;ci|i~ohw>v}4rm@O?9Om+2rJUz$mUvd!a2t)e=Og01Fj**z> zs`ZpPwnnKXB5pmU6B?v9)8zMHLXf$(sd9?j=o1R zz6q~o!1CDbvam*xYn3}oJnXlvZ;V=PE`p#w^o6S#eXnZ}jFWf2Ijw1m;LC%;{oM$o z$zUY`OJ$UxUBbYO)plW;UC+LO&rdzi+adRZky!mhAdc0=MtDfS` zjOs>@*N0ZH#9UmkG5nxrK8_5C{+sbQ@{73!r?%dBljqHnq8*M_JD&L@+vWVJ_AY@J z4NIXalOlPRmB}2@U2a7#8D9Df3tvlL!((;a0WD31@qmMwB4mA^UCcJmZ@|~(^%wQb z_@rP*$BK)Aw70~;d=u-ZsTP&z`t{VRu7LyQJhT6fVw}RWcLQvi6*uKw+=nlO-&8|^XG$XCJWS?7br`4gOL9Rq?wr+ECO;< z*qBi-$`^vK$??l%BMxH8cB}c>d_S%Ob%9`-C&Wi&96tnVY(-^dn(fwyy|h(r&LV~< zWPxYmB?`*C;%XF1g-kJNtrGlzw*!+HqbY)jxnHJ+_B`4Rc0u5HA79W1zh7LuR%G)v z>rFRYVT&_HAQ%b(iGBY(Ko4sD~zT-bwX<@w#LV0~!&+0G# z4Ky04KXeD9>5MouLTxh~wxc+Wj*}{ehKA$(E6gVdoz}s62E)3@q89rH`V8+wV{7O5 z891;C3e32??yC`tl$6W{OkxDWTb%c{7=2&S;Su0b(D1^+d?jThCnPo8=HvMHkB>%A zx2GurwlsTV9fT2f9dhuqfBp!`{^r9aA?ap$2J6pZLho+q9(yz`23y}c8D_jn|sC&ol7}8ElmJ{?C{-5psBDj*a<$7(6d(7c;CW!dO!OEf0kv)fCg7f7b z9cIfdGCs=byTUK_7@xFCn7Dnmxa?B8J|Mq58c~PeOg>EcU<5lL>MS>)sZvkzbh2MM zU0v)8zDTcWzzf=)Xg(jt_=3;oXGEPoZ}Q8lE6`mR|JRt`Sq6S7DHhzOTfN9@$(HgH z{pUV+y!Zl6V!`iOMk;zP-Bv!16I25wlWfGhlXsV~<#`&O+$0oE>JJMKXL(pIah634{DK!0^u0ctk!&2!;`We%Uv)iQ9${K-1xU!-eU2vNXAtxH zg>ehM-jT>hDfzvqwLk*dn3?5z-n}Q6wsSdv^yODZ2K{!P30FX5RuCMsLhkF#Zk9Gu zd4>Q$=1jqug@i;{9StSTXC)AdbIos;R-iv7&8P3&=gqg)seAAsfSBau2ILLu$0ijh z2=aV+1P}Vyx`r$ogl!}cMQ(8Qtvx|MS?@BqvE;I9Q!i!9k-uTI8n})W5#p%+6tbKEM@_mxy5eR8!7XUu*osMiyZp2ENXPZ^i8EV^ zE0n1d8@q;xh;@tCnQr*=4XW|)p|Ps4~2^vqb2WQaMtmBAPy6~tL`@)5@|$BHdS z&=xtEb5DUR234=sMf~n;6&2-xF^C_|i+}dAOcYPvh3{dmUP0K zPo#@`ctCl{c3#|F#aHZ2@V}+w*R9ep$h$tQH3GmaNW*jdC)>0Rp%dr_I1_K%9!-Oj zqKT-gC6klxP8HqV-6A$m*{!8AYdZGXPhekezj5+#1semKyuBp&uw!Cr@3(&lUj3Fh z2jEl8@+vq(e0SR`8&Qpo2xSH!in#B8PPm;>(9vnz+U?gnMQ_wXBO?<;)B^^x;!(&h zRco5;*L`-dF^EM130Pc05uHyCQ1Q7OghJ0nxa~Sj2BVdUGEJ6o%ZQGj}!=wR-hfgpqu&3cQPbm-G#c56cpjS|lVCb*wO+3G?T7W|)A zga?Uhw6}3E6Rlu9i&=7+3w2Zm#ynjsB#4LtLp%k?pUbK`droj!K^FnYBUk|Ao#I$9 za|_|d<^M!^{O|0bfC8*o%jF+t#ek!p=bnhSKly*-3;fpZdyzFkheb}yU>cTugEwIa zX8TvKLrJ>MD|s>sav5f?lLh8ONxcOXWd>s6KSU5PpX0VJCUbfhYCX_dSnDQB)vR5P z@?E0VJDihOiUceYAxsg^9zB3MNDEUpk+{6-t}~r3hiIAViskFzH6(9NInaG645KUVONX@Dz4bG7I`S_aAwwY{z?M zKv!9gmW-qt)2@^ZHT?(>-gc0y=eDA3pZp;Y3E*)u~fkLahxybC0yH>QG-j z;{L6rb=lZOiydA?IZIwyM(5hCDlKlnjH13B_NL-Ae^gV0Y zueLqrz>VI+iiwKqZEaZJUU2L`YUS0(+!sDnU1qj2IgBgd^4zPp`719YBj(rT4B=UM zaji{lOBFRl(^b$agHJ0B{|xWU?d0TSn&P(Z0h7jQAA85ZK!Jsd8as{m+@F9U7H(FG zA)PcK`dI*DqE|4}SO07fd^EDLmV*!zBZ&SixxB(DP zUa#7&P*BFsjFC-Ts;1QC1ry=2t1-g|X}I;eHd|*xpgAQ~hW39_ba@eD(%bW?;517a z9ojUM)U3`?J!e@#bhaB*v`hyECGCi{R@7-<~LLHizbe=hb<1J~X^y{}Iw z%x|21=l`AtmW~2kTKShMzkjmuH#n0vN`<$J{;!&5gfk!tj&kXv2c}2QBns=~|NXkK zrDq<1Q|R%2{{4IY`_EKd@Pi7KHX2?2@6(PxgY%~U{eb27_vkN~P3V}5v--bs1rwqQ z4EX8)R}>~$*8c~M@VnyP^WBab2euHvv@aa z1*@#{drJ2&g@6C~-@oVejGg@Z0$saiz8)qG(*N)4{=Z-0eWsYW ze8O7qc=#gAP^Iqu_S39Leskfk3Rm^c_qhrFpoz*}CDhl2zpI)))`gO+T3EMQk%Hch z5X;fjgFFp4g3Xlnp9t^Q-R_T;6)uLOa;&8O_xty(w!<-xgWP-q=}RqKU0~e2qTI65 zBX3hXE5G`-nn6Q1oriL4+x78B)bXP&BK3A?KF+^w2Cq$pUVlVPG~1Gg%05bV+fJ$> zm@MfPk~O#w#RFHj{^#*6OU*Po^WJ$pCJO{r#&e#WbKk1Fn%>xCfP^46&x0|9J<-TneeF9=9*7-Le)dE~7aV7gm+9AnHE*KN2AOD?RL{Q~C+;*^ zxKtj4=zn~+uUw2il}uqli_n8Wu;u9E zpuyWzU=K4I6QL*y-cD?M;Ht56RaQt}z8Ijwm8!hy$^DyAn^MYK&s}p@Rg5OB=uvnP zXnCmcuv35GOrP#$2kO~Ms+|qK2qjv*_q5_&G>32`|Pi*@tAlrxp_-SB+aR<$I^SYxc{MZnIn&)(ZkD4S4_FBzS zcJGDrl%zgMy?AEE*6**$JNpqZ+j-6H-AuB1N|ZJ7xlf1YncdTO0%FQeaYx5^Xb0 zLH}EV$%18f*&hIya4?qlbqUsc-&OW-6@s9Xr|1#CH<-hAvPl6svellOE@?@2r9pf@ ze`afG-$W)P+Jf@|*_a3r?>i**z41FaSzCT!=B9_Y=QJLx5QJ&7_i|Qw2xLnt%jD zQu;mWh)9BW8LNWvsS0`@$TK&lx$?6LVYfMU;!>1)p6^eCoz&gh%)Zakq;hY5ZI#jz zK>3-Aks-yE3*Zwo|2THxNtC;ZI^yHaanNfA#YPT6e>L$3IA_8^)|!^|pFcjrIa*0~ zNrzs}hYfprQ{Q}&$LFU@4v_9M;MDkc2&5$W%{%$z^hAD%DOhO1*rbH=bc%dG^k*h# zrOUywIA#g9asjMC?KMP`KNxTgd0OW^sNS-YqKI&QuwLHXn!E?}eB_vD#^ywhj{Ejn zl(gM+=N0KKK!!fCy@J5G*^R_4_gz}Rdd$1|%Gc9j;4p(fB&y3Gau<8ZZ}lVH1JE^H zb*`M+`Ri-jfoO}t!E3U^a330%{oP#uUVG zV}9ez4xkNQHKVTbSg-$+R>J(0TFUD14A*R-@_12bO`1=llZlFNFu^H_(iVQsqV z48qy;{D~%>{@(Ps`gV^6`1dR0e(n$yP1nf3F1mi*aZ3|2H)g&O&+50j`&g*X7AsGG zDCQ{qvGdsrO1(n&=goRmKlJ8M3?y$*j=C$>DOgRTbMm!a(-r3;;^d7O2@BkpV6(QA zJtCWzc3F2l9&7&P)LmidhH(@lcw4+uWaL;6{f5^mV4t+w9A7919^JciZ(@tEd?W1H z0N}P=_rC9*5YPhJ2?nK8SZ?u$#1p+1GXVRFHt0TkTYu5PY%Nigmy=9LUkG*U0lbVV zm}xa>)!V(4$(L+((l4!wfq9iLRI%~q9S|v#^GVcfSep*%bp{czZ$x8=5hBT-YK|w2 z=7-_&N*%6<^m}!(d_x#H-U45qkhix+=a1C)b@{H7yi?`R0>M$3$%oe0+CMz{87o2d zlzH)J@SQ6rZR*AB8G%ju`R9u*1m|6MpBeP)JIV&52?t8mXm>b77?&(<{&_WBBr=%$ zt(+a4vM*S`fjgQlKlaKIr+N^rKkafSoM!l6d*Z^iW*?=)R|+395d z5Z<$UjJ8r~HR$Zqi{&p}0B;et1XsWi^8&j?Z8(r+#}^x{k@#npgwhDSoV5833l4sk zj|WT}`k*!(h$YqD1dq?l$#(slA`qoLU`p&BKAd2(zn~+ZBDal+*kLBW9_y?@H|wMg zwLyYvqP@TGao)5aS#PSy1=A7GL1^W4Xr3TtJb+lAwB6#RTPMzXJ%1x zNY)M~mw&Dd)$%n+WN4-lSsbUsqNwH+U~k6xN6-hwOEi8Cuy@&ewTypJN% zI;P@%1haa6AM_=E+jFAcRNyQ%(x552vDJt~rX{?!?fB(yERnF$_3K2F+d6DF_`;4F z>_Y^mcVoV5>zLW&r{jM!J&2R_Gt17 z8@}F;Yq2VlZDzY~cu*JVY!#A1gz~;jA6UQ3Iv)AlYL_>NXVrw1w^>&lLIRxK$fpUW z#CQSm!0hIu=^nxrOPbumH)N%{q(2x-&)Nr3ui)_vuPW5xx-FroF=aW{#!QdI8Tl@YjY_V)BRF6Xv6OuTd@*sb}eZJsOi&ZmnyDm8L@G#w`d6huE^7 zKb;^K+R4Busb=d|_A}yd)7Y?7I?M`LbKbV1v~FQcmnQTWg%C1w)$cTQzj!x9FKP%7 zo%7HK)p85q-no4f%N8eyXK+`u9hN`2CV3=RB25<^HlO~+gruih1|lEq>^E>*D)en5 zVOH0>M5(D_8Rq|V8obJojB^f)grt^?0gZ&WrFP5}RDcEGhYMSqxK>n)qbDph)(mIJ zX%$I}tHM>H&s?nK)0C+@)dgrV&?Q-E_PIJI8T(aHKnEgwLw5IQd3{oJbmXN=+=WFk z=5kt@VTa5nMB9i}S@WaLMIXg|Qc`mergIb9$@lH%jO(Pt+Bv_cRLl&SG(zsBR6Jf* z@on#*{0JwC$^jBj$!+UScmA~3Uf09=N%-YVtnU|$IIJ8OFo{qG8K1nmFU@FA32T1;5A z#7I#|D~#R1%Z^|DyDJ5S-0!nSr|g0Y5g9Bjd~O5ACc3W*|6>t4<>;w~MFwamsq4Ea zM@qfE!5ZtC(QBoK0&O<{K>HQNNwX@6jyA2B@O{|2f-nqfVfBP@`{Vx9foc`SLQ~C4 zGfQ<_Ik4h>{fc#}DV)?MVAJ;z`Rv%d7VE0gMZ{nsKvWId()}z|c#27tu>YrEiSuF= zUr_wk;G`|7M38p5N+UOgt<W6FW^Ea^Cf*HhVq)EDPa+85Z4Et5c_TU^(Nt(0J)`AkMg-!89x+ z1(Js7k|_NE34{-Hz&$;hKcDq3{g9>rLLxRtH_i$?NeA|@Lt;<~mB2lr>?Q%qtYz@E zHSEc`^eL2lfcw<&gipxz9VM}KKcA@&3xT*!R^s9Ix(}&WA2+(pk5ToRZP(<(oW7=c zX)mm{dzuJFQjb>*Y`bh zPEzOoPnt3;sFOE8Ap7p(H&3=_)`8clcWR;DxfaXLt`iD-8g8NHWk$3`d>!%%%s~{n zb4b=GJdems(37)ikpq9aMR(4@G}963<#a74(Mvt?LWDeC7##LXp?Q*@OFA<*kB>uA zQn;vZ338GyIZl_p@>krhS;P1)A;f1@abZtyHPw<(J+$VXpjxCWc-&SgXZa^x{&0B6M*e+P+2*-IRNdORQJ4Ax$;=eEb}!xx|J)*INSIS#?pDbJ7~ObSpp3 z3BST(Y-tIaebMqaaMQ(YH;Cm!SE%9-@(xkh>|yl$I(U4&7%2JHs4I64Td#9ZR4(B3 zLGZ-|#S_^#*p~r6lEWym$wzf6{Alq2s$ol4QDu#+f8s#Q-4kgmm3JcXhSw zouQ&jAY)}$1Fh5H;(32W(oaA6nH>+k&%@KMq<10fxutX(H>f`QJ}ACUMr@C8MP4z9 z*RamtJ6bAZ|$4dF0;X;yi(P}9;IbQ6`eLT&LEEU8Ea;qW(P#H5+3oioK`$Bd+x1Y$oZY3i3+w52)?aL z;G_D-Rj2rEAqW~Dnq+N>@#`3gc6mb95&C`+%wN*}<^?~#UG&BuTJscMnQJ`m!Pk%s z-v?hJxek;=zr$*bCHHA5&#IL(`kNQCdBe{=4NIhTj9e-^c!=rSlj8mOsmVOh=kAMa zD~R!a$B@HGyd{0>sz}EF$ZLl{GYa_jQoD+O6=|)D8$Gk9O1aN<#}jnp64}NJ_THpM zAb9{?Ig5TA;`b@{LQX!Xzss6+<>-Y_Fhu-dp18Q_VRb>!)~$Kb);?%jy6Tbl=$w?Ke{J zhE3=ScG%zUmQ%_wxJuM&djj%7Tw`eMlzhO>hT51VKX4d1gThvMYYh{*`*^`w)<4UciW{B zl;^7xxfsB!+4~u%30C3d!hmm50d(xW9AYJ9cr(^9=P+{-5sK2FdCRm{HhAj23^Og+ zYrdNWs;haK_2$W)@dGt)+OL!DaH3DjJtFnB7c_j~M|c@yx59tiMtd}A6qsu}7- z05&Es^CC4vyoFB!(**-P2&@Jq7p9x`xR=MPzDm3vH6N8#Uq4nJHQe?A-dq>XPt4to zx(%;S3s06?CSYZ~uT6@8WnEp{SuXk;NULugulD1Lkq2wIt8G-3I#t3r%;!LNS3o0P zI0&P|0_YY6bn^i2=@(T;McKP(h($hqp@|5z7~`i8G$r?U>8f;x2DPaEviT*|Z+K;!s;gP$rh*_~ z3i%_y9R_0?td@Yy=GN3MK`($*VNCK``4XD>iiL>TKlJiwmry|Es?yHQ5H&^V&m-G# ztDG(KN#$7Bsby)f$PP%7xm;XgPnAe&T5UHJFn`ZaVlyP_gwGST%xO*}T7a_tvBU1C z@9{?~*z?MG-O*X#=DH&d9Tvi4RMn*S3Xl=8)-> zR4%uy1;Wsjd(vn05bBTZTy~&X1x39i2$g5zzST!v1j0frr5=NxKW?cl~q? zhh#0L0T)R#Bluc@494w|=j$H{Cpq;M=Gd%-OQ^So#?=O7*aH8OXR@2a;dK2<-}GugZLus|y)&HM=&iM}D{QM%M_!9!DIDP#prl z*dJOoA*%{O1XkA6N@|(NqKOp_#iPkD0jmuby@>Uoi=Gv{O#tGexvZS&(6aV80Wr{a2A{bYwX%yiR8a)KLyf=?mW;F zd_~%ws zypT*}0Oj1tk^h%;E$G~ghgD9&$8OA}2y{BTbV~hxdLPc_%2$B8e|D>PpTpJr`uKFt z)ST1DCcxLVLXyF_b0!&dG4?XadcR*D%hu&fa5`iNkxNC2kLmhPZYm664PA}~PzhAe zb|0irT^F9lN-W5V$1IYvf>fCdpP0m zo!98o0-53I=RQGkUq^yc8nD@?Vbf5evECf+RU#;&=CJ%5p78-D8m+3>L{GAZ5>?L8 zTfh2#fDV)cxo#C?db1S~Mtens>l zDW;JTH~Ve-e>i&!pt`ngTYHn>?(P!YA`qP5?(P~OSb*T}ZV4LP-F@Ni?(Vv9cm7Gv z-uIk)@2h%$y()@YunOi}Q^p*lf339+4Mmd1e@3MWi7QVfL{Re$Tt;OLUOnnc9p}S@ z{xvr$xRirpUlLh=Eo{c+#gJ#>>G7+yTg7)m5Dx{+&4c*OMQ!T#c^`EZ53iODar� z>VYeQlZTc`f{#Xfoid*~gp!9%(WwoNuI!m==qMI6uK!{0YaD7urzHxr4< z%xrabQfy%+tyC9c7)A4Pa}(0;=2u3E(_WO?bF;Qxd$=?L*J&8nD|S?577(;lZ2CmC z;I^1ghap2tcvpwFJtd~HKVL&G1@*`!6;N=+uXa9~!C?FgH2vX?=>Zd&XB=t??5!&QhT_4_Ff;Mv!0gYzjeMCKA^EkE5(jD zq(cU`b|Ul?FYoM4EJNu-(2rVu{_neqEF#qy(OaF#hO0TNc(w!VHf7SRJZMqbNnE@( zG-2b{&`{>BGTTjs7csk(>4OZ*SNL1s(F?~6eiMJgdNJ6BpSRbpf|ecJ+Wj`v@FAb- z>2dx84HIK&jk312UId}KukQ63jF>n_S%4l>{_^~lKoeUv&`4DuA0B|-$rtaS0vZbC zNbJrwAHDOAdumzWLE@QPUoD5zZ#8GT%e0g><=6`OHp()--dgcItQiyz7uqWdGBSTO z;rybqGV9q|8*ujdw`NMN1x24gQx=rd0qrC_qGk!9JrCb#o@L=)hC5z#Ank#vjd?28zPTTVVXGY3*IQu+pKfMMXtEW% znP&;u^I==vgAQV@O(NXRpGHM4{VjD-vWB%hej4u$^I9PkAN4S;Jc<1uR#fWdf^g3P zcQM0H#_I+!ajeHUMyhWbY8qwS(7fnYjP)tPm;Lses5<53Mknko`*1h(*!kY5njM`_ zNIMiirmVXi-qL+Q9Dc{c-%;wfMpdLmopHb^mkEvCA^r#D$0-62|WCCJKI? zZmK)35nO8D^A5yq_Z6m13(c{3NIkV<(1nfl4;kXtPNVcfEg8mLvGy4gIXBxHDZ$@N zLuF5pb^B^YYY9KJh-FZN(l3wpY4ABy3;4hk|>w1=BR zg;`j8(^!V2F&|K=0sYn7!z4D;x@>4f($RM;m`)aZZ%sh5040#A!I#Gg=lEMT1=7h< z4!5^qR+f-wDLZZ>_~+zm=4~FkF@2S_7D>XJ%;>uPQGRu48}SVl4Qpy|4fTL?gn=oY zR0B+ddDP#en!808JdHB=6sZ@T7!wA~-D?ziFrXdxlB(4FfCf3hLJVMJhNa4pSGm8|<7dyc0_Ztxk@W*h_1W(hM0qL>m5(wPC0yp} z)X}BGjWYG$VoiPrjIGp>8SPQf%s)V%J5Ek%0@H0N!8K{~J3h`XLysT0aV9ux8Ixv( zC)doK(M8s ztW&sT0ZzHc(*l0L9~W+?V8pu=f62c~BKbvkGjEBxh6=l`YONud9G zj}+^)zlLn&t@o^Q2RAfZUckXDow{*}MB=M&{hxGQ2Sm?Zap*Wl)-r=em1n`17z)m|bN@&nig3rDW$LAj}cS62Hi zJoTf1#b_6xaYGe#v%qFWcvuNo)h4juVZ%#kG}q@-3i_-{2pg^6*S0j;S*zDi0FF{G zVwFBhPHj6N_Us+~S#&tTAKDu05-)wXn9?KJo9+Hdq2&&JUh!+@MXBl(SRuktb5`!S z{c1jqQ~Jh31z|5wJKNub$(m{?F==1R;wC2FS+`l32j$PR?V{3OUeEmW&u7(2EdS&L z9Q+0Y%^58EgU}o?xBa_3$8UUKRw5gFMDxjhr>^No8Z4~$Zrzz?#&w-qTW5rLtrqUyv+=Sc_gdcUO$K&d zpBQbo!HmvNMEilHO9&ctH6~@P?DR#8`)n_$i)tr^$l2WC$R%LdfG~3XHh+cSqg>uKTci_a*OzHYeRlv=$t1mb@L{#dt z)LpL)gEn}cUw@^_-1#3}T7X%BR)#?{UqEfe+7_$(EU|x7b@QCMo={$?uQCZ#Z#kKn znE(hM6)Wo`;0SLdBDC1;j2eCXthRJZT3p8AHz->UbCtxmv$Dc?6JlDl{S0K-ScB!` zp^Fq=NUH3%dan<*WlU;eXnTI$S4Jj#Np*cez=DJtg!bH={h2rt*DeZg96QTV> zczlWK8$(%BHQdsqPdFdGj&}b=Hp7LG!K(s$t%=R_bMf`2%%wV$pEVi^Elqr(y1UzG zzoj8g83yzyHo_rSpt^fDwuU~L3wdl~$%pOEsA&HmZ}G;f!r^AQatJ)}6)w1?MRSaS zd7Eoi_$S97_xjLeW<_Vwgw!u=EezSLM>mE_S~;Ltvu|QSijw!z0x@+mN-jED63t#1 zz&d7I5B+R*IQGxjkV}%b&@E8d<;Nb!32fBdLw%I+lm+2MdwOuH`Q z$4hBXzaf`$T0rl-O#xQ}Egy!uNOOA0JR@(dCV_o{jl7T@Cg|!%nzzx{?TjYvRs50# ze|J}|Pb?-!J*AmBbx5-}J)g`zUvY+;MG9yY*-l5AN&Np-Js4>2{&&?wsa!=Vu0$5o zROHBHr1Np)KEi`!r`>hW47YbK{zHkN+X$^SJB*#HdBDD3dCDmQ$I*PEC4I?ewcrg= z)P~(&algtS*a%|TMxwIEkhx`vqHDVC;b35OI0JDjAT2CIQ_fWP=>>{Wf+57FX8!_jjP z;14POLdo|lg|ESAT~rRYnJ?T1xSPyiOHZ9=h<49QIaV9619n8})P<=Dcac z><(CVQu=};434RB(zaU zlk(ET#Q=1GKBdve2vF@T%)xs;gH<#8qx1HQ;txZyqgYHcN%+#ZT<|YNXxkc=v3RPS z|M?WxYBoqIZu~X=8R=k0ret@8pYg!RPsSHC4A$J_A*-MK=ojt^J#9SShux7;Io9|@ zK#=A6In$&GYIV=5P*z$3nMrsh&SdJ7E20RA-?c{2T8m>lDlU{#Y}Vn>P2b`rwUR1k zen#@1(Gebs?-6-B5oX)Py+CpS2G9rerKfdL=jPS3VKC%y&~V(- zp5HXlm6iw~ZQt3uqNk0s!|HbudwVvT>mdfkdC-jTueY$v|Jb9b$ZS>xs`%8T==z-` z{+^3)EcZ~e51iy8+!5(Ib%o|^L%^EjY1=?4es(z^_(O$G+U`J#T3xRF;#r@%GlA-c zlen!dK^P$yagnNfgwLBro|_w#wjp&pG^{K{NqTzP_Fek8d4Dn>se{$^*bNerwxp6n zUHukV3<7Am-(D0bmr_N{V-w7lb&gX6D(SlJB?AaKA~c@KU>Jw~=+Vv1(r0R#qedv- zSj!w}q&!%OP|mP<9-jitUS3bn0#YjAZ$`y0JemFr5&vUX5$hhN3iA{k9j23{vUsiB z$L?}WZFKT1xhqQ%prx0BMJlS@yhAC7K{dv{P#J~D6W5Yp> zZV+wEjE=mQhY>R?4ZrjqM1K|<$2Jn})bM|&`wD0$SKW)%C}OxF<-yDyn9E2z$rvoV zDOjm!um_IRWJ zjYO@Bo_r2%8<}m_L%U(V_zO{>+|`q4A&MwE8oGO6^&o`2an~=E=nnA{jlE~7mLb1h z(s)qH1)L9Pl@uOY>*Hwvpw8Gxeek61y0ExSJk&J$l%b=g5yr0b6#pY}K2d>Tk_`!c z?83SpkE_v1RV?pz`iF20QRdew($X7zCe@b@pZBW9dovketY!AmF@5s z;Nfm(-^O8E6`)b)S(NlVw89YqXM$^;!FsTQ8<92hqnGt~>p&tA72oUxS+r-DeY)tX zq9UIShwP$=E4ubaSPK2pIXi4l#K2)E4NsK{k|jz_7>q+ARA_x^av3%mc#tcq>VS>x z=ZCfUk8ixiJExBZjUtAYpfKYPHsbY%)+GEr zy_0edw}KU|Xf45)gmfDVlbZpT^=KZf%kt6oka%fB{Qux@p?a^Zt6cFph; zhnpMOfAF_BfWP}p^2rLocH8h-*02U;njw9(W$m~#A}Ru`se&czKquk&lEp1Tv(*d= zA0MA`=T4MDl&#mooe$*s*m_pE^Q1^T<5ubE)s>)>R5Ip6#8^X(*(~wCnOR|^Ir4Kg z&O1I`8>U(b8sM=ENU98))vIs_QXkC2_eVcE+W(L>VWRf;hhjqN-QQKpGqyao2MQ$t zdo&Sokiq+HsqCRtZzYi3NxRg7E8D%jy3kl|1G6?Zkd=(+N=~*LsP$y#5qfC+^3|L%u)tRYFp1+#=-$xWs-GA8CcW` zt5>F6z2fY$3@iqlaSG`#Mcy;A?9v*330JOFF$d&FuLzNmtCmoC>K=F_RjAvau~M?h zvx8+nuM21AU5h->)TaS6b|du@o4tFfmcgZWyF%~;Mp0Djvpg=Hvk0QB%AU~AIfbwfI1R7HdrSkXt&6-i8DisUKLjB2@@MrZ1Xz_{CWw_(L(aU z7U3=c&g?(Xn8@;5kUese2MivHXz&L2McqdvhCrJ z`&kka*1YeL@s#ZO^3b(fgTne@#fMfYahTL??P-F~>KdjpN23!HH+&9Cm+U!$2iAg1 z2Ndm8X5&;hRR;56;MldP){4G-_cr?J>4LZ?**IR=9_MU$h zduG?6YxO>>Nfij_DxXVr>_`Gjvi z)M&;v%G~X_^&sTa$ivKID)`Eh`%d^t>k2dV>*ELvMBU3T7gA8_fk11+u*cVC2;dh4dZXWKts*#aV-yfJ3 z6dLL~Z_$%DnWseJ`Y82|qbHT_6>>IOJUL?3QvFmYZIb<{om6M~0OW*ygnaeLRQUSU zx0rKh*gN0MEV#O#vig%+cmC?TH$a<+AH_CsD?v?sXNIL^j`yE{^K58-Bc8!kk=^z{ zMn+_i&Nf2w%YIRW@Vm!?PufA9Ar}PN@Kz?bbq8>(b1VEdoD!oRW%r!kAZ&tzTj#5@ zmhXG8!CmRzH~q&G#?-TJ%1UAaB6G`6 z)CvkCWPG!1kbVrUK+dwD_FLrRRcgSU^>yC<*#XTB_Rm+&3iUXqG-Q-bQ%T zdRp5}T(_fplpRNlm9rwXp6fsT=U#$6Q2T9!yYnpo@}a`8*7@jaP+Hh{hK$Us8vbo4 zrod$p-UT@w(~+>;?0it_IZ4-Q6LQ4`Z>*wvBBH?QePCbQekDdxmo?R!{>=JuT?g+Q zvuWKBx)K5|>1JWZOc&ARGa@)sK0J|D)R;W0qMMI)6H%%}4F0NAw(zBZ1o&`7 zeSd;jpXf%Wqz{Tq7k!AV4VL|0=$dh?uo~_Bp%&pqy=r_wdd70%kyGpDiIG6F# zFNRA6HH(V*%E=lN1;QyBo3tL%r><{~($dmSejK_=Qs#6NGePu2tb}jRo(uv8Hr?03 zZIYp297*eFr|64zeAZW{FMFrdMuU{Yd^&D=1-`8B<@cl)-^LiVQFaws3%Q!(+@4D| z%137f2^=^`E$>~8*hH8C#Pf!HT~j7t>_3U8{qNPK#GKQC$EuAoVYlS{i(+$#Pa#i! zx9^qW(nETxLRTvhl8#0bH5`ftjfJ6<)s#XmPQMb`TJGz?hX@aa)vYISYb5VF803uij!NuQ&Wk-*TW2@VO9Eml2CID5?e^zn->!IY23;hz5dD@L9|2}E%7d*`h&}kE5Z!rUtM(*m!)-}CuUM0s z!X-{3$3A9aoYj)H`6|Kf%^_$Qz`ygS&zwjbcw>SA*!>AalON^kemwn1m>PE5%4c=x zS;|*V(ip$mTritowArG3{x{WB@T+_ z@&|am=}>a_=wz4a{50^~eu-*?FW!kd#DU|^-^AotMSDafR7IqNXpnNtjUXM83!Uz7 z$?_kr%5kM>Wal?(uVTkGSfJ}f)LOfd$Vc8R%EoM76+Ac{-}m~J+gllpO@eD9Pi*4P zpzM>$OBNPcNXs9%6M27x|0wb6-DjMbCP*_JH(ru%H#$+M$b-FfLNk&+GFVlA@9QuB4w z#7C`g4oB$VmkX28^!n=h85R3xZw^}{B#-%C5>l$|CVZcUbO)1JgtLXQYoN$wMuV6U zZBzOi8h3|Iz)XM&MWjHCqSp@c)*~9G_Mu{RQI>*TxX)HSSBtMwB zUF$pXye<rniP_KP{A*=Wnpj9b0JXoZr-Z2WGx+b8p*emY%uc zZ<)^SA6~uFQ8WUS7z*ybEnP{F5o5G}FGE^-sSq;cl>!-ORFC_U5q? zh(&EyroyxBd+W1l1a@h!HF>Ro;H^wv46^p=9LwWCwO~ zrfS(0cEece5gq;B<>whCyaq_ASw!Jf%j$Pl}67cSi1!Q`@Q>NSa31+Qqfp?ZKLV*j8>ubIOgHiYa$CLFYsnS^b*rDA zeX6uoG>b7T2cE%*%%SgHJi$I*1`30moP0djE7w3BxB$qk%Jom@-P!29dn=0+D+VjkUhD@*jv~G`=XDSU;DX2 zeU_Oi+`4|*x_oF>qwaut!Eb*$iPKKGXlcMP{us9`n7{o|1eP0J`c5DSC+$gQ*`QOt zc+$!B;6U2W_!lc1x*z55(3|F90kXmv=bmY>Eh_ku0T=-o@-E0LggdGq4}l`tqpDKu z^hc3x_}_uN7F#4+PVSZ2vL$s>gQV7zB-=51I>A?f`j*rz2Bd-^Erp({RhM^m*Ly9n z7evi3NW8Ym-0dzL=Ok0d7kVyv?KAdkQ=!OZ>eFa@ojo63+Tp#26%o8&pS_f(>_(Q# zQMq|4n%RYjx~QH_5WYeMG?^rWn&C+LW%b@O-Yn zGIurK%;`u}uOW~;{2DapbDt1OvWvoPj0tEZRDnEXLe1WSSfK0WaNV&~F&Dg>YRUO4 zWU`~$ls0#^!v<4Fl3?Xv$n&BZqtON*`PEz(Sya&^DV;GqZh@8zkSGv7BHNheSL{9h zAW%MJpI#ba3FG;18^V3vP^%hsb(}2_sh2n=)c9_Q9rg>a=~xv0qWIJwnmFC_SP%P{ z1*Fs=KMD9hSx`pEA#k6aHvC{1?E5u14Dr9=W`I5bH{Szrv+DS0B>niDVd9mI7UBKY zecCMT7dzKGVDk}r3UW^!HXT<2Kx+a$2{u>?;mhAc>U%^@T>m(#nNNg`J?5{d;R-xE z!}9SpT7gBCf^sg}iZ_}3m~-2=0|f9R#u2k-xtH1Hp9{_hln|Hn69pD)<sOoWD5V_HT*`?+eAq z3aR@^&|cDeW~cq@66&I3gym~ss#ELidlN25i2sd&lW$oB>p}Wc-3LU&|HHw<1OujN zAU=*Rm+>i+jRQwX0kYV%=2kAU!-f4shJ!1Z@0nfdrPSo#CGws3(<3O6_7Rel(z zoQ)#q|G6g9^X?A5Sfk+$xK%e4sUw;M&H>&o6m~H4^~5(Uh+nh!uOeW@&MC+l?DjZUEalGf`oK#~`GW6Mh0NuQx@Z^i1VD5l ziz@H`zWeIb^5SfoPgf`)K_8-zgFcKO@3(wn1)Q0rfS^pDNlN}HA=i8I`PG~Wh84s2 z_X+ppA0OW?v|c_#k`@^%&N1lsDvqrSarM-hZ(|8Fl3Ybr@S24|zoxiOQJG~T0S2u9 zp`1YMd{s_hfwdd2+UCsP6`DsaFE!U(%gk(;45b#8esM^;srBdiA1tKYxn_*usS}N7 zlM$%oD7t@Bu>DSZUdx?TI&TO#CaY%!Aa9xx0@`TO3ki))T0~cJ`7%Hq%^AEeGwx_? z_p}M*oc&h=O^P(P>y9*|+%&UbN$m+<8Z$}(=qEy6R-W#fL_ON!Fa6`P(XG46HkMf5 zXhzExf8B-wf)0Xf*vCcfw}$-Hmx4CXz?3C8Q;;MW>!|tsv7Q$q8kXRh=5bNRYn-`$ zWfqNf!v?6GDQj2hkMIT@GUH@{xOK12h)oQdc}HWpDy*czwVTmZ=WL~2XI=##Ovw1y zaWvU1mE4y$>A3Hxsq2(yF_Dj7`YoFlc>fJKe*Rk2n~2%3ciJbPajTdZ8SR~YCpIV{ zae5bGOhc3ZP~}o{DrXyJAzg+70FU4P{!V{J#m!9;+{YNu5DR01#(TuZ;nEJ!sp^MM zJghb)fM6rP^b^m~q9cFP$bzfI55&i(C;z$Y;y2zJ+r2XND%y%PbPT6Xo=9n4G?2AP zUf;+tLnBMPgo7e>{Mz?INy)UrTD%1q<26#aWl22c-xY}LM@Qz+6a_<|b$a-wL);9w z;M?63ld(~(6U-vCpb^QtIF!t_N+6j7rBYKNnR|Ai;@+NIp&P{dL2CU7b?hs{0J8=5 z8z59r-LXmf!OJfLw)I+fBY8t_gojEWy)Ek05Iq8_D9yc&KwUXkKL!dB{(!HDJ;j_$DC%MZc<8w_WkA+J}37J@BjXDMx zS*m5kV#u`+Fo1Q}mIG1wHMp!CXc=>^2G`%ex6({4lfvy?SQy8H>}vi6F3xy+c94jP zNzt&eNlvyt`HpEZODJ+&I z^M`nS4go7;O~cNd(96sd>Zdzp=T*CzM?|c|z%`P2JhaJG;PxSO1``YIHz0j8C71%? zeL6xSYq`%f?d6lNKVi%$e?;Zlr@DO?`DK6HxNmvx(!SU`xD$2kjuX?u64O zwgeWfqXI-p1OOmGWt-o1b?#;h>AMI&x-S3-s#DQ}>N{kQ<#}{7#T1LWA)# z6op85^lFE-|6FXz3=VU>B}5q`cko?e)y@olB*j!EF$M;8yrY2USNkW;j9)-g7r)Y6TvN#h;qKC z8Sz8v+PiM+PSN~cs8qovZLmC5$n4@MEn<<6;uc085F%i7xEjC{FA;kJ>5uWU*BU@R zBV5pXkhhp`&|0wL5TJj^+C}9+%Gl1LN*3a!5}%yDnvVhYQ>!jTu#vtC*2*$YY>3*6 zBi>MjGePCkz-=gdEVBRtICT*??e}LGx;UkWYdxMc@&Yz5?Fto-nl_ifzdyIiV7~8f z%?Yv>mU_Wysc821x+e;WEK{hP%L?wOoLnU}IqK{Xb;i!@d4__}-c7$83+!8d#M#fI z<`24LA$vx|5>{!KfUHXjI)xLM+es7M!KupvHJLT4{WQ%TpgH1%6~1kzj;~>w{zLJ; zk;oFgDq6!IdFcFThVOTFJ9;n zEWd~?(?mzKzG3%l!%7#cLe*m3)MIsoW5?`llXA7f=k9%`?1IiL9D>o;k99Cuo?FM4 z+C%p{@L|Z#{+ii`>D}dUglca?G(${}nT8^4R0T|Adjj*U3=^=C;cU_8Nm_0qFqa@} zV$AIdf7vCwrgX6Rv7m?%2m5t5qPjl8bMPj^?z5r5-4OmHr}~%Ika6RL*J~!!fz)D* zSqN5hM`jZQh>)o^)7>{t76KFStlKFe;l6YPJZ^sV{L2@09zVCuw2SE${><_4i{4^I zVVMc!J0N1{hojP05|RDHnnG)7w^xVg&d}S9GU+H4BU-}|r1b#~PJ@sG#9z8J4E{Ls z+TXy(I?=B1*ko(r5NM}pi#+X^QwPC(!4-`o~=VQNA zhtSHF0gU`Is_jOWFa!`D48~pm8X!L26foX_Sd>)sW0nRN2<`bu%7wW;l^lI$&X z+%HAkYI?@pNVu*bEs!c;S(pCm*%6g>B8GE3mR}(|W4fb4#@4j3nQ*!fW5y|XXzKLzbK~)-lTUNdITXHi3+&) zUY9UTDF^t&h*Q|DglT)qz}h!N&eb`i1@&dC`K2T72Rf|x?N{~n$$VKj zKJ^`cTuchtt77Y;gXMC>FIp3u{UM#hXMHRWZq>rq8E3((#4${Wd7;1Exu17PJ#a0RPkxL`@` zxoP0IO~?~_a(^Wh7Smz)sIbp8{2Oqw73P`uIcXji->d_1HFLuZjbW;P8}>v2!yd-X zrj>dHzhOT;f+E;{S;EaR__m|?%*+%E;mq+!^zyRKsLXe%>_kL;Akwyxy|)IFmIn*4 z>|s4X4H_3xveXdM#22}{9XJqe+=czV2Px2!Lpt69c?jI8I18Nt+dD*w1>3UVd5) z)1-#cl;&K9~U2QRLz0LX&4K1w=-rrD5 z++%NCg>IfrMzzvrSVnw&V-I5;=??XMx8M4x=CFD{`THj zt~orKXdP!B4+w_H2P}S2Isdl!5&nn8Z~lp>d!L5qq4@v|iEm<=zqvcz`_Pd=L5c1Q zy#nKlYVqF@81GC!75NdlC@&mebi_0{BfMiX19uVFWBGjxwNbYZ`YL_LFHj%7TF84N zoTHG?MSrp3{{_JSdmqC88wC?CSop`@NB%1KxS1yEkfa`H{#>@kRHYZTA20y;fZaKP zj>dQUS2Xj2Hv_`!$!6GcvzNn3Y?(j@ONWx}QW|FFUyOTGKV=vXgvvagq7xID>NtQP zaRn84Q!L2pmySj3L8fy=zkFpniRQ!(X@sKJ69;=4*edMy5R#%=i8IR*5Fd_Ekdu!r z*3l;4InKd^E@C*G3iNgOh-A+o{T|Wolb}xu;;`9Xd{W3jv7o?TW?0bJw0?Uy9unp> z|KR{61+rFxQf>;82L_B#eP;QDYNY^C5|sx%+T7Pe|Z3v01u$q0pmBcX|98a z6ES|E1KhoTI=8)Mb6z6FTm2~Q_U5eL7L-cL0~Nhz2<&qyRTDWp0xC*!{!lgKIEQZH zemBLZd*Yn9PaVK~Nf&m{g@;tg`WOX>25?na*5HbmE$O=X86-<6`fAcV@dGJmXce23 zxvIgBR6B~ovA!_RcMx)HIG&>2Okz}T{>-Qc>Zt>Ua@I(SKO7Sj*)pA8xFqvB?g zq$K>+wcq@F+mvLd-D+(|Dkn3p8t^_)#l9|iA?O6_&Y;21M>TV%~!k7wmh6f^LjuAaIdrm;&LiTBn zS@n|qzg>a=GizGVqKv;%+DXImWZc-4N;A=3AE3F$*cg;k_o2fdW%3wgvZ&=V`8Hp| z6pw|aq%Ti9(wSt_SCivQOM?xFKLV`JO>I(lqiYTvV)7PT^qgFmYj1n<&lrDVksVh6 zOAQG#?-en{QaIMbBb$Boel0cvvzMdrYW4?m*JX-RI5Vm`w``C4Z11*&HGn91E04L5o3aUj)moe|jMeR;;nQ?EvdH|Cuzqm6_JXV4f^b z8pK?FAWCp4=k32dg9!$pjExR#qkp*uJ1@Wv#A%h*mbit(`K41g*!iw57`f>xr`S{njwo3VI#VUZl- za3Co-7nbcb{0A8G#W?WcXgd&zK2_K|=D=~H!+%~P|Qf&*m24T9c``H+-lKKIn27Mr(V-c&49PNW zM~Gh^d7`M>k-UW{ld#g~V2^1JcSCJ|4~37$OYvP2hhdI-h>|}`4yYbh1fEB5wqI?&BXj%KZJ2zx{)=g% z>n(NDjBJ3q)US;<)F{;b7$lmbd+E2kMlD1eOk;NqXjKUw1>{^#dA2OEc9~M4oV6*^ zgp99QjY=9+rG4*UiLNv&mc0hTd~FF^B0oDGu%$Ha5GzHaRcS=oMWZ|*6^M`BKAsS~n%%FYOYB9f;6%P2_pZ=)c+?5n)hRLfB>GD(g~$XZ!EfbiVw#ri~g zZIfo?@nkhj1b?~CNHegVt=3qojZ%*QQRWQ;9O|3(0SJN!N`}UV7Iik5B;UgqcXl_2 zi=Rd~=gv37cQCdV$Zt66f1;w>843!twcq$xP%dT-f*8Uh66;bA4ib+OQ^&)sB!SG4 zgTlPj!hN$Vsp+z!B2d0cWa*7X3)gk=rIfDf&b_M6*<1Grq5B9L)+Iy%`125X-EBq`z=DI*3;IhmKw6mh@586Ad#`66~R?D=O!%|tp{Sf@fSO?x<|?| z5z(nTO$^r&m!6X<3%Ek&2PU`f&}!X!OZqodq3bA+SDX+tRa48Om34fPBfG_#MFXA) z-i5Jy&g-jJypR$H^3MB?SN`@dUCZ3OV;dW;1bzBSIYEp z3klU+Bp#42ZL>+Ctr?Q>29N5jR@u4E2)JhwuD(#->pr9s8;_Lm5P3h+5xPDPwym*l zqKS5u=rr?C=ZjKx0*#c_?qb!hWAj&r_E5=}6Psldtyk|ZcdtUO^Fz1pCTgo~sl6;q*U)dUBvG}RlnEi|9pP)z^CSM5Z6blZ3(9w-=t+8O~7CPe;{YzoyX!R3 zdWc7U(in9UFIzeZjW~F5mXSvSrM|F(Uv^0+Z)g=UIXyiauTo>8;-PlQp8{vzG0OJwWf9ccON98((Gpzvfa?G{7?n@v^EzO zY~7x+pFz9VH06S0PxS266PB0Bh zkr#X+jA4BINLUdv(X<-zhItNPGIvz5gG)B%vW4YUS6SY_+a-OVo#u1%_Tb0 z9JRPhI{`=LH)OnZcfhAP9~6K{y!FMff`1Rj^O5)D$K=HLFeL-fla1=vF}yFe-I1iKyi*A1>^Ey4oV2k=|JD0S#=&c9!yz8?g3 zvnrHY0ii1**1R); zvb)!@2ysHnH8oy zAC;AwcCEH{eoyycWkETT{rEMo`aP@S&mIEbIM5PRDu|2WHewo+%C~gm@COgO`F>D; z^DM^?^mx9(eP6rJFLGI-4@c+7<28c)&@dyBuj_y^Q>^aui&Iyy7s0bl7a679al+WN z{=ftBDNb(`uO7o`{V$N}YQTU--q=4M+LoNv(m>nqzOt-XNJp92R%tB@tJ#$Qp&@>q zsO4zSw)B81@7dZ=Tu6yuQ`MKcC!@zHsgJa z^&|Nk?!LbdqOHJtMuTPSgATb~)QBY@bmnB`U4YoiQ5&suTgz$|vjM`>A3VR6d{-emeXBpL&xqT zwJJ`ZQ|6hBES{&D=rKH5gJBRiB6mHScCUr*)o+qk_+1ib!bal8&N&NwRFGDz`VUz5 z)ka(%R&P%(0g@-k8KOHlWNzp9ieb^I0?QGrlV3}T`-%jC@gY4E@-@nVDtVNpCu(vH zabGMM`O+5VctOR_HRlXT&EXp{Skk7JX5;Er;Xfx7njV&M^fSzdA=6v)U?REC5iScE zfeZA#E~h^1>+H!2#Ij@;kj7FNvE6mYWBC>A8Uo*R67^qOn+M_B4rT zOA{9c4mDA{DvKt){`P!JT>CS|#f?BKF+U>TZg`{brJ~^bC$F=m}eZpf({C!d&@@qo?rDvkK|NbS|Rwp{#q0@C*a( zKL(OeG2I4RtQC)IPD6-@>W^7OyLPqTdgyRKd8y~2u1G#nV4C3(~+ycXxxD|GwXhu z+$HFSU(crCKu?mjQ4n} zJ*yp5<6E|V8p)gKe=-$(WsVBEUj6=6ogJFE0Xik4{x1x)6Gd{5MBSs!1cRrqex*Pg zz*@erl-37T!?z1@ynZ=2B?9wcU6G5pG<PfUwa)qeIJ4HQiM5{n+|R!Ix~_fi?x#NtDqVsQYAno| z$gk&yo)e3baR`0l{bY-RePWd%@1$~ksXpKLA;1O%Rw-uQk)3+Bbg)m6p9q9w?rf3jl;z+3;o`u zmL8~I61!1Xq*8z4d@br3ZL^k28#=ifXae*6RkTeNZC?ZY}v< z^JKHX>}Ag|_X+9#IQv8dvPkWV-V=El;S2_Kk$Q8luhsa7S|_B-;EGgqF4Tl1|3wEL z%bF|&WBXxL8WtpJ^qhbb;*^j+&mcZ&+dQP5(U#9fS7IBooTj_e(i2J0 zA!|e5SUg(Xf8Jpc!l3TA)A)BjAr&&V;3APmF2_3i8bsJ=1wtUiQjWn5wHgV<^JYPA zpBjWVHe2?IyI7(U#*y{RIQ6J{Vo{tjZ%07MUv{>m-+JPBsa!oJ$)XRfEjA`76xXL4 zh-2Ha?NzPEBL&yu=7q1~oOv@Qi?|!Mo;6(BAg{D~8tdi@?;*hZPQ9;t&xbJsM%gpI zp4Q%~`*jl#vSkG^o+C{u?W=?JV!vq>+${`K9$5w=sZ;ZU8OiStJklR}O=LHp0>dPS zTizyvRyz6BJq~yvaFUS8f~`4V+0o3n@?jU{Foef(=Hnb^NSrKPh%t=L4`^kxjK8r# zNf4{N?8Ab%_Q25yM#9WHmN`Dzfw~J5?jCnnNLIQpE(c^momGRMaxC4`>G_TirkqM_ zP>)<=6>RMS;U2cNS$%$Kpcx3%jD%;+@~xd6rG)3Ncw0whD4gDpu6<{{2|*`O_KP_K zXy%?Qa@iKoe#Sgpy>5|z6)-&Q&VZaYx+FsPTJDk>c&|V2Tyo&g+y@O6JRl(G}hT_WavA1WVG_&Ei3DDX6CIkv&3uoY#b;S99Jrq)a*9P=ii1# zaVTGRgvlVC;t3eAB&K}&EP-BhWEDH9gIlJENJbm!dh5NO6GdRPClSU#Rw!~!VZRs( ze@}6($fVo0x117QkaE{^rg5@#^g=xt`?Itm@7#DL3U+fl5lS?4i#hp1F-v=kN&v^! z4yQ#g|MF^~8RJ*)l2(s9Y4tV5z%=s5X${PQFJL)qDkB9Lao2qm>QV!c#>gM-eIi@W zCUS|xCbDjQV39Ptw?(Q|xHfiFXnK9S8e9GVoCmHBaz5|9jRKZl0H)whmZig9d40`A z!vzXfciY^mfb&$6*OvGX*yZDfg25f3in;$JLUj2Ev z#Jf9}UzS(Vjwc^emH8U0E^%-!(6c6YrzT<*!Oer%pMl^VL66reW$LdKv!)oUeBm8* zjMVA05xb0WaVtUzNX2Q+f~q1s0PK=4qc0!ax8RYLEs=D5Ho~h(MIWvl=T_fm5*qY9 z+#eaLmYtb`P!xH;U8e7KSa~h;$yN9p{Gh752b*O0i#ip9VkO2NnEx5;^dp3`M(UTK zw;`v<>qrw#F-%-8y=QxJmBJdZ-BKNS4Np(j8*>`vSXVnT@l}+Wi+ynGllcdHiTZ

OgBnTOOLJB*0wl2b3D}GUn?Rxclc^&>>6mRw5K&CAT-Sb!$Di>|{jTb$B^gz*d)&XN zAVY$?{hzC-sR@}ZohFknHH9#xQbq3WF!CT zWx4F7S!v;8KS6Z!RX1QO_2*p*@@nTb1Vd3BY84tp++NF@eoR?#KoScO*mC141k)jtpg zb;QB+SmHZ=fxqtU@R)nn4Crf0q&4*$SRw&v!F-Hdnv5|2I+fIXQJ+7$i3(m zU3`Lp%}t944p#wx(;j`?0KCz>$${td7hpIr`p|UI-|5FLr;6sX-yFGx?<29JpG-}$WtnHJuDORNqVm6Awun5vRmSuxcuD&CVK-8};lwbi68TIj z!>MQBEd8s!E!~_@P(Qu-(PM9fxp3p-&1s4F&U&Ei@LVLX>o1#;iN(;3y}7K_*g#6( zokyal=>>N;zpW*q@gr&3kli-(b7kTD%=gdy0{e-tLcwZiAc?0FI8jc>C#Ge97ui6RO zKVELUXC3&mxc8lb&(WB$uc~3{X^m{VHjvsUXg5HgrZwlup5RqfQAhrP1>S(TSsgN0C6g?vE#w1odJrzeZVs zJ;2UyY__6w@!L6(EFt{Q=%BO*e;ya`mM-03o5W7M2#E-o1OhjLC*Jr1OadwZXkL3Y z>g~hh_S&p_^%$=3=n$3Nv5Tp85`m|0Zx3ClaOf@8Ne})QuIDzk4Hmj5l>W)TQWa>{ z=F~t|Km2^3Ph4euTmO^G;LMFQ*FEdxQOpvO08sji13ITf-nR%iOf0ypcX(R_q|uSp}xpo4LC4>yt!CE25G_xgL?Q%TI1jnTG_Y zf#iQ-J+Yl=aneE0%Xp8Unp=sydBrDMihhu2Maoca^tuovP2@h%Ytn5Q z)~W?D!xfZFNE!hqk+6*&S#)k}ls)vao<~Hi7J)5_8?B^{=F5-P%b{a>L4p?%5wdj4 zG3A4YVJ@Wv#;|+zX9VIUXFvQFZI{h*xsCjzIcyf8+yJa6ILig=NjW(u?F3%IIws~- z3)O&1!`tEVydklJZw`{*whIQ^?pHy^6dG${4|RJ)MpxeJNsG6s>OuWJght+2g^Eo0 zbiq%HcAL^FAKHTP_vnP*@+^^I8|FjLYXW*b=T(r{Bh~^h?>`xVhzOd2qQQ z?C5rSeP$4dpa__Y`c!XYsy|GAe&{86nVYCgNPpNSU{d4a=OYmiRNjw8x<11Xe0y6Y zvxS-u6n6Lbnd|rX!?f`Mg0fI$leeg+$lJu@X zu<1r6g2Q_}{0DgM4Mn}Udl){63Ef+o))+kC+dNSakr$W$!}$Y;h2`Cm;q;|nkXc8$ z8f^q+z8K8`4*lH}|43|EL;`)umR2gzGlAA>+VZ63UW|4E2mKj&Zp7T4P{9_Or0j2u zkl40b<{s%J*`VP1BlYb>BizwjRv&3LUM>JF$1)-0sIlt=zE31CA2` z@Y{AFDg>JxbrkC<*F}YGH`%eSkXi91;T#=QZhHFScv2Wyeg|%wljqZgJG%59(umcp zqBaY<32H{Bs^Rx|bnSjalUv(3FT-?rhJ#-lvdloe_5W@eduFqlG^P2=^FpXYKzT7^ z9xi+h`kxo9gh>Cb8|;NSliyt@SezWR`M0J>gG@zQ8qn_2zoc!*t=oSm$MI& z3^c&`^J`gBE&AF8PP7%{aU=t}39$~nZ{Ztm-4klunNDmKc%ohLDiE%J?h^FV-Sc;X zTDs0J-$CfG3%eUIVUBGgb_;{%4B5md5J)BGXvI%FV2Hk4@P`1QETS6M)Lyt_+tAVL2;_);WAZ*vgU(jMaBWF=MO3Od&_5-axE7-VxpFKPu_tn#vt0ghR4^HL}x?@SPXti zUTWI!;QoWVPTP?8F8${(80H*^gtICnMwS!Q*?v68uZ4Ps4ryli!7(nZz1{Xv((cIw z$H5CXmo62HXGMEPS|CC`ZS~4wDSIC%!TqubMsC4AdL!oj90sw=Hmjxcho&{`d(7%p zMidk_%>8cr=mD$O=S^`}rQv=bW)tR5+Zx<=lsl;+3yOW82?m_@r(}|m#;`i)A|Lb; zOfnhL7-4D}+upCl0Xxy=U6p!yHsoACAmc^y!0CAzIsa5)ozUO9Mv-sdeS?&{lMSv6 za`xB)apa!OBNVszun!itEqLxFxgpyG=|2JQ1K}3-V>B4e_0T()!*^d>6u>!4Clv%@ za*j@XA&c+@sx#lF=&t5Ah#ak{4E7I9!Yr1+f-2LO(QlR2B zE`8IvxIaC__VOJrt^d-7wOsI`h#~}FUS~ld$L}kn+qB8dJn<}PzKOn}$+*V6Syld* zIEAC1#yl~l^YW+n%Vy|`R2nt=#DkeBk)7JQjJpIc0^!|tMc`25NSH0X;`G8B_O(jW zep!DgbU|XNeg~LZgD|mtHGX+eedNKu$7yt7(q0}!O^2;xT$GT|ChrH9>ghG4QJStg z<1lugayrh)jZ69!B6S59bZXee$-b!^b@K`0vCFP(a+V}n>WnPh%=iTit}QR7`ju;u z5DGe{n*!KAnXE`!Hr-m~v{Z${23q2mSjI0YMXZhA_XFJ`pqyQuB_;7PHY=kcXIMmY zYRC&WahnB`pDH>A8NKyZVQ;96<#t@|W~y3f{g{kcDq6*efU|(rIf7s&Z>2VmPa;_E zysO)iw~!?t^HE1<8z1ZwNX;M$F11{(r~-bmxBZw%Lj7OJ^UXxh>bF8j-4M|QrBJkz zl>5uDIfGz{dPtC`{=LJdzF+`VH#_H-kvTpOoJWc!YI#}QeH=&GC|quA&F$3D%g-|V z1!os)^&_6^qu@(fhj%cTh@v|T@z29&jCwPy%s{!mIfQJ#edK`~84g*Aj8z zOCx8;9uv?(r*UIgGg(n>)GP%l7)hu&9ilVAWEmXXWFcnB>|3zz^AOcGH=Ya%66N5z zQQP1NB6#(DDj`v+c>5dpYseAFjh@vhYEz=NLG!`o z_xwS|S$jYfmU%8hydzfF<(d)<^)GIGN&~y^oeA`-fP%|zxRnj_bAD|CkQsB0f-)13 zx=VslO#jIM_&iHOhEjsVG9%+n2=_*Me)uRnN;Je_h;9pJa?^2k#7~m zIe6}?q3WZE+mIg9J?nda?Tlbeu-0#p*^!8^l{I7C=Z9$3xSxq+09p0e5F}Yyj)lWD$|M4%V+N379k(t9_?}jl9%x$fu4Lq-j0uV6Pp)1XtT5`u+8_oaBlOMSlBmFXp$|D}$l$1U*9)8G1Ja{DT+@`W)=fYr%{%VSSgP|Tt$X~)2 zLx4$}9*1gi`mWf|3y|%~X_R>3mHZSIeF~2Je`)|6EEieaJdNaLtu}r9mRhF!TB1B} zoA;#3HT+QA(uNF6_UI{?$2i=fLh(dhoMf=!VO=GDIn+$2F zCBmb8)1pGC5puYfB|d82;u`A}>6;!LtJ?Ckey5CW!Mh)#?j6ly-TGb|gWmGZ|Cbuz zF^Xenl_32O@dl*3g^VnlNvrx#de!E(=6vbKPF3yfwg39UA7_a3kN=wlU^d!oTy0eN zAT*aTh}t3Lc_a_LWv8ovuM|s^3rO&NtGDxXY;XU|BhpeB!cvfEZ#b?frIUFbE6W>IdP;!S+TX&85M{K% zdi^bNqJGSx&&h71YoRDTKNiZv>{-f?gUVQjyuT%5eX-w3$XE5Z%ug-qH8kcK`$t>& zehdCpiqP|i?Z*0g$_RU__U%WY{PNoJWwrKWUCQ!*Trore0=-vGQ}fym&!v-M!HMzW zi|nt4xcae@dsS~7YC9$Wwp)og{&#Kcqx>wxpOpQR?dL!4T3*FNgewc8ykhc--CeW{ z&mDXzaS?M&`d5vEnWZull8vQ};99YDo26{Z+T*;2NgCcFxnM)ZW{)oCQVRCS?OA-2PsY z*w2)h9SdC-XOYDe(Ll9=u1`uPto8?_oXv()U2RuY7KeU&=|Nu`=}_>Ps4D6TLcT0g zGP0tQz09=4`Bm}OSDJ3wtv4eGD@P+q`Ig zoGEvzUR+)>5=Vdi82XQlCgr`eN%gKpT;aA}BV=Z#oiMgZ%V+*2bx>iG#dAJ)hHy(P z`6(Ovg3W{i_>``O{<0~T^Ro(A0S^;OHbWWPZQEgtxmbtiMdkdOoKM?Vz~Q+V9_CuXJ{*Raai6Vqemk(gJOX{e~?oSucl>@1=6K9-sia z&&ipjn-)n;c2#g$`1oMkKQjpu+BRbiagQ)nokVQ$3@sQ6Z==UyLCrmFAba6f{$KVH)zLn?c z5c6J+l^zc6)r-g`YPmS7xr3(&BgZmEYA>v`Z6N+fgOdSj&&Fusk=+pWSOl)7LTMl>-QX9S?3k^Fp&srsy@ju1#5^1v zQf3N7*r&0nrUa$WgpJV@|N8$r?p$Ew#IbfaKy91%+>>=kBLn&QP?719b*=q582Xu! zC)Y48E(eo--E^S)MhnxcgMDh*9tIEx7=8SH`eNho`2BS7IV@1fpFqM!g!7sGVec`< zRH5DcqHWOXZI3;#`q{?;F){ihZssA$#1})Fv53_%u@OXdMNMS`IYXPorTt zPOHCWNL)J!12xsxyDtio#G1thC^gNyd5r$t*nu_VHw=R78AoTdAJ5K6#OO`L2)k2v zVROuk5c832JPm{I9SD@^%S@W*7>R~o+((YG0tmwdN-KEYsb0RL-lY&wjY$^GG0F`) zOb>%UR~(~x%@`v6+=1yry*p1WM8W%|rT{b*pQT(TwX)zL)lnSRm@pYs`dYUI^n_Yj~ zKo3q9$~!@^ZD(L9n|byh-`i--8Y@pmy$79_xsNnEmrm;gxm@~d!v2hSiwV&xE8jNp z@nP;FC@Cmds5jPaf-;6`S1uV@<)O^V1_vd}k}>N+sLXe(LT}=da$cOCZT7R`2bg0< zjSc{9x zPu>$d`4x4FnZozV;Tv>4rW@fi(qtO&E1Z3Q?dIsVmr{MjudK|2M8jLu-R()9)54zR zsx5@}H4GQ7%*OJbuFxGDFhzBGJ%q2MhKw79LE|0Vp83Bz?%RaltvemN+%jP~_ zwvZWjzgrg~4?#OB*ivAIom6s(`Lx#7H zW|T46w3LDT5V*enq8qd)IiNkJW8|naRxU4e@x5cZ(0JP6UJu`UB*L8jy0*KsBT>(Z&~j(e`^V)D194T<0ywcmJ9cvNGo!L6 z6)ls{uB6&l2#?XnffTjw(=-*m4^*%G!iT(-amwc%Ij!!K8WzrRjP#Ih#5e3%>_GsN z(Ec8;%f;eXvj`%o9LtweR1#CAx}E^uyqF#0U8&>Wy`yfvkqY`77lFhxV&MfS&ZRte zZae#O$~gWxbJTt7k-SZxxMbTgJQpr*No-Mz%l5?o<|6C73-iKr1yeCebG1puZHd?g z@}bT+WuF`_hM^rqPvIo( zv*tINPGh8SMC(0?bYb;ZW#F%}8(4;p*HO66`&`5^in*%J3nbEUKs9Ttt(Tw<+~|!@kUWyFnsB1mN_ppNHn5l zB;;IyL}?`obNd52M~O}){={T~NyG04CrYE&XhHn^7`!~xJ-qb@LlQIv!D7b^>Qf#6 za)>miPQv;=8+WtL7_y>4bhlJ9QMHwf7sjG1w8io*pg&zauR+7DOxmR_y!B4cnYiv_ zqcpiBYIV|G(sfuVgJt9A>~W`gG`%M7=h7`f3o-e)7AWa1_bkm(mwGndSge6Lvg6T{ zqFmw9wObGfp3L2XZ>sBq4!vVgIw#>{%M$>f_s3sO2&@8>Ek9!_Hh#qz&C{P7WpGQL zuc~WW7*CzlhXfi9%!R0YUdl}8vF0O^S1yY9TcrvLT^!)?Im_9q(m6$gdB@5+E1k|o zr8Y6?eff-ujx<;Fj6NGv)6CSw^LN>J9X8P(I10Dt2Z#PX#=+*gg%YEOxQGh3TIk2a znwJip{T&jo=@PXoX)e0HUeE`RzD4R-oQz?UWT;0a*9M}?Jxhf*I^p7K0^ZDPOm^+A z9M>_hNH=y6j}dY1{B(xpGTqu{$avt|T&Jp{7S3{0*!&CRJq2Le_r&}B3=`uTM&?fP zCF?lsQMRs?Jj**)Y!ouhGT%4vhskn!2aq8ww33q)*_nrFJ;(!df#{~N>w4Ui?P^1B zG5gh0UDs;^w|iar;!#0KQKwC8oe%pQ))?`BM(u2Ll)L8NwPT!2KskJUjgGYmApUHxS{%O`JKQ4%c;raFRRRn!rVhSHU9Ql#oQmWD#aN<3yP$=8} zxlMT}$A|$6==URUh#c^d8Bc*Q(p%=lIS9`v)eNVq4+D?wNIYt3ODib#W)W*TK2`v&@rR;f3@&O zeon88D%nkl-41)VQV+T-CmKZKW;az?d{YrpRTVL*A8#fKeqL4SL=av2#WV6P*RFha zxAW<5;2_sEi`uqWw4Z**mGELOK0ajl=g(JvUgXPPD-YL>w2^^f4H(8PjbF!l3CxEb zTvm=hQcwraA#L`LQU!a>e4eeJwJ^3dv{RyGwOzJ{C>}dW?*Wk;<$FB0Eo(?z+;P;b zkTdjWrH6RO1i^a4LFX2mm9qEcPIeQMe!RP>t0j?bCL)VMgU&dZjDy2+$~WgfBr4E4 z_WjZ+*~X`ak=pkqOW}o2E;GzZcUZVaf6Zqd2Yl^~ zEQoowq0*CK?}X?6Ih%JO?e3d6nDWe(0;4_YGhe#vi_@7G;*MuWwUs9ixj!5$!`;*d z_-9$jAKJoyWj? z!U4fxoTSO+xA5BEdVWj9T6hQ2x8He0po)k8Z@ETT52s;Z5)T>=&0F~;zEmJ=cE7ig zsKuRMCs#LaNr>Orw3<@*-)fC~IAF!;tp#C(ypQQKR)!(_9>*~1rodi~(zDHn5(Zu% zXLZXur1%ORPt+|sY&oCj4XTe$(<#j?wkoO;Ee!QHCRnWoc7nR_K&DBy2;y_xzg-%& znPpI@vWZEIX?lBkp{TKBf)G#N)SjEoKOX?(NUYOqqaL>3v@_$>sRMQDL@qy{e0$*K z%b7EC41@ICgwJ?@wINx*s5*&AM#)y{`>A_(Ui-#{PgU~ZSUY4M0nO^H-u?|jTI{krB29Rg-Zi88yTl!)!8 zYamNuAUUng9o2RPdpf6-OoYX}dFP@aGjhgRw28R?-8Da|uAOSSMA6WGMFVOXxrfHF zJn6OX%bnEx-()ue+b~ws@}o{6IF@Uwm|5h3^$4Z)d@H_RuV0)CC9Kil1&ku@9Yz3@ z!;PDA;njDjGtyn;&eU8w5+TG?9xW9rHzbmWtX1i0?x`cAs5nY|9=rEm4kZm!U@{@9 z*5cu-?$fHMG?z7RrgYE30oM6kt6YtQ=SJU8a$IP=h^1=3Hx;AHCs6aUOZ7!7w5d?% zFRAD%PCDt*c_?k>m#M3jsweL(STG%+u#lLqD8es}d?5lv5d6sDVkv%V8|G4(MPh)Y zNN;P!@914l_=DP7GCNPOyZpJCV1+TV+6%~W>r=;yR)RPe-5@WYaaN~nfzv>}@fnEe z%m`m`w<1O{5cxg(siT9GbuHM(PO5K0^TUUjqDVuP7(zbDKAHXUhFRx4i^Hc743CyV0lN2wpGDEj_+<;9i1b6 z73~$-a@g_B)G)IQ6bA=K{o#oUL{eK4W)EgIHeY zTEy23F6%ue(a0`-rpLVa4gDZf#{R^4-EQbhe^~^fxn^~j|5-=aU!Z2S|NXG_#s-6a zF;3QmMFu|=M;mFJt$mDBaALnR8!JEodD3FZSLN(};1rMKqCO677L$V<Q_*0ix4bDWt?cSRyZzh9A1L-d_z6mhKv*=V1Z|Ace&jit)JN}#(`1d1PsT6V;u z|1SQ#Ro~qgUOHK-KNUU(Ddypo&q|ez`68%sTAwi!1j0>W^v<=yu*u^TE@Zj#oDEOx zAfUJOU)hdNB*Bws%+}82%DG4Hm^c~@>H~F&Vxd4*6#EcuCV_pZ@|>Dh)Ly_oU7)~| zYbUD$wH~Kuq;J+#si#opL^mkndhgciQym&=}RI=uLdycSj{*!2L z`iRB|%{Cm(g{kk00I9yFvMMqN^mj2T!Y~&1`L-wCesRM=G>=S@YM&!&1WQa6mUzB2 z`kKji$Fl8R+_wM3*7cM0QU1YL8KQj5d21B3Lkk$R zq7|V;twJkFn?aVzBJB^%w~vo?aMGk4wC~)LpPB2;rI(ac(DdIlOv5X3w0C^=G%ZW6 zn=frTUaT>Vyj^>|^di*q98F=dEOR$)Ti0lKXltn^e+R84%smX~UyERP{UHB>A9BRN zf8k&B0r-F6J?#JQ$+ za>B)CD4DP-hBC6Myz2ctlRT^zWQ(#6%KPrMbvu!o_!vo0?qlrdk-*>1fGj+%Va~xr zPsqhVN#?mx=vZ!8d9aT+=@c~XRLy_WejlLb=~Ggq8Kif{1aPFCOC}soeJN{~`us!8 z0kM82@uW1xITDSR%2UO8aqMx&amG%pZ+v7~zQ)qmR?AgScw$ydO^d}gpMi%FY;G^5 zms>}zhTux!`Pw?w*BsC`$!*8!d3dWb-ZGE2o?Pmgh^1P0a`L@kdUbwovdz-;0b<4C zQ_QFdGMt*T)s6hL#!jRl>zZ?xb{vku@;7MEz2p%{3HauCwENR&)WwiQ8NldpG==CG z&u(9H+M}YBqHElq{KiUG1crMkIA zf&6=%wz(Se&fRi{iYHWt?tBjGn35D+SF)?zTFmO(!Vl z@EpmF@ zwgRr=UK6fTzr`=5;8elrF3{9s3O^&XgXKGu{{BT@Wx*A$Tey7C5aa1r{_`^h}*})I**x{0;#YjbEBlNmjO4S>|Xx_z49D zlF#`s5>!_KY$w`h3KGT)p49?{?;=5lLrZi|;fS+p<4oXy-)W`VI8bFIsZ&awQ%)dT z1yTz25Od##i0Dcqy=>&=oD8@$aHAo|=XBUXFOlIv1t>*7SjiH4kWux6IdyNJ*}*E^HTb+|Y^6{)Kgd!T{};N6?z{Bqo(E zw-OI7_Q!Z={W!6hb!u(6m<*h(bJBtZI)LYot4NRR1*^;rP{+rpFMzTU`{Rt#FYTc=jfi;{B3M|aR;LSXJt|NGk z1$KrP7Ffn&kYRbz(`sLxR@5i*a%54{ZucnS{C4e@d%t1$u9cpa>l9KcQKU?wkallf zK9!uF>n?wx3PcS%Xa37+N4v>tnKQrmb$|TesCt@`j!7;^?FbRMP1o z#gOj|PuG?73Yv%RThCPH(xmyYjC4pz@Q zO=wK^tEJ!uFg7%Y;_r>sS+FN!)5UX0Hoi|)+px#Y52ELqVL@J`8A99}uT56l5D+y^ ztSk??Jp`Qo>i^&|KGYs_uNs&8J%O*7o&hn7a^`=g;oG5qbYw^=o@~E&VEH7U&l?7(6%yJ`7KH9#vEi|WO$KQB6**3(6y)$*j-P@&vCdhU*? zn{R+SvK@nBrt5_l9b|Mp(4)2>oywXIYEAqh=F`( zSx=0l6#EiG36#!3vzNt=(sR`4+l)ocnZ(OF9^7cKXC~XUN3L+ch@Sr_%o#cu(o)Sj z*w9z~y`OnzlXrO@?jf?42++vvHd=daa^E*f6R;=Ow$MH{_9=IzxgOnZI*c{}Y2QQOu{%`+P?+O}1X0hPZBQITR#a zqULYr^6g=($dwHCZ}~aa9ULjKm#06V&2qvpt9xYy%DnlTr8CAh7${A;0eHz07sa}cvMpsM>OMe zPD!bOG=dk zUeIg87J|NdN^K>@{gw*|VX;)CNPtX;3=$sYV_$ULEgf1Gs#|fy^+B5djT@&UxP$}` zTqwG%ZoeSbQ;hA_+SVet*y=*-oLU z^t2JrsBC=MWVbL8Q|K^!4DTf@aaBc}`OC?PW1HU>)9r=~RaKT{CQguH=c!t`ALl*ML1hD)WjYtFnEkXWlc3%LKPC-2ZStIZoaFZPtfU?)?|7Fb=9_yfz_| zsVf!sW&-MN6Dpy0+=pGA+()Bw%P6?9O+5_sK!`jkh9gCOay)VkgLl?3vIBHS=cg9w z#AaJozPMy}KTtLO!4`K5KIa>dl`tH4<6J9ImVk@Uyl_!-72o|}_BCuC(_H{_=Wo_1 zC|jBOGW=-oQSS2c^pw}f@Nac-p|)$<@Vd`bYs2T>4o-biO6m!WPP)uuNYq~Vp!_Ty zRi4L0G`2WOJKC2$E9rAYmiGk+U#Ev$qp#{0=M_cHHVSnr0$Y9$hn)7gCkU}N4#V@J z)V4fr1kSr3dRq5tC&$?2{(zi=>^r#uOwIH{x}ZZ+0qJ4M^a4FnG0`O6PrEDgF;)PB zQ_}Oz?QLX;nHK}7>sDsqt$=*$B;o7c1ox5GcJVmzp|7eN(j3 z?7`d^PO?3i+ilz0ygUcKl=bBD&eR56%*_g{96N0?YAe zMr<><6pi-AXpp}o!T#Fnm)uR6SsNI*dDUHpm9TajDIfvL9y&USmZP-J49@J_7Q9#s9UDV(g@a&QJj+tFs{Fa9P z#1mv3=-#*lX8!g7>SCV!b~_~3B&E01Fq8`U9aR0$gI64b)6`pE15uOip#YAwFh8!@ zhZ(*7q|=h7@!VRm@JEe;{7xHSvIrK-_8qPvL+jhtTWzQs%Ct1P9gIiCza!WmOdM|M zUUZ#IerXGOBEfb>L1`h_i?dDX!F^5Aa#Y6Jkv$2Z1+E!d>@GbdDKQI1qk6IOi$#N% z#R|OXtp76Mx3q-u_`_fr{w9}$`3hMH5>gp;c@Zz)5Lar^#*lMh)TN5*MD%mbA ziu5rV5!A9ArM1nZ!E=T-IZ5y7IPpM=2WuDpGU#hPny`3 zcNKfIhuy9%Q9tBpYuuR;eVJzwP?KAveq!*b#H8_-iC=n_d|@)u;b|$}j&#_OPHL*H zr0%N7_C5n%M8|E%qJg?vkEdqR-_@^T_??-7~}y4C*e+SpA>OGU1{zO zojy%@Of8vi#(_cg!*!3m{SzMKkM+$GfDe%%!6QC4S1LG0lt0&;MEfY;PV=h*U1XMz{ z6ht9WcJGC0dp#-7Yv-6%o_J(JPDue39kuoH6S>Q1c)6Od+F;>Y#BZ72(nr4?eY@lG zdaXeD(?N?~g<#u*<5KXA=G)LK1;G>EDZ^qPUvo4vo=HIvDJ9kVuU3Qh8O_8TfNHrGP>}UO#!_uYU{VFB6l+aNTKaKzP_ni(KEhZ<23C zYu;4KQZ^?!aA>IR%%M(sM@AW#l%zP)ux_*3#M-+jksAW}4yXl7Nfu>JoTA1QFczZ; z>r!sKrr>ly&Icxr82X_N;q*;+e`V??!Et zGjQ6k1??OWz(>`-gHl$R^67t#1H09h!f!I)8Tfp)(Ysh^Fpkm&Y`lDnS-q;OX^GDv z2W)tYDQnQI9NR{rJe>AMI~uadY1b2t_eTC}@bwN|zc-yuQgwSw$M0B*wI=tzHgd*j z=d+>NIs&VtA75Z`EJ@H3Q6H^FBi80lGm?)9mv z$)dPrZg1-V7RILmYZGC`UPTzmIrUEs>ZOGqY0)uSO4nzy$$GR- z4kn^T5ZxNLbG)9Q=hM>J%yC!A7F5j&7oa-)R(K0!Q~N{+C(}9r4;2ulk0tKpv-iyq z;#M0zu=Hn%i<4qSQBlg_(>w}QoBR`3?QmqzPNQxbJRCnup3 z+d<|+s?fGEc7hsfO<4))($cbI?wQMFCx#pm7KJuAP@$Z?-9Kx5Tb?4}Q13CM#8sf9 zx!)gxRs;m5<#P>6@ua(WN2NMYMXZFQI_7&kgADJ>hOy~WaQ6A!uk*TF8v5EQd_q87 z+#jWrx5;i)7TQ~(%PmgAmv;om!tD%f&KAzO ztCRzLS8Gdr63{Xvb0Z*jDW~)|itKkPDVcCD@icmmas0<(G(LdnMjve9SebUn_YU1* z9pqar*+E!JAhV?0;WDhf6-7D4#O0@;G`Op%dTxT*ZrQ{!SYn_w-Zv!g_y%Kao`)RnWg64ZYeOj!)&Al2 zIL0~!A}?m`1VHUCkgQ9_TGCc-@ynX|_R~1WPdXihC9EG|&3X?0!z1Aj>E}<^UJU|q|=<7S&`g&FTWTSvk zX=1c&e*_|1j#SP41qor)=*)yfB~~SI$?r&eWOV)sRWPEW0;ZAkpO?Q+^``p}V6D30 zefqNm5@J7-abxv%+&-j|ZwG#&lH2z*^H_#4iW4UTWR2LFm`Vhl(tpgAMf7F~X8t%b zoV#BIt>O_*xOsrXeA{$!?;oiCN6=thq$DUxiFg;Ti_T$dKbE8QT6be&}?Kh zk|z|ZzslVE$n!n+oBO?23bz_(J>;CbcWUN?1ydez#-Pf3_s)W;%Mq5cMwe%ws4rEp zGSovMy}fW&o?8TWbx26BpUy5?v;$k@Lo6qQkrPp|*2l#tHx)_e${Lj-<6=n_^N((u(`&619eg38XIhQsh)!b$E-gO!%ySG8>tj%2R{oPzDkIT zCUHtx-K~OrErI9Oq_iVt(RWjo9%c_5mzA!K&;C%Y+0ETre*pNAu_3b>AXzE0=B;tluCPyL(AcY9t9Q zIp($ zH{0-O40Ju{#3;QE=ZatReY_6I0}laj`-FxzW4txls5Jg#HTn$+uocM=Ex)bTs=zkY zIIv;1mC>b7IseE5e?E$<`&dQr^AJ3Ahc5f1`RQl7I4I&LW>pZ~H71t57iHQV=Yp3M z?bsxi5e#MMEG8@!IdBAs${;>2YDGnC84=bWsm=U)yMV_rXB=46)`GjL|Ht`5-U4Vd z?+SUHueP6AUBBi{?r;EpIs!LkFV^+1_&J__pe?}Q@q6GAlH^t3+>eInN)p$K1Tv@pIGu0q)(pE z5VQ$4@!h78k_mquKUe`Wp$thwb>t~%S|^FNCdJzB_eziX>F=CrJ{>V>bJ*WZRX_pg zY%L0tU0QII_~pCY9oz*tO)X8l9mF$dhp&^l6vB8y%-kJ6<@&{^2NFC*znq)jBTUVfiA%-9t`DK=5ddbh1@B3coHBSNlnPkwus7?m z^2y>coAWNIFJXc4uJ$|c_=fXc*d%brIPgKJnNv6K$FnkyTRIL47C5jeCnIE*gD4U5 z6=}VZ180@#@NnWw$&#ZFlk7Ku!CKSspRIWeqrXC;aVaK9NF8f?K4@6>n2M7 zc|@enCk&ml2&(ouF0w=WtEnK);BL`gt1lNK@9Ggzm*{8(m^8Xn%xHA>{O{`FeX|H`biAGw8j+s#FSFdawn-7Jd zSFcP0YGPzkKXzJ^`>BYjC+ot3kyEXk!S-ROw@q_T0pxdr*qTj`wBX5d&%xrfiEO0{ z2V{J3t#z8Ggs59sC<{2SM|2A5uNQ7Z04cSR8j9%72 zgLoxX8$FIIhthE$`UQ{en3LN?&h6brc)=Brzo6vPrx`{rbi(${`~mpSMeI(Z=IJ9y zdc23HXJE-E*GwagnIwxcg z)>O3GQsN6MYfZEe@zB2^*V4(seG$mbhJ3Gs7v{!$qC^X{=FRG>GA$i~XZ*Dd&iIWD z$YOF;a=yDzGNso8wDVZuBDC{xd%bj7n##5Ab63;H8bW6?#|d-ILX^!I)FJZC3n{=A zS7C=W>724_=CQ8~UN*>E$tduPBR-e*$wP~iRrbh3r==n%)aKa+er!)90%Qp!dpZ9d zO?4RRo-fb9V?PCdu1tqas4F_&_av7H#i&?zyFk&_Dcrk$r;ul{CB1#qUN%1R3zZyS zfB@~nlILTWmLgsFN~^;~trXjoS*1(ZJ*41geL`P0X3Yyj=rt`cq?99-CLF~%h1ftr z%Vt_?L;AM*PzR3o;43L@v6TmvVnSRTs!=3A7#7ATGIv166Yx$ntkiQC8w0bVypUme zu#i%(*3dj6^IMGY;E)!lrI1SKfau0E0&knoSRkCL#VR#zQOwk6%`Ucj2Xn$Ezi2LO z6e`TBn;pkzaYOT%y-HEkEB3i;KKGZ9u$DA5+-zH&h(g8rkLcIf)?}- zYyY7@f&nlf?@a(kes;Jr{se{BiT&N|o zV)VIu&|DBS=mUD4BmBz;1LO4`@ELGDyA;R z$qmu%Xi$ly#N-aiB|y~g|Kj#C_`7vNq+s~_&a*C*s>%0g2q|@brzyS0qvfGWls)GT zgru1>Rni0P3z4fnW57hcoA9*bbmD7d;*x10i_v+Ih(=u?BB3lKk8l16^W)lI_vf^p zkex|^PNpz?JW(rTAhSmO;wLd`Wj`4Vahb$=6%vgyR-O};?0-`K=+1Wv-W1Jzhw>P) zR7}U2+gt|si*=yV!@J>-*2qzXR$_5{uTI1tj3RT@kNM^8%`uCTjkXR_B-T1SS_wPU z8{f{OTTCf+DOR)4sK5|VyZ+>uxTTt2Zj0@3KtfIyy6g@dEpU!cwY>39%dKBI17&a@NV!Ck=R?$>v{q9y>(oq9U2k;xT2N4m2$N$R`<2C_0($t>i2YQe zbPTGMd)A@b6fSkNqG-TD*r5k-mB(3SCrt8?NcJ57^*?mb9&Yb`hWS4EU7Yc~UGa51 z-tZ}rKr{+f<2^nV3EOlgBs51n!g?(ni*POD;?g+Io>vVn(OrY)XRFGJiz^G=oK^5R zlpi&eiTkN2Ee^t*oUE2L^svB=y3B$>(T(8`#5gr0af9(7mqFjwJDSI>Hocd}gBKl1=FW}w9KPpyqPC~l%>1Y&_Gi;| z0*}46I}JvkyD|42GedoC;Ll{8nUudJ=Z}&e$u?#F5dBhbx2L7!3q^5(S>57H9x@FQ zsI}V2-G!O7Mq;JU>nlWqnx2A5eyA|E0&uuC_2)4PO>EF523}E=R;NwC-e>J$?tp3A z%lEcMZ(==@!z-|96NPu(RXGB9_1N37Wxw`%=NczO?fZlr33$0{x$}KmOK%8%I~d92 z%qQa0Yq>WnCsu##@Z8JB{r0WUCVuG?)dyqY>J4ucIV@qJUB1>12E`WLU$Kk)qCK5r z!?vRbttr+BC|~m+oKdKuu>;u5jgZEx;Wze$m(9e;^zGC8^DsTtY=mskrs^|D@bPXf zypw_E;^l&Z@18@>?!F~6v8#jmyzkD}Yp+dD`z--u|HGNy;zU2>U?a1-)=bV7FZFo3 zw!oqfQ3a=EI#aGyBrSuw3`gQKf< zA4TrOjMnOkqu|hZ^O0#VG-mhIsPoC;;*z|7Y3^vu%}S*pI~MTQ30rs7MY$w^%n8j# ze89-c87RyvP43l73CFKzrq7J+mNa&8vnv0P>56qgnxkocXcZ!3v%y>Z@Tf8Q)ujAl z7(O=3<#r}svZM%8YGGZmwUpRHxnrI{ZN}F&N-BIKA z(^1N213GOCJJ?O+DA;Ds$i9?R1fb!Qcg5P8ms>c&m zC(*lZ`68C`v#j%GnIHwS{xys^D~eEJaL*Rk9o5)47eVIJ%X+(Q>u8NHpU+bQnphA< z-+H_Kj;HMxf~PazVtmC(aNs15-MwZ1>vqdtu+OvOmPNp|G-Stnpg<=-K=7S9@hx>C6TtPj2=}b{!sYN&b<2erW~wzz5G%o@j2T)(NvJ$6rV_ zDDO1i>nChja~-833rkAYqMghl{cds7U|jVN;-uc)&2F}7g2z8KNx`+CMERL_)55$J zoewT1$OcJv%O>T`ld;60LD*%fYGz z`J7-`SjzzBMrMm736gj%TU70)I+dBi3JHrfZ*ACus?O*ZMU!(yn-a9%m%OvMmf8!$ zaI4X6s>vx+X#tj$kXTKLN^NWwH`BA0M2zHUw1`1Xq~vZ1w7@j0Cw7mNa3KE1FOvy{GBSmt*Xd>6gC&M6XAY&7N=kp?}duMB$M$UtSp& zqfyp~c<-L_g?PoQA?Liqimjrxb67R5?P=V%3rrsMWv2eFo14K}>f*II>V*dxLoB7y z+3YEN`uJ8<#6C>Jv7)fD1x~R|Y-Q?jl6~%P)(+R&i)-gZL=E={| zh--_8XoGu93B1J7lP1IDGqoH^<#!%V~*f{0)3!r>iX;-sRII zGd`HH3zEoCX6$HR7KQAXe#Pg4_~>NbBLuT@CJ{Dh*TE^L|eBeedI+a9Yf5^Nk*T^aVy z)o+zqJ)r8IR7dp~xm&F`KZwiHvL7MZ@ENLy#i^=tAY z{|?`z(oU>vR73O^kSr?ui=Par#xBZK96d_F9D$%sUl_H#P3f=EWtG$O zy}Yk~8o_W1V; zIcV*v^DX;)tRl06`&r5Rk@Us$P0beNMbC(NJG|jW{$Ra~4avaZ@$PmVH!%XeSSznS z{k!hE7FMX*A=Lgla!)ckdB-u@Vd0nUx)g<~sHNX?P(p*+W?kx;{9cRNu{N{Sc{&AC z2{A@Zw_kRpUf1#wvA*WD;R6d(Y5kZcnc_FybV&hB$6qms%-xsx&I+2=Ggu7SZ@=cE znxy-OslL3kw9Y{b>@3N12#2?iLapDa>tE8XnagThs=og5lc+EwD+q7FI0>BJk|)0q zK)ec%`;8H^=a8M5Xjn2on}PwUQdsNUrmJEV!Luq($sx zdR-#}EG!pF-*2Q(12hEG&(bzYCoW-etXLVn-|)%)4q&_jTrLI|@Lth83SFrOVb24F zd;PG)Zudt90gQ`si-Q+mDL($u{%s%fFi;rtwM(Rfxuv|+iZl*%NLd#A$yN|p%(#CEpcNJ&q?CTY!;1-0vTS4hFedXJacOuhg4ve>&Z)@_wD zViA75n9B1KmqHjp&u}d!IRClT)YH3sW^Vu2axcS_=kxPT3C-c~tw;(oPIuKr|tGdBwvJ zV@vyx2G@aRUk@@3E5Kxt$vGTn(y5?Y5f3zBG5bql+#;Ig`c^7KvP&PUaQ@SoQWeGS zNYDinA~lJ%u?UxYM+(!HDSh$m$W*pDlG{_uv=15KaBf+(wwCCvzSCf(r-jGUysfrQ z6-HN%$UoNVT0uzb=2#Z;c$Mny0+fw~X}jx_$k;Hi>~JW=@Oo?1_EtQTzpq3}kbGw- zhks9S^=NajpK>2&uNVg|zA(-2m!?FPc>oPDW7^p-92*)Y>^V#Z=j$?dH>#SdEpcV4xYEiqg(K0xmA=-*BTgw zl^(78mqop`zU^R&$HePIURynHWxVdGMvw^KH>q`QiXR0GgvxSdW!~uH1A|#4HN_L< z<%F1(Ly5MFFY((L)^Y|cChMN12C)W8%eh9s`quoe6{z8k5B)S!WMqv2ow|xoLkYc4)9TGK(wnlyB9VV*JB;lF9WblXb-l10@umy3vWilfp{o&K;`v(TxK5k~Y0_J;NSRQ} zIs&b_Sfq7>(WOMc``Ws>DtTe*0Fu15@Y_&927@8FOR4@b)+DoFVUj0NyUi5CMYIR) z{yiuzinn6ivv_vJ@wMZ=Q%xg;k*(|a1|{>Qz1_cOq4|*YtQ*=d_ls;KxMmcnNxf3H zrr5zOG{3?xZ^d(Mk$jfRX3Q#f9g$3}3S(4-&aL;tU2%DrGkplHsAkmSWQM3G)GYSF z<`v1EJVVUZvm`BPTSnazUZT?(37i}$stMv?>qu=TT5t2)>HCMr>gao8SUEA5?&%tt zib*ToV)HxFkGlt>=)!J1%jGi*b(2k*>*U>x;6NYrcyow`W3eh?sJ<48Hf;*_@59}1 z_=FuDhq>3uVXX1&Ed?bz1K=^Enq~H>c2v}hsB_vn zg5&60pM5HHJ%mlB-s_s{aC$e^drcU^H7EY%q3rVdXk6OF{-7M4=&5Kee%{w9um{ta zrfS6vPbD4J{V8%;I4a!>I~bP8%e<_Do|c+{Mr)X+rpV74S3y}67Z(yT3a!_BPqtvD<7g{X z%c}v1_Xd7mAVj+4^eIa%D^NW4HeA>3x0!oM-|6gQ2HINM8l{TLlhvAQWw4)7bxlP& z3(;ZMF-jR_;!L-rmM3D-Q%E8KI^X|nG2Dm=D9EX%s4+wK&#U-kk))&w6|825N$g4VK;lZ=1b9Z>8IhOLsS%#i5WvbSRV-p zrAid5>8sfir0(?7PRzWFxirVI@|4mg-W|$Md>KJj*juE@C^f29M5G8^TxsNNZVF*) z5utGpo9~}szEiJ`^*3a-wLP`>-yr1EWa-l(5K_B}nuERj*YJy&pYtcmC|H84=xLytUuSt*dR?Wvs2=T=A0u0x04|*|~-g~!l`?hFsBS${xO$_a{{Tr?4Prd_@qRk!R ze6}4WCqfTpZ$&38$Kt1xKXv-}?qqE`Mw~PZ2;( zzU$V|+>5NpwH&u} zr(nt4I7To+!DTE7&>?^H{LVYPJ@NHkt6=3D*$s?MDL(iW305M*KO6M24;0}d|=vPD{?HqQIuMEn;l4Ve8OBYbU00hq7 zv7!!BY{sAn{0Auz6H?QwJd>Ow&t@oQ!oWo3SFYVSsiDb5(sDz_9PgP#Gq^!u*i_xd!2LxI?P{%6P*?VWPxK z)nLAaU_d4jpXme;(0A(Q!Wo8wAW@=$-+&=MQOYkGT#SzSZvr^tp|Mk8QBY)&$vUXx zg|zRzGL!l;0u&-SfzE_>mwU9g4O%Ywf^~l0)KK6gm&#xmUUsd2x74?kJG$am0hh8% z@jEX^#DDdJ9*q~|_i;Kn{1O>&ds&*y>FYlvl9vNglqhPIM}ZOp1t=u^2bmJr z`@il;`hU}j_5Ypr4<`~&NnPF7w8(Lqv>LOAm0lVcJ3mOE^iQOq5mCn6-~Rxkf$$$dun4(LIOanmMFl?s95MYs;6RlBN$h`UD4Xt<{@f3S@#7B? z-pz$2fBz3h%w=9wy5wc`j7Ee1VLOoaKFuECAFN0vqx*{QB=Q61n&KxVGB8PVrf-DwO2HXu}Wv ziLp>KX8`7}zFn}O_!_R}WI_-`hTAImIS7nlpzQS4UkeyA+Ct@ItbH|(k{~s7J|&$c z4~R##oU>I9^v6yp)2+z;Pzr0KKUh<8oq#$#k0sXpw3%&3M$4Y_8_wv~e`n|eI<}L? zrKWXMG^q{r^YMS5hnK;LW3{^9=*?l;QZLDGBKKw`VZ0UXvXT+}jw1aa6{C~a05P*V zA_1RYzm6-P+5AEf$r+HVbD<3VAv~a|x;`_jrUueNKndrEjOBB0)ll6XhR*Yy%F_+>Xc z9Fnz+fA)t$V8rrcdC1eta}$e#Nr3NbIbCB6Vv~u1s;6OT%}(HZRx(WR_7vi?+2e4C zF`oKgmv{saiSI25*$URLzOCu?VO86|zUUXoj{h8Jv!uAH%G$~tOuYd{T8?s-jw;pb zexj)>{&aNC1UFYR=aUAT+n(|LKmoxdicC`Sot4zPDvq9>G~%$RcljAA>P=-$uEW$U zD{OvR>0Exx#?8YaWYN=VqK!6<9BvnvAIG%Vf^BtpyS8$hAn^Tv{Od{>seuk>Gz+&q zyxvJUJMJ7QTn?RJk7OxZj-!ev%0 zT!-LxB9RqpliW}x)fn442I8@r%5A-ilndlaHaKj`BT%M@?;H$CQfF`NtYm1lsKI-O@@4XyD)A7W4;^ble<&C1ZDJ>u4Zf zcTlDn1q&aWSWERwVZT~$ua@YkbO9m>J+Fc_(>tJk-m^lW&ZSu#s2hlTQa8H$PRssI zX&$v}>&`?H@lWHP#!#hrI3e&it!Zv82r{L`^PnFinW;x9ufW+sW0`2^AgTHg@7 z%J`2c<*Fq8V);oPl^~M(+4ws1oAn#PZYH=x6rbqTFl-B&K%Z6hX1x}!ap%^F$JWk_ zlga55_&M@eYT)ZDk?$YpfcHPI;1LExn!NW!#f7wa6)iYOW5+-w34SW9Z=H)$Z+(`t zs-pN0QbVaO%s~+1_q8RAbimSYrz3@jp-!&Y<0{=J1OM>7Iz1ucO4 z{{{Z`eXxAqmNt1-%SvlFrxukOjJ)gF!JEe-D%PIKceCi*1vsNsp_;5XJ>}I6Gt6ux z|3NSPpe8G^6yXme*$MX)W#G)3&8)phl&=BswJmW;0UKzB;Tci1gNUoyZ&kU_#B$W zHcqJ6)BoSU3EbbqM^<|KQ3=lZm$gk|h}x_Y;_e%7{Kxa|@OQp#d8Wk<743re_Ve$g zW=4mr6)6^O6KU-)rFY{M2TkCGfsp!+d$uhzD*)Qptgp#^jK1ZJY!Om8A@H3 zw>4e3$p32Zt-|UEo;P6#BuGNwAR$14ySoK6xB0Q(fKtc2&Jqc%j&qh1BL#o+-{C)RuAfU=P|o!(arFng zn`zM;?C$tTXzYD&GCggJWG@mqH=_zj*ZER{Tnmp^YkTT8xN3 zzppx85Os68?2=zlL=BA^trCAYGBFHm=~WMCe-7B5Z2CMlV${Q^(}*k8Q;G2NyaIYj zha)Lid8MwVZBM{orn6yosb?^h2K9<7X3wWXJrC`gLYzbs#HZ^>Nvd~7si}2kqnq!Yct>dKOp6jcujZ@$=3_h4n})Jn~Tg-Nz{8Uv?Y5fecO_*fvGsOra2e_|4Y81L{u4(qaKk%^G*xH=iJ zckfd_H#y!9m={3szj#;$yIh#tJqz|k3)0z`p8O3le2Kc`c97oNDFm-w{+!p~D9<pw>aCyrIR3k)EGDV7h3SsHkc{b!tfzX552SVm zeYnUptxbe`40!!(%g8G-*jjA}0Ot(&{XLiGVZwV?w*)-38PW06P17$?=?6f#G%lz?rrXMr;`@TQMg)wH#i;ZW+ zY>}D;QGme2#(ncL9ezQPOa~yUA+z%clt#((+5T7K^fo6`a8+Rn$I2)NFD44@5^h#l zFBp_-6#q64@wNR2nuQ`Z{({D3V{?2(19Sl9q|BpI6(|r($+*RQ+y5L9<{!CvtvLx# z%)fY(JTWbtL`e8n&(MKATu*!G3(I_o$w%CPpM|*wWH=p_@6C*=l&NP$gpX3#mD$y? z*L4Tlx8@!-0}s@9iN2WC3iVKs_}2CVoL9%5pOpT}I?eJT7(n3p-AHr+0l=q6sRwv; ze`h5z7?JGUGL<39kHZI;-w3OFgY}1+z&h8j@$?#tC4D+J@FEb=V*n=ba>XUuBF}Yp z)ZZWkD@tK}^E#^)qleFM@^75}$cb5e>%!r0yPM{HOl;{7hB-uL?!;Vwb3mf%dVHuK zq2pGY_cQLrbJpQiT~|vrA8tm8vRL}LHQzSEqD(K#u}||VRuXye-k`&YJI@wmZRB!p ziB7C7b`eJ#9@voefh#{;zj5D8qnn$N^yZ_ibQb=|B#58uFABIlkwZV?qaOdd@YHy{ zfNwkE)wEhL8Xl#_mJrn|Y!tQcbYF|RNhuXVdb330lCDUXrsi7N@w}}b6um~_eI)!l zO6#o`Tw6Kh{P2-Od;4ZtTLywZ<85Z4RdiQ!2jt~p$y~FlglQybi|v|XFw$@|L#ja? z^F~U>-SNk$EZF5NCRt6Qg0Gm@Z(d8;M_nT{bQ*UbFbvu=oz{nY{*abZK)_>_ zo~vPRCeh$Uj%lUi+R?Tn3`Jbdv%T+BY+Qi!2jeBacfmzdIW^K}XU^U#v2OcvcGR5M z_H@yS&lsvty0cnAer~C(-;WSbx_1%KYXX5%^B; z$g9XhC)Gfx@%XBcIs0tv+4E=l&FJ$z;=$G#H3{O@ew(B}^2dg!|$p(C?|)t^YFIh4(x?Y7jNo+r-M_#BR;H+ftdtEvW&MdTW;M}wq( z(tjIxCoO&`6#}?5q7Fxx*F%^=2Evuro|1VMS}0gMU%7^NWV;*46PWg2jw$?Ez4oUlE(=Z>r%9G`@C1O9F zi#1X|j~Kw#4AGe(*HZA;;$XPAo{I?ov(f*1h}qzpquh*!=h;@j9v`+9WXo*+q@+O~ zMVtBC?bvH|ZU;3?AbG|wXsb*Bu&S~oa+vX61?1muegJas*n>q4N#2WzmzO~}8jT`a zLajWs{aSA&S?FgI94|#Rsh8L>ezp1w&J10O*1Df<#J;vbBW)(lMiCv1rAx{P78k43 zp1TyQ6uiJU-1dTDChjFPuF47rH zGMCRc&+N-$Y5Pr8MC22Wor7`rI6t4{X~v(& zIP{|c;fh%27T&QRN8c;amBm;qf1pLCp@_j7ru)D4P}mq7AM7F(U*=xYU)ibzD4-?` zj2%o5u6lpvFas&zSO8C#*(6^o<7fsWM&`@O4{c0XI*PV|g5fzCE+eP?XU4t7kq3c# zHd6lLJyWQ~=WQE`FiU985W%nC+*fID!bKbYN$HLKW-fjbUP51thH!-(1EZlE5=*18 zCW%&^%)ORYeiqo4T~Em@=WVDat*wm9%o5~rG1wFg!)%a$pL&}IY#llU=_|h`5Z7qf z3|em$s|Ny<5>O)smldyBRryZ4(@of|Tv|3`Rlj6dY!j(AKm3~VCH?6NX7-K9Z{&TA zF=I+rwy^o*RO?*{NdlklFsn${(Evicuv!9NhmrrUbZDghKe^pVDr56Cgvum7=~iv8 zwLkX}xNm5|*}-#srSPd+?exec%nx6!VO!#6zd$TA;}jo?80%yB^xc4Y`>gz}VbJi` zZg$2_T9URij^n43d?a$hqwt5MC(m=5vykt=St2|J6hJe>R%^~O4(zf^EWCQ3(l}jG zu5RBMCR<#^@!)5WpxSpE-0{?TmKIsrM^;@4n#>QZr`^dtJ-miG-QAT(h?yH7Y{=3l zD_1rpFCUkL_4EEzXF8EQlM>EgD=@qC>y>YomPsOaWLI#vYzyEs_UT9bA+~dKE5n+U zV)vo1RA7hp)%`aZ9r7uO%P_0B8dcdDNpuUt1^_66$C?o#}O$fc__ zZb%;DCua#9R63-RPEP^cQyvW$wfq)VNxxx%m;{nW(BS?IeaQ^phlch&BsY}Pv284x zZh1q64gEaV|7>^N)n@FmUdG{Q^eJ(r=(myg^PN2ir9sReeH*t^*KgI@>f znw0P&%;(AZzSe@I@s4LcTkv*~IM9cPp&{Z3dL6tK4`M(jQ>>bfQS zO$r>wl*Xy>!-bt!4Ft9?xDMxyAB!t&J%4Fut^SCtl_8+YXB4@7VM@q)E#|s@zn+{V zFgCp~HfHK>?0wj(+^%svM1e5m{?&nrcY(ieQ~S`pWj%&Vn|^Go4$< zSxWvAnFPYG+WIP4l2CQ^Uq1$qBFLUJ2KQ^*5b7GdUIP4P+Gcu#>lo$D2IhW?>zR8v zep7VO!1(cZ2mzhHRo{~NnI&=}i7v}4f)lN-D^7&45XymBv8=%sMv-kjlYLmHMXOvjwQ}Cy|b(T?l@Ose>-VNs9n6sMfYaAlh?y-~MPAt&@ zMRjUja0C_7+2U+@D5{w$5lLVP;Dzh{jyiGl-eT#yS1icO%I!Jo!?(@(Y1nHIlIuM3OHDv7HT;YiE1fT~wDi(FAp2KqG@hi*9!12G+rJhdZ7mU+??n>6+$yP>bc zoR~E->DCN|kJ(++>e#|n5=vQB<>e? zf=u)VSzy~CU$NKguuul6@v025bzgg)blpln7=4%QlC&G`a(|ygPH3h3k+aP$57ZGB zPN>FC(E3r<=w^OPdBB-_XhGXdovTBhV-S&!e1+F{Fu+4xx0!wf7r)K(=xdEmVjxNR zn_fgAF?e%z9Ac8-#;^niz4PGM&J;d-Cuxy`DpRv#dhNzY{$;68QM&L?R4u>T^AVXL zHhjM+5f{mY6F?6%cwfTH3MGUe1|h5{r@dOw55Kjoe`ZB6buv}zA5z;JiO2x9B~vqg zk$oSC2ao-#y%c$&y*d?#4MTc{d^)}|R(7?69ao7W=?f{S{07bKoaT#)79r_%t@3UQer(wiaP;5HKR~($zTy%Aq=az=ML( z>j6`rNi4vbH|R+TT8KC{MV#TsU1GRADsqAIx}4S4eVEqMduM@cBNqG5rWwJ71Ivu+ z%IF^E%*`Zu$Og4QuL2%n7V9&J$l!i)w8(!qpW*&E&7T3R*LH}UpavhZ(Q?4(9Jp#I zz=UHssxJe&VRWjtv{NyHKao{T?!WHUrSHi!^%?a+FvK`k+mYjBN5YAA zA~n?~`txEwX6=jftrp3-^%HrRpcs-G|dHKw0C`>f&a7_p&>Kyoj zZbL16h{H7-|19s;GK4BfEbNd?UNOOmwFrJ+z?Nx|6)aM>8wjbJg_Y+Cw`8hhb63=*ro>&1_cL zL6q!!=L%N?o_wyD^def4qvZ7G{xW%?iJ4B zS+;nIGsl(;9!8pftld#wrxF?3uK3)bXs&_=7lQ?NyYLiFFzdQ^4N^ zKvKmnaUXg9`((^glO7uRww*Rvtc>mav!c(<{dOWln6S(SDiW`8U|SgXZZ`UJTcsoJq&8Vo?G~o+zyUE#KQ*?Eh$Q60i$W>Kle7V*71sO z_OfUCKzg?cQ!p_7&@F#w(wzQLR+gU&#&f2HjHb4R?>r!{1pkBX8gPgiy#HenT}?-T z?{yuTEsm%8#l;p-jwgV)2pGsk;Hf!B-{`nL#l-V`*V=iznN?JYaWwL{IYY5aAxcP* z>mr*&n~gItn4zqzx^R`Ot4nmfHJX=Wk6rQSdPopCi-%vg_4=sj`m}}6CM~QF=sgFB5r(MhWCZ(~nX-_#PO@>^z8%LE=_m^bTS-TtlZkZFTNrD{0 zioO?m?nX7FzO%l!h!F2CkXj{D$y2FPX~mQXnN$^7chISZMXs2e<+jS!?ZqL;SaDUL zdD_3sSS7+doUBE`RMNbKN44c(U(4WQHzz8R4E>FeWZBBxt`TQ4z=dkt&&b6imC#AU z*ZNbO`~$s?wAjM(ZGcOd`dJik3=o^mGtEZKH5E;9sKJyzPx>}TXyWb;3z1a&l~b;$ zIAkQcwQz9LfUnV69E4AEYlQV!wn$r`t;lq+f2~ZYO3Pcu!_2F2@pT-l|H(xHQ}0?a zE+ySOT}yZ2qIB;xq9!#w_T-F{Q&3g0txSx^+=0Fx_Vht6gUf9rp=^}TE6G!dtsHEc zQ_1w6cbx5B6U?j3>S`D7!hT`Dkm|Uq2SXhr!eM+J!pc(a?VwSES&zg}KeVIOtCRNG}2@(eNs=2fz^PgTT zIvSm{2%AY#1)aMAcRxjHJ zLuVH-o~H8_;xIkR26mEAj?plSX8sg`_#3>n)hJT;rKx}~6cPxWp% zo!d>4cTB#iqxq^%fwie4PFN~pA~%ESzL2V`_HtB7#`kRQDVgD{eXB#_TajDJ`>3sP z(Y*;C+%2!2*kM|Vlrjv5I3qOvXl(!VwL6paoyIL&2}>T8mVlV-!EsTSOxlp$33mnW zCWm`u^p?KHn?bSE=S*lYmi`R6>QRKzDOVRM9Q z)`#thR>D3>ig{cJ6rVTy!u~cz{6<(>K}WIr0^!m5Ad=TXCsY7J5TH=qi4NYTvRN4M z;4wPmz2<$ipuh^!iY+#{#t}CE$_%t?GW1UQK!C_7BNuBE z6Ojool7pUD){LWQg7TFr$z#W4fs?Wf^d#xqx2Vk~Xp<35c7cGYEMMtJm&>OC{tB|& z?~Oa5CHCCW>6~;=4Hnh(p#rb5^C>qr_|7I2)ee%2KR}Q)R)-KioG33w#1eyDK3PO( zuyIG%!x&9CNN|Kmpz=D$rGR^>=7|&R<<>$SA0|}lRct&N_S5GX_Ql&kw4ckoA4Wng z&S{inid}9U$X>1GHSKDf*YrMq$`ku>W~!!LJwRZ;<*+q}op1|SAHa1k?gb~^*5*K{ zg&bdJD7X#UI7V=0PggF{ZQ<#`p{8rxJ=HW9%77Y5M^P;9`E;fCJov2IsgpTGIcG0a z^(ImHB46}a%O4yi(O}ysb%Ib)o+ay5kDn-8AGAOFBRo|rq|jWbWhXjlo2bqOqsgb; zB=%>n2s9A9(gk-;usP};PUX2#U9WPKYZ?~>*z(tWSpi43-8rVjT;`BMF!&8L@-_@H zKGGsl2r+ahtvfYfu;B{Zy0C>Eu~n$oc=CX7D^{pb?uHT$%byk^PH~RM%2*! zWP%!E+ZuzN0g0faSJNySugE0S*UpwgA@`J0bodyq1DNKJAE~~Y|pwUL6yCoT@tb#loF$~R1E$F?NDRUB4BInNANY#z3kD^g71N%3`4yEQCN zE$6xKWZv7K`W5O)Sa6bQRbq)@BtznFNqvwB&Jew3YK>ER=i^_4tr za2$J_bRh8G%|YUY=@q`m{pDJ-!;2Gcxg^D@%CxEd6p>l?GhM7vIWbcz_nvOHA>6br z;9z=zs{d=+8M}FhQmELd{MvwH3l%1DT!zpX0dX7F0N(L0v@)!qFmy$<(|6F%Z?vP( zTdD|m(QZ+Zv(&)uSG<^=vJ~^xCbGnDH`u8UsLO{apWSg`uXzVHq()KM4ji%#@-d0$ z-}|n7j!_`Z-KFrd*eu?#@_Y4qu|EV4bQqTd70ci`RwM+6+)xpx*!e-T%-$M(UA`G) z;t$i*YJ}6%j{c$(&E&}d79F4NuXw9Ie306AZD7%IWA|teXhh<3ZZ5SmkEA2L3{*O> z@pO#Jp?!DvBDqHEy?f;QagB=)LdV3IP&Zm|1vv+`?LFsIxDq^Q#W2tkC5FQi6RH~7 zYKf;tYL$?v9W9+Bq$nANKQ}~HF?jFMavkk?HWA{aE#1w?qie*_ySHUqDYP>|b>`Oc zjss3g&|aTsY`5qG1SWAXoAwj^ic0~$42Bb+c{wX9mVDC2Y&Emb|Sujv5Tv0qL_ z;_Cq3mcrtzCJnoC2jgQ}lEs?;v3gKJe7OP;z*_MZoE;^RRvfbkpYDEM^PbSS{`jwT z<6ZF5>IJLa?*~Jo5uj>2j^yD&G)-b7-BOh)A=<&j24jb%PN zk-IqZ$6vLMLXFv%8r5&k66wrgxy}N*LvnlL@Wg|sKS;d{!7FAYSJZrUn&k~MEu%;! ze(i_xFoqE40j@_`qK7T-ba}IR=)V7-9c)Jq_JWknwO3}%*Q}o@wW}hp*Ih>$D|DA{ zMYuLyHf(p%)Ptnt;gZd#%M0QbJ?#!KV(s$7IOT8vf(n}inL^bESX6A$lNg$H0NsY{ z;hxp}kk-DAuB5Bg24+mrSH3=Wg;l#8u7Se@I2S8XWTO+Q^56)qIwimFTHHQRqG|NU z#J>u*Ycs?RD%hwF)NH5}yQo~+tLds%TmySN3M$cM#@qp6?&O{?bK{$qz}-(F%G90V zBJ{ZRd-GB;aj{Z<&8Nw0&k?rnUc-gBoT^h=5^x@+PWPws5fSr37J9edK5T^uWegc{ z7j>-T)cQ700V zf{8#C^?T7wfp5MK1*!Jms#P3${L%K5Q!Zi;v?;h~bJG(MWF8ik8kJqD$TtzhE`lko z8Ik{u0Xs)9(eiwn?vbcuk@nQ5$Pku&t>l3=+!$qR2YiB^# z_4IGLt#Q0}ewrwrMCnXt17Uwy$li>nS(SwMy<5P|MTcgX_V6Lmdvp(<#nAXdz7p(C zG(8sP-Wg#ctT#dYEsM5Zbie0J=hf?huikcXtMyt;7Wh#60|V+;Pl5X?UBp2UtGR)K zjVJ`H!=z7wm>qddU_xurEoDwQaw3~iYOkUANtet*Vy!_3WYm*7>N%Uvy8VX10-JOW z$Z$n_uNmeWHVNUDdjftUl+zl$$4*FKu!(~3qN3TQ5y=PPk7tyn?^MefWut?W=vP5} z;VN3swALGO=2X}6ztzRY^VIn+KJxm+p;#uw+Q!K<8x*kx|`?p%sQ*<}+WBU{aHC!(GKb7Y4nwA{^V^XwfA4L*y7d6ZP<37Op^ zq8l2=pmh07svtEvukxaVlvI7=N6G(B*I#yrPLDTBrc8N?fhMYe=qc?6m7@x{sZMb7 zErv8JRk%c;TvN3vF4Nw%i1gDvaC;t*;xx~cV(An)xgVhz#=w5yK_uuEETHSIC|Z}W zhl#&xna96dFfC4bqN!vxV`1n88>4YC`EM1H8o(U1=jY@yjhjpe*?WDG z_iNMsH~gKhjpKZK4psM*zWRV!W-_Jcq4PLR2O$hYqy^RVPGf2G^Zr{42G4~}MJ9rgYR0I#X5w+P-MX%DRs&1E;*AC}vOOvD7{b@HAa5R$ zi06*JrOd@sZDUqV+85Mw-noU{;PV#RT`c=@b@D}8f$Y3aY%}3rt_hh-R2NHyUj=V# z!3+$a4W2BZeDCtvB{)<)KwBmt8I^X`Q2wHl>Mg-8Y{Jfi{b$KxSSshcp9m9^5={LZ zVd7~gzyPC^{~O@zcjwrg#gfq+%WVp*Qa=3HJo#g#4q5?|#6I_5_t+IFAvho2kl^K_ zQ;MK2(UvWl(6H@}Og!cZ0N`*t6d%?Mjq+6noiszFijvg%hJE4*v<}?tW9dr6bA4g{j+}K3-*kydyzS{~;fX{L5wDH|n)My^y5ECHP(G~BI^#d) zl-b?PC)O|CZCNg(R;{7(lM#fzJ$}oFWF`W>q*BO(?k62#ygnn_zJQ-lypwziF$<;W zOiKvvO3Vt|{{2C5&|h`-?K#B!By>^4iSDhPh zVo?+u@rG}?@Y>2n%8{GQ9gc74L3Vy*xUvK9mfm_|>0;S2m7Q?V@!I}qtg8!%{-)^< zZP%`9iO3XKwx0KN=T*=Zhfq$r&m#LV!3ok#9m1^(fQ6phj- zwS-4g!Ax9!SO7q}$S>_rWc>jdZP(}742fsIRlQD-%85MBmgO!EUnS(4~Q&k)SvzMLl1KHJoT>v-E_L=X=XF9Z84KUBsB= zb|W%pe}`khn3lsql-|a($&erw7K!1@TvutsW}Ku&A?P(G&y*3FnP4j{`I>=E&`W{r zWY6c*f{8b6l8_M`F|aI$ns`6Q{Ukyz$ibwX7Z=K9;HM^y?dkPZp>%mq*tY@KOLU;u zR+ofX-(Y)zsEEPnJdVsItBbYn<9@ZeM!hARW+BU;CM`}yMPKit3hnu24D8NPT&M5; zqI9nttbTRKW4Yb^Mavtf;;jc9}WTZ_|}Z)Q|b{kWFXBR%9_xGd5&@m7?d z^Pbs%IhDHHU_A5$17-p(zh5Z1gX4oAI4th`JT)z2#A}AJ;v@N;vrQs1cf!^cd<{Hm z;~S20UZyU_Q7_KyMke8ksp~qW#?zeELesiW{$k`{dOH}4S6hX`A$TIISS?-c)^@wD z`<}X#3lrJm&u)8S3d+AH zF;$Js{pr_46zWw^K|r|J6nb7J54O}$(l7%kF&bm)t4loS)GDy`^iN&J<32Vi?$hJQ zmlEB15#05@_8aGNB49~ZChiNn9y_j{#v@$INhy)qi^Ecv<=Zn^i zXos8eQBRr5k&uise$8@`bDwK@d!P$cr8<1BmTe-Duow3S2?-(r0kWR+ufG(>k8$wu zk8V4O$K=bXg58%{Hh{T4xuY}Be6VghSn@kypTxTVH4qEmhr35gLSELace<-fd1to= z9bIX=JtwH}a0#=662zg983G-d(-Gzz$PB#tc5Y2d5GT+ENIR;;xcgtM^b0HGD)w!a z+dkN8R6cxwCu2^58E_#GZX~;pdH@T1y30`w>1U|z{K(xWzueexLa|5twbSx(;HfYI zXTkDfrWka7PYq(991QLL`67gXq65Ky#Z3yAd1-eiq`tr0$Qas92Yj0}J37K!R^Yd{ zN*5#?I*@^TH70g#&{PQJTzW=3uvi{>?ot78p56o|b-3UM$GJd$%&&TZ#>M%n8N&_;ZKoQY!U-Ah? z{SXlI9{Wchl7VA>^)EXij1h2&ko6z)XA-!S1^Yq{N(K@aA_DyYg$6DOn7+KRKt6Cu z2)>s1Q1XHF{vgIr_JeB#agxv zo#lf#{n@1T6~{>wjIoH@Gh6yiTC`TZczK$oDPy(AX#*KBjo@KkI?Kd@KG{9nQiVi_ zGoVg}2%F$-pGB=2i5!!q=XDqcHY6`B^NSGGGkhvz?16{z_I^DS^wK)9>Jw~q%o z8Pd}VvYqZut2?E;#%^WE{^VqajsW=z6o9%$js(x&R-I%2_Z#lk58q|RWoBv84C%e;Pv zm5!*+s0p3Jmeb(~P`ESU)-Ve~NU96o)}Dgdn%vEryOVXg8`~?h^ViaRpDZ=@(Y>co zSQrS2$2kInH@PcC;*-L-$8g}QV zwsdm8Q*+v<5e$F-vGrIm5i$0tn9oC$KOnAyJmKtBdUdqVm9k$Vg#BYYd;NCzPui!G zxi|ReWhT^~_uPgPA?b(aCR%`t>$NMiOqzj|mFYE16y?iO)ENtcrwU1Y+BF{{TDt9w zW}p$@=v5O#tGCiyrB@?C!vV<}rQr+aG-a5F{Wj`eMLODce1~IuNr~q=1_lCpKg6mC z)q*USXw)@WTWg2_Q|7Im=f$Eq?a3vd6Y_CY1MgT-L1vU!IECq^#?(0;MNUt~{TWx; zN@pr`F_y>eED9Nh(EVlA^QR^WCXDw#TF%yWmmFSGwmz}CTENy_r{_Y%`3COmFx*DT zxxjfN*pKLu?@P!Hq|qo$FBx~y)heR~7;7j;t1f+ATO@3y^1c*39OY33QbS8qC+jaf zh_;iN;WfNF&Hz=hk7+pXTK`^YbDD|3!Gyp0CxL_)31C03(k!n0b*&cU!bSLilaSFNv15OQVk|K1KXC|)zvc8@aAC<7|t%0r^Su~ zmRXqg$|p8@spo*PtPiTtY0Vr3E4JoE znB0G2V%85ep7Pk{pYRmQz!T(?CxBY>=6t!gcbE2yA1018!THuw-R^eZS>@rL*E>U! z*kCU!ij#Ga{!^F~)cpZ>@pPqOxbBgC#x{64g+p)ai#*`5%O(m8ht4}(px_^FHVy9#xh;p4ffV^Q!MqEVB3KUI%^00Y*Eb6&fs6A zEnvU#(OF`Y79x2>nfKh!q(ZvwLkudA77aW*o?1uHc7D026Xf=|ri^ z+K{6T?4tg?I<<>a49Nch#lc{6JAPI-!lDmh4ECe(zgH$D@qFGgT%3e @3!k7PQ zeA?5qiVEa(eTXOI9|lSu|9=016o~qR#W~`SJ(}27Q3HSwlFApT@Un0KxWFIo{{Sw4 zm-U=pJ_71h+>N@_dPL6@YjXjZgB0gKFh=kNgMGAo`2+zmc-c1t!I$w$AwcX4>c3YD z&U_(NhqM0&)cC%nXJ(v#fjtsH4cg|yT80Trg=Ssu+%N5m6YoicfReL&gZzO>3wtgkqC4A*}eM3vN8;uiR@(VNk(}0)#S1b*)Ud|;= zv`L~{A>1prH!u=(FK?7v6TTYB4rG6F4tLdF(m>7_;K@Eo`CC{M{%2txm*krz)1Z2#N4XzG40H3xFiVc zC;amYJNQXOY{2)NCkzw~yR}Prg5#1s)Z8wq$-y`FC*vQ#(QN!%Q``fHfH2}ksiNDM zJ7?H_e7PsL%wk*><{q00`hO zJ6UucGx5r18OnsJSQ35TQse6cd*xYQA8mSboIK^P%W+0*BEI8@cCd%k@Gw!GF9H^@ z_Qz_DW1F=CtKA-(O4u+9Nek{p1f!R52$jH!<9yR%#rs1w&I9Io3ll~CZ$$KPh}^{C zhGE|ZnK*h@H#-W3<>y)`!Bv~0iNnQ#%5NQZ-!kMMB8-`RGU^gtqIwN=65PtqA^CM)IQ zhw^`5j{V;R=Ob1~%zKmmcFO1~+HTkv-aIA}x{C|g`|GQ6t-Cnm9&-`n6!#!Ak SHtSwa(2}BZBIQE*zW)s$LF%sn From a5afa0fe01f240fb948a652e325dacef03a6d0cd Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 3 Oct 2023 19:19:52 +0200 Subject: [PATCH 117/122] Update inav-configurator-next url --- docs/development/How to test a pull request.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/development/How to test a pull request.md b/docs/development/How to test a pull request.md index 44a8507fcf..4726349b93 100644 --- a/docs/development/How to test a pull request.md +++ b/docs/development/How to test a pull request.md @@ -16,7 +16,7 @@ Building the pull request manually or using custom/unofficial targets is not the - Make sure the pull request has passed all checks, otherwise you may not have pre-compiled firmware images. - Make a diff all backup of your existing INAV configuration. - Take notes of what INAV target you are using. -- You will need a recent version of INAV Configurator from master, or even a specific branch. If you don't need a specific branch, [inav-configurator-next](http://seyrsnys.myzen.co.uk/inav-configurator-next/) usually has recent unofficial pre-built versions of INAV Configurator. If your pull requests refers to an inav-configruator pull request, you are likely to need a specific branch of the configurator. In that case you can try to build it from source by following the build [``Instructions``](https://github.com/iNavFlight/inav-configurator#building-and-running-inav-configurator-locally-for-development) or follow instructions on how to do any needed configuration changes using the CLI. +- You will need a recent version of INAV Configurator from master, or even a specific branch. If you don't need a specific branch, [inav-configurator-next](https://seyrsnys-inav-cfg-next.surge.sh/) usually has recent unofficial pre-built versions of INAV Configurator. If your pull requests refers to an inav-configruator pull request, you are likely to need a specific branch of the configurator. In that case you can try to build it from source by following the build [``Instructions``](https://github.com/iNavFlight/inav-configurator#building-and-running-inav-configurator-locally-for-development) or follow instructions on how to do any needed configuration changes using the CLI. # Finding the pull request This is easy, but you will need to be logged in to your GitHub account. @@ -32,7 +32,7 @@ Once you find the one you are looking for, go ahead an open it! Click on the ``Checks`` tab Click on the down arrow next to the number of artifacts -![Search_results](assets/pt_testing/artifacts_download.png) +![Artifact list](assets/pt_testing/artifacts_download.png) You should see a list of files. The one without SITL in the name, the biggest one, will be a zip file with all official target .hex files. Click on it to download it to your computer. Extract all files and select the firmware for your target using the configurator by clicking on ``Load Firmware [Local]`` button. Don't forget to use the ``Full chip erase`` option, as there are no guarantees the firmware will be compatible with your existing settings. From 72612e5033000c317c199ca1f303667a26c45131 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Tue, 3 Oct 2023 19:38:56 +0200 Subject: [PATCH 118/122] Fix typo --- docs/development/How to test a pull request.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/development/How to test a pull request.md b/docs/development/How to test a pull request.md index 4726349b93..4da0c27e73 100644 --- a/docs/development/How to test a pull request.md +++ b/docs/development/How to test a pull request.md @@ -32,7 +32,7 @@ Once you find the one you are looking for, go ahead an open it! Click on the ``Checks`` tab Click on the down arrow next to the number of artifacts -![Artifact list](assets/pt_testing/artifacts_download.png) +![Artifact list](assets/pr_testing/artifacts_download.png) You should see a list of files. The one without SITL in the name, the biggest one, will be a zip file with all official target .hex files. Click on it to download it to your computer. Extract all files and select the firmware for your target using the configurator by clicking on ``Load Firmware [Local]`` button. Don't forget to use the ``Full chip erase`` option, as there are no guarantees the firmware will be compatible with your existing settings. From 3f5e7c1dd0c685332eda3ac71a777e1b83c6cc73 Mon Sep 17 00:00:00 2001 From: shota Date: Wed, 4 Oct 2023 11:34:49 +0900 Subject: [PATCH 119/122] fix mixer config init sequence --- src/main/fc/config.c | 2 +- src/main/flight/mixer_profile.c | 8 ++++++-- src/main/flight/mixer_profile.h | 1 + 3 files changed, 8 insertions(+), 3 deletions(-) diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 27ed9eddd0..3950d76376 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -305,6 +305,7 @@ static void activateConfig(void) { activateControlRateConfig(); activateBatteryProfile(); + activateMixerConfig(); resetAdjustmentStates(); @@ -486,7 +487,6 @@ bool setConfigMixerProfile(uint8_t profileIndex) profileIndex = 0; } systemConfigMutable()->current_mixer_profile_index = profileIndex; - // setMixerProfile(profileIndex); return ret; } diff --git a/src/main/flight/mixer_profile.c b/src/main/flight/mixer_profile.c index 3b0b1fd18f..de1cdecb3b 100644 --- a/src/main/flight/mixer_profile.c +++ b/src/main/flight/mixer_profile.c @@ -77,11 +77,15 @@ void pgResetFn_mixerProfiles(mixerProfile_t *instance) } } -void mixerConfigInit(void) -{ +void activateMixerConfig(){ currentMixerProfileIndex = getConfigMixerProfile(); currentMixerConfig = *mixerConfig(); nextProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT; +} + +void mixerConfigInit(void) +{ + activateMixerConfig(); servosInit(); mixerUpdateStateFlags(); mixerInit(); diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h index cb040665ce..bf52d45c3d 100644 --- a/src/main/flight/mixer_profile.h +++ b/src/main/flight/mixer_profile.h @@ -73,5 +73,6 @@ static inline const mixerProfile_t* mixerProfiles_CopyArray_by_index(int _index) bool outputProfileHotSwitch(int profile_index); bool checkMixerProfileHotSwitchAvalibility(void); +void activateMixerConfig(void); void mixerConfigInit(void); void outputProfileUpdateTask(timeUs_t currentTimeUs); \ No newline at end of file From 8249e7733e49d10c49688fa69da1529c700f4fbb Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 4 Oct 2023 15:45:41 +0200 Subject: [PATCH 120/122] Fix for Rate dynamics MSP layer --- 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 2b2d4a8437..0f3d80829a 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -3059,7 +3059,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) case MSP2_INAV_SET_RATE_DYNAMICS: - if (dataSize == 8) { + if (dataSize == 6) { ((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.sensitivityCenter = sbufReadU8(src); ((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.sensitivityEnd = sbufReadU8(src); ((controlRateConfig_t*)currentControlRateProfile)->rateDynamics.correctionCenter = sbufReadU8(src); From df0993cb88b39efc5d02f106fff17c04cc0ed9e6 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 5 Oct 2023 00:16:43 +0200 Subject: [PATCH 121/122] Add myself to Authors --- AUTHORS | 1 + 1 file changed, 1 insertion(+) diff --git a/AUTHORS b/AUTHORS index 2a1f2744c4..7c2f94fcdb 100644 --- a/AUTHORS +++ b/AUTHORS @@ -56,6 +56,7 @@ Krzysztof Rosinski Kyle Manna Larry Davis Marc Egli +Marcelo Bezerra Mark Williams Martin Budden Matthew Evans From 3611477276ec8fa2f76b670e51c74b648bf104a2 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 7 Oct 2023 16:49:17 +0100 Subject: [PATCH 122/122] 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/).