1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 21:05:35 +03:00

Configurable UART

This commit is contained in:
jflyper 2017-05-15 16:54:30 +09:00
parent 4ee7a330d6
commit fdfe9e8af3
15 changed files with 1617 additions and 1604 deletions

View file

@ -17,9 +17,11 @@
/*
* Authors:
* jflyper - Refactoring, cleanup and made pin-configurable
* Dominic Clifton - Serial port abstraction, Separation of common STM32 code for cleanflight, various cleanups.
* Hamasaki/Timecop - Initial baseflight code
*/
#include <stdbool.h>
#include <stdint.h>
@ -29,207 +31,12 @@
#include "common/utils.h"
#include "drivers/gpio.h"
#include "inverter.h"
#include "drivers/inverter.h"
#include "drivers/rcc.h"
#include "serial.h"
#include "serial_uart.h"
#include "serial_uart_impl.h"
static void usartConfigurePinInversion(uartPort_t *uartPort) {
#if !defined(USE_INVERTER) && !defined(STM32F303xC)
UNUSED(uartPort);
#else
bool inverted = uartPort->port.options & SERIAL_INVERTED;
#ifdef USE_INVERTER
if (inverted) {
// Enable hardware inverter if available.
enableInverter(uartPort->USARTx, true);
}
#endif
#ifdef STM32F303xC
uint32_t inversionPins = 0;
if (uartPort->port.mode & MODE_TX) {
inversionPins |= USART_InvPin_Tx;
}
if (uartPort->port.mode & MODE_RX) {
inversionPins |= USART_InvPin_Rx;
}
USART_InvPinCmd(uartPort->USARTx, inversionPins, inverted ? ENABLE : DISABLE);
#endif
#endif
}
static void uartReconfigure(uartPort_t *uartPort)
{
USART_InitTypeDef USART_InitStructure;
USART_Cmd(uartPort->USARTx, DISABLE);
USART_InitStructure.USART_BaudRate = uartPort->port.baudRate;
// according to the stm32 documentation wordlen has to be 9 for parity bits
// this does not seem to matter for rx but will give bad data on tx!
if (uartPort->port.options & SERIAL_PARITY_EVEN) {
USART_InitStructure.USART_WordLength = USART_WordLength_9b;
} else {
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
}
USART_InitStructure.USART_StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_StopBits_2 : USART_StopBits_1;
USART_InitStructure.USART_Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_Parity_Even : USART_Parity_No;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = 0;
if (uartPort->port.mode & MODE_RX)
USART_InitStructure.USART_Mode |= USART_Mode_Rx;
if (uartPort->port.mode & MODE_TX)
USART_InitStructure.USART_Mode |= USART_Mode_Tx;
USART_Init(uartPort->USARTx, &USART_InitStructure);
usartConfigurePinInversion(uartPort);
if(uartPort->port.options & SERIAL_BIDIR)
USART_HalfDuplexCmd(uartPort->USARTx, ENABLE);
else
USART_HalfDuplexCmd(uartPort->USARTx, DISABLE);
USART_Cmd(uartPort->USARTx, ENABLE);
}
serialPort_t *uartOpen(UARTDevice device, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options)
{
uartPort_t *s = serialUART(device, baudRate, mode, options);
if (!s)
return (serialPort_t *)s;
s->txDMAEmpty = true;
// common serial initialisation code should move to serialPort::init()
s->port.rxBufferHead = s->port.rxBufferTail = 0;
s->port.txBufferHead = s->port.txBufferTail = 0;
// callback works for IRQ-based RX ONLY
s->port.rxCallback = rxCallback;
s->port.mode = mode;
s->port.baudRate = baudRate;
s->port.options = options;
uartReconfigure(s);
// Receive DMA or IRQ
DMA_InitTypeDef DMA_InitStructure;
if (mode & MODE_RX) {
#ifdef STM32F4
if (s->rxDMAStream) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr;
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ;
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ;
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
#else
if (s->rxDMAChannel) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr;
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
#endif
DMA_InitStructure.DMA_BufferSize = s->port.rxBufferSize;
#ifdef STM32F4
DMA_InitStructure.DMA_Channel = s->rxDMAChannel;
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)s->port.rxBuffer;
DMA_DeInit(s->rxDMAStream);
DMA_Init(s->rxDMAStream, &DMA_InitStructure);
DMA_Cmd(s->rxDMAStream, ENABLE);
USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE);
s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAStream);
#else
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->port.rxBuffer;
DMA_DeInit(s->rxDMAChannel);
DMA_Init(s->rxDMAChannel, &DMA_InitStructure);
DMA_Cmd(s->rxDMAChannel, ENABLE);
USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE);
s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAChannel);
#endif
} else {
USART_ClearITPendingBit(s->USARTx, USART_IT_RXNE);
USART_ITConfig(s->USARTx, USART_IT_RXNE, ENABLE);
}
}
// Transmit DMA or IRQ
if (mode & MODE_TX) {
#ifdef STM32F4
if (s->txDMAStream) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr;
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ;
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ;
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
#else
if (s->txDMAChannel) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr;
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
#endif
DMA_InitStructure.DMA_BufferSize = s->port.txBufferSize;
#ifdef STM32F4
DMA_InitStructure.DMA_Channel = s->txDMAChannel;
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
DMA_DeInit(s->txDMAStream);
DMA_Init(s->txDMAStream, &DMA_InitStructure);
DMA_ITConfig(s->txDMAStream, DMA_IT_TC | DMA_IT_FE | DMA_IT_TE | DMA_IT_DME, ENABLE);
DMA_SetCurrDataCounter(s->txDMAStream, 0);
#else
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
DMA_DeInit(s->txDMAChannel);
DMA_Init(s->txDMAChannel, &DMA_InitStructure);
DMA_ITConfig(s->txDMAChannel, DMA_IT_TC, ENABLE);
DMA_SetCurrDataCounter(s->txDMAChannel, 0);
s->txDMAChannel->CNDTR = 0;
#endif
USART_DMACmd(s->USARTx, USART_DMAReq_Tx, ENABLE);
} else {
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
}
}
USART_Cmd(s->USARTx, ENABLE);
return (serialPort_t *)s;
}
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate)
{
@ -417,3 +224,75 @@ const struct serialPortVTable uartVTable[] = {
.endWrite = NULL,
}
};
#ifdef USE_UART1
// USART1 Rx/Tx IRQ Handler
void USART1_IRQHandler(void)
{
uartPort_t *s = &(uartDevmap[UARTDEV_1]->port);
uartIrqHandler(s);
}
#endif
#ifdef USE_UART2
// USART2 Rx/Tx IRQ Handler
void USART2_IRQHandler(void)
{
uartPort_t *s = &(uartDevmap[UARTDEV_2]->port);
uartIrqHandler(s);
}
#endif
#ifdef USE_UART3
// USART3 Rx/Tx IRQ Handler
void USART3_IRQHandler(void)
{
uartPort_t *s = &(uartDevmap[UARTDEV_3]->port);
uartIrqHandler(s);
}
#endif
#ifdef USE_UART4
// UART4 Rx/Tx IRQ Handler
void UART4_IRQHandler(void)
{
uartPort_t *s = &(uartDevmap[UARTDEV_4]->port);
uartIrqHandler(s);
}
#endif
#ifdef USE_UART5
// UART5 Rx/Tx IRQ Handler
void UART5_IRQHandler(void)
{
uartPort_t *s = &(uartDevmap[UARTDEV_5]->port);
uartIrqHandler(s);
}
#endif
#ifdef USE_UART6
// USART6 Rx/Tx IRQ Handler
void USART6_IRQHandler(void)
{
uartPort_t *s = &(uartDevmap[UARTDEV_6]->port);
uartIrqHandler(s);
}
#endif
#ifdef USE_UART7
// UART7 Rx/Tx IRQ Handler
void UART7_IRQHandler(void)
{
uartPort_t *s = &(uartDevmap[UARTDEV_7]->port);
uartIrqHandler(s);
}
#endif
#ifdef USE_UART8
// UART8 Rx/Tx IRQ Handler
void UART8_IRQHandler(void)
{
uartPort_t *s = &(uartDevmap[UARTDEV_8]->port);
uartIrqHandler(s);
}
#endif