1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 14:25:20 +03:00

Merge pull request #1481 from blckmn/timer_irq_removal

Remove need for IRQ to be provided in target.c
This commit is contained in:
Martin Budden 2016-11-07 07:54:23 +01:00 committed by GitHub
commit d62a258a03
54 changed files with 667 additions and 636 deletions

View file

@ -207,6 +207,16 @@ rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
return 0;
}
uint8_t timerInputIrq(TIM_TypeDef *tim)
{
for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
if (timerDefinitions[i].TIMx == tim) {
return timerDefinitions[i].inputIrq;
}
}
return 0;
}
void timerNVICConfigure(uint8_t irq)
{
NVIC_InitTypeDef NVIC_InitStructure;
@ -239,9 +249,11 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
{
configTimeBase(timerHardwarePtr->tim, period, mhz);
TIM_Cmd(timerHardwarePtr->tim, ENABLE);
timerNVICConfigure(timerHardwarePtr->irq);
uint8_t irq = timerInputIrq(timerHardwarePtr->tim);
timerNVICConfigure(irq);
// HACK - enable second IRQ on timers that need it
switch(timerHardwarePtr->irq) {
switch(irq) {
#if defined(STM32F10X)
case TIM1_CC_IRQn:
timerNVICConfigure(TIM1_UP_IRQn);
@ -271,7 +283,7 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
}
// allocate and configure timer channel. Timer priority is set to highest priority of its channels
void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority)
void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority, uint8_t irq)
{
unsigned channel = timHw - timerHardware;
if(channel >= USABLE_TIMER_CHANNEL_COUNT)
@ -288,7 +300,7 @@ void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriori
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = timHw->irq;
NVIC_InitStructure.NVIC_IRQChannel = irq;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(irqPriority);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(irqPriority);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;

View file

@ -81,13 +81,13 @@ typedef struct timerOvrHandlerRec_s {
typedef struct timerDef_s {
TIM_TypeDef *TIMx;
rccPeriphTag_t rcc;
uint8_t inputIrq;
} timerDef_t;
typedef struct timerHardware_s {
TIM_TypeDef *tim;
ioTag_t tag;
uint8_t channel;
uint8_t irq;
timerUsageFlag_e usageFlags;
uint8_t output;
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
@ -121,6 +121,8 @@ typedef enum {
#endif
#elif defined(STM32F3)
#define HARDWARE_TIMER_DEFINITION_COUNT 10
#elif defined(STM32F411xE)
#define HARDWARE_TIMER_DEFINITION_COUNT 10
#elif defined(STM32F4)
#define HARDWARE_TIMER_DEFINITION_COUNT 14
#elif defined(STM32F7)
@ -167,7 +169,7 @@ void timerChITConfigDualLo(const timerHardware_t* timHw, FunctionalState newStat
void timerChITConfig(const timerHardware_t* timHw, FunctionalState newState);
void timerChClearCCFlag(const timerHardware_t* timHw);
void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority);
void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority, uint8_t irq);
void timerInit(void);
void timerStart(void);
@ -178,6 +180,7 @@ uint8_t timerClockDivisor(TIM_TypeDef *tim);
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz); // TODO - just for migration
rccPeriphTag_t timerRCC(TIM_TypeDef *tim);
uint8_t timerInputIrq(TIM_TypeDef *tim);
const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag);

View file

@ -216,6 +216,16 @@ rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
return 0;
}
uint8_t timerInputIrq(TIM_TypeDef *tim)
{
for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
if (timerDefinitions[i].TIMx == tim) {
return timerDefinitions[i].inputIrq;
}
}
return 0;
}
void timerNVICConfigure(uint8_t irq)
{
HAL_NVIC_SetPriority(irq, NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER), NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER));
@ -285,9 +295,11 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
configTimeBase(timerHardwarePtr->tim, period, mhz);
HAL_TIM_Base_Start(&timerHandle[timerIndex].Handle);
timerNVICConfigure(timerHardwarePtr->irq);
uint8_t irq = timerInputIrq(timerHardwarePtr->tim);
timerNVICConfigure(irq);
// HACK - enable second IRQ on timers that need it
switch(timerHardwarePtr->irq) {
switch(irq) {
case TIM1_CC_IRQn:
timerNVICConfigure(TIM1_UP_TIM10_IRQn);
@ -300,7 +312,7 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
}
// allocate and configure timer channel. Timer priority is set to highest priority of its channels
void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority)
void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority, uint8_t irq)
{
uint8_t timerIndex = lookupTimerIndex(timHw->tim);
if (timerIndex >= USED_TIMER_COUNT) {
@ -320,8 +332,8 @@ void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriori
HAL_TIM_Base_Start(&timerHandle[timerIndex].Handle);
HAL_NVIC_SetPriority(timHw->irq, NVIC_PRIORITY_BASE(irqPriority), NVIC_PRIORITY_SUB(irqPriority));
HAL_NVIC_EnableIRQ(timHw->irq);
HAL_NVIC_SetPriority(irq, NVIC_PRIORITY_BASE(irqPriority), NVIC_PRIORITY_SUB(irqPriority));
HAL_NVIC_EnableIRQ(irq);
timerInfo[timer].priority = irqPriority;
}

View file

@ -17,16 +17,16 @@
#include "timer.h"
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1) },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2) },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3) },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4) },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6) },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7) },
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8) },
{ .TIMx = TIM15, .rcc = RCC_APB2(TIM15) },
{ .TIMx = TIM16, .rcc = RCC_APB2(TIM16) },
{ .TIMx = TIM17, .rcc = RCC_APB2(TIM17) },
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), .inputIrq = TIM1_CC_IRQn },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2), .inputIrq = TIM2_IRQn },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3), .inputIrq = TIM3_IRQn },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4), .inputIrq = TIM4_IRQn },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6), .inputIrq = 0 },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7), .inputIrq = 0 },
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8), .inputIrq = TIM8_CC_IRQn },
{ .TIMx = TIM15, .rcc = RCC_APB2(TIM15), .inputIrq = TIM1_BRK_TIM15_IRQn },
{ .TIMx = TIM16, .rcc = RCC_APB2(TIM16), .inputIrq = TIM1_UP_TIM16_IRQn },
{ .TIMx = TIM17, .rcc = RCC_APB2(TIM17), .inputIrq = TIM1_TRG_COM_TIM17_IRQn },
};
uint8_t timerClockDivisor(TIM_TypeDef *tim)

View file

@ -42,20 +42,24 @@
#define CCMR_Offset ((uint16_t)0x0018)
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1) },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2) },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3) },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4) },
{ .TIMx = TIM5, .rcc = RCC_APB1(TIM5) },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6) },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7) },
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8) },
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9) },
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10) },
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11) },
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12) },
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13) },
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14) },
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), .inputIrq = TIM1_CC_IRQn},
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2), .inputIrq = TIM2_IRQn},
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3), .inputIrq = TIM3_IRQn},
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4), .inputIrq = TIM4_IRQn},
{ .TIMx = TIM5, .rcc = RCC_APB1(TIM5), .inputIrq = TIM5_IRQn},
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6), .inputIrq = 0},
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7), .inputIrq = 0},
#ifndef STM32F411xE
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8), .inputIrq = TIM8_CC_IRQn},
#endif
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9), .inputIrq = TIM1_BRK_TIM9_IRQn},
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10), .inputIrq = TIM1_UP_TIM10_IRQn},
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11), .inputIrq = TIM1_TRG_COM_TIM11_IRQn},
#ifndef STM32F411xE
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12), .inputIrq = TIM8_BRK_TIM12_IRQn},
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13), .inputIrq = TIM8_UP_TIM13_IRQn},
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14), .inputIrq = TIM8_TRG_COM_TIM14_IRQn},
#endif
};
/*

View file

@ -42,20 +42,20 @@
#define CCMR_Offset ((uint16_t)0x0018)
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1) },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2) },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3) },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4) },
{ .TIMx = TIM5, .rcc = RCC_APB1(TIM5) },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6) },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7) },
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8) },
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9) },
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10) },
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11) },
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12) },
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13) },
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14) },
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1), .inputIrq = TIM1_CC_IRQn},
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2), .inputIrq = TIM2_IRQn},
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3), .inputIrq = TIM3_IRQn},
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4), .inputIrq = TIM4_IRQn},
{ .TIMx = TIM5, .rcc = RCC_APB1(TIM5), .inputIrq = TIM5_IRQn},
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6), .inputIrq = 0},
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7), .inputIrq = 0},
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8), .inputIrq = TIM8_CC_IRQn},
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9), .inputIrq = TIM1_BRK_TIM9_IRQn},
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10), .inputIrq = TIM1_UP_TIM10_IRQn},
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11), .inputIrq = TIM1_TRG_COM_TIM11_IRQn},
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12), .inputIrq = TIM8_BRK_TIM12_IRQn},
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13), .inputIrq = TIM8_UP_TIM13_IRQn},
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14), .inputIrq = TIM8_TRG_COM_TIM14_IRQn},
};
/*

View file

@ -25,16 +25,16 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// PPM / UART2 RX
{ TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // PPM
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM1
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM2
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM3
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM4
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM5
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM6
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM8
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // UART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // UART3_RX (AF7)
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, //LED_STRIP
{ TIM8, IO_TAG(PA15), TIM_Channel_1, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // PPM
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM1
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM2
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM3
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM4
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM5
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM6
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM8
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // UART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // UART3_RX (AF7)
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, //LED_STRIP
};

View file

@ -24,14 +24,14 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM16, IO_TAG(PB8), TIM_Channel_1, 0, TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
};

View file

@ -24,18 +24,18 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PPM | TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM | TIM_USE_LED, 0, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0}, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0}, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0}, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0}, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_11, NULL, 0}, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0}, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0}, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0}, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0} // PWM14 - OUT6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PPM | TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0}, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_PWM | TIM_USE_LED, 0, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0}, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0}, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0}, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0}, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_11, NULL, 0}, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0}, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0}, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0}, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0} // PWM14 - OUT6
};

View file

@ -24,18 +24,18 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, NULL, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, NULL, 0 } // PWM14 - OUT6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, NULL, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, NULL, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_PWM, 0, NULL, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_PWM, 0, NULL, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_PWM, 0, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM_USE_PWM, 0, NULL, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, NULL, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, NULL, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, NULL, 0 } // PWM14 - OUT6
};

View file

@ -24,16 +24,16 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// up to 10 Motor Outputs
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
};

View file

@ -23,18 +23,18 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1 }, // PWM1 - PA8 RC1
{ TIM1, IO_TAG(PB0), TIM_Channel_2, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // PWM2 - PB0 RC2
{ TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // PWM3 - PB1 RC3
{ TIM8, IO_TAG(PB14),TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // PWM4 - PA14 RC4
{ TIM8, IO_TAG(PB15),TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // PWM5 - PA15 RC5
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // PWM6 - PB8 OUT1
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // PWM7 - PB9 OUT2
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // PWM8 - PA0 OUT3
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // PWM9 - PA1 OUT4
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM10 - PC6 OUT5
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM11 - PC7 OUT6
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM13 - PC8 OUT7
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM13 - PC9 OUT8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1 }, // PWM1 - PA8 RC1
{ TIM1, IO_TAG(PB0), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // PWM2 - PB0 RC2
{ TIM1, IO_TAG(PB1), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // PWM3 - PB1 RC3
{ TIM8, IO_TAG(PB14),TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // PWM4 - PA14 RC4
{ TIM8, IO_TAG(PB15),TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // PWM5 - PA15 RC5
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // PWM6 - PB8 OUT1
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // PWM7 - PB9 OUT2
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // PWM8 - PA0 OUT3
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // PWM9 - PA1 OUT4
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM10 - PC6 OUT5
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM11 - PC7 OUT6
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM13 - PC8 OUT7
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM13 - PC9 OUT8
};

View file

@ -26,44 +26,44 @@
#if defined(USE_DSHOT)
// DSHOT TEST
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PPM | TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S1_IN
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM_USE_PPM | TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S1_IN
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, DMA1_Stream7, DMA_CHANNEL_2, DMA1_ST7_HANDLER }, // S10_OUT 1
{ TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream1, DMA_CHANNEL_3, DMA1_ST1_HANDLER }, // S6_OUT 2
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream6, DMA_CHANNEL_3, DMA1_ST6_HANDLER }, // S1_OUT 4
{ TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, DMA1_Stream4, DMA_CHANNEL_6, DMA1_ST4_HANDLER }, // S2_OUT
{ TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, DMA1_Stream5, DMA_CHANNEL_5, DMA1_ST5_HANDLER }, // S4_OUT
{ TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, DMA1_Stream2, DMA_CHANNEL_6, DMA1_ST2_HANDLER }, // S7_OUT
{ TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S5_OUT 3
{ TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 1, GPIO_AF3_TIM9, NULL, 0, 0 }, // S3_OUT
{ TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S8_OUT
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S9_OUT
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, DMA1_Stream7, DMA_CHANNEL_2, DMA1_ST7_HANDLER }, // S10_OUT 1
{ TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream1, DMA_CHANNEL_3, DMA1_ST1_HANDLER }, // S6_OUT 2
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream6, DMA_CHANNEL_3, DMA1_ST6_HANDLER }, // S1_OUT 4
{ TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, DMA1_Stream4, DMA_CHANNEL_6, DMA1_ST4_HANDLER }, // S2_OUT
{ TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, DMA1_Stream5, DMA_CHANNEL_5, DMA1_ST5_HANDLER }, // S4_OUT
{ TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, DMA1_Stream2, DMA_CHANNEL_6, DMA1_ST2_HANDLER }, // S7_OUT
{ TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S5_OUT 3
{ TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF3_TIM9, NULL, 0, 0 }, // S3_OUT
{ TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S8_OUT
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S9_OUT
};
#else
// STANDARD LAYOUT
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S1_IN
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S1_IN
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S10_OUT 1
{ TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S6_OUT 2
{ TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S5_OUT 3
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S1_OUT 4
{ TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM5_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF2_TIM5, DMA1_Stream4, DMA_CHANNEL_6, 0 }, // S2_OUT
{ TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 1, GPIO_AF3_TIM9, NULL, 0, 0 }, // S3_OUT
{ TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S4_OUT
{ TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, NULL, 0, 0 }, // S7_OUT
{ TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S8_OUT
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S9_OUT
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S10_OUT 1
{ TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S6_OUT 2
{ TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S5_OUT 3
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S1_OUT 4
{ TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF2_TIM5, DMA1_Stream4, DMA_CHANNEL_6, 0 }, // S2_OUT
{ TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF3_TIM9, NULL, 0, 0 }, // S3_OUT
{ TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S4_OUT
{ TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, NULL, 0, 0 }, // S7_OUT
{ TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S8_OUT
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S9_OUT
};
#endif

View file

@ -24,16 +24,16 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // RC PPM - PB7 - TIM17_CH1N AF1, TIM4_CH2 AF2, TIM8_BKIN AF5, TIM3_CH4 AF10
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // RC PPM - PB7 - TIM17_CH1N AF1, TIM4_CH2 AF2, TIM8_BKIN AF5, TIM3_CH4 AF10
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM1 - PA6 - TIM3_CH1 AF2, TIM8_BKIN AF4, TIM1_BKIN AF6, *TIM16_CH1 AF1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM2 - PA7 - TIM3_CH2 AF2, TIM8_CH1 AF4, TIM1_CH1N AF6, *TIM17_CH1 AF1
{ TIM8, IO_TAG(PB8), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10,DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM3 - PB8 - TIM16_CH1 AF1, TIM4_CH3 AF2, TIM8_CH2 AF10, TIM1_BKIN AF12
{ TIM8, IO_TAG(PB9), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA2_Channel2, DMA2_CH2_HANDLER }, // PWM4 - PB9 - TIM17_CH1 AF1, TIM4_CH4 AF2, TIM8_CH3 AF10
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // SOFTSERIAL RX - TIM3_CH3 AF2, TIM8_CH2N AF4, TIM1_CH2N AF6
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // SOFTSERIAL TX - TIM3_CH4 AF2, TIM8_CH3N AF4, TIM1_CH3N AF6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA0 - TIM2_CH1 AF1, TIM8_BKIN AF9, TIM8_ETR AF10
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA2 - TIM2_CH3 AF1, TIM15_CH1 AF9
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM1 - PA6 - TIM3_CH1 AF2, TIM8_BKIN AF4, TIM1_BKIN AF6, *TIM16_CH1 AF1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM2 - PA7 - TIM3_CH2 AF2, TIM8_CH1 AF4, TIM1_CH1N AF6, *TIM17_CH1 AF1
{ TIM8, IO_TAG(PB8), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_10,DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM3 - PB8 - TIM16_CH1 AF1, TIM4_CH3 AF2, TIM8_CH2 AF10, TIM1_BKIN AF12
{ TIM8, IO_TAG(PB9), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA2_Channel2, DMA2_CH2_HANDLER }, // PWM4 - PB9 - TIM17_CH1 AF1, TIM4_CH4 AF2, TIM8_CH3 AF10
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // SOFTSERIAL RX - TIM3_CH3 AF2, TIM8_CH2N AF4, TIM1_CH2N AF6
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // SOFTSERIAL TX - TIM3_CH4 AF2, TIM8_CH3N AF4, TIM1_CH3N AF6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA0 - TIM2_CH1 AF1, TIM8_BKIN AF9, TIM8_ETR AF10
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA2 - TIM2_CH3 AF1, TIM15_CH1 AF9
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
};

View file

@ -23,12 +23,12 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S1_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S4_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S5_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S6_OUT
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_PPM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S1_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S4_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S5_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S6_OUT
};

View file

@ -23,17 +23,17 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_PWM, 0, }, // S1_IN
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, }, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, }, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, }, // S4_IN - Current
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0, }, // S5_IN - Vbattery
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, }, // S6_IN - PPM IN
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, }, // S1_OUT
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, }, // S2_OUT
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, }, // S3_OUT
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, }, // S4_OUT
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, }, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, } // S6_OUT
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_PWM, 0, }, // S1_IN
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM_USE_PWM, 0, }, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, }, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, }, // S4_IN - Current
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM, 0, }, // S5_IN - Vbattery
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM | TIM_USE_PPM, 0, }, // S6_IN - PPM IN
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, }, // S1_OUT
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, }, // S2_OUT
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 1, }, // S3_OUT
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, }, // S4_OUT
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_MOTOR, 1, }, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, } // S6_OUT
};

View file

@ -24,23 +24,23 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// INPUTS CH1-8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM1 - PA8
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM2 - PB8
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM3 - PB9
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4 }, // PWM4 - PC6
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4 }, // PWM5 - PC7
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4 }, // PWM6 - PC8
{ TIM15, IO_TAG(PF9), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_PWM, 0, GPIO_AF_3 }, // PWM7 - PF9
{ TIM15, IO_TAG(PF10), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_PWM, 0, GPIO_AF_3 }, // PWM8 - PF10
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM9 - PD12
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM10 - PD13
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM11 - PD14
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM12 - PD15
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM13 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM14 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM15 - PA3
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM16 - PB0
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM17 - PB1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 } // PWM18 - PA4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM1 - PA8
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM2 - PB8
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM3 - PB9
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_4 }, // PWM4 - PC6
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_4 }, // PWM5 - PC7
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_4 }, // PWM6 - PC8
{ TIM15, IO_TAG(PF9), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_3 }, // PWM7 - PF9
{ TIM15, IO_TAG(PF10), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_3 }, // PWM8 - PF10
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM9 - PD12
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM10 - PD13
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM11 - PD14
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM12 - PD15
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM13 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM14 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM15 - PA3
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM16 - PB0
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM17 - PB1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_2 } // PWM18 - PA4
};

View file

@ -23,19 +23,19 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 0 } // PWM14 - OUT6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_PWM, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_PWM, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_PWM, 0 }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM_USE_PWM, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11),TIM_Channel_4, TIM_USE_MOTOR, 1 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 0 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 0 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 0 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 0 } // PWM14 - OUT6
};

View file

@ -25,21 +25,21 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1, NULL, 0, 0 }, // S1_IN
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S2_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S4_IN
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM2 , NULL, 0, 0 }, // S5_IN
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM2 , NULL, 0, 0 }, // S6_IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM5 , NULL, 0, 0 }, // S7_IN
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM5 , NULL, 0, 0 }, // S8_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 , NULL, 0, 0 }, // S1_OUT
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 , NULL, 0, 0 }, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 , NULL, 0, 0 }, // S3_OUT
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM12, NULL, 0, 0 }, // S4_OUT
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 , NULL, 0, 0 }, // S5_OUT
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM12, NULL, 0, 0 }, // S6_OUT
{ TIM10, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM10_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM10, NULL, 0, 0 }, // S7_OUT
{ TIM11, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM11_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM11, NULL, 0, 0 }, // S8_OUT
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 0, TIM_USE_LED , 0, GPIO_AF_TIM11, DMA1_Stream3, DMA_Channel_2, DMA1_ST3_HANDLER }, // S8_OUT
{ TIM1, IO_TAG(PA10), TIM_Channel_3, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1, NULL, 0, 0 }, // S1_IN
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S2_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S4_IN
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM2 , NULL, 0, 0 }, // S5_IN
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM2 , NULL, 0, 0 }, // S6_IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM5 , NULL, 0, 0 }, // S7_IN
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM5 , NULL, 0, 0 }, // S8_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 , NULL, 0, 0 }, // S1_OUT
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 , NULL, 0, 0 }, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 , NULL, 0, 0 }, // S3_OUT
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM12, NULL, 0, 0 }, // S4_OUT
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 , NULL, 0, 0 }, // S5_OUT
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM12, NULL, 0, 0 }, // S6_OUT
{ TIM10, IO_TAG(PB8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM10, NULL, 0, 0 }, // S7_OUT
{ TIM11, IO_TAG(PB9), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM11, NULL, 0, 0 }, // S8_OUT
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_LED , 0, GPIO_AF_TIM11, DMA1_Stream3, DMA_Channel_2, DMA1_ST3_HANDLER }, // S8_OUT
};

View file

@ -24,16 +24,16 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_6, NULL, 0 }, // PWM1 - PA8
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM2 - PC6
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM3 - PC7
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel1, DMA2_CH1_HANDLER }, // PMW4 - PC8
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel2, DMA2_CH2_HANDLER }, // PWM5 - PC9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM7 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM8 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM9 - PA3
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM10 - PB14
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM11 - PB15
{ TIM16, IO_TAG(PA6), TIM_Channel_1, 0, TIM_USE_LED, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM11 - PB15
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_PPM, 0, GPIO_AF_6, NULL, 0 }, // PWM1 - PA8
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM2 - PC6
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM3 - PC7
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel1, DMA2_CH1_HANDLER }, // PMW4 - PC8
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel2, DMA2_CH2_HANDLER }, // PWM5 - PC9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM7 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM8 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM9 - PA3
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM10 - PB14
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM11 - PB15
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM11 - PB15
};

View file

@ -24,14 +24,14 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_6 , NULL, 0 }, // PWM1 - PA8
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0 }, // PWM2 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0 }, // PWM3 - PB9
{ TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0 }, // PMW4 - PA10
{ TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0 }, // PWM5 - PA9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0 }, // PWM7 - PA1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0 }, // PWM8 - PB1
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0 }, // PWM9 - PB0
{ TIM16, IO_TAG(PA6), TIM_Channel_1, 0, TIM_USE_LED, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM9 - PB0
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_PPM, 0, GPIO_AF_6 , NULL, 0 }, // PWM1 - PA8
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0 }, // PWM2 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0 }, // PWM3 - PB9
{ TIM2, IO_TAG(PA10), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0 }, // PMW4 - PA10
{ TIM2, IO_TAG(PA9), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0 }, // PWM5 - PA9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0 }, // PWM7 - PA1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0 }, // PWM8 - PB1
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0 }, // PWM9 - PB0
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM9 - PB0
};

View file

@ -6,22 +6,22 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S1_IN
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S2_IN
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S3_IN
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S4_IN
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S5_IN
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S6_IN
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S7_IN
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S8_IN
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S1_OUT
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S2_OUT
{ TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S3_OUT
{ TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S4_OUT
{ TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S5_OUT
{ TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S6_OUT
{ TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S7_OUT
{ TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S8_OUT
{ TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_TIM9 }, // sonar echo if needed
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S1_IN
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S2_IN
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S3_IN
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S4_IN
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S5_IN
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S6_IN
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S7_IN
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S8_IN
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S1_OUT
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S2_OUT
{ TIM5, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S3_OUT
{ TIM5, IO_TAG(PA3), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S4_OUT
{ TIM1, IO_TAG(PE9), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S5_OUT
{ TIM1, IO_TAG(PE11), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S6_OUT
{ TIM1, IO_TAG(PE13), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S7_OUT
{ TIM1, IO_TAG(PE14), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S8_OUT
{ TIM9, IO_TAG(PE6), TIM_Channel_2, TIM_USE_MOTOR, 0, GPIO_AF_TIM9 }, // sonar echo if needed
};

View file

@ -25,12 +25,12 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PPM IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_6, NULL, 0 }, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM3, IO_TAG(PB7), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM4 - S1
{ TIM8, IO_TAG(PB6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_5, DMA2_Channel3, DMA2_CH3_HANDLER }, // PWM5 - S2
{ TIM8, IO_TAG(PB5), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, (1 | TIMER_OUTPUT_N_CHANNEL), GPIO_AF_3, DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM6 - S3
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM7 - S4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO TIMER - LED_STRIP
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PPM IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM1, IO_TAG(PB1), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_6, NULL, 0 }, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM3, IO_TAG(PB7), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM4 - S1
{ TIM8, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_5, DMA2_Channel3, DMA2_CH3_HANDLER }, // PWM5 - S2
{ TIM8, IO_TAG(PB5), TIM_Channel_3, TIM_USE_MOTOR, (1 | TIMER_OUTPUT_N_CHANNEL), GPIO_AF_3, DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM6 - S3
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM7 - S4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO TIMER - LED_STRIP
};

View file

@ -24,11 +24,11 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM_IN
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM_USE_PPM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM_IN
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
// { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5 }, // LED Strip
};

View file

@ -25,12 +25,12 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF3_TIM8, NULL, 0, 0 }, // PPM_IN
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM_USE_PPM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // PPM_IN
{ TIM3, IO_TAG(PB0), TIM_CHANNEL_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM3, DMA1_Stream7, DMA_CHANNEL_5, DMA1_ST7_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_CHANNEL_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM3, DMA1_Stream2, DMA_CHANNEL_5, DMA1_ST2_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF1_TIM2, DMA1_Stream6, DMA_CHANNEL_3, DMA1_ST6_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF1_TIM2, DMA1_Stream1, DMA_CHANNEL_3, DMA1_ST1_HANDLER }, // S4_OUT
{ TIM3, IO_TAG(PB0), TIM_CHANNEL_3, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, DMA1_Stream7, DMA_CHANNEL_5, DMA1_ST7_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, DMA1_Stream2, DMA_CHANNEL_5, DMA1_ST2_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream6, DMA_CHANNEL_3, DMA1_ST6_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream1, DMA_CHANNEL_3, DMA1_ST1_HANDLER }, // S4_OUT
// { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5 }, // LED Strip
};

View file

@ -23,12 +23,12 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0}, // PPM/SERIAL RX
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2, NULL, 0}, // PWM1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2, NULL, 0}, // PWM2
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2, NULL, 0}, // PWM3
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2, NULL, 0}, // PWM4
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0}, // PWM5
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0}, // PWM6
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER}, // LED_STRIP
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0}, // PPM/SERIAL RX
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_MOTOR, 0, GPIO_AF_2, NULL, 0}, // PWM1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM_USE_MOTOR, 0, GPIO_AF_2, NULL, 0}, // PWM2
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 0, GPIO_AF_2, NULL, 0}, // PWM3
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 0, GPIO_AF_2, NULL, 0}, // PWM4
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0}, // PWM5
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0}, // PWM6
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER}, // LED_STRIP
};

View file

@ -23,22 +23,22 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
};

View file

@ -24,24 +24,24 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM |TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM |TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
// Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype.
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0 },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0 },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0}, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0}, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 , NULL, 0}, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 , NULL, 0}, // PWM8 - PA3
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0 },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0 },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0}, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0}, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_9 , NULL, 0}, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9 , NULL, 0}, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6 , DMA1_Channel2, DMA1_CH2_HANDLER}, // GPIO_TIMER / LED_STRIP
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_6 , DMA1_Channel2, DMA1_CH2_HANDLER}, // GPIO_TIMER / LED_STRIP
};

View file

@ -24,17 +24,17 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PB14), TIM_Channel_2, TIM1_CC_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL | TIMER_OUTPUT_INVERTED, GPIO_AF_6, DMA1_Channel3, DMA1_CH3_HANDLER },
{ TIM8, IO_TAG(PB0), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL | TIMER_OUTPUT_INVERTED, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER },
{ TIM15, IO_TAG(PB15), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL | TIMER_OUTPUT_INVERTED, GPIO_AF_2, DMA1_Channel5, DMA1_CH5_HANDLER },
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER },
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER },
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER },
{ TIM1, IO_TAG(PB14), TIM_Channel_2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL | TIMER_OUTPUT_INVERTED, GPIO_AF_6, DMA1_Channel3, DMA1_CH3_HANDLER },
{ TIM8, IO_TAG(PB0), TIM_Channel_2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL | TIMER_OUTPUT_INVERTED, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER },
{ TIM15, IO_TAG(PB15), TIM_Channel_1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL | TIMER_OUTPUT_INVERTED, GPIO_AF_2, DMA1_Channel5, DMA1_CH5_HANDLER },
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER },
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER },
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER },
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0}, // TODO - Cleanup. KISS FC uses the same pin for serial and PPM
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0},
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0},
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0},
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0}, // TODO - Cleanup. KISS FC uses the same pin for serial and PPM
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0},
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0},
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0},
//{ TIM4, IO_TAG(PA13), TIM_Channel_2, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_10, NULL, 0},
//{ TIM8, IO_TAG(PA14), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_5, NULL, 0},
};

View file

@ -24,19 +24,19 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_6, NULL, 0 }, // PWM1 - PA8
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM2 - PC6
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM3 - PC7
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel1, DMA2_CH1_HANDLER }, // PMW4 - PC8
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel2, DMA2_CH2_HANDLER }, // PWM5 - PC9
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_PPM, 0, GPIO_AF_6, NULL, 0 }, // PWM1 - PA8
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM2 - PC6
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM3 - PC7
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel1, DMA2_CH1_HANDLER }, // PMW4 - PC8
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel2, DMA2_CH2_HANDLER }, // PWM5 - PC9
#ifndef LUXV2_RACE
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM7 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM8 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM9 - PA3
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM10 - PB14
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM11 - PB15
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM7 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM8 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM9 - PA3
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM10 - PB14
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM11 - PB15
#endif
{ TIM16, IO_TAG(PA6), TIM_Channel_1, 0, TIM_USE_LED, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER },
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER },
};

View file

@ -24,18 +24,18 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, NULL, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM | TIM_USE_LED, 0, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, NULL, 0 } // PWM14 - OUT6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, NULL, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, NULL, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_PWM, 0, NULL, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_PWM, 0, NULL, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_PWM | TIM_USE_LED, 0, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM_USE_PWM, 0, NULL, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, NULL, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, NULL, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, NULL, 0 } // PWM14 - OUT6
};

View file

@ -24,15 +24,15 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM16, IO_TAG(PB8), TIM_Channel_1, 0, TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
};

View file

@ -24,18 +24,18 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PPM | TIM_USE_PWM, 0, NULL, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM | TIM_USE_LED, 0, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, NULL, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, NULL, 0 } // PWM14 - OUT6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PPM | TIM_USE_PWM, 0, NULL, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, NULL, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_PWM, 0, NULL, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_PWM, 0, NULL, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_PWM | TIM_USE_LED, 0, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM_USE_PWM, 0, NULL, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, NULL, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, NULL, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, NULL, 0 } // PWM14 - OUT6
};

View file

@ -25,18 +25,18 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// PPM Pad
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // PPM - PB4
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // PPM - PB4
// PB5 / TIM3 CH2 is connected to USBPresent
{ TIM8, IO_TAG(PB8), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM1 - PB8
{ TIM8, IO_TAG(PB9), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM2 - PB9
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM3 - PA3
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, DMA1_Channel5, DMA1_CH5_HANDLER }, // PWM4 - PA2
{ TIM8, IO_TAG(PB8), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM1 - PB8
{ TIM8, IO_TAG(PB9), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM2 - PB9
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM3 - PA3
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_9, DMA1_Channel5, DMA1_CH5_HANDLER }, // PWM4 - PA2
// UART3 RX/TX
//{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM5 - PB10 - TIM2_CH3 / UART3_TX (AF7)
//{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PB11 - TIM2_CH4 / UART3_RX (AF7)
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM7 - PB7
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM8 - PB6
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
//{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM5 - PB10 - TIM2_CH3 / UART3_TX (AF7)
//{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PB11 - TIM2_CH4 / UART3_RX (AF7)
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM7 - PB7
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM8 - PB6
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
};

View file

@ -24,17 +24,17 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S4_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1, NULL, 0, 0 }, // S6_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S4_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM1, NULL, 0, 0 }, // S6_OUT
};

View file

@ -24,15 +24,15 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM16, IO_TAG(PB8), TIM_Channel_1, 0, TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
};

View file

@ -23,10 +23,10 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PPM, 1, GPIO_AF_1, NULL, 0 },
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM2 - PC6
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM3 - PC7
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PMW4 - PC8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM5 - PC9
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 0, TIM_USE_LED, 1, GPIO_AF_2, DMA1_Channel2, DMA1_CH2_HANDLER }, // PWM5 - PC9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PPM, 1, GPIO_AF_1, NULL, 0 },
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM2 - PC6
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM3 - PC7
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PMW4 - PC8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM5 - PC9
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_2, DMA1_Channel2, DMA1_CH2_HANDLER }, // PWM5 - PC9
};

View file

@ -25,11 +25,11 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM1 - PA4
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM2 - PA7
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0 }, // PWM3 - PA8
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM4 - PB0
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM5 - PB1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PWM6 - PPM
{ TIM16, IO_TAG(PB8), TIM_Channel_1, 0, TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER}, // PWM6 - PPM
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM1 - PA4
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM2 - PA7
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0 }, // PWM3 - PA8
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM4 - PB0
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM5 - PB1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PWM6 - PPM
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER}, // PWM6 - PPM
};

View file

@ -24,20 +24,20 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
#ifdef REVOLT
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_LED, 0, GPIO_AF_TIM4, DMA1_Stream0, DMA_Channel_2, DMA1_ST0_HANDLER }, // LED for REVOLT
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_LED, 0, GPIO_AF_TIM4, DMA1_Stream0, DMA_Channel_2, DMA1_ST0_HANDLER }, // LED for REVOLT
#else
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S5_OUT / LED for REVO
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S6_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S5_OUT / LED for REVO
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S6_OUT
#endif
};

View file

@ -23,18 +23,18 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM2 }, // PPM
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S2_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S3_IN
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S4_IN
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S5_IN
{ TIM2, IO_TAG(PA5), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM2 }, // S6_IN
{ TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S1_OUT
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S2_OUT
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // S3_OUT
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // S4_OUT
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM5 }, // S5_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S6_OUT
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM2 }, // PPM
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S2_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S3_IN
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S4_IN
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S5_IN
{ TIM2, IO_TAG(PA5), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM2 }, // S6_IN
{ TIM1, IO_TAG(PA10), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S1_OUT
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S2_OUT
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // S3_OUT
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // S4_OUT
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM5 }, // S5_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S6_OUT
};

View file

@ -24,21 +24,21 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0}, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0}, // PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0}, // PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0}, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0}, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 , NULL, 0}, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 , NULL, 0}, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0}, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0}, // PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0}, // PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0}, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0}, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_9 , NULL, 0}, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9 , NULL, 0}, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
};

View file

@ -24,15 +24,15 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PPM/SERIAL RX
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // PWM1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // PWM2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // PWM3
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // PWM4
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM5
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // SOFTSERIAL1 RX (NC)
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // SOFTSERIAL1 TX
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // LED_STRIP
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PPM/SERIAL RX
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // PWM1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // PWM2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // PWM3
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // PWM4
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM5
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // SOFTSERIAL1 RX (NC)
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // SOFTSERIAL1 TX
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // LED_STRIP
};

View file

@ -24,13 +24,13 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM1 - PB6
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PB6
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM4 - PB9
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB0 - *TIM3_CH3
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB1 - *TIM3_CH4
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)y
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM1 - PB6
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PB6
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM4 - PB9
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB0 - *TIM3_CH3
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB1 - *TIM3_CH4
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)y
};

View file

@ -23,16 +23,16 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 , NULL, 0, 0 }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 , NULL, 0, 0 }, // S2_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM9 , NULL, 0, 0 }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 , NULL, 0, 0 }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, NULL, 0, 0 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM5 , DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S6_OUT
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_TIM8 , NULL, 0, 0 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 , NULL, 0, 0 }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 , NULL, 0, 0 }, // S2_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM9 , NULL, 0, 0 }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 , NULL, 0, 0 }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, NULL, 0, 0 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM5 , DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S6_OUT
};

View file

@ -25,18 +25,18 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// 6 3-pin headers
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2, NULL, 0 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, 0, TIM_USE_MOTOR | TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_1, NULL, 0 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6, NULL, 0 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 0, GPIO_AF_2, NULL, 0 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR | TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 0, GPIO_AF_1, NULL, 0 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
// PWM7 - PMW10
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PWM, 1, GPIO_AF_1, NULL, 0 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // PWM9 - PA4 - *TIM3_CH2
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_PWM, 1, GPIO_AF_1, NULL, 0 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // PWM9 - PA4 - *TIM3_CH2
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
// PPM PORT - Also USART2 RX (AF5)
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
};

View file

@ -23,16 +23,16 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM8 }, // PPM IN
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12 }, // S2_IN
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12 }, // S3_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S4_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S5_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S2_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM9 }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S6_OUT
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM8 }, // PPM IN
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM12 }, // S2_IN
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM12 }, // S3_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S4_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S5_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S2_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM9 }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S6_OUT
};

View file

@ -24,24 +24,24 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
// Production boards swapped RC_CH3/4 swapped to make it easierTIM_USE_MOTOR, to using supplied cables - compared to first prototype.
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA1_Channel1, DMA1_CH1_HANDLER },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA1_Channel4, DMA1_CH4_HANDLER },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM8 - PA3
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA1_Channel1, DMA1_CH1_HANDLER },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA1_Channel4, DMA1_CH4_HANDLER },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
};

View file

@ -25,16 +25,16 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// PPM / UART2 RX
{ TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // PPM
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM2
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM3
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM8
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
{ TIM8, IO_TAG(PA15), TIM_Channel_1, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // PPM
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM2
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM3
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM8
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
};

View file

@ -26,27 +26,27 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// PPM Pad
#ifdef SPRACINGF3MINI_MKII_REVA
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // PPM - PB5
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // PPM - PB5
// PB4 / TIM3 CH1 is connected to USBPresent
#else
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // PPM - PB4
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // PPM - PB4
// PB5 / TIM3 CH2 is connected to USBPresent
#endif
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM1 - PA6
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM2 - PA7
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM3 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM4 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM5 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM6 - PA3
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM7 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM8 - PA1
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM1 - PA6
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM2 - PA7
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM3 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM4 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM5 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM6 - PA3
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM7 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM8 - PA1
// UART3 RX/TX
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, 1, GPIO_AF_1, NULL, 0 }, // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, 1, GPIO_AF_1, NULL, 0 }, // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, 0, 1, GPIO_AF_1, NULL, 0 }, // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, 0, 1, GPIO_AF_1, NULL, 0 }, // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7)
// LED Strip Pad
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
};

View file

@ -24,19 +24,19 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_PPM | TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER },
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, 0, GPIO_AF_1, NULL, 0 },
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER },
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel3, DMA2_CH3_HANDLER },
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER },
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel1, DMA2_CH1_HANDLER },
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, 0, GPIO_AF_1, NULL, 0 },
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, 0, GPIO_AF_1, NULL, 0 }
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM_USE_PPM | TIM_USE_LED, 0, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER },
{ TIM17, IO_TAG(PB9), TIM_Channel_1, 0, 0, GPIO_AF_1, NULL, 0 },
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER },
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel3, DMA2_CH3_HANDLER },
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER },
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_4, DMA2_Channel1, DMA2_CH1_HANDLER },
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM3, IO_TAG(PA4), TIM_Channel_2, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD12), TIM_Channel_1, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD13), TIM_Channel_2, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD14), TIM_Channel_3, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM4, IO_TAG(PD15), TIM_Channel_4, 0, 0, GPIO_AF_2, NULL, 0 },
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, 0, GPIO_AF_1, NULL, 0 },
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, 0, GPIO_AF_1, NULL, 0 }
};

View file

@ -23,16 +23,16 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1 }, // PPM
{ TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // S2_IN
{ TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // S3_IN
{ TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // S4_IN
{ TIM9, IO_TAG(PE6), TIM_Channel_1, TIM1_BRK_TIM9_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM9 }, // S5_IN
{ TIM9, IO_TAG(PE7), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM9 }, // S6_IN
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S1_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S3_OUT
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S4_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S5_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S6_OUT
{ TIM1, IO_TAG(PE9), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1 }, // PPM
{ TIM1, IO_TAG(PE11), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // S2_IN
{ TIM1, IO_TAG(PE13), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // S3_IN
{ TIM1, IO_TAG(PE14), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // S4_IN
{ TIM9, IO_TAG(PE6), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_TIM9 }, // S5_IN
{ TIM9, IO_TAG(PE7), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_TIM9 }, // S6_IN
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S1_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S3_OUT
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S4_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S5_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S6_OUT
};

View file

@ -9,19 +9,19 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH5 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH6 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0 },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0 },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0}, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0}, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 , NULL, 0}, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 , NULL, 0}, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_6 , DMA1_Channel2, DMA1_CH2_HANDLER}, // GPIO_TIMER / LED_STRIP
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_1 , NULL, 0}, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH5 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2 , NULL, 0}, // RC_CH6 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 , NULL, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0 },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_10, NULL, 0 },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0}, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2 , NULL, 0}, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_9 , NULL, 0}, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9 , NULL, 0}, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_6 , DMA1_Channel2, DMA1_CH2_HANDLER}, // GPIO_TIMER / LED_STRIP
};

View file

@ -23,12 +23,12 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM IN
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // MS1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // MS2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // MS3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // MS4
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, NULL, 0, 0 }, // MS5
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // MS6
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM_USE_PPM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM IN
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // MS1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // MS2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // MS3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, NULL, 0, 0 }, // MS4
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, NULL, 0, 0 }, // MS5
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // MS6
};

View file

@ -8,22 +8,22 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
};