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

[H7] Enable UART

This commit is contained in:
jflyper 2019-05-04 23:32:24 +09:00
parent 77ef37bad0
commit f58b3eab03
4 changed files with 657 additions and 19 deletions

View file

@ -42,19 +42,29 @@ typedef struct uartPort_s {
serialPort_t port;
#ifdef USE_DMA
#if defined(STM32F7)
bool rxUseDma;
bool txUseDma;
#ifdef USE_HAL_DRIVER
DMA_HandleTypeDef rxDMAHandle;
DMA_HandleTypeDef txDMAHandle;
#endif
#if defined(STM32F4) || defined(STM32F7)
DMA_Stream_TypeDef *rxDMAStream;
DMA_Stream_TypeDef *txDMAStream;
uint32_t rxDMAChannel;
uint32_t txDMAChannel;
#else
#elif defined(STM32H7)
DMA_Stream_TypeDef *rxDMAStream;
DMA_Stream_TypeDef *txDMAStream;
uint8_t rxDMARequest;
uint8_t txDMARequest;
#elif defined(STM32F1) || defined(STM32F3)
DMA_Channel_TypeDef *rxDMAChannel;
DMA_Channel_TypeDef *txDMAChannel;
#endif
uint32_t rxDMAIrq;
uint32_t txDMAIrq;

View file

@ -117,10 +117,15 @@ void uartReconfigure(uartPort_t *uartPort)
// Receive DMA or IRQ
if (uartPort->port.mode & MODE_RX)
{
#ifdef USE_DMA
if (uartPort->rxDMAStream)
{
uartPort->rxDMAHandle.Instance = uartPort->rxDMAStream;
#if !defined(STM32H7)
uartPort->rxDMAHandle.Init.Channel = uartPort->rxDMAChannel;
#else
uartPort->txDMAHandle.Init.Request = uartPort->rxDMARequest;
#endif
uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
uartPort->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
@ -143,8 +148,8 @@ void uartReconfigure(uartPort_t *uartPort)
uartPort->rxDMAPos = __HAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle);
}
else
} else
#endif
{
/* Enable the UART Parity Error Interrupt */
SET_BIT(uartPort->USARTx->CR1, USART_CR1_PEIE);
@ -159,10 +164,14 @@ void uartReconfigure(uartPort_t *uartPort)
// Transmit DMA or IRQ
if (uartPort->port.mode & MODE_TX) {
#ifdef USE_DMA
if (uartPort->txDMAStream) {
uartPort->txDMAHandle.Instance = uartPort->txDMAStream;
#if !defined(STM32H7)
uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel;
#else
uartPort->txDMAHandle.Init.Request = uartPort->txDMARequest;
#endif
uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH;
uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
uartPort->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
@ -186,7 +195,10 @@ void uartReconfigure(uartPort_t *uartPort)
__HAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle);
__HAL_DMA_SET_COUNTER(&uartPort->txDMAHandle, 0);
} else {
} else
#endif
{
/* Enable the UART Transmit Data Register Empty Interrupt */
SET_BIT(uartPort->USARTx->CR1, USART_CR1_TXEIE);
}
@ -202,7 +214,9 @@ serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr callback, v
return (serialPort_t *)s;
}
#ifdef USE_DMA
s->txDMAEmpty = true;
#endif
// common serial initialisation code should move to serialPort::init()
s->port.rxBufferHead = s->port.rxBufferTail = 0;
@ -233,10 +247,11 @@ void uartSetMode(serialPort_t *instance, portMode_e mode)
uartReconfigure(uartPort);
}
#ifdef USE_DMA
void uartTryStartTxDMA(uartPort_t *s)
{
ATOMIC_BLOCK(NVIC_PRIO_SERIALUART_TXDMA) {
if (s->txDMAStream->CR & DMA_SxCR_EN) {
if (s->txDMAStream->CR & 1) {
// DMA is already in progress
return;
}
@ -253,7 +268,7 @@ void uartTryStartTxDMA(uartPort_t *s)
}
uint16_t size;
uint32_t fromWhere = s->port.txBufferTail;
uint32_t fromwhere = s->port.txBufferTail;
if (s->port.txBufferHead > s->port.txBufferTail) {
size = s->port.txBufferHead - s->port.txBufferTail;
@ -262,17 +277,18 @@ void uartTryStartTxDMA(uartPort_t *s)
size = s->port.txBufferSize - s->port.txBufferTail;
s->port.txBufferTail = 0;
}
s->txDMAEmpty = false;
HAL_UART_Transmit_DMA(&s->Handle, (uint8_t *)&s->port.txBuffer[fromWhere], size);
HAL_UART_Transmit_DMA(&s->Handle, (uint8_t *)&s->port.txBuffer[fromwhere], size);
}
}
#endif
uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance)
{
uartPort_t *s = (uartPort_t*)instance;
#ifdef USE_DMA
if (s->rxDMAStream) {
uint32_t rxDMAHead = __HAL_DMA_GET_COUNTER(s->Handle.hdmarx);
@ -282,6 +298,7 @@ uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance)
return s->port.rxBufferSize + rxDMAHead - s->rxDMAPos;
}
}
#endif
if (s->port.rxBufferHead >= s->port.rxBufferTail) {
return s->port.rxBufferHead - s->port.rxBufferTail;
@ -302,6 +319,7 @@ uint32_t uartTotalTxBytesFree(const serialPort_t *instance)
bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail;
}
#ifdef USE_DMA
if (s->txDMAStream) {
/*
* When we queue up a DMA request, we advance the Tx buffer tail before the transfer finishes, so we must add
@ -321,6 +339,7 @@ uint32_t uartTotalTxBytesFree(const serialPort_t *instance)
return 0;
}
}
#endif
return (s->port.txBufferSize - 1) - bytesUsed;
}
@ -328,9 +347,11 @@ uint32_t uartTotalTxBytesFree(const serialPort_t *instance)
bool isUartTransmitBufferEmpty(const serialPort_t *instance)
{
const uartPort_t *s = (uartPort_t *)instance;
#ifdef USE_DMA
if (s->txDMAStream)
return s->txDMAEmpty;
else
#endif
return s->port.txBufferTail == s->port.txBufferHead;
}
@ -339,11 +360,14 @@ uint8_t uartRead(serialPort_t *instance)
uint8_t ch;
uartPort_t *s = (uartPort_t *)instance;
#ifdef USE_DMA
if (s->rxDMAStream) {
ch = s->port.rxBuffer[s->port.rxBufferSize - s->rxDMAPos];
if (--s->rxDMAPos == 0)
s->rxDMAPos = s->port.rxBufferSize;
} else {
} else
#endif
{
ch = s->port.rxBuffer[s->port.rxBufferTail];
if (s->port.rxBufferTail + 1 >= s->port.rxBufferSize) {
s->port.rxBufferTail = 0;
@ -358,16 +382,21 @@ uint8_t uartRead(serialPort_t *instance)
void uartWrite(serialPort_t *instance, uint8_t ch)
{
uartPort_t *s = (uartPort_t *)instance;
s->port.txBuffer[s->port.txBufferHead] = ch;
if (s->port.txBufferHead + 1 >= s->port.txBufferSize) {
s->port.txBufferHead = 0;
} else {
s->port.txBufferHead++;
}
#ifdef USE_DMA
if (s->txDMAStream) {
uartTryStartTxDMA(s);
} else {
} else
#endif
{
__HAL_UART_ENABLE_IT(&s->Handle, UART_IT_TXE);
}
}

View file

@ -58,6 +58,15 @@
#ifndef UART_TX_BUFFER_SIZE
#define UART_TX_BUFFER_SIZE 256
#endif
#elif defined(STM32H7)
#define UARTDEV_COUNT_MAX 8
#define UARTHARDWARE_MAX_PINS 5
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 128
#endif
#ifndef UART_TX_BUFFER_SIZE
#define UART_TX_BUFFER_SIZE 256
#endif
#else
#error unknown MCU family
#endif
@ -116,7 +125,7 @@
typedef struct uartPinDef_s {
ioTag_t pin;
#if defined(STM32F7)
#if defined(STM32F7) || defined(STM32H7)
uint8_t af;
#endif
} uartPinDef_t;
@ -124,33 +133,54 @@ typedef struct uartPinDef_s {
typedef struct uartHardware_s {
UARTDevice_e device; // XXX Not required for full allocation
USART_TypeDef* reg;
#if defined(STM32F1) || defined(STM32F3)
DMA_Channel_TypeDef *txDMAChannel;
DMA_Channel_TypeDef *rxDMAChannel;
#elif defined(STM32F4) || defined(STM32F7)
#ifdef USE_DMA
#if defined(STM32F4) || defined(STM32F7)
uint32_t DMAChannel;
DMA_Stream_TypeDef *txDMAStream;
DMA_Stream_TypeDef *rxDMAStream;
#elif defined(STM32H7)
// DMAMUX input from peripherals (DMA_REQUEST_xxx); RM0433 Table 110.
uint8_t txDMARequest;
uint8_t rxDMARequest;
DMA_Stream_TypeDef *txDMAStream;
DMA_Stream_TypeDef *rxDMAStream;
#elif defined(STM32F1) || defined(STM32F3)
DMA_Channel_TypeDef *txDMAChannel;
DMA_Channel_TypeDef *rxDMAChannel;
#endif
#endif // USE_DMA
uartPinDef_t rxPins[UARTHARDWARE_MAX_PINS];
uartPinDef_t txPins[UARTHARDWARE_MAX_PINS];
#if defined(STM32F7)
#if defined(STM32F7) || defined(STM32H7)
uint32_t rcc_ahb1;
rccPeriphTag_t rcc_apb2;
rccPeriphTag_t rcc_apb1;
#else
rccPeriphTag_t rcc;
#endif
#if !defined(STM32F7)
uint8_t af;
#endif
#if defined(STM32F7)
#if defined(STM32F7) || defined(STM32H7)
uint8_t txIrq;
uint8_t rxIrq;
#else
uint8_t irqn;
#endif
uint8_t txPriority;
uint8_t rxPriority;
#ifdef STM32H7
volatile uint8_t *txBuffer;
volatile uint8_t *rxBuffer;
uint16_t txBufferSize;
uint16_t rxBufferSize;
#endif
} uartHardware_t;
extern const uartHardware_t uartHardware[];
@ -163,8 +193,14 @@ typedef struct uartDevice_s {
const uartHardware_t *hardware;
uartPinDef_t rx;
uartPinDef_t tx;
#ifdef STM32H7
// For H7, buffers with possible DMA access is placed in D2 SRAM.
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[];

View file

@ -0,0 +1,563 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
/*
* jflyper - Refactoring, cleanup and made pin-configurable
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#ifdef USE_UART
#include "drivers/system.h"
#include "drivers/dma.h"
#include "drivers/io.h"
#include "drivers/nvic.h"
#include "drivers/rcc.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
#ifndef UART1_TX_DMA_STREAM
#define UART1_TX_DMA_STREAM NULL
#endif
#ifndef UART1_RX_DMA_STREAM
#define UART1_RX_DMA_STREAM NULL
#endif
#ifndef UART2_TX_DMA_STREAM
#define UART2_TX_DMA_STREAM NULL
#endif
#ifndef UART2_RX_DMA_STREAM
#define UART2_RX_DMA_STREAM NULL
#endif
#ifndef UART3_TX_DMA_STREAM
#define UART3_TX_DMA_STREAM NULL
#endif
#ifndef UART3_RX_DMA_STREAM
#define UART3_RX_DMA_STREAM NULL
#endif
#ifndef UART4_TX_DMA_STREAM
#define UART4_TX_DMA_STREAM NULL
#endif
#ifndef UART4_RX_DMA_STREAM
#define UART4_RX_DMA_STREAM NULL
#endif
#ifndef UART5_TX_DMA_STREAM
#define UART5_TX_DMA_STREAM NULL
#endif
#ifndef UART5_RX_DMA_STREAM
#define UART5_RX_DMA_STREAM NULL
#endif
#ifndef UART6_TX_DMA_STREAM
#define UART6_TX_DMA_STREAM NULL
#endif
#ifndef UART6_RX_DMA_STREAM
#define UART6_RX_DMA_STREAM NULL
#endif
#ifndef UART7_TX_DMA_STREAM
#define UART7_TX_DMA_STREAM NULL
#endif
#ifndef UART7_RX_DMA_STREAM
#define UART7_RX_DMA_STREAM NULL
#endif
#ifndef UART8_TX_DMA_STREAM
#define UART8_TX_DMA_STREAM NULL
#endif
#ifndef UART8_RX_DMA_STREAM
#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,
.rxDMAStream = UART1_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_USART1_TX,
.txDMAStream = UART1_TX_DMA_STREAM,
#endif
.rxPins = {
{ DEFIO_TAG_E(PA10), GPIO_AF7_USART1 },
{ DEFIO_TAG_E(PB7), GPIO_AF4_USART1 },
{ DEFIO_TAG_E(PB15), GPIO_AF4_USART1 },
},
.txPins = {
{ DEFIO_TAG_E(PA9), GPIO_AF7_USART1 },
{ DEFIO_TAG_E(PB6), GPIO_AF4_USART1 },
{ DEFIO_TAG_E(PB14), GPIO_AF4_USART1 },
},
.rcc_apb2 = RCC_APB2(USART1),
.rxIrq = USART1_IRQn,
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART1,
.txBuffer = uart1TxBuffer,
.rxBuffer = uart1RxBuffer,
.txBufferSize = sizeof(uart1TxBuffer),
.rxBufferSize = sizeof(uart1RxBuffer),
},
#endif
#ifdef USE_UART2
{
.device = UARTDEV_2,
.reg = USART2,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_USART2_RX,
.rxDMAStream = UART2_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_USART2_TX,
.txDMAStream = UART2_TX_DMA_STREAM,
#endif
.rxPins = {
{ DEFIO_TAG_E(PA3), GPIO_AF7_USART2 },
{ DEFIO_TAG_E(PD6), GPIO_AF7_USART2 }
},
.txPins = {
{ DEFIO_TAG_E(PA2), GPIO_AF7_USART2 },
{ DEFIO_TAG_E(PD5), GPIO_AF7_USART2 }
},
.rcc_apb1 = RCC_APB1L(USART2),
.rxIrq = USART2_IRQn,
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART2,
.txBuffer = uart2TxBuffer,
.rxBuffer = uart2RxBuffer,
.txBufferSize = sizeof(uart2TxBuffer),
.rxBufferSize = sizeof(uart2RxBuffer),
},
#endif
#ifdef USE_UART3
{
.device = UARTDEV_3,
.reg = USART3,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_USART3_RX,
.rxDMAStream = UART3_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_USART3_TX,
.txDMAStream = UART3_TX_DMA_STREAM,
#endif
.rxPins = {
{ DEFIO_TAG_E(PB11), GPIO_AF7_USART3 },
{ DEFIO_TAG_E(PC11), GPIO_AF7_USART3 },
{ DEFIO_TAG_E(PD9), GPIO_AF7_USART3 }
},
.txPins = {
{ DEFIO_TAG_E(PB10), GPIO_AF7_USART3 },
{ DEFIO_TAG_E(PC10), GPIO_AF7_USART3 },
{ DEFIO_TAG_E(PD8), GPIO_AF7_USART3 }
},
.rcc_apb1 = RCC_APB1L(USART3),
.rxIrq = USART3_IRQn,
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART3,
.txBuffer = uart3TxBuffer,
.rxBuffer = uart3RxBuffer,
.txBufferSize = sizeof(uart3TxBuffer),
.rxBufferSize = sizeof(uart3RxBuffer),
},
#endif
#ifdef USE_UART4
{
.device = UARTDEV_4,
.reg = UART4,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_UART4_RX,
.rxDMAStream = UART4_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_UART4_TX,
.txDMAStream = UART4_TX_DMA_STREAM,
#endif
.rxPins = {
{ DEFIO_TAG_E(PA1), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PA11), GPIO_AF6_UART4 },
{ DEFIO_TAG_E(PB8), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PC11), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PD0), GPIO_AF8_UART4 }
},
.txPins = {
{ DEFIO_TAG_E(PA0), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PA12), GPIO_AF6_UART4 },
{ DEFIO_TAG_E(PB9), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PC10), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PD1), GPIO_AF8_UART4 }
},
.rcc_apb1 = RCC_APB1L(UART4),
.rxIrq = UART4_IRQn,
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART4,
.txBuffer = uart4TxBuffer,
.rxBuffer = uart4RxBuffer,
.txBufferSize = sizeof(uart4TxBuffer),
.rxBufferSize = sizeof(uart4RxBuffer),
},
#endif
#ifdef USE_UART5
{
.device = UARTDEV_5,
.reg = UART5,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_UART5_RX,
.rxDMAStream = UART5_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_UART5_TX,
.txDMAStream = UART5_TX_DMA_STREAM,
#endif
.rxPins = {
{ DEFIO_TAG_E(PB5), GPIO_AF14_UART5 },
{ DEFIO_TAG_E(PB12), GPIO_AF14_UART5 },
{ DEFIO_TAG_E(PD2), GPIO_AF8_UART5 },
},
.txPins = {
{ DEFIO_TAG_E(PB6), GPIO_AF14_UART5 },
{ DEFIO_TAG_E(PB13), GPIO_AF14_UART5 },
{ DEFIO_TAG_E(PC12), GPIO_AF8_UART5 },
},
.rcc_apb1 = RCC_APB1L(UART5),
.rxIrq = UART5_IRQn,
.txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART5,
.txBuffer = uart5TxBuffer,
.rxBuffer = uart5RxBuffer,
.txBufferSize = sizeof(uart5TxBuffer),
.rxBufferSize = sizeof(uart5RxBuffer),
},
#endif
#ifdef USE_UART6
{
.device = UARTDEV_6,
.reg = USART6,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_USART6_RX,
.rxDMAStream = UART6_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_USART6_TX,
.txDMAStream = UART6_TX_DMA_STREAM,
#endif
.rxPins = {
{ DEFIO_TAG_E(PC7), GPIO_AF7_USART6 },
{ DEFIO_TAG_E(PG9), GPIO_AF7_USART6 }
},
.txPins = {
{ DEFIO_TAG_E(PC6), GPIO_AF7_USART6 },
{ DEFIO_TAG_E(PG14), GPIO_AF7_USART6 }
},
.rcc_apb2 = RCC_APB2(USART6),
.rxIrq = USART6_IRQn,
.txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART6,
.txBuffer = uart6TxBuffer,
.rxBuffer = uart6RxBuffer,
.txBufferSize = sizeof(uart6TxBuffer),
.rxBufferSize = sizeof(uart6RxBuffer),
},
#endif
#ifdef USE_UART7
{
.device = UARTDEV_7,
.reg = UART7,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_UART7_RX,
.rxDMAStream = UART7_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_UART7_TX,
.txDMAStream = UART7_TX_DMA_STREAM,
#endif
.rxPins = {
{ DEFIO_TAG_E(PA8), GPIO_AF11_UART7 },
{ DEFIO_TAG_E(PB3), GPIO_AF11_UART7 },
{ DEFIO_TAG_E(PE7), GPIO_AF7_UART7 },
{ DEFIO_TAG_E(PF6), GPIO_AF7_UART7 },
},
.txPins = {
{ DEFIO_TAG_E(PA15), GPIO_AF11_UART7 },
{ DEFIO_TAG_E(PB4), GPIO_AF11_UART7 },
{ DEFIO_TAG_E(PE8), GPIO_AF7_UART7 },
{ DEFIO_TAG_E(PF7), GPIO_AF7_UART7 },
},
.rcc_apb1 = RCC_APB1L(UART7),
.rxIrq = UART7_IRQn,
.txPriority = NVIC_PRIO_SERIALUART7_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART7,
.txBuffer = uart7TxBuffer,
.rxBuffer = uart7RxBuffer,
.txBufferSize = sizeof(uart7TxBuffer),
.rxBufferSize = sizeof(uart7RxBuffer),
},
#endif
#ifdef USE_UART8
{
.device = UARTDEV_8,
.reg = UART8,
#ifdef USE_DMA
.rxDMARequest = DMA_REQUEST_UART8_RX,
.rxDMAStream = UART8_RX_DMA_STREAM,
.txDMARequest = DMA_REQUEST_UART8_TX,
.txDMAStream = UART8_TX_DMA_STREAM,
#endif
.rxPins = {
{ DEFIO_TAG_E(PE0), GPIO_AF8_UART8 }
},
.txPins = {
{ DEFIO_TAG_E(PE1), GPIO_AF8_UART8 }
},
.rcc_apb1 = RCC_APB1L(UART8),
.rxIrq = UART8_IRQn,
.txPriority = NVIC_PRIO_SERIALUART8_TXDMA,
.rxPriority = NVIC_PRIO_SERIALUART8,
.txBuffer = uart8TxBuffer,
.rxBuffer = uart8RxBuffer,
.txBufferSize = sizeof(uart8TxBuffer),
.rxBufferSize = sizeof(uart8RxBuffer),
},
#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->txDMAStream &&
#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->txDMAStream) {
handleUsartTxDma(s);
}
#endif
}
}
#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)
{
uartDevice_t *uartdev = uartDevmap[device];
if (!uartdev) {
return NULL;
}
uartPort_t *s = &(uartdev->port);
s->port.vTable = uartVTable;
s->port.baudRate = baudRate;
const uartHardware_t *hardware = uartdev->hardware;
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->rxDMAStream) {
s->rxDMAStream = hardware->rxDMAStream;
#if defined(STM32H7)
s->rxDMARequest = hardware->rxDMARequest;
#else // F4 & F7
s->rxDMAChannel = hardware->DMAChannel;
#endif
}
if (hardware->txDMAStream) {
s->txDMAStream = hardware->txDMAStream;
#if defined(STM32H7)
s->txDMARequest = hardware->txDMARequest;
#else // F4 & F7
s->txDMAChannel = hardware->DMAChannel;
#endif
// DMA TX Interrupt
dmaIdentifier_e identifier = dmaGetIdentifier(hardware->txDMAStream);
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;
#endif
s->Handle.Instance = hardware->reg;
IO_t txIO = IOGetByTag(uartdev->tx.pin);
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
if ((options & SERIAL_BIDIR) && txIO) {
ioConfig_t ioCfg = IO_CONFIG(
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP)) ? GPIO_MODE_AF_PP : GPIO_MODE_AF_OD,
GPIO_SPEED_FREQ_HIGH,
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP)) ? GPIO_PULLDOWN : GPIO_PULLUP
);
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
IOConfigGPIOAF(txIO, ioCfg, uartdev->tx.af);
} else {
if ((mode & MODE_TX) && txIO) {
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
IOConfigGPIOAF(txIO, IOCFG_AF_PP, uartdev->tx.af);
}
if ((mode & MODE_RX) && rxIO) {
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
IOConfigGPIOAF(rxIO, IOCFG_AF_PP, uartdev->rx.af);
}
}
#ifdef USE_DMA
#if defined(STM32H7)
if (!s->rxDMAStream)
#else
if (!s->rxDMAChannel)
#endif
#endif
{
HAL_NVIC_SetPriority(hardware->rxIrq, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
HAL_NVIC_EnableIRQ(hardware->rxIrq);
}
return s;
}
#endif // USE_UART