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

UART DMA code refactor (#8980)

UART DMA code refactor
This commit is contained in:
Michael Keller 2019-10-18 03:32:56 +13:00 committed by GitHub
commit d5c858e5b1
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
9 changed files with 421 additions and 435 deletions

View file

@ -37,12 +37,62 @@
#include "common/utils.h"
#include "drivers/dma.h"
#include "drivers/dma_reqmap.h"
#include "drivers/rcc.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
#include "pg/serial_uart.h"
#if defined(STM32H7)
#define UART_BUFFER_ATTRIBUTE DMA_RAM // D2 SRAM
#elif defined(STM32F7)
#define UART_BUFFER_ATTRIBUTE FAST_RAM_ZERO_INIT // DTCM RAM
#elif defined(STM32F4) || defined(STM32F3) || defined(STM32F1)
#define UART_BUFFER_ATTRIBUTE // NONE
#else
#error Undefined UART_BUFFER_ATTRIBUTE for this MCU
#endif
#define UART_BUFFERS(n) \
UART_BUFFER(UART_BUFFER_ATTRIBUTE, n, R); \
UART_BUFFER(UART_BUFFER_ATTRIBUTE, n, T); struct dummy_s
#ifdef USE_UART1
UART_BUFFERS(1);
#endif
#ifdef USE_UART2
UART_BUFFERS(2);
#endif
#ifdef USE_UART3
UART_BUFFERS(3);
#endif
#ifdef USE_UART4
UART_BUFFERS(4);
#endif
#ifdef USE_UART5
UART_BUFFERS(5);
#endif
#ifdef USE_UART6
UART_BUFFERS(6);
#endif
#ifdef USE_UART7
UART_BUFFERS(7);
#endif
#ifdef USE_UART8
UART_BUFFERS(8);
#endif
#undef UART_BUFFERS
serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_e mode, portOptions_e options)
{
uartPort_t *s = serialUART(device, baudRate, mode, options);
@ -232,6 +282,60 @@ const struct serialPortVTable uartVTable[] = {
}
};
#ifdef USE_DMA
void uartConfigureDma(uartDevice_t *uartdev)
{
uartPort_t *s = &(uartdev->port);
const uartHardware_t *hardware = uartdev->hardware;
#ifdef USE_DMA_SPEC
UARTDevice_e device = hardware->device;
const dmaChannelSpec_t *dmaChannelSpec;
if (serialUartConfig(device)->txDmaopt != DMA_OPT_UNUSED) {
dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_TX, device, serialUartConfig(device)->txDmaopt);
if (dmaChannelSpec) {
s->txDMAResource = dmaChannelSpec->ref;
s->txDMAChannel = dmaChannelSpec->channel;
}
}
if (serialUartConfig(device)->rxDmaopt != DMA_OPT_UNUSED) {
dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_RX, device, serialUartConfig(device)->txDmaopt);
if (dmaChannelSpec) {
s->rxDMAResource = dmaChannelSpec->ref;
s->rxDMAChannel = dmaChannelSpec->channel;
}
}
#else
// Non USE_DMA_SPEC does not support configurable ON/OFF of UART DMA
if (hardware->rxDMAResource) {
s->rxDMAResource = hardware->rxDMAResource;
s->rxDMAChannel = hardware->rxDMAChannel;
}
if (hardware->txDMAResource) {
s->txDMAResource = hardware->txDMAResource;
s->txDMAChannel = hardware->txDMAChannel;
}
#endif
if (s->txDMAResource) {
dmaIdentifier_e identifier = dmaGetIdentifier(s->txDMAResource);
dmaInit(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(hardware->device));
dmaSetHandler(identifier, uartDmaIrqHandler, hardware->txPriority, (uint32_t)uartdev);
s->txDMAPeripheralBaseAddr = (uint32_t)&UART_REG_TXD(hardware->reg);
}
if (s->rxDMAResource) {
dmaIdentifier_e identifier = dmaGetIdentifier(s->rxDMAResource);
dmaInit(identifier, OWNER_SERIAL_RX, RESOURCE_INDEX(hardware->device));
s->rxDMAPeripheralBaseAddr = (uint32_t)&UART_REG_RXD(hardware->reg);
}
}
#endif
#define UART_IRQHandler(type, dev) \
void type ## dev ## _IRQHandler(void) \
{ \

View file

@ -44,9 +44,6 @@ typedef struct uartPort_s {
serialPort_t port;
#ifdef USE_DMA
bool rxUseDma;
bool txUseDma;
#ifdef USE_HAL_DRIVER
DMA_HandleTypeDef rxDMAHandle;
DMA_HandleTypeDef txDMAHandle;
@ -54,13 +51,8 @@ typedef struct uartPort_s {
dmaResource_t *rxDMAResource;
dmaResource_t *txDMAResource;
#if defined(STM32F4) || defined(STM32F7)
uint32_t rxDMAChannel;
uint32_t txDMAChannel;
#elif defined(STM32H7)
uint8_t rxDMARequest;
uint8_t txDMARequest;
#endif
uint32_t rxDMAIrq;
uint32_t txDMAIrq;

View file

@ -111,7 +111,7 @@ void uartReconfigure(uartPort_t *uartPort)
#if !defined(STM32H7)
uartPort->rxDMAHandle.Init.Channel = uartPort->rxDMAChannel;
#else
uartPort->txDMAHandle.Init.Request = uartPort->rxDMARequest;
uartPort->txDMAHandle.Init.Request = uartPort->rxDMAChannel;
#endif
uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
@ -159,7 +159,7 @@ void uartReconfigure(uartPort_t *uartPort)
#if !defined(STM32H7)
uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel;
#else
uartPort->txDMAHandle.Init.Request = uartPort->txDMARequest;
uartPort->txDMAHandle.Init.Request = uartPort->txDMAChannel;
#endif
uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH;
uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
@ -230,6 +230,100 @@ void uartTryStartTxDMA(uartPort_t *s)
HAL_UART_Transmit_DMA(&s->Handle, (uint8_t *)&s->port.txBuffer[fromwhere], size);
}
}
static void handleUsartTxDma(uartPort_t *s)
{
uartTryStartTxDMA(s);
}
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
{
uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
HAL_DMA_IRQHandler(&s->txDMAHandle);
}
#endif
void uartIrqHandler(uartPort_t *s)
{
UART_HandleTypeDef *huart = &s->Handle;
/* UART in mode Receiver ---------------------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_RXNE) != RESET)) {
uint8_t rbyte = (uint8_t)(huart->Instance->RDR & (uint8_t) 0xff);
if (s->port.rxCallback) {
s->port.rxCallback(rbyte, s->port.rxCallbackData);
} else {
s->port.rxBuffer[s->port.rxBufferHead] = rbyte;
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
}
CLEAR_BIT(huart->Instance->CR1, (USART_CR1_PEIE));
/* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */
CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE);
__HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST);
}
/* UART parity error interrupt occurred -------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_PE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_PEF);
}
/* UART frame error interrupt occurred --------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_FE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_FEF);
}
/* UART noise error interrupt occurred --------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_NE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_NEF);
}
/* UART Over-Run interrupt occurred -----------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_ORE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_OREF);
}
/* UART in mode Transmitter ------------------------------------------------*/
if (
#ifdef USE_DMA
!s->txDMAResource &&
#endif
(__HAL_UART_GET_IT(huart, UART_IT_TXE) != RESET)) {
/* Check that a Tx process is ongoing */
if (huart->gState != HAL_UART_STATE_BUSY_TX) {
if (s->port.txBufferTail == s->port.txBufferHead) {
huart->TxXferCount = 0;
/* Disable the UART Transmit Data Register Empty Interrupt */
CLEAR_BIT(huart->Instance->CR1, USART_CR1_TXEIE);
} else {
if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) {
huart->Instance->TDR = (((uint16_t) s->port.txBuffer[s->port.txBufferTail]) & (uint16_t) 0x01FFU);
} else {
huart->Instance->TDR = (uint8_t)(s->port.txBuffer[s->port.txBufferTail]);
}
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
}
}
}
/* UART in mode Transmitter (transmission end) -----------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_TC) != RESET)) {
HAL_UART_IRQHandler(huart);
#ifdef USE_DMA
if (s->txDMAResource) {
handleUsartTxDma(s);
}
#endif
}
if (__HAL_UART_GET_IT(huart, UART_IT_IDLE)) {
if (s->port.idleCallback) {
s->port.idleCallback();
}
__HAL_UART_CLEAR_IDLEFLAG(huart);
}
}
#endif // USE_UART

View file

@ -137,13 +137,10 @@ typedef struct uartHardware_s {
#ifdef USE_DMA
dmaResource_t *txDMAResource;
dmaResource_t *rxDMAResource;
#if defined(STM32F4) || defined(STM32F7)
uint32_t DMAChannel;
#elif defined(STM32H7)
// DMAMUX input from peripherals (DMA_REQUEST_xxx); RM0433 Table 110.
uint8_t txDMARequest;
uint8_t rxDMARequest;
#endif
// For H7, {tx|rx}DMAChannel are DMAMUX input index for peripherals (DMA_REQUEST_xxx); RM0433 Table 110.
// For F4 and F7, these are 32-bit channel identifiers (DMA_CHANNEL_x).
uint32_t txDMAChannel;
uint32_t rxDMAChannel;
#endif // USE_DMA
uartPinDef_t rxPins[UARTHARDWARE_MAX_PINS];
@ -170,12 +167,10 @@ typedef struct uartHardware_s {
uint8_t txPriority;
uint8_t rxPriority;
#if defined(STM32H7) || defined(STM32F4)
volatile uint8_t *txBuffer;
volatile uint8_t *rxBuffer;
uint16_t txBufferSize;
uint16_t rxBufferSize;
#endif
} uartHardware_t;
extern const uartHardware_t uartHardware[];
@ -188,15 +183,8 @@ typedef struct uartDevice_s {
const uartHardware_t *hardware;
uartPinDef_t rx;
uartPinDef_t tx;
#if defined(STM32H7) || defined(STM32F4)
// For H7, buffers with possible DMA access is placed in D2 SRAM.
// For F4, buffers should NOT be in CCM DATA RAM (uartDevice is).
volatile uint8_t *rxBuffer;
volatile uint8_t *txBuffer;
#else
volatile uint8_t rxBuffer[UART_RX_BUFFER_SIZE];
volatile uint8_t txBuffer[UART_TX_BUFFER_SIZE];
#endif
} uartDevice_t;
extern uartDevice_t *uartDevmap[];
@ -210,3 +198,55 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
void uartIrqHandler(uartPort_t *s);
void uartReconfigure(uartPort_t *uartPort);
void uartConfigureDma(uartDevice_t *uartdev);
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor);
#if defined(STM32F3) || defined(STM32F7) || defined(STM32H7)
#define UART_REG_RXD(base) ((base)->RDR)
#define UART_REG_TXD(base) ((base)->TDR)
#elif defined(STM32F1) || defined(STM32F4)
#define UART_REG_RXD(base) ((base)->DR)
#define UART_REG_TXD(base) ((base)->DR)
#endif
#define UART_BUFFER(type, n, rxtx) type volatile uint8_t uart ## n ## rxtx ## xBuffer[UART_ ## rxtx ## X_BUFFER_SIZE]
#define UART_BUFFERS_EXTERN(n) \
UART_BUFFER(extern, n, R); \
UART_BUFFER(extern, n, T); struct dummy_s
#ifdef USE_UART1
UART_BUFFERS_EXTERN(1);
#endif
#ifdef USE_UART2
UART_BUFFERS_EXTERN(2);
#endif
#ifdef USE_UART3
UART_BUFFERS_EXTERN(3);
#endif
#ifdef USE_UART4
UART_BUFFERS_EXTERN(4);
#endif
#ifdef USE_UART5
UART_BUFFERS_EXTERN(5);
#endif
#ifdef USE_UART6
UART_BUFFERS_EXTERN(6);
#endif
#ifdef USE_UART7
UART_BUFFERS_EXTERN(7);
#endif
#ifdef USE_UART8
UART_BUFFERS_EXTERN(8);
#endif
#undef UART_BUFFERS_EXTERN

View file

@ -73,7 +73,11 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.rcc = RCC_APB2(USART1),
.irqn = USART1_IRQn,
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART1
.rxPriority = NVIC_PRIO_SERIALUART1,
.txBuffer = uart1TxBuffer,
.rxBuffer = uart1RxBuffer,
.txBufferSize = sizeof(uart1TxBuffer),
.rxBufferSize = sizeof(uart1RxBuffer),
},
#endif
#ifdef USE_UART2
@ -88,7 +92,11 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.rcc = RCC_APB1(USART2),
.irqn = USART2_IRQn,
.txPriority = NVIC_PRIO_SERIALUART2,
.rxPriority = NVIC_PRIO_SERIALUART2
.rxPriority = NVIC_PRIO_SERIALUART2,
.txBuffer = uart2TxBuffer,
.rxBuffer = uart2RxBuffer,
.txBufferSize = sizeof(uart2TxBuffer),
.rxBufferSize = sizeof(uart2RxBuffer),
},
#endif
#ifdef USE_UART3
@ -103,12 +111,16 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.rcc = RCC_APB1(USART3),
.irqn = USART3_IRQn,
.txPriority = NVIC_PRIO_SERIALUART3,
.rxPriority = NVIC_PRIO_SERIALUART3
.rxPriority = NVIC_PRIO_SERIALUART3,
.txBuffer = uart3TxBuffer,
.rxBuffer = uart3RxBuffer,
.txBufferSize = sizeof(uart3TxBuffer),
.rxBufferSize = sizeof(uart3RxBuffer),
},
#endif
};
void uart_tx_dma_IRQHandler(dmaChannelDescriptor_t* descriptor)
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
{
uartPort_t *s = (uartPort_t*)(descriptor->userParam);
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
@ -132,30 +144,18 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
s->port.baudRate = baudRate;
s->port.rxBuffer = uartdev->rxBuffer;
s->port.txBuffer = uartdev->txBuffer;
s->port.rxBufferSize = ARRAYLEN(uartdev->rxBuffer);
s->port.txBufferSize = ARRAYLEN(uartdev->txBuffer);
const uartHardware_t *hardware = uartdev->hardware;
s->USARTx = hardware->reg;
s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;
RCC_ClockCmd(hardware->rcc, ENABLE);
if (hardware->rxDMAResource) {
dmaInit(dmaGetIdentifier(hardware->rxDMAResource), OWNER_SERIAL_RX, RESOURCE_INDEX(device));
s->rxDMAResource = hardware->rxDMAResource;
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
}
if (hardware->txDMAResource) {
const dmaIdentifier_e identifier = dmaGetIdentifier(hardware->txDMAResource);
dmaInit(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
dmaSetHandler(identifier, uart_tx_dma_IRQHandler, hardware->txPriority, (uint32_t)s);
s->txDMAResource = hardware->txDMAResource;
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
}
uartConfigureDma(uartdev);
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
IO_t txIO = IOGetByTag(uartdev->tx.pin);

View file

@ -83,6 +83,18 @@
# define UART3_TX_DMA 0
#endif
#ifdef USE_UART4_RX_DMA
# define UART4_RX_DMA DMA2_Channel3
#else
# define UART4_RX_DMA 0
#endif
#ifdef USE_UART4_TX_DMA
# define UART4_TX_DMA DMA2_Channel5
#else
# define UART4_TX_DMA 0
#endif
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1
{
@ -97,6 +109,10 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.irqn = USART1_IRQn,
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART1_RXDMA,
.txBuffer = uart1TxBuffer,
.rxBuffer = uart1RxBuffer,
.txBufferSize = sizeof(uart1TxBuffer),
.rxBufferSize = sizeof(uart1RxBuffer),
},
#endif
@ -113,6 +129,10 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.irqn = USART2_IRQn,
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART2_RXDMA,
.txBuffer = uart2TxBuffer,
.rxBuffer = uart2RxBuffer,
.txBufferSize = sizeof(uart2TxBuffer),
.rxBufferSize = sizeof(uart2RxBuffer),
},
#endif
@ -129,6 +149,10 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.irqn = USART3_IRQn,
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART3_RXDMA,
.txBuffer = uart3TxBuffer,
.rxBuffer = uart3RxBuffer,
.txBufferSize = sizeof(uart3TxBuffer),
.rxBufferSize = sizeof(uart3RxBuffer),
},
#endif
@ -146,6 +170,10 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.irqn = UART4_IRQn,
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART4_RXDMA,
.txBuffer = uart4TxBuffer,
.rxBuffer = uart4RxBuffer,
.txBufferSize = sizeof(uart4TxBuffer),
.rxBufferSize = sizeof(uart4RxBuffer),
},
#endif
@ -163,11 +191,15 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.irqn = UART5_IRQn,
.txPriority = NVIC_PRIO_SERIALUART5,
.rxPriority = NVIC_PRIO_SERIALUART5,
.txBuffer = uart5TxBuffer,
.rxBuffer = uart5RxBuffer,
.txBufferSize = sizeof(uart5TxBuffer),
.rxBufferSize = sizeof(uart5RxBuffer),
},
#endif
};
static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor)
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
{
uartPort_t *s = (uartPort_t*)(descriptor->userParam);
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
@ -217,30 +249,19 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
s->port.baudRate = baudRate;
s->port.rxBuffer = uartDev->rxBuffer;
s->port.txBuffer = uartDev->txBuffer;
s->port.rxBufferSize = sizeof(uartDev->rxBuffer);
s->port.txBufferSize = sizeof(uartDev->txBuffer);
const uartHardware_t *hardware = uartDev->hardware;
s->USARTx = hardware->reg;
s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;
RCC_ClockCmd(hardware->rcc, ENABLE);
if (hardware->rxDMAResource) {
dmaInit(dmaGetIdentifier(hardware->rxDMAResource), OWNER_SERIAL_RX, RESOURCE_INDEX(device));
s->rxDMAResource = hardware->rxDMAResource;
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
}
if (hardware->txDMAResource) {
const dmaIdentifier_e identifier = dmaGetIdentifier(hardware->txDMAResource);
dmaInit(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
dmaSetHandler(identifier, handleUsartTxDma, hardware->txPriority, (uint32_t)s);
s->txDMAResource = hardware->txDMAResource;
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
}
uartConfigureDma(uartDev);
serialUARTInitIO(IOGetByTag(uartDev->tx.pin), IOGetByTag(uartDev->rx.pin), mode, options, hardware->af, device);

View file

@ -39,42 +39,13 @@
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
#define UART_BUFFERS(n) \
volatile uint8_t uart ## n ## RxBuffer[UART_RX_BUFFER_SIZE]; \
volatile uint8_t uart ## n ## TxBuffer[UART_TX_BUFFER_SIZE]; struct dummy_s
#ifdef USE_UART1
UART_BUFFERS(1);
#endif
#ifdef USE_UART2
UART_BUFFERS(2);
#endif
#ifdef USE_UART3
UART_BUFFERS(3);
#endif
#ifdef USE_UART4
UART_BUFFERS(4);
#endif
#ifdef USE_UART5
UART_BUFFERS(5);
#endif
#ifdef USE_UART6
UART_BUFFERS(6);
#endif
#undef UART_BUFFERS
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1
{
.device = UARTDEV_1,
.reg = USART1,
.DMAChannel = DMA_Channel_4,
.rxDMAChannel = DMA_Channel_4,
.txDMAChannel = DMA_Channel_4,
#ifdef USE_UART1_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA2_Stream5,
#endif
@ -107,7 +78,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{
.device = UARTDEV_2,
.reg = USART2,
.DMAChannel = DMA_Channel_4,
.rxDMAChannel = DMA_Channel_4,
.txDMAChannel = DMA_Channel_4,
#ifdef USE_UART2_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA1_Stream5,
#endif
@ -132,7 +104,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{
.device = UARTDEV_3,
.reg = USART3,
.DMAChannel = DMA_Channel_4,
.rxDMAChannel = DMA_Channel_4,
.txDMAChannel = DMA_Channel_4,
#ifdef USE_UART3_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA1_Stream1,
#endif
@ -157,7 +130,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{
.device = UARTDEV_4,
.reg = UART4,
.DMAChannel = DMA_Channel_4,
.rxDMAChannel = DMA_Channel_4,
.txDMAChannel = DMA_Channel_4,
#ifdef USE_UART4_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA1_Stream2,
#endif
@ -182,7 +156,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{
.device = UARTDEV_5,
.reg = UART5,
.DMAChannel = DMA_Channel_4,
.rxDMAChannel = DMA_Channel_4,
.txDMAChannel = DMA_Channel_4,
#ifdef USE_UART5_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA1_Stream0,
#endif
@ -207,7 +182,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{
.device = UARTDEV_6,
.reg = USART6,
.DMAChannel = DMA_Channel_5,
.rxDMAChannel = DMA_Channel_5,
.txDMAChannel = DMA_Channel_5,
#ifdef USE_UART6_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA2_Stream1,
#endif
@ -246,7 +222,7 @@ static void handleUsartTxDma(uartPort_t *s)
uartTryStartTxDMA(s);
}
void dmaIRQHandler(dmaChannelDescriptor_t* descriptor)
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
{
uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF))
@ -292,21 +268,9 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
s->USARTx = hardware->reg;
if (hardware->rxDMAResource) {
dmaInit(dmaGetIdentifier(hardware->rxDMAResource), OWNER_SERIAL_RX, RESOURCE_INDEX(device));
s->rxDMAChannel = hardware->DMAChannel;
s->rxDMAResource = hardware->rxDMAResource;
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
}
if (hardware->txDMAResource) {
const dmaIdentifier_e identifier = dmaGetIdentifier(hardware->txDMAResource);
dmaInit(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
dmaSetHandler(identifier, dmaIRQHandler, hardware->txPriority, (uint32_t)uart);
s->txDMAChannel = hardware->DMAChannel;
s->txDMAResource = hardware->txDMAResource;
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
}
#ifdef USE_DMA
uartConfigureDma(uart);
#endif
IO_t txIO = IOGetByTag(uart->tx.pin);
IO_t rxIO = IOGetByTag(uart->rx.pin);
@ -330,7 +294,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
}
}
if (!(s->rxDMAChannel)) {
#ifdef USE_DMA
if (!(s->rxDMAResource)) {
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
@ -339,6 +304,7 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
}
#endif
return s;
}

View file

@ -41,14 +41,13 @@
#include "stm32f7xx_ll_usart.h"
static void handleUsartTxDma(uartPort_t *s);
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1
{
.device = UARTDEV_1,
.reg = USART1,
.DMAChannel = DMA_CHANNEL_4,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
#ifdef USE_UART1_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA2_Stream5,
#endif
@ -75,7 +74,11 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.rcc_apb2 = RCC_APB2(USART1),
.rxIrq = USART1_IRQn,
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART1
.rxPriority = NVIC_PRIO_SERIALUART1,
.txBuffer = uart1TxBuffer,
.rxBuffer = uart1RxBuffer,
.txBufferSize = sizeof(uart1TxBuffer),
.rxBufferSize = sizeof(uart1RxBuffer),
},
#endif
@ -83,7 +86,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{
.device = UARTDEV_2,
.reg = USART2,
.DMAChannel = DMA_CHANNEL_4,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
#ifdef USE_UART2_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA1_Stream5,
#endif
@ -104,7 +108,11 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.rcc_apb1 = RCC_APB1(USART2),
.rxIrq = USART2_IRQn,
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART2
.rxPriority = NVIC_PRIO_SERIALUART2,
.txBuffer = uart2TxBuffer,
.rxBuffer = uart2RxBuffer,
.txBufferSize = sizeof(uart2TxBuffer),
.rxBufferSize = sizeof(uart2RxBuffer),
},
#endif
@ -112,7 +120,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{
.device = UARTDEV_3,
.reg = USART3,
.DMAChannel = DMA_CHANNEL_4,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
#ifdef USE_UART3_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA1_Stream1,
#endif
@ -135,7 +144,11 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.rcc_apb1 = RCC_APB1(USART3),
.rxIrq = USART3_IRQn,
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART3
.rxPriority = NVIC_PRIO_SERIALUART3,
.txBuffer = uart3TxBuffer,
.rxBuffer = uart3RxBuffer,
.txBufferSize = sizeof(uart3TxBuffer),
.rxBufferSize = sizeof(uart3RxBuffer),
},
#endif
@ -143,7 +156,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{
.device = UARTDEV_4,
.reg = UART4,
.DMAChannel = DMA_CHANNEL_4,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
#ifdef USE_UART4_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA1_Stream2,
#endif
@ -172,7 +186,11 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.rcc_apb1 = RCC_APB1(UART4),
.rxIrq = UART4_IRQn,
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART4
.rxPriority = NVIC_PRIO_SERIALUART4,
.txBuffer = uart4TxBuffer,
.rxBuffer = uart4RxBuffer,
.txBufferSize = sizeof(uart4TxBuffer),
.rxBufferSize = sizeof(uart4RxBuffer),
},
#endif
@ -180,7 +198,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{
.device = UARTDEV_5,
.reg = UART5,
.DMAChannel = DMA_CHANNEL_4,
.rxDMAChannel = DMA_CHANNEL_4,
.txDMAChannel = DMA_CHANNEL_4,
#ifdef USE_UART5_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA1_Stream0,
#endif
@ -209,7 +228,11 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.rcc_apb1 = RCC_APB1(UART5),
.rxIrq = UART5_IRQn,
.txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART5
.rxPriority = NVIC_PRIO_SERIALUART5,
.txBuffer = uart5TxBuffer,
.rxBuffer = uart5RxBuffer,
.txBufferSize = sizeof(uart5TxBuffer),
.rxBufferSize = sizeof(uart5RxBuffer),
},
#endif
@ -217,7 +240,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{
.device = UARTDEV_6,
.reg = USART6,
.DMAChannel = DMA_CHANNEL_5,
.rxDMAChannel = DMA_CHANNEL_5,
.txDMAChannel = DMA_CHANNEL_5,
#ifdef USE_UART6_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA2_Stream1,
#endif
@ -238,7 +262,11 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.rcc_apb2 = RCC_APB2(USART6),
.rxIrq = USART6_IRQn,
.txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART6
.rxPriority = NVIC_PRIO_SERIALUART6,
.txBuffer = uart6TxBuffer,
.rxBuffer = uart6RxBuffer,
.txBufferSize = sizeof(uart6TxBuffer),
.rxBufferSize = sizeof(uart6RxBuffer),
},
#endif
@ -246,7 +274,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{
.device = UARTDEV_7,
.reg = UART7,
.DMAChannel = DMA_CHANNEL_5,
.rxDMAChannel = DMA_CHANNEL_5,
.txDMAChannel = DMA_CHANNEL_5,
#ifdef USE_UART7_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA1_Stream3,
#endif
@ -275,7 +304,11 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.rcc_apb1 = RCC_APB1(UART7),
.rxIrq = UART7_IRQn,
.txPriority = NVIC_PRIO_SERIALUART7_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART7
.rxPriority = NVIC_PRIO_SERIALUART7,
.txBuffer = uart7TxBuffer,
.rxBuffer = uart7RxBuffer,
.txBufferSize = sizeof(uart7TxBuffer),
.rxBufferSize = sizeof(uart7RxBuffer),
},
#endif
@ -283,7 +316,8 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
{
.device = UARTDEV_8,
.reg = UART8,
.DMAChannel = DMA_CHANNEL_5,
.rxDMAChannel = DMA_CHANNEL_5,
.txDMAChannel = DMA_CHANNEL_5,
#ifdef USE_UART8_RX_DMA
.rxDMAResource = (dmaResource_t *)DMA1_Stream6,
#endif
@ -302,99 +336,15 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.rcc_apb1 = RCC_APB1(UART8),
.rxIrq = UART8_IRQn,
.txPriority = NVIC_PRIO_SERIALUART8_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART8
.rxPriority = NVIC_PRIO_SERIALUART8,
.txBuffer = uart8TxBuffer,
.rxBuffer = uart8RxBuffer,
.txBufferSize = sizeof(uart8TxBuffer),
.rxBufferSize = sizeof(uart8RxBuffer),
},
#endif
};
void uartIrqHandler(uartPort_t *s)
{
UART_HandleTypeDef *huart = &s->Handle;
/* UART in mode Receiver ---------------------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_RXNE) != RESET)) {
uint8_t rbyte = (uint8_t)(huart->Instance->RDR & (uint8_t) 0xff);
if (s->port.rxCallback) {
s->port.rxCallback(rbyte, s->port.rxCallbackData);
} else {
s->port.rxBuffer[s->port.rxBufferHead] = rbyte;
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
}
CLEAR_BIT(huart->Instance->CR1, (USART_CR1_PEIE));
/* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */
CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE);
__HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST);
}
/* UART parity error interrupt occurred -------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_PE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_PEF);
}
/* UART frame error interrupt occurred --------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_FE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_FEF);
}
/* UART noise error interrupt occurred --------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_NE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_NEF);
}
/* UART Over-Run interrupt occurred -----------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_ORE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_OREF);
}
/* UART in mode Transmitter ------------------------------------------------*/
if (!s->txDMAResource && (__HAL_UART_GET_IT(huart, UART_IT_TXE) != RESET)) {
/* Check that a Tx process is ongoing */
if (huart->gState != HAL_UART_STATE_BUSY_TX) {
if (s->port.txBufferTail == s->port.txBufferHead) {
huart->TxXferCount = 0;
/* Disable the UART Transmit Data Register Empty Interrupt */
CLEAR_BIT(huart->Instance->CR1, USART_CR1_TXEIE);
} else {
if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) {
huart->Instance->TDR = (((uint16_t) s->port.txBuffer[s->port.txBufferTail]) & (uint16_t) 0x01FFU);
} else {
huart->Instance->TDR = (uint8_t)(s->port.txBuffer[s->port.txBufferTail]);
}
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
}
}
}
/* UART in mode Transmitter (transmission end) -----------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_TC) != RESET)) {
HAL_UART_IRQHandler(huart);
if (s->txDMAResource) {
handleUsartTxDma(s);
}
}
if (__HAL_UART_GET_IT(huart, UART_IT_IDLE)) {
if (s->port.idleCallback) {
s->port.idleCallback();
}
__HAL_UART_CLEAR_IDLEFLAG(huart);
}
}
static void handleUsartTxDma(uartPort_t *s)
{
uartTryStartTxDMA(s);
}
void dmaIRQHandler(dmaChannelDescriptor_t* descriptor)
{
uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
HAL_DMA_IRQHandler(&s->txDMAHandle);
}
// XXX Should serialUART be consolidated?
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
@ -410,32 +360,18 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
s->port.baudRate = baudRate;
s->port.rxBuffer = uartdev->rxBuffer;
s->port.txBuffer = uartdev->txBuffer;
s->port.rxBufferSize = ARRAYLEN(uartdev->rxBuffer);
s->port.txBufferSize = ARRAYLEN(uartdev->txBuffer);
const uartHardware_t *hardware = uartdev->hardware;
s->USARTx = hardware->reg;
if (hardware->rxDMAResource) {
s->rxDMAChannel = hardware->DMAChannel;
s->rxDMAResource = hardware->rxDMAResource;
}
s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;
if (hardware->txDMAResource) {
s->txDMAChannel = hardware->DMAChannel;
s->txDMAResource = hardware->txDMAResource;
// DMA TX Interrupt
dmaIdentifier_e identifier = dmaGetIdentifier(hardware->txDMAResource);
dmaInit(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
dmaSetHandler(identifier, dmaIRQHandler, hardware->txPriority, (uint32_t)uartdev);
}
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
#ifdef USE_DMA
uartConfigureDma(uartdev);
#endif
s->Handle.Instance = hardware->reg;
@ -464,10 +400,12 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
}
}
if (!s->rxDMAChannel) {
#ifdef USE_DMA
if (!s->rxDMAResource) {
HAL_NVIC_SetPriority(hardware->rxIrq, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
HAL_NVIC_EnableIRQ(hardware->rxIrq);
}
#endif
return s;
}

View file

@ -88,53 +88,15 @@
#define UART8_RX_DMA_STREAM NULL
#endif
#define UART_BUFFERS(n) \
DMA_RAM volatile uint8_t uart ## n ## RxBuffer[UART_RX_BUFFER_SIZE]; \
DMA_RAM volatile uint8_t uart ## n ## TxBuffer[UART_TX_BUFFER_SIZE]; struct dummy_s
#ifdef USE_UART1
UART_BUFFERS(1);
#endif
#ifdef USE_UART2
UART_BUFFERS(2);
#endif
#ifdef USE_UART3
UART_BUFFERS(3);
#endif
#ifdef USE_UART4
UART_BUFFERS(4);
#endif
#ifdef USE_UART5
UART_BUFFERS(5);
#endif
#ifdef USE_UART6
UART_BUFFERS(6);
#endif
#ifdef USE_UART7
UART_BUFFERS(7);
#endif
#ifdef USE_UART8
UART_BUFFERS(8);
#endif
#undef UART_BUFFERS
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1
{
.device = UARTDEV_1,
.reg = USART1,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_USART1_RX,
.rxDMAChannel = DMA_REQUEST_USART1_RX,
.rxDMAResource = (dmaResource_t *)UART1_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_USART1_TX,
.txDMAChannel = DMA_REQUEST_USART1_TX,
.txDMAResource = (dmaResource_t *)UART1_TX_DMA_STREAM,
#endif
.rxPins = {
@ -163,9 +125,9 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.device = UARTDEV_2,
.reg = USART2,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_USART2_RX,
.rxDMAChannel = DMA_REQUEST_USART2_RX,
.rxDMAResource = (dmaResource_t *)UART2_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_USART2_TX,
.txDMAChannel = DMA_REQUEST_USART2_TX,
.txDMAResource = (dmaResource_t *)UART2_TX_DMA_STREAM,
#endif
.rxPins = {
@ -192,9 +154,9 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.device = UARTDEV_3,
.reg = USART3,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_USART3_RX,
.rxDMAChannel = DMA_REQUEST_USART3_RX,
.rxDMAResource = (dmaResource_t *)UART3_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_USART3_TX,
.txDMAChannel = DMA_REQUEST_USART3_TX,
.txDMAResource = (dmaResource_t *)UART3_TX_DMA_STREAM,
#endif
.rxPins = {
@ -223,9 +185,9 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.device = UARTDEV_4,
.reg = UART4,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_UART4_RX,
.rxDMAChannel = DMA_REQUEST_UART4_RX,
.rxDMAResource = (dmaResource_t *)UART4_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_UART4_TX,
.txDMAChannel = DMA_REQUEST_UART4_TX,
.txDMAResource = (dmaResource_t *)UART4_TX_DMA_STREAM,
#endif
.rxPins = {
@ -258,9 +220,9 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.device = UARTDEV_5,
.reg = UART5,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_UART5_RX,
.rxDMAChannel = DMA_REQUEST_UART5_RX,
.rxDMAResource = (dmaResource_t *)UART5_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_UART5_TX,
.txDMAChannel = DMA_REQUEST_UART5_TX,
.txDMAResource = (dmaResource_t *)UART5_TX_DMA_STREAM,
#endif
.rxPins = {
@ -289,9 +251,9 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.device = UARTDEV_6,
.reg = USART6,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_USART6_RX,
.rxDMAChannel = DMA_REQUEST_USART6_RX,
.rxDMAResource = (dmaResource_t *)UART6_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_USART6_TX,
.txDMAChannel = DMA_REQUEST_USART6_TX,
.txDMAResource = (dmaResource_t *)UART6_TX_DMA_STREAM,
#endif
.rxPins = {
@ -318,9 +280,9 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.device = UARTDEV_7,
.reg = UART7,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_UART7_RX,
.rxDMAChannel = DMA_REQUEST_UART7_RX,
.rxDMAResource = (dmaResource_t *)UART7_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_UART7_TX,
.txDMAChannel = DMA_REQUEST_UART7_TX,
.txDMAResource = (dmaResource_t *)UART7_TX_DMA_STREAM,
#endif
.rxPins = {
@ -351,9 +313,9 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
.device = UARTDEV_8,
.reg = UART8,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_UART8_RX,
.rxDMAChannel = DMA_REQUEST_UART8_RX,
.rxDMAResource = (dmaResource_t *)UART8_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_UART8_TX,
.txDMAChannel = DMA_REQUEST_UART8_TX,
.txDMAResource = (dmaResource_t *)UART8_TX_DMA_STREAM,
#endif
.rxPins = {
@ -374,107 +336,6 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#endif
};
#ifdef USE_DMA
static void handleUsartTxDma(uartPort_t *s);
#endif
void uartIrqHandler(uartPort_t *s)
{
UART_HandleTypeDef *huart = &s->Handle;
/* UART in mode Receiver ---------------------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_RXNE) != RESET)) {
uint8_t rbyte = (uint8_t)(huart->Instance->RDR & (uint8_t) 0xff);
if (s->port.rxCallback) {
s->port.rxCallback(rbyte, s->port.rxCallbackData);
} else {
s->port.rxBuffer[s->port.rxBufferHead] = rbyte;
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
}
CLEAR_BIT(huart->Instance->CR1, (USART_CR1_PEIE));
/* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */
CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE);
__HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST);
}
/* UART parity error interrupt occurred -------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_PE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_PEF);
}
/* UART frame error interrupt occurred --------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_FE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_FEF);
}
/* UART noise error interrupt occurred --------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_NE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_NEF);
}
/* UART Over-Run interrupt occurred -----------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_ORE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_OREF);
}
/* UART in mode Transmitter ------------------------------------------------*/
if (
#ifdef USE_DMA
!s->txDMAResource &&
#endif
(__HAL_UART_GET_IT(huart, UART_IT_TXE) != RESET)) {
/* Check that a Tx process is ongoing */
if (huart->gState != HAL_UART_STATE_BUSY_TX) {
if (s->port.txBufferTail == s->port.txBufferHead) {
huart->TxXferCount = 0;
/* Disable the UART Transmit Data Register Empty Interrupt */
CLEAR_BIT(huart->Instance->CR1, USART_CR1_TXEIE);
} else {
if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) {
huart->Instance->TDR = (((uint16_t) s->port.txBuffer[s->port.txBufferTail]) & (uint16_t) 0x01FFU);
} else {
huart->Instance->TDR = (uint8_t)(s->port.txBuffer[s->port.txBufferTail]);
}
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
}
}
}
/* UART in mode Transmitter (transmission end) -----------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_TC) != RESET)) {
HAL_UART_IRQHandler(huart);
#ifdef USE_DMA
if (s->txDMAResource) {
handleUsartTxDma(s);
}
#endif
}
if (__HAL_UART_GET_IT(huart, UART_IT_IDLE)) {
if (s->port.idleCallback) {
s->port.idleCallback();
}
__HAL_UART_CLEAR_IDLEFLAG(huart);
}
}
#ifdef USE_DMA
static void handleUsartTxDma(uartPort_t *s)
{
uartTryStartTxDMA(s);
}
static void dmaIRQHandler(dmaChannelDescriptor_t* descriptor)
{
uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
HAL_DMA_IRQHandler(&s->txDMAHandle);
}
#endif
// XXX Should serialUART be consolidated?
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, portOptions_e options)
@ -494,39 +355,13 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
s->USARTx = hardware->reg;
#ifdef STM32H7
s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;
#endif
#ifdef USE_DMA
if (hardware->rxDMAResource) {
s->rxDMAResource = hardware->rxDMAResource;
#if defined(STM32H7)
s->rxDMARequest = hardware->rxDMARequest;
#else // F4 & F7
s->rxDMAChannel = hardware->DMAChannel;
#endif
}
if (hardware->txDMAResource) {
s->txDMAResource = hardware->txDMAResource;
#if defined(STM32H7)
s->txDMARequest = hardware->txDMARequest;
#else // F4 & F7
s->txDMAChannel = hardware->DMAChannel;
#endif
// DMA TX Interrupt
dmaIdentifier_e identifier = dmaGetIdentifier(hardware->txDMAResource);
dmaInit(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
dmaSetHandler(identifier, dmaIRQHandler, hardware->txPriority, (uint32_t)uartdev);
}
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
uartConfigureDma(uartdev);
#endif
s->Handle.Instance = hardware->reg;
@ -556,11 +391,7 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
}
#ifdef USE_DMA
#if defined(STM32H7)
if (!s->rxDMAResource)
#else
if (!s->rxDMAChannel)
#endif
#endif
{
HAL_NVIC_SetPriority(hardware->rxIrq, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));