1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 04:15:44 +03:00

STM32F30x - Enable serial PWM (PPM) input on PWM1.

This might also fix parallel PWM input too, but untested.
This commit is contained in:
Dominic Clifton 2014-05-01 20:20:24 +01:00
parent 133f75a17b
commit fbe2f82c05
6 changed files with 84 additions and 40 deletions

View file

@ -13,7 +13,9 @@
#include "pwm_common.h" #include "pwm_common.h"
/* /*
Configuration maps: Configuration maps
Note: this documentation is only valid for STM32F10x, for STM32F30x please read the code itself.
1) multirotor PPM input 1) multirotor PPM input
PWM1 used for PPM PWM1 used for PPM
@ -250,7 +252,7 @@ static pwmPortData_t *pwmInConfig(uint8_t port, timerCCCallbackPtr callback, uin
p->channel = channel; p->channel = channel;
pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_IPD); pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, timerHardwarePtr->gpioInputMode);
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
timerConfigure(timerHardwarePtr, 0xFFFF, PWM_TIMER_MHZ); timerConfigure(timerHardwarePtr, 0xFFFF, PWM_TIMER_MHZ);
@ -372,10 +374,17 @@ void pwmInit(drv_pwm_config_t *init, failsafe_t *initialFailsafe)
mask = 0; mask = 0;
if (init->useServos && !init->airplane) { if (init->useServos && !init->airplane) {
// remap PWM9+10 as servos (but not in airplane mode LOL) #ifdef STM32F10X_MD
// remap PWM9+10 as servos
if (port == PWM9 || port == PWM10) if (port == PWM9 || port == PWM10)
mask = TYPE_S; mask = TYPE_S;
} #endif
#ifdef STM32F303xC
// remap PWM5+6 as servos
if (port == PWM5 || port == PWM6)
mask = TYPE_S;
#endif
}
if (init->extraServos && !init->airplane) { if (init->extraServos && !init->airplane) {
// remap PWM5..8 as servos when used in extended servo mode // remap PWM5..8 as servos when used in extended servo mode

View file

@ -97,16 +97,40 @@ void systemInit(bool overclock)
#endif #endif
// Turn on clocks for stuff we use // Turn on clocks for stuff we use
#ifdef STM32F303xC
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17 | RCC_APB2Periph_USART1, ENABLE);
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1 | RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB | RCC_AHBPeriph_GPIOC | RCC_AHBPeriph_GPIOD | RCC_AHBPeriph_GPIOF | RCC_AHBPeriph_ADC12, ENABLE);
#endif
#ifdef STM32F10X_MD #ifdef STM32F10X_MD
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE); RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC | RCC_APB2Periph_TIM1 | RCC_APB2Periph_ADC1 | RCC_APB2Periph_USART1, ENABLE); RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC | RCC_APB2Periph_TIM1 | RCC_APB2Periph_ADC1 | RCC_APB2Periph_USART1, ENABLE);
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
#endif #endif
#ifdef STM32F303xC
RCC_APB1PeriphClockCmd(
RCC_APB1Periph_TIM2 |
RCC_APB1Periph_TIM3 |
RCC_APB1Periph_TIM4 |
RCC_APB1Periph_I2C2,
ENABLE
);
RCC_APB2PeriphClockCmd(
RCC_APB2Periph_TIM1 |
RCC_APB2Periph_TIM8 |
/*RCC_APB2Periph_TIM15 | */
RCC_APB2Periph_TIM16 |
RCC_APB2Periph_TIM17 |
RCC_APB2Periph_USART1,
ENABLE
);
RCC_AHBPeriphClockCmd(
RCC_AHBPeriph_DMA1 |
RCC_AHBPeriph_GPIOA |
RCC_AHBPeriph_GPIOB |
RCC_AHBPeriph_GPIOC |
RCC_AHBPeriph_GPIOD |
/*RCC_AHBPeriph_GPIOF | */
RCC_AHBPeriph_ADC12,
ENABLE
);
#endif
RCC_ClearFlag(); RCC_ClearFlag();
// Make all GPIO in by default to save power and reduce noise // Make all GPIO in by default to save power and reduce noise

View file

@ -51,20 +51,20 @@
#if defined(STM32F10X_MD) || defined(NAZE) #if defined(STM32F10X_MD) || defined(NAZE)
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, }, // PWM1 { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD}, // PWM1
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, }, // PWM2 { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // PWM2
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, }, // PWM3 { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD}, // PWM3
{ TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, }, // PWM4 { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD}, // PWM4
{ TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, }, // PWM5 { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD}, // PWM5
{ TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, }, // PWM6 { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD}, // PWM6
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, }, // PWM7 { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD}, // PWM7
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, }, // PWM8 { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD}, // PWM8
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, }, // PWM9 { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD}, // PWM9
{ TIM1, GPIOA, Pin_11, TIM_Channel_4, TIM1_CC_IRQn, 1, }, // PWM10 { TIM1, GPIOA, Pin_11, TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD}, // PWM10
{ TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, }, // PWM11 { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD}, // PWM11
{ TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, }, // PWM12 { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD}, // PWM12
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, }, // PWM13 { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD}, // PWM13
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, }, // PWM14 { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD}, // PWM14
}; };
#define MAX_TIMERS 4 // TIM1..TIM4 #define MAX_TIMERS 4 // TIM1..TIM4
@ -101,28 +101,28 @@ static const TIM_TypeDef *timers[MAX_TIMERS] = {
#if defined(STM32F303xC) || defined(STM32F3DISCOVERY) #if defined(STM32F303xC) || defined(STM32F3DISCOVERY)
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, }, // PWM1 { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP}, // PWM1
{ TIM16, GPIOB, Pin_8, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, }, // PWM2 { TIM16, GPIOB, Pin_8, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, Mode_AF_PP}, // PWM2
{ TIM17, GPIOB, Pin_9, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, }, // PWM3 { TIM17, GPIOB, Pin_9, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, Mode_AF_PP}, // PWM3
{ TIM8, GPIOC, Pin_6, TIM_Channel_1, TIM8_CC_IRQn, 1, }, // PWM4 { TIM8, GPIOC, Pin_6, TIM_Channel_1, TIM8_CC_IRQn, 1, Mode_AF_PP}, // PWM4
{ TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 1, }, // PWM5 { TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 1, Mode_AF_PP}, // PWM5
{ TIM8, GPIOC, Pin_8, TIM_Channel_3, TIM8_CC_IRQn, 1, }, // PWM6 { TIM8, GPIOC, Pin_8, TIM_Channel_3, TIM8_CC_IRQn, 1, Mode_AF_PP}, // PWM6
//{ TIM15, GPIOF, Pin_9, TIM_Channel_1, TIM15_IRQn, 0, }, // PWM7 - Potential alternate, untested //{ TIM15, GPIOF, Pin_9, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 0, }, // PWM1 - Potential alternate, untested
//{ TIM15, GPIOF, Pin_10, TIM_Channel_2, TIM15_IRQn, 0, }, // PWM8 - Potential alternate, untested //{ TIM15, GPIOF, Pin_10, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, }, // PWM1 - Potential alternate, untested
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, }, // PWM7 { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP}, // PWM7
{ TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 0, }, // PWM8 { TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP}, // PWM8
{ TIM4, GPIOD, Pin_12, TIM_Channel_1, TIM4_IRQn, 0, }, // PWM9 { TIM4, GPIOD, Pin_12, TIM_Channel_1, TIM4_IRQn, 0, Mode_AF_PP}, // PWM9
{ TIM4, GPIOD, Pin_13, TIM_Channel_2, TIM4_IRQn, 0, }, // PWM10 { TIM4, GPIOD, Pin_13, TIM_Channel_2, TIM4_IRQn, 0, Mode_AF_PP}, // PWM10
{ TIM4, GPIOD, Pin_14, TIM_Channel_3, TIM4_IRQn, 0, }, // PWM11 { TIM4, GPIOD, Pin_14, TIM_Channel_3, TIM4_IRQn, 0, Mode_AF_PP}, // PWM11
{ TIM4, GPIOD, Pin_15, TIM_Channel_4, TIM4_IRQn, 0, }, // PWM12 { TIM4, GPIOD, Pin_15, TIM_Channel_4, TIM4_IRQn, 0, Mode_AF_PP}, // PWM12
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, }, // PWM13 { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP}, // PWM13
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, }, // PWM14 { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP}, // PWM14
}; };
#define MAX_TIMERS 7 #define MAX_TIMERS 7
static const TIM_TypeDef *timers[MAX_TIMERS] = { static const TIM_TypeDef *timers[MAX_TIMERS] = {
TIM1, TIM2, TIM3, TIM4, TIM8, TIM16, TIM17 TIM1, TIM2, TIM3, TIM4, TIM8, /*TIM15, */TIM16, TIM17
}; };
#endif #endif
@ -278,6 +278,7 @@ static void timCCxHandler(TIM_TypeDef *tim)
timerConfig->callback(timerConfig->reference, capture); timerConfig->callback(timerConfig->reference, capture);
} }
} }
void TIM1_CC_IRQHandler(void) void TIM1_CC_IRQHandler(void)
{ {
timCCxHandler(TIM1); timCCxHandler(TIM1);
@ -304,6 +305,13 @@ void TIM8_IRQHandler(void)
timCCxHandler(TIM8); timCCxHandler(TIM8);
} }
/*
void TIM15_IRQHandler(void)
{
timCCxHandler(TIM15);
}
*/
void TIM1_UP_TIM16_IRQHandler(void) void TIM1_UP_TIM16_IRQHandler(void)
{ {
timCCxHandler(TIM16); timCCxHandler(TIM16);

View file

@ -11,6 +11,7 @@ typedef struct {
uint8_t channel; uint8_t channel;
uint8_t irq; uint8_t irq;
uint8_t outputEnable; uint8_t outputEnable;
GPIO_Mode gpioInputMode;
} timerHardware_t; } timerHardware_t;
extern const timerHardware_t timerHardware[]; extern const timerHardware_t timerHardware[];

View file

@ -3,6 +3,7 @@
#include "platform.h" #include "platform.h"
#include "drivers/gpio_common.h"
#include "drivers/timer_common.h" #include "drivers/timer_common.h"
#include "drivers/serial_common.h" #include "drivers/serial_common.h"
#include "drivers/serial_softserial.h" #include "drivers/serial_softserial.h"

View file

@ -11,6 +11,7 @@
#include "drivers/system_common.h" #include "drivers/system_common.h"
#include "drivers/accgyro_common.h" #include "drivers/accgyro_common.h"
#include "drivers/gpio_common.h"
#include "drivers/timer_common.h" #include "drivers/timer_common.h"
#include "drivers/serial_common.h" #include "drivers/serial_common.h"
#include "serial_common.h" #include "serial_common.h"