mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
Update PWM driver so that all 10 PWM outputs work. Softserial also now
works as expected. PWM/PPM input untested. UART2 probably broken.
This commit is contained in:
parent
7e79a245c2
commit
133f75a17b
4 changed files with 123 additions and 10 deletions
|
@ -45,7 +45,13 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
|
#ifdef STM32F303xC
|
||||||
|
volatile uint32_t *ccr;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef STM32F10X_MD
|
||||||
volatile uint16_t *ccr;
|
volatile uint16_t *ccr;
|
||||||
|
#endif
|
||||||
uint16_t period;
|
uint16_t period;
|
||||||
|
|
||||||
// for input only
|
// for input only
|
||||||
|
@ -215,7 +221,6 @@ static pwmPortData_t *pwmOutConfig(uint8_t port, uint8_t mhz, uint16_t period, u
|
||||||
configTimeBase(timerHardware[port].tim, period, mhz);
|
configTimeBase(timerHardware[port].tim, period, mhz);
|
||||||
pwmGPIOConfig(timerHardware[port].gpio, timerHardware[port].pin, Mode_AF_PP);
|
pwmGPIOConfig(timerHardware[port].gpio, timerHardware[port].pin, Mode_AF_PP);
|
||||||
pwmOCConfig(timerHardware[port].tim, timerHardware[port].channel, value);
|
pwmOCConfig(timerHardware[port].tim, timerHardware[port].channel, value);
|
||||||
// Needed only on TIM1
|
|
||||||
if (timerHardware[port].outputEnable)
|
if (timerHardware[port].outputEnable)
|
||||||
TIM_CtrlPWMOutputs(timerHardware[port].tim, ENABLE);
|
TIM_CtrlPWMOutputs(timerHardware[port].tim, ENABLE);
|
||||||
TIM_Cmd(timerHardware[port].tim, ENABLE);
|
TIM_Cmd(timerHardware[port].tim, ENABLE);
|
||||||
|
@ -343,6 +348,7 @@ void pwmInit(drv_pwm_config_t *init, failsafe_t *initialFailsafe)
|
||||||
continue;
|
continue;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef STM32F10X_MD
|
||||||
// skip UART ports for GPS
|
// skip UART ports for GPS
|
||||||
if (init->useUART && (port == PWM3 || port == PWM4))
|
if (init->useUART && (port == PWM3 || port == PWM4))
|
||||||
continue;
|
continue;
|
||||||
|
@ -350,6 +356,12 @@ void pwmInit(drv_pwm_config_t *init, failsafe_t *initialFailsafe)
|
||||||
// skip softSerial ports
|
// skip softSerial ports
|
||||||
if (init->useSoftSerial && (port == PWM5 || port == PWM6 || port == PWM7 || port == PWM8))
|
if (init->useSoftSerial && (port == PWM5 || port == PWM6 || port == PWM7 || port == PWM8))
|
||||||
continue;
|
continue;
|
||||||
|
#endif
|
||||||
|
#ifdef STM32F303xC
|
||||||
|
// skip softSerial ports
|
||||||
|
if (init->useSoftSerial && (port == PWM9 || port == PWM10 || port == PWM11 || port == PWM12))
|
||||||
|
continue;
|
||||||
|
#endif
|
||||||
|
|
||||||
// skip ADC for powerMeter if configured
|
// skip ADC for powerMeter if configured
|
||||||
if (init->adcChannel && (init->adcChannel == port))
|
if (init->adcChannel && (init->adcChannel == port))
|
||||||
|
|
|
@ -11,11 +11,19 @@
|
||||||
#include "serial_common.h"
|
#include "serial_common.h"
|
||||||
#include "serial_softserial.h"
|
#include "serial_softserial.h"
|
||||||
|
|
||||||
#define SOFT_SERIAL_TIMER_MHZ 3
|
#ifdef STM32F10X_MD
|
||||||
#define SOFT_SERIAL_1_TIMER_RX_HARDWARE 4
|
#define SOFT_SERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
|
||||||
#define SOFT_SERIAL_1_TIMER_TX_HARDWARE 5
|
#define SOFT_SERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
|
||||||
#define SOFT_SERIAL_2_TIMER_RX_HARDWARE 6
|
#define SOFT_SERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
|
||||||
#define SOFT_SERIAL_2_TIMER_TX_HARDWARE 7
|
#define SOFT_SERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef STM32F303xC
|
||||||
|
#define SOFT_SERIAL_1_TIMER_RX_HARDWARE 8 // PWM 9
|
||||||
|
#define SOFT_SERIAL_1_TIMER_TX_HARDWARE 9 // PWM 10
|
||||||
|
#define SOFT_SERIAL_2_TIMER_RX_HARDWARE 10 // PWM 11
|
||||||
|
#define SOFT_SERIAL_2_TIMER_TX_HARDWARE 11 // PWM 12
|
||||||
|
#endif
|
||||||
|
|
||||||
#define RX_TOTAL_BITS 10
|
#define RX_TOTAL_BITS 10
|
||||||
#define TX_TOTAL_BITS 10
|
#define TX_TOTAL_BITS 10
|
||||||
|
|
|
@ -99,8 +99,8 @@ void systemInit(bool overclock)
|
||||||
// Turn on clocks for stuff we use
|
// Turn on clocks for stuff we use
|
||||||
#ifdef STM32F303xC
|
#ifdef STM32F303xC
|
||||||
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_TIM1 | RCC_APB2Periph_USART1, 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_ADC12, 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
|
#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);
|
||||||
|
@ -128,6 +128,28 @@ void systemInit(bool overclock)
|
||||||
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;
|
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef STM32F303xC
|
||||||
|
GPIO_PinAFConfig(GPIOA, GPIO_PinSource8, GPIO_AF_6);
|
||||||
|
GPIO_PinAFConfig(GPIOB, GPIO_PinSource8, GPIO_AF_1);
|
||||||
|
GPIO_PinAFConfig(GPIOB, GPIO_PinSource9, GPIO_AF_1);
|
||||||
|
GPIO_PinAFConfig(GPIOC, GPIO_PinSource6, GPIO_AF_4);
|
||||||
|
GPIO_PinAFConfig(GPIOC, GPIO_PinSource7, GPIO_AF_4);
|
||||||
|
GPIO_PinAFConfig(GPIOC, GPIO_PinSource8, GPIO_AF_4);
|
||||||
|
//GPIO_PinAFConfig(GPIOF, GPIO_PinSource9, GPIO_AF_3); // Potential alternate, untested
|
||||||
|
//GPIO_PinAFConfig(GPIOF, GPIO_PinSource10, GPIO_AF_3); // Potential alternate, untested
|
||||||
|
|
||||||
|
GPIO_PinAFConfig(GPIOD, GPIO_PinSource12, GPIO_AF_2);
|
||||||
|
GPIO_PinAFConfig(GPIOD, GPIO_PinSource13, GPIO_AF_2);
|
||||||
|
GPIO_PinAFConfig(GPIOD, GPIO_PinSource14, GPIO_AF_2);
|
||||||
|
GPIO_PinAFConfig(GPIOD, GPIO_PinSource15, GPIO_AF_2);
|
||||||
|
GPIO_PinAFConfig(GPIOA, GPIO_PinSource1, GPIO_AF_1);
|
||||||
|
GPIO_PinAFConfig(GPIOA, GPIO_PinSource2, GPIO_AF_1);
|
||||||
|
|
||||||
|
GPIO_PinAFConfig(GPIOB, GPIO_PinSource0, GPIO_AF_2);
|
||||||
|
GPIO_PinAFConfig(GPIOB, GPIO_PinSource1, GPIO_AF_2);
|
||||||
|
GPIO_PinAFConfig(GPIOA, GPIO_PinSource4, GPIO_AF_2);
|
||||||
|
#endif
|
||||||
|
|
||||||
beeperInit();
|
beeperInit();
|
||||||
LED0_OFF;
|
LED0_OFF;
|
||||||
LED1_OFF;
|
LED1_OFF;
|
||||||
|
|
|
@ -37,7 +37,7 @@
|
||||||
Outputs
|
Outputs
|
||||||
PWM1 TIM1_CH1 PA8
|
PWM1 TIM1_CH1 PA8
|
||||||
PWM2 TIM1_CH4 PA11
|
PWM2 TIM1_CH4 PA11
|
||||||
PWM3 TIM4_CH1 PB6? [also I2C1_SCL]
|
PWM3 TIM4_CH1 PB6 [also I2C1_SCL]
|
||||||
PWM4 TIM4_CH2 PB7 [also I2C1_SDA]
|
PWM4 TIM4_CH2 PB7 [also I2C1_SDA]
|
||||||
PWM5 TIM4_CH3 PB8
|
PWM5 TIM4_CH3 PB8
|
||||||
PWM6 TIM4_CH4 PB9
|
PWM6 TIM4_CH4 PB9
|
||||||
|
@ -49,6 +49,7 @@
|
||||||
TIM4 4 channels
|
TIM4 4 channels
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#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, }, // PWM1
|
||||||
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, }, // PWM2
|
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, }, // PWM2
|
||||||
|
@ -67,12 +68,65 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
#define MAX_TIMERS 4 // TIM1..TIM4
|
#define MAX_TIMERS 4 // TIM1..TIM4
|
||||||
#define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
|
|
||||||
|
|
||||||
static const TIM_TypeDef *timers[MAX_TIMERS] = {
|
static const TIM_TypeDef *timers[MAX_TIMERS] = {
|
||||||
TIM1, TIM2, TIM3, TIM4
|
TIM1, TIM2, TIM3, TIM4
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
// Parallel PWM Inputs
|
||||||
|
// RX1 TIM1_CH1 PA8
|
||||||
|
// RX2 TIM16_CH1 PB8
|
||||||
|
// RX3 TIM17_CH1 PB9
|
||||||
|
// RX4 TIM8_CH1 PC6
|
||||||
|
// RX5 TIM8_CH2 PC7
|
||||||
|
// RX6 TIM8_CH3 PC8
|
||||||
|
// RX7 TIM15_CH1 PF9
|
||||||
|
// RX8 TIM15_CH2 PF10
|
||||||
|
|
||||||
|
// Servo PWM1 TIM3_CH3 PB0
|
||||||
|
// Servo PWM2 TIM3_CH4 PB1
|
||||||
|
// Servo PWM3 TIM3_CH2 PA4
|
||||||
|
|
||||||
|
// ESC PWM1 TIM4_CH1 PD12
|
||||||
|
// ESC PWM2 TIM4_CH2 PD13
|
||||||
|
// ESC PWM3 TIM4_CH3 PD14
|
||||||
|
// ESC PWM4 TIM4_CH4 PD15
|
||||||
|
// ESC PWM5 TIM2_CH2 PA1
|
||||||
|
// ESC PWM6 TIM2_CH3 PA2
|
||||||
|
|
||||||
|
|
||||||
|
#if defined(STM32F303xC) || defined(STM32F3DISCOVERY)
|
||||||
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
|
||||||
|
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, }, // PWM1
|
||||||
|
{ TIM16, GPIOB, Pin_8, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, }, // PWM2
|
||||||
|
{ TIM17, GPIOB, Pin_9, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, }, // PWM3
|
||||||
|
{ TIM8, GPIOC, Pin_6, TIM_Channel_1, TIM8_CC_IRQn, 1, }, // PWM4
|
||||||
|
{ TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 1, }, // PWM5
|
||||||
|
{ TIM8, GPIOC, Pin_8, TIM_Channel_3, TIM8_CC_IRQn, 1, }, // PWM6
|
||||||
|
//{ TIM15, GPIOF, Pin_9, TIM_Channel_1, TIM15_IRQn, 0, }, // PWM7 - Potential alternate, untested
|
||||||
|
//{ TIM15, GPIOF, Pin_10, TIM_Channel_2, TIM15_IRQn, 0, }, // PWM8 - Potential alternate, untested
|
||||||
|
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, }, // PWM7
|
||||||
|
{ TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 0, }, // PWM8
|
||||||
|
{ TIM4, GPIOD, Pin_12, TIM_Channel_1, TIM4_IRQn, 0, }, // PWM9
|
||||||
|
{ TIM4, GPIOD, Pin_13, TIM_Channel_2, TIM4_IRQn, 0, }, // PWM10
|
||||||
|
{ TIM4, GPIOD, Pin_14, TIM_Channel_3, TIM4_IRQn, 0, }, // PWM11
|
||||||
|
{ TIM4, GPIOD, Pin_15, TIM_Channel_4, TIM4_IRQn, 0, }, // PWM12
|
||||||
|
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, }, // PWM13
|
||||||
|
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, }, // PWM14
|
||||||
|
};
|
||||||
|
|
||||||
|
#define MAX_TIMERS 7
|
||||||
|
|
||||||
|
static const TIM_TypeDef *timers[MAX_TIMERS] = {
|
||||||
|
TIM1, TIM2, TIM3, TIM4, TIM8, TIM16, TIM17
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
|
||||||
static const uint8_t channels[CC_CHANNELS_PER_TIMER] = {
|
static const uint8_t channels[CC_CHANNELS_PER_TIMER] = {
|
||||||
TIM_Channel_1, TIM_Channel_2, TIM_Channel_3, TIM_Channel_4
|
TIM_Channel_1, TIM_Channel_2, TIM_Channel_3, TIM_Channel_4
|
||||||
};
|
};
|
||||||
|
@ -243,3 +297,20 @@ void TIM4_IRQHandler(void)
|
||||||
{
|
{
|
||||||
timCCxHandler(TIM4);
|
timCCxHandler(TIM4);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if defined(STM32F303xC) || defined(STM32F3DISCOVERY)
|
||||||
|
void TIM8_IRQHandler(void)
|
||||||
|
{
|
||||||
|
timCCxHandler(TIM8);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TIM1_UP_TIM16_IRQHandler(void)
|
||||||
|
{
|
||||||
|
timCCxHandler(TIM16);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TIM1_TRG_COM_TIM17_IRQHandler(void)
|
||||||
|
{
|
||||||
|
timCCxHandler(TIM17);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue