Skip to content

Commit

Permalink
Merge pull request #7928 from iNavFlight/dzikuvx-configurable-outputs…
Browse files Browse the repository at this point in the history
…-mode

Configurable outputs mode
  • Loading branch information
DzikuVx authored Mar 30, 2022
2 parents 9c3d413 + 665af0f commit 362f5c5
Show file tree
Hide file tree
Showing 103 changed files with 159 additions and 101 deletions.
10 changes: 10 additions & 0 deletions docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -4712,6 +4712,16 @@ Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, and `HD`

---

### output_mode

Output function assignment mode. AUTO assigns outputs according to the default mapping, SERVOS assigns all outputs to servos, MOTORS assigns all outputs to motors

| Default | Min | Max |
| --- | --- | --- |
| AUTO | | |

---

### pid_type

Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID`
Expand Down
33 changes: 32 additions & 1 deletion src/main/drivers/pwm_mapping.c
Original file line number Diff line number Diff line change
Expand Up @@ -198,13 +198,44 @@ static bool checkPwmTimerConflicts(const timerHardware_t *timHw)
return false;
}

static void timerHardwareOverride(timerHardware_t * timer) {
if (mixerConfig()->outputMode == OUTPUT_MODE_SERVOS) {

//Motors are rewritten as servos
if (timer->usageFlags & TIM_USE_MC_MOTOR) {
timer->usageFlags = timer->usageFlags & ~TIM_USE_MC_MOTOR;
timer->usageFlags = timer->usageFlags | TIM_USE_MC_SERVO;
}
if (timer->usageFlags & TIM_USE_FW_MOTOR) {
timer->usageFlags = timer->usageFlags & ~TIM_USE_FW_MOTOR;
timer->usageFlags = timer->usageFlags | TIM_USE_FW_SERVO;
}

} else if (mixerConfig()->outputMode == OUTPUT_MODE_MOTORS) {

// Servos are rewritten as motors
if (timer->usageFlags & TIM_USE_MC_SERVO) {
timer->usageFlags = timer->usageFlags & ~TIM_USE_MC_SERVO;
timer->usageFlags = timer->usageFlags | TIM_USE_MC_MOTOR;
}
if (timer->usageFlags & TIM_USE_FW_SERVO) {
timer->usageFlags = timer->usageFlags & ~TIM_USE_FW_SERVO;
timer->usageFlags = timer->usageFlags | TIM_USE_FW_MOTOR;
}
}
}

void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos)
{
timOutputs->maxTimMotorCount = 0;
timOutputs->maxTimServoCount = 0;

for (int idx = 0; idx < timerHardwareCount; idx++) {
const timerHardware_t *timHw = &timerHardware[idx];

timerHardware_t *timHw = &timerHardware[idx];

timerHardwareOverride(timHw);

int type = MAP_TO_NONE;

// Check for known conflicts (i.e. UART, LEDSTRIP, Rangefinder and ADC)
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/timer.h
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ extern timHardwareContext_t * timerCtx[HARDWARE_TIMER_DEFINITION_COUNT];
extern const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT];

// Per target timer output definitions
extern const timerHardware_t timerHardware[];
extern timerHardware_t timerHardware[];
extern const int timerHardwareCount;

typedef enum {
Expand Down
3 changes: 2 additions & 1 deletion src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -1484,8 +1484,9 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF

case MSP2_INAV_OUTPUT_MAPPING:
for (uint8_t i = 0; i < timerHardwareCount; ++i)
if (!(timerHardware[i].usageFlags & (TIM_USE_PPM | TIM_USE_PWM)))
if (!(timerHardware[i].usageFlags & (TIM_USE_PPM | TIM_USE_PWM))) {
sbufWriteU8(dst, timerHardware[i].usageFlags);
}
break;

case MSP2_INAV_MC_BRAKING:
Expand Down
9 changes: 8 additions & 1 deletion src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,9 @@ tables:
enum: smartportFuelUnit_e
- name: platform_type
values: ["MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT"]
enum: flyingPlatformType_e
- name: output_mode
values: ["AUTO", "MOTORS", "SERVOS"]
enum: outputMode_e
- name: tz_automatic_dst
values: ["OFF", "EU", "USA"]
enum: tz_automatic_dst_e
Expand Down Expand Up @@ -1262,6 +1264,11 @@ groups:
field: appliedMixerPreset
min: -1
max: INT16_MAX
- name: output_mode
description: "Output function assignment mode. AUTO assigns outputs according to the default mapping, SERVOS assigns all outputs to servos, MOTORS assigns all outputs to motors"
default_value: "AUTO"
field: outputMode
table: output_mode

- name: PG_REVERSIBLE_MOTORS_CONFIG
type: reversibleMotorsConfig_t
Expand Down
3 changes: 2 additions & 1 deletion src/main/flight/mixer.c
Original file line number Diff line number Diff line change
Expand Up @@ -83,13 +83,14 @@ PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig,
.neutral = SETTING_3D_NEUTRAL_DEFAULT
);

PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 4);
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
.outputMode = SETTING_OUTPUT_MODE_DEFAULT,
);

#ifdef BRUSHED_MOTORS
Expand Down
8 changes: 8 additions & 0 deletions src/main/flight/mixer.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,13 @@ typedef enum {
PLATFORM_OTHER = 6
} flyingPlatformType_e;


typedef enum {
OUTPUT_MODE_AUTO = 0,
OUTPUT_MODE_MOTORS,
OUTPUT_MODE_SERVOS
} outputMode_e;

typedef struct motorAxisCorrectionLimits_s {
int16_t min;
int16_t max;
Expand All @@ -62,6 +69,7 @@ typedef struct mixerConfig_s {
uint8_t platformType;
bool hasFlaps;
int16_t appliedMixerPreset;
uint8_t outputMode;
} mixerConfig_t;

PG_DECLARE(mixerConfig_t, mixerConfig);
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/AIKONF4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
#include "drivers/timer.h"
#include "drivers/timer_def.h"

const timerHardware_t timerHardware[] = {
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
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/AIRBOTF4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "drivers/timer.h"
#include "drivers/bus.h"

const timerHardware_t timerHardware[] = {
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
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/AIRBOTF7/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_imu1_mpu6000, DEVHW_MPU6000, GYRO_1_SPI_BUS,
BUSDEV_REGISTER_SPI_TAG(busdev_imu1_mpu6500, DEVHW_MPU6500, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, GYRO_1_EXTI_PIN, 1, DEVFLAGS_NONE, GYRO_1_ALIGN);
#endif

const timerHardware_t timerHardware[] = {
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

Expand Down
2 changes: 1 addition & 1 deletion src/main/target/AIRHEROF3/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include "drivers/timer.h"
#include "drivers/bus.h"

const timerHardware_t timerHardware[] = {
timerHardware_t timerHardware[] = {
DEF_TIM(TIM2, CH1, PA0, TIM_USE_PPM | TIM_USE_PWM, 0),
DEF_TIM(TIM2, CH2, PA1, TIM_USE_PWM, 0),
DEF_TIM(TIM2, CH3, PA2, TIM_USE_PWM, 0),
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/ALIENFLIGHTF3/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
timerHardware_t timerHardware[] = {
// up to 10 Motor Outputs
DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1 - PB15 - NONE
DEF_TIM(TIM15, CH1, PB14, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PB14 - DMA1_CH5
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/ALIENFLIGHTF4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
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
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/ALIENFLIGHTNGF7/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
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
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/ANYFC/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
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
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/ANYFCF7/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
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
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/ANYFCM7/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#define TIM_EN TIMER_OUTPUT_ENABLED
#define TIM_EN_N TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL

const timerHardware_t timerHardware[] = {
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 DMA2_ST2 DMA2_ST2
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/ASGARD32F4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
#include "drivers/timer.h"
#include "drivers/bus.h"

const timerHardware_t timerHardware[] = {
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)
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/ASGARD32F7/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
#include "drivers/timer.h"
#include "drivers/bus.h"

const timerHardware_t timerHardware[] = {
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)
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/BEEROTORF4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
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
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/BETAFLIGHTF3/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include "drivers/timer.h"
#include "drivers/pwm_mapping.h"

const timerHardware_t timerHardware[] = {
timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0), // PPM DMA(1,4)

// Motors 1-4
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/BETAFLIGHTF4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
/*#include "drivers/dma.h"*/
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH3, PB8, TIM_USE_PPM, 0, 0), // PPM

// Motors
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/BETAFPVF722/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
timerHardware_t timerHardware[] = {
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)
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/BLUEJAYF4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
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
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/CLRACINGF4AIR/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
timerHardware_t timerHardware[] = {
DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0),
DEF_TIM(TIM4, CH3, PB8, TIM_USE_LED, 0, 0),

Expand Down
2 changes: 1 addition & 1 deletion src/main/target/COLIBRI/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH3, PA10, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // S1_IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0), // S2_IN
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0), // S3_IN
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/COLIBRI_RACE/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
timerHardware_t timerHardware[] = {
DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0), // PWM1 - PA8
DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PC6
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PC7
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/DALRCF405/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
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)
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/DALRCF722DUAL/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
#define TIM_EN TIMER_OUTPUT_ENABLED
#define TIM_EN_N TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL

const timerHardware_t timerHardware[] = {
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_MOTOR,0,0), //S1 DMA2_ST2 T8CH1
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/F4BY/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
timerHardware_t timerHardware[] = {
DEF_TIM(TIM3, CH4, PC9, TIM_USE_PPM | TIM_USE_PWM, 0, 0), // S1_IN
DEF_TIM(TIM3, CH3, PC8, TIM_USE_PWM, 0, 0), // S2_IN
DEF_TIM(TIM3, CH1, PC6, TIM_USE_PWM, 0, 0), // S3_IN
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/FALCORE/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
timerHardware_t timerHardware[] = {
// MOTOR outputs
DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR, 1),
DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR, 1),
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/FF_F35_LIGHTNING/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
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),
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/FF_FORTINIF4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[] = {
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
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/FF_PIKOF4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@

#define TIM_EN TIMER_OUTPUT_ENABLED

const timerHardware_t timerHardware[] = {
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 ),
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/FIREWORKSV2/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_1_mpu6500, DEVHW_MPU6500, IMU_1_SPI_BUS, IMU_
BUSDEV_REGISTER_SPI_TAG(busdev_2_mpu6000, DEVHW_MPU6000, IMU_2_SPI_BUS, IMU_2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_2_ALIGN);
BUSDEV_REGISTER_SPI_TAG(busdev_2_mpu6500, DEVHW_MPU6500, IMU_2_SPI_BUS, IMU_2_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_2_ALIGN);

const timerHardware_t timerHardware[] = {
timerHardware_t timerHardware[] = {
DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM

// Motor output 1: use different set of timers for MC and FW
Expand Down
Loading

0 comments on commit 362f5c5

Please sign in to comment.