diff --git a/.gitignore b/.gitignore index c86d809162..b2c3b9ff54 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/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 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/). diff --git a/docs/MixerProfile.md b/docs/MixerProfile.md new file mode 100644 index 0000000000..f6688feaee --- /dev/null +++ b/docs/MixerProfile.md @@ -0,0 +1,144 @@ +# MixerProfile + +A MixerProfile is a set of motor mixer, servo-mixer and platform type configuration settings to enable VTOL transitions. + +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 +- A VTOL specific FC target or `timer_output_mode` overrides was required in the early stage of the development, But since unified mapping introduced in INAV 7.0 It is not needed anymore. +- ~~For mixer profile switching it is necessary to keep motor and servo PWM mapping consistent between Fixed-Wing (FW) and Multi-rotor (MR) profiles~~ +- ~~Traditionally, FW and MR have had different enumerations to define the PWM mappings. For VTOL operation it is necessary to set the `timer_output_mode` overrides to allow a consistent enumeration and thus mapping between MR and FW modes.~~ +- ~~In operation, it is necessary to set the `mixer_profile` and the `pid_profile` separately and to set a [RC mode](#rc-mode-settings) to switch between them.~~ +## Configuration +### Timer overrides +Set the timer overrides for the outputs that you are intended to use. +For SITL builds, is not necessary to set timer overrides. +Please note that there are some display issues on the configurator that will show wrong mapping on the mixer_profile which has less motor/servo compared with the another +### Profile Switch + +Setup the FW mode and MR mode separately in two different mixer profiles: + +In this example, FW mode is `mixer_profile` 1 and MR mode is `mixer_profile` 2. + +Currently, the INAV Configurator does not fully support `mixer_profile`, so some of the settings have to be done in CLI. + +Add `set mixer_pid_profile_linking = ON` in order to enable `pid_profile` auto handling. It will change the `pid profile` index according to the `mixer_profile` index on FC boot and allow `mixer_profile` hot switching (this is recommended usage). + +The following 2 `mixer_profile` sections are added in the CLI: + +``` +#switch to mixer_profile by cli +mixer_profile 1 + +set platform_type = AIRPLANE +set model_preview_type = 26 +# motor stop feature have been moved to here +set motorstop_on_low = ON +# enable pid_profile auto handling (recommended). +set mixer_pid_profile_linking = ON +save +``` +Then finish the aeroplane setting on mixer_profile 1 + +``` +mixer_profile 2 + +set platform_type = TRICOPTER +set model_preview_type = 1 +# also enable pid_profile auto handling +set mixer_pid_profile_linking = ON +save +``` +Then finish the multi-rotor setting on `mixer_profile` 2. + +Note that default profile is profile `1`. + +You can use `MAX` servo input to set a fixed input for the tilting servo. Speed setting for `MAX` input is available in the CLI. + +It is recommended to have some amount of control surface (elevon / elevator) mapped for stabilization even in MR mode to get improved authority when airspeed is high. + +**Double check all settings in CLI with the `diff all` command**; make sure you have set the correct settings. Also check what will change with `mixer_profile`. For example servo output min / max range will not change. But `smix` and `mmix` will change. + +### Mixer Transition input + +Typically, 'transition input' will be useful in MR mode to gain airspeed. +Both the servo mixer and motor mixer can accept transition mode as an input. +The associated motor or servo will then move accordingly when transition mode is activated. +Transition input is disabled when navigation mode is activate + +The use of Transition Mode is recommended to enable further features and future developments like fail-safe support. Mapping motor to servo output, or servo with logic conditions is **not** recommended + +#### Servo + +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: + +``` +# rule no; servo index; input source; rate; speed; activate logic function number +smix 6 1 38 45 150 -1 +``` +Please note there will be a time window that tilting motors is providing up lift but rear motor isn't. Result in a sudden pitch raise on the entering of the mode. More forward tilting servo position on transition input(you can use 'speed' in servo rules to slowly move to this position), A faster tilting servo speed on `MAX` servo input will reduce the time window. OR lower the throttle on the entering of the FW mode to mitigate the effect. + +#### Motor + +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, 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__)) @@ -114,8 +114,7 @@ typedef union { fp_angles_def angles; } fp_angles_t; -typedef struct stdev_s -{ +typedef struct stdev_s { float m_oldM, m_newM, m_oldS, m_newS; int m_n; } stdev_t; diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index 68ff86d147..368ea8c887 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -36,8 +36,8 @@ //#define PG_TRANSPONDER_CONFIG 17 #define PG_SYSTEM_CONFIG 18 #define PG_FEATURE_CONFIG 19 -#define PG_MIXER_CONFIG 20 -#define PG_SERVO_MIXER 21 +#define PG_MIXER_PROFILE 20 +// #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/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index 147725ab46..d867cc50c0 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -228,6 +228,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/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 0aaeec4745..0486eb5ac1 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -211,18 +211,17 @@ static bool checkPwmTimerConflicts(const timerHardware_t *timHw) } static void timerHardwareOverride(timerHardware_t * timer) { - 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; } @@ -266,7 +265,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]; @@ -277,49 +275,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); } } } @@ -327,6 +304,7 @@ void pwmEnsureEnoughtMotors(uint8_t motorCount) void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos) { + UNUSED(isMixerUsingServos); timOutputs->maxTimMotorCount = 0; timOutputs->maxTimServoCount = 0; @@ -338,8 +316,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) @@ -348,47 +324,27 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU continue; } - // Determine if timer belongs to motor/servo - if (mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER) { - // Multicopter + // Make sure first motorCount motor outputs get assigned to motor + if (TIM_IS_MOTOR(timHw->usageFlags) && (motorIdx < motorCount)) { + timHw->usageFlags &= ~TIM_USE_SERVO; + pwmClaimTimer(timHw->tim, timHw->usageFlags); + motorIdx += 1; + } - // 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; - } + 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; } 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/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 14c3f9293b..e9b3a0f957 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -19,6 +19,7 @@ #include "drivers/io_types.h" #include "flight/mixer.h" +#include "flight/mixer_profile.h" #include "flight/servos.h" #if defined(TARGET_MOTOR_COUNT) diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index bf38ec9340..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]; @@ -419,7 +420,7 @@ static int getDShotCommandRepeats(dshotCommands_e cmd) { return repeats; } -static void executeDShotCommands(void){ +static bool executeDShotCommands(void){ timeUs_t tNow = micros(); @@ -430,18 +431,30 @@ static void 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 { - return; + if (commandPostDelay) { + if (tNow - lastCommandSent < commandPostDelay) { + return false; + } + commandPostDelay = 0; + } + + 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 +477,9 @@ void pwmCompleteMotorUpdate(void) { #ifdef USE_DSHOT if (isMotorProtocolDshot()) { - executeDShotCommands(); + if (!executeDShotCommands()) { + return; + } #ifdef USE_DSHOT_DMAR for (int index = 0; index < motorCount; index++) { diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index b822114147..a207aff0c5 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -110,16 +110,22 @@ 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) +#define TIM_USE_OUTPUT_AUTO (TIM_USE_MOTOR | TIM_USE_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)) enum { TIMER_OUTPUT_NONE = 0x00, diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index ea9ca53991..f2ccec9ec0 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -81,7 +81,7 @@ 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" @@ -289,7 +289,7 @@ 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), SHOW_DEFAULTS = (1 << 6), @@ -1045,7 +1045,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]; @@ -1869,7 +1869,7 @@ 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}; char *ptr = strtok_r(cmdline, " ", &saveptr); @@ -3132,6 +3132,39 @@ 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_MIXER_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); + cliPrintHashLine("Mixer: motor mixer"); + cliDumpPrintLinef(dumpMask, primaryMotorMixer_CopyArray()[0].throttle == 0.0f, "\r\nmmix reset\r\n"); + printMotorMix(dumpMask, primaryMotorMixer_CopyArray(), primaryMotorMixer(0)); + cliPrintHashLine("Mixer: servo mixer"); + cliDumpPrintLinef(dumpMask, customServoMixers_CopyArray()[0].rate == 0, "smix reset\r\n"); + printServoMix(dumpMask, customServoMixers_CopyArray(), customServoMixers(0)); +} + #ifdef USE_CLI_BATCH static void cliPrintCommandBatchWarning(const char *warning) { @@ -3687,6 +3720,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 { @@ -3699,12 +3734,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 @@ -3738,16 +3775,6 @@ static void printConfig(const char *cmdline, bool doDiff) cliPrintHashLine("Timer overrides"); printTimerOutputModes(dumpMask, timerOverrides_CopyArray, timerOverrides(0), -1); - cliPrintHashLine("Mixer: motor 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("Mixer: servo mixer"); - cliDumpPrintLinef(dumpMask, customServoMixers_CopyArray[0].rate == 0, "smix reset\r\n"); - printServoMix(dumpMask, customServoMixers_CopyArray, customServoMixers(0)); - // print servo parameters cliPrintHashLine("Outputs [servo]"); printServo(dumpMask, servoParams_CopyArray, servoParams(0)); @@ -3829,6 +3856,10 @@ 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_MIXER_PROFILE_COUNT; ++ii) { + cliDumpMixerProfile(ii, dumpMask); + } for (int ii = 0; ii < MAX_PROFILE_COUNT; ++ii) { cliDumpProfile(ii, dumpMask); } @@ -3837,8 +3868,10 @@ static void printConfig(const char *cmdline, bool doDiff) } setConfigProfile(currentProfileIndexSave); setConfigBatteryProfile(currentBatteryProfileIndexSave); + setConfigMixerProfile(currentMixerProfileIndexSave); cliPrintHashLine("restore original profile selection"); + cliPrintLinef("mixer_profile %d", currentMixerProfileIndexSave + 1); cliPrintLinef("profile %d", currentProfileIndexSave + 1); cliPrintLinef("battery_profile %d", currentBatteryProfileIndexSave + 1); @@ -3847,11 +3880,15 @@ static void printConfig(const char *cmdline, bool doDiff) #endif } else { // dump just the current profiles + cliDumpMixerProfile(getConfigMixerProfile(), dumpMask); cliDumpProfile(getConfigProfile(), dumpMask); cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask); } } - + if (dumpMask & DUMP_MIXER_PROFILE) { + cliDumpMixerProfile(getConfigMixerProfile(), dumpMask); + } + if (dumpMask & DUMP_PROFILE) { cliDumpProfile(getConfigProfile(), dumpMask); } @@ -4011,6 +4048,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 fa7d893655..52cb06f81a 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -108,6 +108,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) @@ -305,6 +306,7 @@ static void activateConfig(void) { activateControlRateConfig(); activateBatteryProfile(); + activateMixerConfig(); resetAdjustmentStates(); @@ -331,6 +333,7 @@ void readEEPROM(void) setConfigProfile(getConfigProfile()); setConfigBatteryProfile(getConfigBatteryProfile()); + setConfigMixerProfile(getConfigMixerProfile()); validateAndFixConfig(); activateConfig(); @@ -473,6 +476,36 @@ 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; + return ret; +} + +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); +} + void setGyroCalibration(float getGyroZero[XYZ_AXIS_COUNT]) { gyroConfigMutable()->gyro_zero_cal[X] = (int16_t) getGyroZero[X]; diff --git a/src/main/fc/config.h b/src/main/fc/config.h index e32a705e1a..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_MOTOR_STOP = 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, @@ -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) @@ -138,6 +139,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 setGyroCalibration(float getGyroZero[XYZ_AXIS_COUNT]); void setGravityCalibration(float getGravity); diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 8cf5a5ce10..87d9fbe746 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -81,6 +81,7 @@ #include "telemetry/telemetry.h" +#include "flight/mixer_profile.h" #include "flight/mixer.h" #include "flight/servos.h" #include "flight/pid.h" @@ -618,7 +619,7 @@ void processRx(timeUs_t currentTimeUs) const bool throttleIsLow = throttleStickIsLow(); // 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 (throttleIsLow) { @@ -705,14 +706,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 } } @@ -745,8 +746,8 @@ void processRx(timeUs_t currentTimeUs) } else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER) { if (throttleIsLow) { - if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { - if ((rollPitchStatus == CENTERED) || (feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING_LEGACY))) { + if (STATE(AIRMODE_ACTIVE)) { + if ((rollPitchStatus == CENTERED) || (ifMotorstopFeatureEnabled() && !STATE(FIXED_WING_LEGACY))) { ENABLE_STATE(ANTI_WINDUP); } else { @@ -764,7 +765,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); } @@ -792,7 +793,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 68990d37e2..849cdc2b7c 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -305,9 +305,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.c b/src/main/fc/fc_msp.c index f2c80bfd95..cdaac609ba 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -74,6 +74,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" @@ -1469,7 +1470,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); @@ -1599,6 +1601,20 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, ezTune()->expo); } 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 @@ -2888,7 +2904,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); @@ -3083,6 +3100,27 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) #endif +#ifdef USE_RATE_DYNAMICS + + case MSP2_INAV_SET_RATE_DYNAMICS: + + if (dataSize == 6) { + ((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; } @@ -3278,6 +3316,10 @@ 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) diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index 59aba5f8fe..f7c88d6e5b 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" @@ -99,6 +100,8 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = { { .boxId = BOXCHANGEMISSION, .boxName = "MISSION CHANGE", .permanentId = 59 }, { .boxId = BOXBEEPERMUTE, .boxName = "BEEPER MUTE", .permanentId = 60 }, { .boxId = BOXMULTIFUNCTION, .boxName = "MULTI FUNCTION", .permanentId = 61 }, + { .boxId = BOXMIXERPROFILE, .boxName = "MIXER PROFILE 2", .permanentId = 62 }, + { .boxId = BOXMIXERTRANSITION, .boxName = "MIXER TRANSITION", .permanentId = 63 }, { .boxId = CHECKBOX_ITEM_COUNT, .boxName = NULL, .permanentId = 0xFF } }; @@ -350,6 +353,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) @@ -418,6 +426,10 @@ void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags) #endif #ifdef USE_MULTI_FUNCTIONS CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXMULTIFUNCTION)), BOXMULTIFUNCTION); +#endif +#if (MAX_MIXER_PROFILE_COUNT > 1) + 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/rc_controls.c b/src/main/fc/rc_controls.c index c396fa8814..8a03ed8128 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -51,6 +51,7 @@ #include "flight/pid.h" #include "flight/failsafe.h" +#include "flight/mixer.h" #include "io/gps.h" #include "io/beeper.h" @@ -213,7 +214,7 @@ void processRcStickPositions(bool isThrottleLow) // perform actions bool armingSwitchIsActive = IS_RC_MODE_ACTIVE(BOXARM); - 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 (!isThrottleLow) { tryArm(); diff --git a/src/main/fc/rc_modes.h b/src/main/fc/rc_modes.h index 674fdded8d..6b56fa556b 100644 --- a/src/main/fc/rc_modes.h +++ b/src/main/fc/rc_modes.h @@ -79,6 +79,8 @@ typedef enum { BOXCHANGEMISSION = 50, BOXBEEPERMUTE = 51, BOXMULTIFUNCTION = 52, + BOXMIXERPROFILE = 53, + BOXMIXERTRANSITION = 54, CHECKBOX_ITEM_COUNT } boxId_e; diff --git a/src/main/fc/settings.c b/src/main/fc/settings.c index bef0750e88..109f430f84 100644 --- a/src/main/fc/settings.c +++ b/src/main/fc/settings.c @@ -241,6 +241,8 @@ static uint16_t getValueOffset(const setting_t *value) return value->offset + sizeof(ezTuneSettings_t) * getConfigProfile(); case BATTERY_CONFIG_VALUE: return value->offset + sizeof(batteryProfile_t) * getConfigBatteryProfile(); + case MIXER_CONFIG_VALUE: + return value->offset + sizeof(mixerProfile_t) * getConfigMixerProfile(); } return 0; } diff --git a/src/main/fc/settings.h b/src/main/fc/settings.h index a6cc403842..75e8bdbef3 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_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,12 +29,13 @@ typedef enum { } setting_type_e; typedef enum { - // value section, bits 4-5 + // 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), - EZ_TUNE_VALUE = (4 << SETTING_SECTION_OFFSET) + MIXER_CONFIG_VALUE = (4 << SETTING_SECTION_OFFSET), + EZ_TUNE_VALUE = (5 << SETTING_SECTION_OFFSET) } setting_section_e; typedef enum { @@ -43,8 +44,9 @@ typedef enum { MODE_LOOKUP = (1 << SETTING_MODE_OFFSET), // 0x40 } setting_mode_e; -#define SETTING_TYPE_MASK (0x0F) -#define SETTING_SECTION_MASK (0x30) + +#define SETTING_TYPE_MASK (0x07) +#define SETTING_SECTION_MASK (0x38) #define SETTING_MODE_MASK (0xC0) typedef struct settingMinMaxConfig_s { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index dbb479da13..d5531a22e8 100755 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -44,10 +44,10 @@ 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"] + values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "SPAN", "NONE"] enum: sbasMode_e - name: gps_dyn_model values: ["PEDESTRIAN", "AIR_1G", "AIR_4G"] @@ -1134,31 +1134,56 @@ groups: field: powerLimits.burstPowerFalldownTime max: 3000 - - name: PG_MIXER_CONFIG - type: mixerConfig_t + - name: PG_MIXER_PROFILE + type: mixerProfile_t + headers: ["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: motorstop_on_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. 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_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.automated_switch + type: bool + - name: mixer_switch_trans_timer + 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 + max: 200 + + - name: PG_REVERSIBLE_MOTORS_CONFIG type: reversibleMotorsConfig_t @@ -2301,7 +2326,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/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/flight/mixer.c b/src/main/flight/mixer.c index 771a22b321..35674c1f5d 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -32,6 +32,7 @@ #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,15 +83,6 @@ PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig, .neutral = SETTING_3D_NEUTRAL_DEFAULT ); -PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 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 -); - PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 10); PG_RESET_TEMPLATE(motorConfig_t, motorConfig, @@ -100,9 +92,6 @@ PG_RESET_TEMPLATE(motorConfig_t, motorConfig, .mincommand = SETTING_MIN_COMMAND_DEFAULT, .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); - PG_REGISTER_ARRAY_WITH_RESET_FN(timerOverride_t, HARDWARE_TIMER_DEFINITION_COUNT, timerOverrides, PG_TIMER_OVERRIDE_CONFIG, 0); #define CRASH_OVER_AFTER_CRASH_FLIP_STICK_MIN 0.15f @@ -125,14 +114,29 @@ 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){ + return currentMixerConfig.motorstopOnLow; } uint8_t getMotorCount(void) { @@ -158,35 +162,44 @@ 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); } + 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) @@ -208,7 +221,7 @@ void mixerInit(void) mixerResetDisarmedMotors(); - if (mixerConfig()->motorDirectionInverted) { + if (currentMixerConfig.motorDirectionInverted) { motorYawMultiplier = -1; } else { motorYawMultiplier = 1; @@ -231,7 +244,7 @@ void mixerResetDisarmedMotors(void) reversibleMotorsThrottleState = MOTOR_DIRECTION_FORWARD; - if (feature(FEATURE_MOTOR_STOP)) { + if (ifMotorstopFeatureEnabled()) { motorValueWhenStopped = motorZeroCommand; } else { motorValueWhenStopped = throttleIdleValue; @@ -289,7 +302,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); @@ -468,7 +481,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(void) @@ -614,6 +627,16 @@ 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 (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.h b/src/main/flight/mixer.h index 4274b28417..9ee6a20654 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -64,7 +64,6 @@ typedef struct motorMixer_s { float yaw; } motorMixer_t; -PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer); typedef struct timerOverride_s { uint8_t outputMode; @@ -72,15 +71,6 @@ typedef struct timerOverride_s { PG_DECLARE_ARRAY(timerOverride_t, HARDWARE_TIMER_DEFINITION_COUNT, timerOverrides); -typedef struct mixerConfig_s { - int8_t motorDirectionInverted; - uint8_t platformType; - bool hasFlaps; - int16_t appliedMixerPreset; -} mixerConfig_t; - -PG_DECLARE(mixerConfig_t, mixerConfig); - typedef struct reversibleMotorsConfig_s { uint16_t deadband_low; // min 3d value uint16_t deadband_high; // max 3d value @@ -117,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(bool); uint16_t setDesiredThrottle(uint16_t throttle, bool allowMotorStop); @@ -135,6 +126,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 new file mode 100644 index 0000000000..de1cdecb3b --- /dev/null +++ b/src/main/flight/mixer_profile.c @@ -0,0 +1,243 @@ +#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 "common/axis.h" +#include "flight/pid.h" +#include "flight/servos.h" +#include "flight/failsafe.h" +#include "navigation/navigation.h" +#include "navigation/navigation_private.h" + +#include "fc/fc_core.h" +#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; +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); + +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 + .motorstopOnLow = SETTING_MOTORSTOP_ON_LOW_DEFAULT, + .PIDProfileLinking = SETTING_MIXER_PID_PROFILE_LINKING_DEFAULT, + .automated_switch = SETTING_MIXER_AUTOMATED_SWITCH_DEFAULT, + .switchTransitionTimer = SETTING_MIXER_SWITCH_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); + } + 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 + ); + } + } +} + +void activateMixerConfig(){ + currentMixerProfileIndex = getConfigMixerProfile(); + currentMixerConfig = *mixerConfig(); + nextProfileIndex = (currentMixerProfileIndex + 1) % MAX_MIXER_PROFILE_COUNT; +} + +void mixerConfigInit(void) +{ + activateMixerConfig(); + servosInit(); + mixerUpdateStateFlags(); + mixerInit(); + if (currentMixerConfig.PIDProfileLinking) + { + // LOG_INFO(PWM, "mixer switch pidInit"); + setConfigProfile(getConfigMixerProfile()); + pidInit(); + pidInitFilters(); + pidResetErrorAccumulators(); //should be safer to reset error accumulators + schedulePidGainsUpdate(); + navigationUsePIDs(); // set navigation pid gains + } +} + +void setMixerProfileAT(void) +{ + mixerProfileAT.transitionStartTime = millis(); + mixerProfileAT.transitionTransEndTime = mixerProfileAT.transitionStartTime + (timeMs_t)currentMixerConfig.switchTransitionTimer * 100; +} + +bool checkMixerATRequired(mixerProfileATRequest_e required_action) +{ + //return false if mixerAT condition is not required or setting is not valid + if ((!STATE(AIRPLANE)) && (!STATE(MULTIROTOR))) + { + return false; + } + if (!isModeActivationConditionPresent(BOXMIXERPROFILE)) + { + return false; + } + + 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; +} + +bool mixerATUpdateState(mixerProfileATRequest_e required_action) +{ + //return true if mixerAT is done or not required + bool reprocessState; + do + { + reprocessState=false; + if (required_action==MIXERAT_REQUEST_ABORT){ + isMixerTransitionMixing_requested = false; + mixerProfileAT.phase = MIXERAT_PHASE_IDLE; + return true; + } + switch (mixerProfileAT.phase){ + case MIXERAT_PHASE_IDLE: + //check if mixerAT is required + 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_TRANSITIONING; + reprocessState = true; + break; + case MIXERAT_PHASE_TRANSITIONING: + isMixerTransitionMixing_requested = true; + if (millis() > mixerProfileAT.transitionTransEndTime){ + isMixerTransitionMixing_requested = false; + outputProfileHotSwitch(nextProfileIndex); + mixerProfileAT.phase = MIXERAT_PHASE_IDLE; + reprocessState = true; + //transition is done + } + return false; + break; + default: + break; + } + } + while (reprocessState); + return true; +} + +bool checkMixerProfileHotSwitchAvalibility(void) +{ + if (MAX_MIXER_PROFILE_COUNT != 2) + { + return false; + } + return true; +} + +void outputProfileUpdateTask(timeUs_t currentTimeUs) +{ + UNUSED(currentTimeUs); + bool mixerAT_inuse = mixerProfileAT.phase != MIXERAT_PHASE_IDLE; + // transition mode input for servo mix and motor mix + if (!FLIGHT_MODE(FAILSAFE_MODE) && (!mixerAT_inuse)) + { + 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)); +} + +// switch mixerprofile without reboot +bool outputProfileHotSwitch(int profile_index) +{ + static bool allow_hot_switch = true; + // 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 (areSensorsCalibrating()) + { // it seems like switching before sensors calibration complete will cause pid stops to respond, especially in D + return false; + } + if (!checkMixerProfileHotSwitchAvalibility()) + { + // LOG_INFO(PWM, "mixer switch failed, checkMixerProfileHotSwitchAvalibility"); + return false; + } + 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; + } + if (!setConfigMixerProfile(profile_index)) + { + // LOG_INFO(PWM, "mixer switch failed to set config"); + return false; + } + mixerConfigInit(); + return true; +} diff --git a/src/main/flight/mixer_profile.h b/src/main/flight/mixer_profile.h new file mode 100644 index 0000000000..bf52d45c3d --- /dev/null +++ b/src/main/flight/mixer_profile.h @@ -0,0 +1,78 @@ +#pragma once + +#include "config/parameter_group.h" +#include "flight/failsafe.h" +#include "flight/mixer.h" +#include "flight/servos.h" + +#ifndef MAX_MIXER_PROFILE_COUNT +#define MAX_MIXER_PROFILE_COUNT 2 +#endif + +typedef struct mixerConfig_s { + int8_t motorDirectionInverted; + uint8_t platformType; + bool hasFlaps; + int16_t appliedMixerPreset; + bool motorstopOnLow; + bool PIDProfileLinking; + bool automated_switch; + int16_t switchTransitionTimer; +} mixerConfig_t; +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); +typedef enum { + MIXERAT_REQUEST_NONE, //no request, stats checking only + MIXERAT_REQUEST_RTH, + MIXERAT_REQUEST_LAND, + MIXERAT_REQUEST_ABORT, +} mixerProfileATRequest_e; + +//mixerProfile Automated Transition PHASE +typedef enum { + MIXERAT_PHASE_IDLE, + MIXERAT_PHASE_TRANSITION_INITIALIZE, + MIXERAT_PHASE_TRANSITIONING, + MIXERAT_PHASE_DONE, +} mixerProfileATState_e; + +typedef struct mixerProfileAT_s { + mixerProfileATState_e phase; + bool transitionInputMixing; + timeMs_t transitionStartTime; + timeMs_t transitionStabEndTime; + timeMs_t transitionTransEndTime; +} mixerProfileAT_t; +extern mixerProfileAT_t mixerProfileAT; +bool checkMixerATRequired(mixerProfileATRequest_e required_action); +bool mixerATUpdateState(mixerProfileATRequest_e required_action); + +extern mixerConfig_t currentMixerConfig; +extern int currentMixerProfileIndex; +extern bool isMixerTransitionMixing; +#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_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)) +#define mixerMotorMixersByIndex(index) (mixerProfiles(index)->MotorMixers) +#define mixerServoMixersByIndex(index) (mixerProfiles(index)->ServoMixers) + +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 diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index b2fd0383a2..2bb4ab7035 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -43,6 +43,7 @@ #include "flight/pid.h" #include "flight/imu.h" #include "flight/mixer.h" +#include "flight/mixer_profile.h" #include "flight/rpm_filter.h" #include "flight/kalman.h" #include "flight/smith_predictor.h" @@ -1065,7 +1066,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 @@ -1213,9 +1214,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/pid_autotune.c b/src/main/flight/pid_autotune.c index 2eaef1175c..140c4ab61d 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/flight/rth_estimator.c b/src/main/flight/rth_estimator.c index eed9adbae3..708c71bd1c 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; } diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 67235a1133..4d4bb497d1 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -70,11 +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) +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, @@ -83,7 +82,7 @@ void pgResetFn_customServoMixers(servoMixer_t *instance) #ifdef USE_PROGRAMMING_FRAMEWORK ,.conditionId = -1 #endif - ); + ); } } @@ -104,7 +103,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; @@ -115,7 +115,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; @@ -172,28 +172,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++; } } @@ -231,7 +234,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; } @@ -261,7 +264,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; } } @@ -297,6 +300,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[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: // data - middle = input @@ -335,19 +340,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 @@ -355,7 +363,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], inputRaw, currentServoMixer[i].speed * 10, dT); servo[target] += ((int32_t)inputLimited * currentServoMixer[i].rate) / 100; } @@ -430,6 +438,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) { @@ -451,6 +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 (!currentServoMixerActivative[i]) {continue;} const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; if (source == axis) { @@ -463,6 +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 (!currentServoMixerActivative[i]) {continue;} const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; if (source == axis) { @@ -496,6 +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 (!currentServoMixerActivative[i]) {continue;} const uint8_t target = currentServoMixer[i].targetChannel; const uint8_t source = currentServoMixer[i].inputSource; if (source == axis) { @@ -593,6 +606,10 @@ void processServoAutotrim(const float dT) { return; } #endif + if(!STATE(AIRPLANE)) + { + return; + } if (feature(FEATURE_FW_AUTOTRIM)) { processContinuousServoAutotrim(dT); } else { diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index 841415ea23..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_MIXER_TRANSITION = 38, INPUT_SOURCE_COUNT } inputSource_e; @@ -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/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..199652a3a2 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, @@ -47,6 +46,7 @@ typedef enum { SBAS_WAAS, SBAS_MSAS, SBAS_GAGAN, + SBAS_SPAN, SBAS_NONE } sbasMode_e; 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/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 }; diff --git a/src/main/io/osd.c b/src/main/io/osd.c index f5daeaf63c..1aee556e1d 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -316,7 +316,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; @@ -326,7 +326,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; @@ -334,7 +334,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; @@ -489,7 +489,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 = '*'; @@ -562,7 +562,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 { @@ -575,7 +575,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 { @@ -1151,7 +1151,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 } @@ -1162,7 +1162,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'; } @@ -1486,13 +1486,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'; } @@ -1508,7 +1508,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(); @@ -1602,7 +1602,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); @@ -1707,7 +1707,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'; @@ -1734,7 +1734,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 { @@ -1749,7 +1749,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'; @@ -1764,7 +1764,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'; @@ -1834,7 +1834,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] = '-'; } @@ -1912,6 +1912,39 @@ static bool osdDrawSingleElement(uint8_t item) osdFormatDistanceSymbol(buff + 1, getTotalTravelDistance(), 0); break; + case OSD_ODOMETER: + { + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_ODOMETER); + 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: + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(odometerDist), FEET_PER_MILE, 1, 0, 6, true); + buff[6] = SYM_MI; + break; + default: + case OSD_UNIT_GA: + 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: + osdFormatCentiNumber(buff, odometerDist, METERS_PER_KILOMETER, 1, 0, 6, true); + buff[6] = SYM_KM; + break; + } + buff[7] = '\0'; + elemPosX++; + } + break; + case OSD_GROUND_COURSE: { buff[0] = SYM_GROUND_COURSE; @@ -1994,7 +2027,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; } @@ -2147,37 +2180,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: @@ -2423,7 +2457,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: @@ -2433,7 +2467,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: @@ -2494,7 +2528,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; @@ -2527,7 +2561,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] = '-'; @@ -2541,7 +2575,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] = '-'; @@ -2836,7 +2870,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'; @@ -2999,7 +3033,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 { @@ -3013,7 +3047,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 { @@ -3029,7 +3063,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 { @@ -3070,17 +3104,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; } @@ -3094,7 +3128,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); } @@ -3107,7 +3141,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); } @@ -3283,7 +3317,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; @@ -3452,14 +3486,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'; @@ -3473,7 +3507,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'; @@ -3750,6 +3784,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); @@ -4012,7 +4047,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); @@ -4023,18 +4058,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; } @@ -4249,22 +4284,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); @@ -4273,7 +4308,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); @@ -4295,7 +4330,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 { @@ -4308,7 +4343,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] = '-'; @@ -4317,7 +4352,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 { @@ -4330,7 +4365,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] = '-'; @@ -4341,7 +4376,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 { @@ -4354,7 +4389,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] = '-'; @@ -4369,19 +4404,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 04794c6cec..877437ff88 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -274,6 +274,7 @@ typedef enum { OSD_PILOT_NAME, OSD_PAN_SERVO_CENTRED, OSD_MULTI_FUNCTION, + OSD_ODOMETER, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; @@ -483,7 +484,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 diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index 3c38c8ffd4..0d7f107fa1 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -92,5 +92,8 @@ #define MSP2_INAV_LED_STRIP_CONFIG_EX 0x2048 #define MSP2_INAV_SET_LED_STRIP_CONFIG_EX 0x2049 -#define MSP2_INAV_EZ_TUNE 0x2050 -#define MSP2_INAV_EZ_TUNE_SET 0x2051 \ No newline at end of file +#define MSP2_INAV_RATE_DYNAMICS 0x2060 +#define MSP2_INAV_SET_RATE_DYNAMICS 0x2061 + +#define MSP2_INAV_EZ_TUNE 0x2070 +#define MSP2_INAV_EZ_TUNE_SET 0x2071 diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 1207612745..7dff6528e1 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -47,7 +47,7 @@ #include "fc/settings.h" #include "flight/imu.h" -#include "flight/mixer.h" +#include "flight/mixer_profile.h" #include "flight/pid.h" #include "io/beeper.h" @@ -69,6 +69,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 @@ -308,6 +309,9 @@ 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 navigationFSMEvent_t navOnEnteringState_NAV_STATE_MIXERAT_ABORT(navigationFSMState_t previousState); static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { /** Idle state ******************************************************/ @@ -328,6 +332,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, } }, @@ -596,6 +601,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, } }, @@ -654,6 +660,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, } }, @@ -807,6 +814,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, } }, @@ -941,6 +949,52 @@ 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 | NAV_REQUIRE_THRTILT | NAV_MIXERAT, + .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 | 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_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_STATE_MIXERAT_ABORT] = { + .persistentId = NAV_PERSISTENT_ID_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, + .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, + + } + }, }; static navigationFSMStateFlags_t navGetStateFlags(navigationFSMState_t state) @@ -1366,6 +1420,10 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_HEAD_HOME(navigatio return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING; } + if (checkMixerATRequired(MIXERAT_REQUEST_RTH) && (calculateDistanceToDestination(&posControl.rthState.homePosition.pos) > (navConfig()->fw.loiter_radius * 3))){ + 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); @@ -1456,12 +1514,22 @@ 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; + 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; @@ -1854,6 +1922,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) +{ + 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); + 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; @@ -2747,6 +2879,9 @@ static void updateNavigationFlightStatistics(void) } } +/* + * Total travel distance in cm + */ uint32_t getTotalTravelDistance(void) { return lrintf(posControl.totalTripDistance); @@ -3784,14 +3919,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; } @@ -4205,15 +4340,6 @@ 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); - } #if defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) /* configure WP missions at boot */ #ifdef USE_MULTI_MISSION @@ -4274,7 +4400,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; } @@ -4369,7 +4495,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_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 0881752fc5..3a88e4ea36 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" @@ -293,6 +294,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. diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index f5072c4219..c408f109c9 100644 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -157,6 +157,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 @@ -164,6 +165,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, @@ -228,6 +230,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, + NAV_PERSISTENT_ID_MIXERAT_ABORT = 41, } navigationPersistentId_e; typedef enum { @@ -275,6 +280,10 @@ typedef enum { NAV_STATE_CRUISE_IN_PROGRESS, NAV_STATE_CRUISE_ADJUSTING, + NAV_STATE_MIXERAT_INITIALIZE, + NAV_STATE_MIXERAT_IN_PROGRESS, + NAV_STATE_MIXERAT_ABORT, + NAV_STATE_COUNT, } navigationFSMState_t; @@ -304,6 +313,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 { diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index f07e487f9c..d3b45453c9 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -46,6 +46,7 @@ #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" @@ -424,6 +425,7 @@ static int logicConditionCompute( pidInit(); pidInitFilters(); schedulePidGainsUpdate(); + navigationUsePIDs(); //set navigation pid gains profileChanged = true; } return profileChanged; @@ -769,6 +771,14 @@ 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 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 779dbb1b98..941e47f8d0 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -135,6 +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 // 39 + LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE, //0,1 // 40 } logicFlightOperands_e; typedef enum { 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 diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 0afc15b5be..78e52f75c2 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -564,7 +564,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 = (throttleStickIsLow() && feature(FEATURE_MOTOR_STOP)) ? 0 : (int32_t)rcCommand[THROTTLE] - 1000; + throttleOffset = (throttleStickIsLow() && 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/AIKONF4/config.c b/src/main/target/AIKONF4/config.c new file mode 100644 index 0000000000..c77bbfaf3a --- /dev/null +++ b/src/main/target/AIKONF4/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/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 diff --git a/src/main/target/AIRBOTF4/target.c b/src/main/target/AIRBOTF4/target.c index 8e324818d8..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_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_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_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_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 a81988d0a6..22d2564821 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_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 bb60067073..e7ee4cf552 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_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/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.c b/src/main/target/ALIENFLIGHTNGF7/target.c index 45b18c71a3..455747923e 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_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/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/target/ANYFC/target.c b/src/main/target/ANYFC/target.c index f9dccae0f2..5353b58911 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_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 c14bf1dbe4..65f807d798 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_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_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_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_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 + 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/ANYFCM7/target.c b/src/main/target/ANYFCM7/target.c index 24f289afa6..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_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_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/AOCODARCF405AIO/target.c b/src/main/target/AOCODARCF405AIO/target.c index 9548cb179a..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_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_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 c18898b84c..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_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_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_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_OUTPUT_AUTO, 0, 0 ), // S5 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 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_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 f48fb445aa..d09fafeda2 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_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_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_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/AOCODARCF7MINI/target.c b/src/main/target/AOCODARCF7MINI/target.c index 7b34bb05df..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_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_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_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_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_MC_MOTOR | TIM_USE_FW_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_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_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 3bc551f5c4..85e8b00493 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_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_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_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_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_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_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/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..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_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_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 fc46a9c0b8..8d4b966b69 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_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 + 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 + 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..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_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_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 2360b6a362..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_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_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 815781e0c6..f065744029 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_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 }; -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..e24689c0ca 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_OUTPUT_AUTO, 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_OUTPUT_AUTO, 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..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_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_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 3b6dbb4bda..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_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_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/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 490372c048..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_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_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_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_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/COLIBRI/target.c b/src/main/target/COLIBRI/target.c index dbeb9c083f..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_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_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 add81e2b28..e1cddea261 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_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_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) DEF_TIM(TIM2, CH1, PA5, TIM_USE_ANY, 0, 0), // FC CAM 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 8ea225e412..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_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_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/F4BY/target.c b/src/main/target/F4BY/target.c index 5565713c03..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_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_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/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/FF_F35_LIGHTNING/target.c b/src/main/target/FF_F35_LIGHTNING/target.c index 61180587f0..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_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_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 853104d01f..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_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_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 ba3cfc5162..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_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_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_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_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/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 133c2bd1d7..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_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_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_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_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_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_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) @@ -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..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_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_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/FLYCOLORF7MINI/target.c b/src/main/target/FLYCOLORF7MINI/target.c index 146aa9fe1c..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_MOTOR, 0, 0), // S1 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 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 }; diff --git a/src/main/target/FLYWOOF405PRO/target.c b/src/main/target/FLYWOOF405PRO/target.c index 753f904613..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_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_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_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_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/FLYWOOF411/target.c b/src/main/target/FLYWOOF411/target.c index 56d8e7afb4..965974162b 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_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_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_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 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..879b66d01f 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_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(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 }; 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..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_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_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/FOXEERF405/target.c b/src/main/target/FOXEERF405/target.c index cf367ba00c..1ad827bb5c 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_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) + 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..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_MC_MOTOR | TIM_USE_FW_MOTOR, 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_MC_MOTOR | TIM_USE_FW_MOTOR, 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_MC_MOTOR | TIM_USE_FW_MOTOR, 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_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_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 2cadae4d77..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_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_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_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_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/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/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/FOXEERH743/target.c b/src/main/target/FOXEERH743/target.c index c8bc9e7ada..3ab6e19529 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_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_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_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_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_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/FRSKYF4/target.c b/src/main/target/FRSKYF4/target.c index 39b1be4890..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_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_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 8594a6f757..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_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_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_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_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/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..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_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_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 ace9b30736..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_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_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 8e206e7b19..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_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_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/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 fa80baf92d..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_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_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_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_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_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_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/GEPRC_F722_AIO/target.c b/src/main/target/GEPRC_F722_AIO/target.c index 6699298db6..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_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, 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]); diff --git a/src/main/target/HAKRCF405D/target.c b/src/main/target/HAKRCF405D/target.c index 3e4e0f763c..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_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_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/HAKRCF405V2/target.c b/src/main/target/HAKRCF405V2/target.c index ba55aed031..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_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_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 7f1abaf76a..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_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_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 6c8aec8d37..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_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_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 eb9b4d87c2..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_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_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/config.c b/src/main/target/HGLRCF722/config.c index 4f04f3b4aa..fd3d57037b 100644 --- a/src/main/target/HGLRCF722/config.c +++ b/src/main/target/HGLRCF722/config.c @@ -26,6 +26,8 @@ #include "platform.h" +#include "drivers/pwm_mapping.h" + #include "fc/fc_msp_box.h" #include "io/piniobox.h" @@ -34,4 +36,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/HGLRCF722/target.c b/src/main/target/HGLRCF722/target.c index faf6725705..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_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_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_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..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_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_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/IFLIGHTF7_TWING/config.c b/src/main/target/IFLIGHTF7_TWING/config.c new file mode 100644 index 0000000000..912c662d05 --- /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(TIM4))->outputMode = OUTPUT_MODE_MOTORS; +} diff --git a/src/main/target/IFLIGHTF7_TWING/target.c b/src/main/target/IFLIGHTF7_TWING/target.c index d596849dd5..6876f07b20 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_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_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_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_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_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_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/IFLIGHT_BLITZ_F722/target.c b/src/main/target/IFLIGHT_BLITZ_F722/target.c index 8bba266c36..ac2af33d20 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_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_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_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_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_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 3c26d72f80..54ba97a490 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_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 + 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..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_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_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_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..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_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_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/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..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_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_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_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_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_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_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_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_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 249047470a..53ae9359de 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_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 3415db1edd..095038960d 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_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(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..8851f95286 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_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 4), // S5 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 5), // S6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 6), // S7 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 7), // S8 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 9), // LED_2812 }; diff --git a/src/main/target/KAKUTEH7WING/target.c b/src/main/target/KAKUTEH7WING/target.c index 2b880fc3b7..30b9a4f5de 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_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_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_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_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_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_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_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/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..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_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_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_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_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/config.c b/src/main/target/MAMBAF405_2022A/config.c index 355605fd90..ba3a5344c2 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" @@ -56,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; } diff --git a/src/main/target/MAMBAF405_2022A/target.c b/src/main/target/MAMBAF405_2022A/target.c index 0e659296e8..d91361a263 100644 --- a/src/main/target/MAMBAF405_2022A/target.c +++ b/src/main/target/MAMBAF405_2022A/target.c @@ -20,18 +20,17 @@ #include "platform.h" #include "drivers/io.h" -#include "drivers/timer.h" #include "drivers/pwm_mapping.h" #include "drivers/bus.h" 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_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 f7db2a3039..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_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_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 56f5483cbd..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_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_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_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_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 c39247afe5..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_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_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_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_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 afe6e36359..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_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_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_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_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/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 f684670a22..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_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_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_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_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/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/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/MATEKF405CAN/target.c b/src/main/target/MATEKF405CAN/target.c index f4c9826ac8..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_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_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_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_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/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" diff --git a/src/main/target/MATEKF405SE/target.c b/src/main/target/MATEKF405SE/target.c index c81fe5a7f0..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_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_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_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_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 70561e001f..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_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_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_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_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_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_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/MATEKF411/target.c b/src/main/target/MATEKF411/target.c index c192e8c69d..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_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_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_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_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 679df39607..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_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_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_MC_SERVO | TIM_USE_FW_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 9bfad340f1..b873201652 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_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 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..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_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_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_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_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_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_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_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_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/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/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 1ea322fb82..6e469dfff3 100644 --- a/src/main/target/MATEKF722SE/target.c +++ b/src/main/target/MATEKF722SE/target.c @@ -30,27 +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_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_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_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_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) -#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_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/MATEKF765/target.c b/src/main/target/MATEKF765/target.c index 0a4e42ac9c..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_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_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_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_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_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_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_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_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/NEUTRONRCF435MINI/target.c b/src/main/target/NEUTRONRCF435MINI/target.c index 995bf8f3d1..472867af57 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_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 }; 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..3a8848911f 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_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_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 - 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..b1cd9031cc 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_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_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_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 }; 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..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_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_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 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_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 0508a0155b..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_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_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 9c7e4b76a8..81b30e11f2 100644 --- a/src/main/target/OMNIBUSF4/target.c +++ b/src/main/target/OMNIBUSF4/target.c @@ -36,27 +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_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_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_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_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_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_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_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_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_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_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_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_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/OMNIBUSF7/target.c b/src/main/target/OMNIBUSF7/target.c index c11e1629bf..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_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_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/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 6f92459630..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_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_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_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_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/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 294c962f24..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_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_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_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_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/RADIX/target.c b/src/main/target/RADIX/target.c index dd05a6b3ce..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_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_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 7cd184b9f6..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_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_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_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_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/RUSH_BLADE_F7/target.c b/src/main/target/RUSH_BLADE_F7/target.c index 565c8a2346..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_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_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/SAGEATF4/target.c b/src/main/target/SAGEATF4/target.c index 3d8ed6feb5..4887541467 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_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_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_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 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); - \ No newline at end of file + diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h index 78f5022a9e..3fbe45a5ca 100644 --- a/src/main/target/SITL/target.h +++ b/src/main/target/SITL/target.h @@ -69,6 +69,8 @@ #define USE_GPS_FAKE #define USE_RANGEFINDER_FAKE #define USE_RX_SIM +#undef MAX_MIXER_PROFILE_COUNT +#define MAX_MIXER_PROFILE_COUNT 2 #define USE_MSP_OSD #define USE_OSD 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 e6bec48b4c..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_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_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), }; diff --git a/src/main/target/SKYSTARSF722HD/target.c b/src/main/target/SKYSTARSF722HD/target.c index cf5906d915..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_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_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/SKYSTARSH743HD/target.c b/src/main/target/SKYSTARSH743HD/target.c index 07a2b0ef70..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_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_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 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_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 4), // S5 - DEF_TIM(TIM5, 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_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 c5ae5109e9..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_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_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/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/SPEEDYBEEF4/target.c b/src/main/target/SPEEDYBEEF4/target.c index be21bfbb26..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_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_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_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_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 1118940e6f..3cc7fbbebb 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_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_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_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 fffac26520..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_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_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_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_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/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)) diff --git a/src/main/target/SPEEDYBEEF405WING/target.c b/src/main/target/SPEEDYBEEF405WING/target.c index a06d783801..c6141b9a73 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_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_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_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_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_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(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..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_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_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_MC_MOTOR | TIM_USE_FW_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/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/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/SPEEDYBEEF7MINI/target.c b/src/main/target/SPEEDYBEEF7MINI/target.c index 7cc2506b66..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_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_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_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_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_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_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/config.c b/src/main/target/SPEEDYBEEF7V2/config.c index dccd2e8a04..c653b78b29 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_mapping.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/SPEEDYBEEF7V2/target.c b/src/main/target/SPEEDYBEEF7V2/target.c index 60b8641073..0914224a05 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_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 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..5d5b064f81 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_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 }; -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/config.c b/src/main/target/SPRACINGF4EVO/config.c index fa1e802297..31e6b2d0fd 100755 --- a/src/main/target/SPRACINGF4EVO/config.c +++ b/src/main/target/SPRACINGF4EVO/config.c @@ -23,10 +23,14 @@ #include "io/serial.h" #include "sensors/barometer.h" #include "telemetry/telemetry.h" +#include "drivers/pwm_mapping.h" 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(TIM3))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/SPRACINGF4EVO/target.c b/src/main/target/SPRACINGF4EVO/target.c index a52df8997d..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_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_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_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_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_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_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_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_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 }; 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..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_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_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_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_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 0a995a8ac2..606ac8819d 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_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_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..310ab66b0a 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_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_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_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_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_OUTPUT_AUTO, 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_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 3794e7032c..cd6a17ee68 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_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 }; 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..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_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_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_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_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_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_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 diff --git a/src/main/target/common.h b/src/main/target/common.h index 380ca547cf..a17ea0209d 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 @@ -190,7 +188,8 @@ #define USE_SERIALRX_SUMD #define USE_TELEMETRY_HOTT #define USE_HOTT_TEXTMODE - +#else +#define MAX_MIXER_PROFILE_COUNT 1 #endif #define USE_EZ_TUNE \ No newline at end of file diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 90c1377bc8..30237c2855 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/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/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")); 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',