mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +03:00
STM32F1/3: convert serial UART to IO code
This commit is contained in:
parent
715d622f1f
commit
5f03470557
26 changed files with 236 additions and 635 deletions
|
@ -29,8 +29,9 @@
|
|||
#include <platform.h>
|
||||
|
||||
#include "system.h"
|
||||
#include "gpio.h"
|
||||
#include "io.h"
|
||||
#include "nvic.h"
|
||||
#include "rcc.h"
|
||||
|
||||
#include "serial.h"
|
||||
#include "serial_uart.h"
|
||||
|
@ -48,13 +49,6 @@ static uartPort_t uartPort2;
|
|||
static uartPort_t uartPort3;
|
||||
#endif
|
||||
|
||||
// Using RX DMA disables the use of receive callbacks
|
||||
#define USE_USART1_RX_DMA
|
||||
|
||||
#if defined(CC3D) // FIXME move board specific code to target.h files.
|
||||
#undef USE_USART1_RX_DMA
|
||||
#endif
|
||||
|
||||
void usartIrqCallback(uartPort_t *s)
|
||||
{
|
||||
uint16_t SR = s->USARTx->SR;
|
||||
|
@ -89,7 +83,7 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
uartPort_t *s;
|
||||
static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE];
|
||||
gpio_config_t gpio;
|
||||
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
s = &uartPort1;
|
||||
|
@ -112,27 +106,23 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
s->txDMAChannel = DMA1_Channel4;
|
||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||
RCC_ClockCmd(RCC_APB2(USART1), ENABLE);
|
||||
RCC_ClockCmd(RCC_AHB(DMA1), ENABLE);
|
||||
|
||||
// USART1_TX PA9
|
||||
// USART1_RX PA10
|
||||
gpio.speed = Speed_2MHz;
|
||||
|
||||
gpio.pin = Pin_9;
|
||||
if (options & SERIAL_BIDIR) {
|
||||
gpio.mode = Mode_AF_OD;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_RXTX, RESOURCE_USART);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_OD);
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
gpio.mode = Mode_AF_PP;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_TX, RESOURCE_USART);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_PP);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
gpio.pin = Pin_10;
|
||||
gpio.mode = Mode_IPU;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(PA10)), OWNER_SERIAL_RX, RESOURCE_USART);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA10)), IOCFG_IPU);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -155,7 +145,6 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
return s;
|
||||
}
|
||||
|
||||
|
||||
// USART1 Tx DMA Handler
|
||||
void DMA1_Channel4_IRQHandler(void)
|
||||
{
|
||||
|
@ -185,7 +174,7 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
uartPort_t *s;
|
||||
static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE];
|
||||
gpio_config_t gpio;
|
||||
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
s = &uartPort2;
|
||||
|
@ -203,27 +192,23 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||
RCC_ClockCmd(RCC_APB1(USART2), ENABLE);
|
||||
RCC_ClockCmd(RCC_AHB(DMA1), ENABLE);
|
||||
|
||||
// USART2_TX PA2
|
||||
// USART2_RX PA3
|
||||
gpio.speed = Speed_2MHz;
|
||||
|
||||
gpio.pin = Pin_2;
|
||||
if (options & SERIAL_BIDIR) {
|
||||
gpio.mode = Mode_AF_OD;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_RXTX, RESOURCE_USART);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_OD);
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
gpio.mode = Mode_AF_PP;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_TX, RESOURCE_USART);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_PP);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
gpio.pin = Pin_3;
|
||||
gpio.mode = Mode_IPU;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL_RX, RESOURCE_USART);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -254,7 +239,7 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
uartPort_t *s;
|
||||
static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE];
|
||||
static volatile uint8_t tx3Buffer[UART3_TX_BUFFER_SIZE];
|
||||
gpio_config_t gpio;
|
||||
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
s = &uartPort3;
|
||||
|
@ -272,29 +257,20 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
|||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||
|
||||
#ifdef USART3_APB1_PERIPHERALS
|
||||
RCC_APB1PeriphClockCmd(USART3_APB1_PERIPHERALS, ENABLE);
|
||||
#endif
|
||||
#ifdef USART3_APB2_PERIPHERALS
|
||||
RCC_APB2PeriphClockCmd(USART3_APB2_PERIPHERALS, ENABLE);
|
||||
#endif
|
||||
RCC_ClockCmd(RCC_APB1(USART3), ENABLE);
|
||||
|
||||
gpio.speed = Speed_2MHz;
|
||||
|
||||
gpio.pin = USART3_TX_PIN;
|
||||
if (options & SERIAL_BIDIR) {
|
||||
gpio.mode = Mode_AF_OD;
|
||||
gpioInit(USART3_GPIO, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(USART3_TX_PIN)), OWNER_SERIAL_RXTX, RESOURCE_USART);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(USART3_TX_PIN)), IOCFG_AF_OD);
|
||||
} else {
|
||||
if (mode & MODE_TX) {
|
||||
gpio.mode = Mode_AF_PP;
|
||||
gpioInit(USART3_GPIO, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(USART3_TX_PIN)), OWNER_SERIAL_TX, RESOURCE_USART);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(USART3_TX_PIN)), IOCFG_AF_PP);
|
||||
}
|
||||
|
||||
if (mode & MODE_RX) {
|
||||
gpio.pin = USART3_RX_PIN;
|
||||
gpio.mode = Mode_IPU;
|
||||
gpioInit(USART3_GPIO, &gpio);
|
||||
IOInit(IOGetByTag(IO_TAG(USART3_RX_PIN)), OWNER_SERIAL_RX, RESOURCE_USART);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(USART3_RX_PIN)), IOCFG_IPU);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue