mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-12 19:10:32 +03:00
Move STM (and clone) related UART implementation to platform (#14128)
This commit is contained in:
parent
51c09efe69
commit
4069fde56e
12 changed files with 201 additions and 238 deletions
|
@ -112,7 +112,6 @@ COMMON_SRC = \
|
|||
drivers/resource.c \
|
||||
drivers/serial.c \
|
||||
drivers/serial_impl.c \
|
||||
drivers/serial_uart_hw.c \
|
||||
drivers/sound_beeper.c \
|
||||
drivers/stack_check.c \
|
||||
drivers/timer_common.c \
|
||||
|
|
|
@ -50,19 +50,7 @@
|
|||
|
||||
#include "pg/serial_uart.h"
|
||||
|
||||
#if defined(STM32H7)
|
||||
#define UART_TX_BUFFER_ATTRIBUTE DMA_RAM // D2 SRAM
|
||||
#define UART_RX_BUFFER_ATTRIBUTE DMA_RAM // D2 SRAM
|
||||
#elif defined(STM32G4)
|
||||
#define UART_TX_BUFFER_ATTRIBUTE DMA_RAM_W // SRAM MPU NOT_BUFFERABLE
|
||||
#define UART_RX_BUFFER_ATTRIBUTE DMA_RAM_R // SRAM MPU NOT CACHABLE
|
||||
#elif defined(STM32F7)
|
||||
#define UART_TX_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT // DTCM RAM
|
||||
#define UART_RX_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT // DTCM RAM
|
||||
#elif defined(STM32F4) || defined(AT32F4) || defined(APM32F4)
|
||||
#define UART_TX_BUFFER_ATTRIBUTE // NONE
|
||||
#define UART_RX_BUFFER_ATTRIBUTE // NONE
|
||||
#else
|
||||
#if !defined(UART_TX_BUFFER_ATTRIBUTE) || !defined(UART_RX_BUFFER_ATTRIBUTE)
|
||||
#error Undefined UART_{TX,RX}_BUFFER_ATTRIBUTE for this MCU
|
||||
#endif
|
||||
|
||||
|
@ -377,13 +365,7 @@ static void uartWrite(serialPort_t *instance, uint8_t ch)
|
|||
} else
|
||||
#endif
|
||||
{
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
__HAL_UART_ENABLE_IT(&uartPort->Handle, UART_IT_TXE);
|
||||
#elif defined(USE_ATBSP_DRIVER)
|
||||
usart_interrupt_enable(uartPort->USARTx, USART_TDBE_INT, TRUE);
|
||||
#else
|
||||
USART_ITConfig(uartPort->USARTx, USART_IT_TXE, ENABLE);
|
||||
#endif
|
||||
uartEnableTxInterrupt(uartPort);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -442,13 +424,7 @@ static void uartEndWrite(serialPort_t *instance)
|
|||
} else
|
||||
#endif
|
||||
{
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
__HAL_UART_ENABLE_IT(&uartPort->Handle, UART_IT_TXE);
|
||||
#elif defined(USE_ATBSP_DRIVER)
|
||||
usart_interrupt_enable(uartPort->USARTx, USART_TDBE_INT, TRUE);
|
||||
#else
|
||||
USART_ITConfig(uartPort->USARTx, USART_IT_TXE, ENABLE);
|
||||
#endif
|
||||
uartEnableTxInterrupt(uartPort);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -469,98 +445,6 @@ const struct serialPortVTable uartVTable[] = {
|
|||
}
|
||||
};
|
||||
|
||||
// TODO - move to serial_uart_hw.c
|
||||
#ifdef USE_DMA
|
||||
void uartConfigureDma(uartDevice_t *uartdev)
|
||||
{
|
||||
uartPort_t *uartPort = &(uartdev->port);
|
||||
const uartHardware_t *hardware = uartdev->hardware;
|
||||
|
||||
#ifdef USE_DMA_SPEC
|
||||
const serialPortIdentifier_e uartPortIdentifier = hardware->identifier;
|
||||
const uartDeviceIdx_e uartDeviceIdx = uartDeviceIdxFromIdentifier(uartPortIdentifier);
|
||||
if (uartDeviceIdx == UARTDEV_INVALID) {
|
||||
return;
|
||||
}
|
||||
const int resourceIdx = serialResourceIndex(uartPortIdentifier);
|
||||
const int ownerIndex = serialOwnerIndex(uartPortIdentifier);
|
||||
const resourceOwner_e ownerTxRx = serialOwnerTxRx(uartPortIdentifier); // rx is always +1
|
||||
|
||||
const dmaChannelSpec_t *dmaChannelSpec;
|
||||
const serialUartConfig_t *cfg = serialUartConfig(resourceIdx);
|
||||
if (!cfg) {
|
||||
return;
|
||||
}
|
||||
if (cfg->txDmaopt != DMA_OPT_UNUSED) {
|
||||
dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_TX, uartDeviceIdx, cfg->txDmaopt);
|
||||
if (dmaChannelSpec) {
|
||||
uartPort->txDMAResource = dmaChannelSpec->ref;
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
|
||||
uartPort->txDMAChannel = dmaChannelSpec->channel;
|
||||
#elif defined(AT32F4)
|
||||
uartPort->txDMAMuxId = dmaChannelSpec->dmaMuxId;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
if (cfg->rxDmaopt != DMA_OPT_UNUSED) {
|
||||
dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_RX, uartDeviceIdx, cfg->txDmaopt);
|
||||
if (dmaChannelSpec) {
|
||||
uartPort->rxDMAResource = dmaChannelSpec->ref;
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
|
||||
uartPort->rxDMAChannel = dmaChannelSpec->channel;
|
||||
#elif defined(AT32F4)
|
||||
uartPort->rxDMAMuxId = dmaChannelSpec->dmaMuxId;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#else /* USE_DMA_SPEC */
|
||||
// Non USE_DMA_SPEC does not support configurable ON/OFF of UART DMA
|
||||
|
||||
if (hardware->rxDMAResource) {
|
||||
uartPort->rxDMAResource = hardware->rxDMAResource;
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
|
||||
uartPort->rxDMAChannel = hardware->rxDMAChannel;
|
||||
#elif defined(AT32F4)
|
||||
uartPort->rxDMAMuxId = hardware->rxDMAMuxId;
|
||||
#endif
|
||||
}
|
||||
|
||||
if (hardware->txDMAResource) {
|
||||
uartPort->txDMAResource = hardware->txDMAResource;
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
|
||||
uartPort->txDMAChannel = hardware->txDMAChannel;
|
||||
#elif defined(AT32F4)
|
||||
uartPort->txDMAMuxId = hardware->txDMAMuxId;
|
||||
#endif
|
||||
}
|
||||
#endif /* USE_DMA_SPEC */
|
||||
|
||||
if (uartPort->txDMAResource) {
|
||||
const dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->txDMAResource);
|
||||
if (dmaAllocate(identifier, ownerTxRx, ownerIndex)) {
|
||||
dmaEnable(identifier);
|
||||
#if defined(AT32F4)
|
||||
dmaMuxEnable(identifier, uartPort->txDMAMuxId);
|
||||
#endif
|
||||
dmaSetHandler(identifier, uartDmaIrqHandler, hardware->txPriority, (uint32_t)uartdev);
|
||||
uartPort->txDMAPeripheralBaseAddr = (uint32_t)&UART_REG_TXD(hardware->reg);
|
||||
}
|
||||
}
|
||||
|
||||
if (uartPort->rxDMAResource) {
|
||||
const dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->rxDMAResource);
|
||||
if (dmaAllocate(identifier, ownerTxRx + 1, ownerIndex)) {
|
||||
dmaEnable(identifier);
|
||||
#if defined(AT32F4)
|
||||
dmaMuxEnable(identifier, uartPort->rxDMAMuxId);
|
||||
#endif
|
||||
uartPort->rxDMAPeripheralBaseAddr = (uint32_t)&UART_REG_RXD(hardware->reg);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#define UART_IRQHandler(type, number, dev) \
|
||||
FAST_IRQ_HANDLER void type ## number ## _IRQHandler(void) \
|
||||
{ \
|
||||
|
|
|
@ -31,20 +31,8 @@
|
|||
// Various serial routines return the buffer occupied size as uint8_t which would need to be extended in order to
|
||||
// increase size further.
|
||||
|
||||
// define some common UART features
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F43x)
|
||||
#define UART_TRAIT_AF_PIN 1 // pin AF mode is configured for each pin individually
|
||||
#else
|
||||
#define UART_TRAIT_AF_PORT 1 // all pins on given uart use same AF
|
||||
#endif
|
||||
#include "platform.h"
|
||||
|
||||
#if !defined(STM32F4) || !defined(APM32F4) // all others support pinswap
|
||||
#define UART_TRAIT_PINSWAP 1
|
||||
#endif
|
||||
|
||||
#if defined(STM32F4)
|
||||
|
||||
#define UARTHARDWARE_MAX_PINS 4
|
||||
#ifndef UART_RX_BUFFER_SIZE
|
||||
#define UART_RX_BUFFER_SIZE 256
|
||||
#endif
|
||||
|
@ -56,77 +44,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#elif defined(STM32F7)
|
||||
|
||||
#define UARTHARDWARE_MAX_PINS 4
|
||||
#ifndef UART_RX_BUFFER_SIZE
|
||||
#define UART_RX_BUFFER_SIZE 256
|
||||
#endif
|
||||
#ifndef UART_TX_BUFFER_SIZE
|
||||
#ifdef USE_MSP_DISPLAYPORT
|
||||
#define UART_TX_BUFFER_SIZE 1280
|
||||
#else
|
||||
#define UART_TX_BUFFER_SIZE 256
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#elif defined(STM32H7)
|
||||
|
||||
#define UARTHARDWARE_MAX_PINS 5
|
||||
#ifndef UART_RX_BUFFER_SIZE
|
||||
#define UART_RX_BUFFER_SIZE 256
|
||||
#endif
|
||||
#ifndef UART_TX_BUFFER_SIZE
|
||||
#ifdef USE_MSP_DISPLAYPORT
|
||||
#define UART_TX_BUFFER_SIZE 1280
|
||||
#else
|
||||
#define UART_TX_BUFFER_SIZE 256
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#elif defined(STM32G4)
|
||||
|
||||
#define UARTHARDWARE_MAX_PINS 3
|
||||
#ifndef UART_RX_BUFFER_SIZE
|
||||
#define UART_RX_BUFFER_SIZE 256
|
||||
#endif
|
||||
#ifndef UART_TX_BUFFER_SIZE
|
||||
#ifdef USE_MSP_DISPLAYPORT
|
||||
#define UART_TX_BUFFER_SIZE 1280
|
||||
#else
|
||||
#define UART_TX_BUFFER_SIZE 256
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#elif defined(AT32F4)
|
||||
|
||||
#define UARTHARDWARE_MAX_PINS 5
|
||||
#ifndef UART_RX_BUFFER_SIZE
|
||||
#define UART_RX_BUFFER_SIZE 256
|
||||
#endif
|
||||
#ifndef UART_TX_BUFFER_SIZE
|
||||
#ifdef USE_MSP_DISPLAYPORT
|
||||
#define UART_TX_BUFFER_SIZE 1280
|
||||
#else
|
||||
#define UART_TX_BUFFER_SIZE 256
|
||||
#endif
|
||||
#endif
|
||||
#elif defined(APM32F4)
|
||||
|
||||
#define UARTHARDWARE_MAX_PINS 4
|
||||
#ifndef UART_RX_BUFFER_SIZE
|
||||
#define UART_RX_BUFFER_SIZE 256
|
||||
#endif
|
||||
#ifndef UART_TX_BUFFER_SIZE
|
||||
#ifdef USE_MSP_DISPLAYPORT
|
||||
#define UART_TX_BUFFER_SIZE 1280
|
||||
#else
|
||||
#define UART_TX_BUFFER_SIZE 256
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#else
|
||||
#error unknown MCU family
|
||||
#if !UART_TRAIT_AF_PIN && !UART_TRAIT_AF_PORT
|
||||
#error "Must specify either AF mode for MCU"
|
||||
#endif
|
||||
|
||||
// compressed index of UART/LPUART. Direct index into uartDevice[]
|
||||
|
@ -188,10 +107,10 @@ typedef struct uartHardware_s {
|
|||
// For H7 and G4 , {tx|rx}DMAChannel are DMAMUX input index for peripherals (DMA_REQUEST_xxx); H7:RM0433 Table 110, G4:RM0440 Table 80.
|
||||
// For F4 and F7, these are 32-bit channel identifiers (DMA_CHANNEL_x)
|
||||
// For at32f435/7 DmaChannel is the dmamux, need to call dmamuxenable using dmamuxid
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(APM32F4)
|
||||
#if DMA_TRAIT_CHANNEL
|
||||
uint32_t txDMAChannel;
|
||||
uint32_t rxDMAChannel;
|
||||
#elif defined(AT32F4)
|
||||
#elif DMA_TRAIT_MUX
|
||||
uint32_t txDMAMuxId;//for dmaspec->dmamux and using dmaMuxEnable(dmax,muxid)
|
||||
uint32_t rxDMAMuxId;
|
||||
#endif
|
||||
|
@ -257,6 +176,7 @@ uartPort_t *serialUART(uartDevice_t *uart, uint32_t baudRate, portMode_e mode, p
|
|||
void uartConfigureExternalPinInversion(uartPort_t *uartPort);
|
||||
|
||||
void uartIrqHandler(uartPort_t *s);
|
||||
void uartEnableTxInterrupt(uartPort_t *uartPort);
|
||||
|
||||
void uartReconfigure(uartPort_t *uartPort);
|
||||
|
||||
|
@ -267,20 +187,6 @@ void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor);
|
|||
bool checkUsartTxOutput(uartPort_t *s);
|
||||
void uartTxMonitor(uartPort_t *s);
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#define UART_REG_RXD(base) ((base)->RDR)
|
||||
#define UART_REG_TXD(base) ((base)->TDR)
|
||||
#elif defined(STM32F4)
|
||||
#define UART_REG_RXD(base) ((base)->DR)
|
||||
#define UART_REG_TXD(base) ((base)->DR)
|
||||
#elif defined(AT32F43x)
|
||||
#define UART_REG_RXD(base) ((base)->dt)
|
||||
#define UART_REG_TXD(base) ((base)->dt)
|
||||
#elif defined(APM32F4)
|
||||
#define UART_REG_RXD(base) ((base)->DATA)
|
||||
#define UART_REG_TXD(base) ((base)->DATA)
|
||||
#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) \
|
||||
|
|
|
@ -22,19 +22,6 @@
|
|||
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#if defined(STM32F7)
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "usbd_cdc.h"
|
||||
|
||||
extern USBD_HandleTypeDef USBD_Device;
|
||||
|
||||
#elif defined(STM32H7) || defined(STM32G4)
|
||||
#include "usbd_cdc.h"
|
||||
|
||||
extern USBD_HandleTypeDef USBD_Device;
|
||||
#endif
|
||||
|
||||
typedef struct {
|
||||
serialPort_t port;
|
||||
|
||||
|
|
|
@ -180,6 +180,7 @@ MCU_COMMON_SRC = \
|
|||
drivers/bus_spi_config.c \
|
||||
common/stm32/bus_spi_hw.c \
|
||||
common/stm32/bus_spi_pinconfig.c \
|
||||
common/stm32/serial_uart_hw.c \
|
||||
drivers/serial_escserial.c \
|
||||
drivers/serial_pinconfig.c \
|
||||
drivers/serial_uart_pinconfig.c \
|
||||
|
@ -205,6 +206,7 @@ MSC_SRC = \
|
|||
msc/usbd_storage_sdio.c
|
||||
|
||||
SPEED_OPTIMISED_SRC += \
|
||||
common/stm32/bus_spi_hw.c \
|
||||
common/stm32/system.c
|
||||
|
||||
SIZE_OPTIMISED_SRC += \
|
||||
|
|
|
@ -187,6 +187,18 @@
|
|||
|
||||
#define USE_TX_IRQ_HANDLER
|
||||
|
||||
#define UART_TX_BUFFER_ATTRIBUTE /* NONE */
|
||||
#define UART_RX_BUFFER_ATTRIBUTE /* NONE */
|
||||
|
||||
#define UART_TRAIT_AF_PORT 1
|
||||
|
||||
#define UARTHARDWARE_MAX_PINS 4
|
||||
|
||||
#define UART_REG_RXD(base) ((base)->DATA)
|
||||
#define UART_REG_TXD(base) ((base)->DATA)
|
||||
|
||||
#define DMA_TRAIT_CHANNEL 1
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(APM32F4)
|
||||
|
|
|
@ -122,6 +122,7 @@ MCU_COMMON_SRC = \
|
|||
drivers/bus_spi_config.c \
|
||||
common/stm32/bus_spi_pinconfig.c \
|
||||
common/stm32/bus_spi_hw.c \
|
||||
common/stm32/serial_uart_hw.c \
|
||||
drivers/serial_escserial.c \
|
||||
drivers/serial_pinconfig.c \
|
||||
drivers/serial_uart_pinconfig.c \
|
||||
|
|
|
@ -134,12 +134,25 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
|||
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_MODE_OUTPUT, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE)
|
||||
#define SPI_IO_CS_HIGH_CFG IO_CONFIG(GPIO_MODE_INPUT, GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_UP)
|
||||
|
||||
#define SPIDEV_COUNT 4
|
||||
#define SPIDEV_COUNT 4
|
||||
|
||||
#define CHECK_SPI_RX_DATA_AVAILABLE(instance) LL_SPI_IsActiveFlag_RXNE(instance)
|
||||
#define SPI_RX_DATA_REGISTER(base) ((base)->DR)
|
||||
|
||||
#define MAX_SPI_PIN_SEL 4
|
||||
#define MAX_SPI_PIN_SEL 4
|
||||
|
||||
#define UART_TX_BUFFER_ATTRIBUTE // NONE
|
||||
#define UART_RX_BUFFER_ATTRIBUTE // NONE
|
||||
|
||||
#define UART_TRAIT_AF_PIN 1
|
||||
#define UART_TRAIT_PINSWAP 1
|
||||
|
||||
#define UARTHARDWARE_MAX_PINS 5
|
||||
|
||||
#define UART_REG_RXD(base) ((base)->dt)
|
||||
#define UART_REG_TXD(base) ((base)->dt)
|
||||
|
||||
#define DMA_TRAIT_MUX 1
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -6,7 +6,8 @@ MCU_COMMON_SRC += \
|
|||
common/stm32/config_flash.c \
|
||||
common/stm32/bus_spi_pinconfig.c \
|
||||
common/stm32/bus_spi_hw.c \
|
||||
common/stm32/io_impl.c
|
||||
common/stm32/io_impl.c \
|
||||
common/stm32/serial_uart_hw.c
|
||||
|
||||
SIZE_OPTIMISED_SRC += \
|
||||
common/stm32/config_flash.c \
|
||||
|
|
|
@ -360,6 +360,57 @@ extern uint8_t _dmaram_end__;
|
|||
#error Unknown MCU family
|
||||
#endif
|
||||
|
||||
#if !defined(STM32G4) && !defined(STM32H7)
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
#define USE_TX_IRQ_HANDLER
|
||||
#endif
|
||||
|
||||
#if defined(STM32H7)
|
||||
#define UART_TX_BUFFER_ATTRIBUTE DMA_RAM /* D2 SRAM */
|
||||
#define UART_RX_BUFFER_ATTRIBUTE DMA_RAM /* D2 SRAM */
|
||||
#elif defined(STM32G4)
|
||||
#define UART_TX_BUFFER_ATTRIBUTE DMA_RAM_W /* SRAM MPU NOT_BUFFERABLE */
|
||||
#define UART_RX_BUFFER_ATTRIBUTE DMA_RAM_R /* SRAM MPU NOT CACHABLE */
|
||||
#elif defined(STM32F7)
|
||||
#define UART_TX_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT /* DTCM RAM */
|
||||
#define UART_RX_BUFFER_ATTRIBUTE FAST_DATA_ZERO_INIT /* DTCM RAM */
|
||||
#elif defined(STM32F4)
|
||||
#define UART_TX_BUFFER_ATTRIBUTE /* EMPTY */
|
||||
#define UART_RX_BUFFER_ATTRIBUTE /* EMPTY */
|
||||
#endif
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
// pin AF mode is configured for each pin individually
|
||||
#define UART_TRAIT_AF_PIN 1
|
||||
#elif defined(STM32F4)
|
||||
// all pins on given uart use same AF
|
||||
#define UART_TRAIT_AF_PORT 1
|
||||
#else
|
||||
#error Unknown STM MCU when defining UART_TRAIT_x
|
||||
#endif
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#define UART_TRAIT_PINSWAP 1
|
||||
#endif
|
||||
|
||||
#if defined(STM32F4)
|
||||
#define UARTHARDWARE_MAX_PINS 4
|
||||
#elif defined(STM32F7)
|
||||
#define UARTHARDWARE_MAX_PINS 4
|
||||
#elif defined(STM32H7)
|
||||
#define UARTHARDWARE_MAX_PINS 5
|
||||
#elif defined(STM32G4)
|
||||
#define UARTHARDWARE_MAX_PINS 3
|
||||
#endif
|
||||
|
||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#define UART_REG_RXD(base) ((base)->RDR)
|
||||
#define UART_REG_TXD(base) ((base)->TDR)
|
||||
#elif defined(STM32F4)
|
||||
#define UART_REG_RXD(base) ((base)->DR)
|
||||
#define UART_REG_TXD(base) ((base)->DR)
|
||||
#endif
|
||||
|
||||
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#define DMA_TRAIT_CHANNEL 1
|
||||
#endif
|
||||
|
|
|
@ -83,6 +83,7 @@ typedef struct __attribute__ ((packed))
|
|||
} LINE_CODING;
|
||||
|
||||
extern USBD_CDC_ItfTypeDef USBD_CDC_fops;
|
||||
extern USBD_HandleTypeDef USBD_Device;
|
||||
|
||||
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength);
|
||||
uint32_t CDC_Send_FreeBytes(void);
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_UART) && !defined(SIMULATOR_BUILD)
|
||||
#if defined(USE_UART)
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
@ -39,6 +39,10 @@
|
|||
#include "drivers/serial_impl.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
#include "drivers/serial_uart_impl.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
|
||||
#include "pg/serial_uart.h"
|
||||
|
||||
// TODO: split this function into mcu-specific UART files ?
|
||||
static void enableRxIrq(const uartHardware_t *hardware)
|
||||
|
@ -207,4 +211,106 @@ void uartConfigureExternalPinInversion(uartPort_t *uartPort)
|
|||
#endif
|
||||
}
|
||||
|
||||
#ifdef USE_DMA
|
||||
void uartConfigureDma(uartDevice_t *uartdev)
|
||||
{
|
||||
uartPort_t *uartPort = &(uartdev->port);
|
||||
const uartHardware_t *hardware = uartdev->hardware;
|
||||
|
||||
#ifdef USE_DMA_SPEC
|
||||
const serialPortIdentifier_e uartPortIdentifier = hardware->identifier;
|
||||
const uartDeviceIdx_e uartDeviceIdx = uartDeviceIdxFromIdentifier(uartPortIdentifier);
|
||||
if (uartDeviceIdx == UARTDEV_INVALID) {
|
||||
return;
|
||||
}
|
||||
const int resourceIdx = serialResourceIndex(uartPortIdentifier);
|
||||
const int ownerIndex = serialOwnerIndex(uartPortIdentifier);
|
||||
const resourceOwner_e ownerTxRx = serialOwnerTxRx(uartPortIdentifier); // rx is always +1
|
||||
|
||||
const dmaChannelSpec_t *dmaChannelSpec;
|
||||
const serialUartConfig_t *cfg = serialUartConfig(resourceIdx);
|
||||
if (!cfg) {
|
||||
return;
|
||||
}
|
||||
if (cfg->txDmaopt != DMA_OPT_UNUSED) {
|
||||
dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_TX, uartDeviceIdx, cfg->txDmaopt);
|
||||
if (dmaChannelSpec) {
|
||||
uartPort->txDMAResource = dmaChannelSpec->ref;
|
||||
#if DMA_TRAIT_CHANNEL
|
||||
uartPort->txDMAChannel = dmaChannelSpec->channel;
|
||||
#elif DMA_TRAIT_MUX
|
||||
uartPort->txDMAMuxId = dmaChannelSpec->dmaMuxId;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
if (cfg->rxDmaopt != DMA_OPT_UNUSED) {
|
||||
dmaChannelSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_UART_RX, uartDeviceIdx, cfg->txDmaopt);
|
||||
if (dmaChannelSpec) {
|
||||
uartPort->rxDMAResource = dmaChannelSpec->ref;
|
||||
#if DMA_TRAIT_CHANNEL
|
||||
uartPort->rxDMAChannel = dmaChannelSpec->channel;
|
||||
#elif DMA_TRAIT_MUX
|
||||
uartPort->rxDMAMuxId = dmaChannelSpec->dmaMuxId;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#else /* USE_DMA_SPEC */
|
||||
// Non USE_DMA_SPEC does not support configurable ON/OFF of UART DMA
|
||||
|
||||
if (hardware->rxDMAResource) {
|
||||
uartPort->rxDMAResource = hardware->rxDMAResource;
|
||||
#if DMA_TRAIT_CHANNEL
|
||||
uartPort->rxDMAChannel = hardware->rxDMAChannel;
|
||||
#elif DMA_TRAIT_MUX
|
||||
uartPort->rxDMAMuxId = hardware->rxDMAMuxId;
|
||||
#endif
|
||||
}
|
||||
|
||||
if (hardware->txDMAResource) {
|
||||
uartPort->txDMAResource = hardware->txDMAResource;
|
||||
#if DMA_TRAIT_CHANNEL
|
||||
uartPort->txDMAChannel = hardware->txDMAChannel;
|
||||
#elif DMA_TRAIT_MUX
|
||||
uartPort->txDMAMuxId = hardware->txDMAMuxId;
|
||||
#endif
|
||||
}
|
||||
#endif /* USE_DMA_SPEC */
|
||||
|
||||
if (uartPort->txDMAResource) {
|
||||
const dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->txDMAResource);
|
||||
if (dmaAllocate(identifier, ownerTxRx, ownerIndex)) {
|
||||
dmaEnable(identifier);
|
||||
#if DMA_TRAIT_MUX
|
||||
dmaMuxEnable(identifier, uartPort->txDMAMuxId);
|
||||
#endif
|
||||
dmaSetHandler(identifier, uartDmaIrqHandler, hardware->txPriority, (uint32_t)uartdev);
|
||||
uartPort->txDMAPeripheralBaseAddr = (uint32_t)&UART_REG_TXD(hardware->reg);
|
||||
}
|
||||
}
|
||||
|
||||
if (uartPort->rxDMAResource) {
|
||||
const dmaIdentifier_e identifier = dmaGetIdentifier(uartPort->rxDMAResource);
|
||||
if (dmaAllocate(identifier, ownerTxRx + 1, ownerIndex)) {
|
||||
dmaEnable(identifier);
|
||||
#if DMA_TRAIT_MUX
|
||||
dmaMuxEnable(identifier, uartPort->rxDMAMuxId);
|
||||
#endif
|
||||
uartPort->rxDMAPeripheralBaseAddr = (uint32_t)&UART_REG_RXD(hardware->reg);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void uartEnableTxInterrupt(uartPort_t *uartPort)
|
||||
{
|
||||
#if defined(USE_HAL_DRIVER)
|
||||
__HAL_UART_ENABLE_IT(&uartPort->Handle, UART_IT_TXE);
|
||||
#elif defined(USE_ATBSP_DRIVER)
|
||||
usart_interrupt_enable(uartPort->USARTx, USART_TDBE_INT, TRUE);
|
||||
#else
|
||||
USART_ITConfig(uartPort->USARTx, USART_IT_TXE, ENABLE);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif /* USE_UART */
|
Loading…
Add table
Add a link
Reference in a new issue