Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Refactor uart #13585

Open
wants to merge 21 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
21 commits
Select commit Hold shift + click to select a range
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
1 change: 1 addition & 0 deletions mk/source.mk
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ COMMON_SRC = \
drivers/serial_pinconfig.c \
drivers/serial_uart.c \
drivers/serial_uart_pinconfig.c \
drivers/serial_uart_hw.c \
drivers/sound_beeper.c \
drivers/stack_check.c \
drivers/system.c \
Expand Down
39 changes: 25 additions & 14 deletions src/main/cli/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -1266,7 +1266,7 @@ static void printSerial(dumpFlags_t dumpMask, const serialConfig_t *serialConfig
{
const char *format = "serial %d %d %ld %ld %ld %ld";
headingStr = cliPrintSectionHeading(dumpMask, false, headingStr);
for (uint32_t i = 0; i < SERIAL_PORT_COUNT; i++) {
for (unsigned i = 0; i < ARRAYLEN(serialConfig->portConfigs); i++) {
if (!serialIsPortAvailable(serialConfig->portConfigs[i].identifier)) {
continue;
};
Expand Down Expand Up @@ -5029,20 +5029,21 @@ const cliResourceValue_t resourceTable[] = {
#if defined(USE_LED_STRIP)
DEFS( OWNER_LED_STRIP, PG_LED_STRIP_CONFIG, ledStripConfig_t, ioTag ),
#endif
#ifdef USE_UART
DEFA( OWNER_SERIAL_TX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagTx[0], SERIAL_UART_COUNT ),
DEFA( OWNER_SERIAL_RX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagRx[0], SERIAL_UART_COUNT ),
#if defined(USE_UART)
DEFA( OWNER_SERIAL_TX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagTx[RESOURCE_UART_OFFSET], RESOURCE_UART_COUNT),
DEFA( OWNER_SERIAL_RX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagRx[RESOURCE_UART_OFFSET], RESOURCE_UART_COUNT),
#endif
#ifdef USE_INVERTER
DEFA( OWNER_INVERTER, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagInverter[0], SERIAL_PORT_MAX_INDEX ),
#if defined(USE_INVERTER)
DEFA( OWNER_INVERTER, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagInverter[RESOURCE_UART_OFFSET], RESOURCE_UART_COUNT),
// LPUART and SOFTSERIAL don't need external inversion
#endif
#if defined(USE_SOFTSERIAL)
DEFA( OWNER_SOFTSERIAL_TX, PG_SOFTSERIAL_PIN_CONFIG, softSerialPinConfig_t, ioTagTx[0], SOFTSERIAL_COUNT ),
DEFA( OWNER_SOFTSERIAL_RX, PG_SOFTSERIAL_PIN_CONFIG, softSerialPinConfig_t, ioTagRx[0], SOFTSERIAL_COUNT ),
DEFA( OWNER_SOFTSERIAL_TX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagTx[RESOURCE_SOFTSERIAL_OFFSET], RESOURCE_SOFTSERIAL_COUNT ),
DEFA( OWNER_SOFTSERIAL_RX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagRx[RESOURCE_SOFTSERIAL_OFFSET], RESOURCE_SOFTSERIAL_COUNT ),
#endif
#ifdef USE_LPUART1
DEFA( OWNER_LPUART_TX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagTx[SERIAL_UART_COUNT], SERIAL_LPUART_COUNT ),
DEFA( OWNER_LPUART_RX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagRx[SERIAL_UART_COUNT], SERIAL_LPUART_COUNT ),
#if defined(USE_LPUART)
ledvinap marked this conversation as resolved.
Show resolved Hide resolved
DEFA( OWNER_LPUART_TX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagTx[RESOURCE_LPUART_OFFSET], RESOURCE_LPUART_COUNT),
DEFA( OWNER_LPUART_RX, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagRx[RESOURCE_LPUART_OFFSET], RESOURCE_LPUART_COUNT),
#endif
#ifdef USE_I2C
DEFW( OWNER_I2C_SCL, PG_I2C_CONFIG, i2cConfig_t, ioTagScl, I2CDEV_COUNT ),
Expand Down Expand Up @@ -5306,6 +5307,7 @@ typedef struct dmaoptEntry_s {
// DEFS : Single entry
// DEFA : Array of uint8_t (stride = 1)
// DEFW : Wider stride case; array of structs.
// DEFW_OFS: array of structs, starting at offset ofs

#define DEFS(device, peripheral, pgn, type, member) \
{ device, peripheral, pgn, 0, offsetof(type, member), 0, MASK_IGNORED }
Expand All @@ -5314,7 +5316,10 @@ typedef struct dmaoptEntry_s {
{ device, peripheral, pgn, sizeof(uint8_t), offsetof(type, member), max, mask }

#define DEFW(device, peripheral, pgn, type, member, max, mask) \
{ device, peripheral, pgn, sizeof(type), offsetof(type, member), max, mask }
DEFW_OFS(device, peripheral, pgn, type, member, 0, max, mask)

#define DEFW_OFS(device, peripheral, pgn, type, member, ofs, max, mask) \
{ device, peripheral, pgn, sizeof(type), offsetof(type, member) + (ofs) * sizeof(type), max, mask }

dmaoptEntry_t dmaoptEntryTable[] = {
DEFW("SPI_SDO", DMA_PERIPH_SPI_SDO, PG_SPI_PIN_CONFIG, spiPinConfig_t, txDmaopt, SPIDEV_COUNT, MASK_IGNORED),
Expand All @@ -5324,8 +5329,14 @@ dmaoptEntry_t dmaoptEntryTable[] = {
DEFW("SPI_RX", DMA_PERIPH_SPI_SDI, PG_SPI_PIN_CONFIG, spiPinConfig_t, rxDmaopt, SPIDEV_COUNT, MASK_IGNORED),
DEFA("ADC", DMA_PERIPH_ADC, PG_ADC_CONFIG, adcConfig_t, dmaopt, ADCDEV_COUNT, MASK_IGNORED),
DEFS("SDIO", DMA_PERIPH_SDIO, PG_SDIO_CONFIG, sdioConfig_t, dmaopt),
DEFW("UART_TX", DMA_PERIPH_UART_TX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, txDmaopt, UARTDEV_CONFIG_MAX, MASK_IGNORED),
DEFW("UART_RX", DMA_PERIPH_UART_RX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, rxDmaopt, UARTDEV_CONFIG_MAX, MASK_IGNORED),
#ifdef USE_UART
DEFW_OFS("UART_TX", DMA_PERIPH_UART_TX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, txDmaopt, RESOURCE_UART_OFFSET, RESOURCE_UART_COUNT, MASK_IGNORED),
DEFW_OFS("UART_RX", DMA_PERIPH_UART_RX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, rxDmaopt, RESOURCE_UART_OFFSET, RESOURCE_UART_COUNT, MASK_IGNORED),
#endif
#ifdef USE_LPUART1
DEFW_OFS("LPUART_TX", DMA_PERIPH_UART_TX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, txDmaopt, RESOURCE_LPUART_OFFSET, RESOURCE_LPUART_COUNT, MASK_IGNORED),
DEFW_OFS("LPUART_RX", DMA_PERIPH_UART_RX, PG_SERIAL_UART_CONFIG, serialUartConfig_t, rxDmaopt, RESOURCE_LPUART_OFFSET, RESOURCE_LPUART_COUNT, MASK_IGNORED),
#endif
#if defined(STM32H7) || defined(STM32G4)
DEFW("TIMUP", DMA_PERIPH_TIMUP, PG_TIMER_UP_CONFIG, timerUpConfig_t, dmaopt, HARDWARE_TIMER_DEFINITION_COUNT, TIMUP_TIMERS),
#endif
Expand Down
2 changes: 1 addition & 1 deletion src/main/common/printf_serial.c
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@

#include "printf_serial.h"

#ifdef SERIAL_PORT_COUNT
#if SERIAL_PORT_COUNT > 0

static serialPort_t *printfSerialPort;

Expand Down
24 changes: 14 additions & 10 deletions src/main/config/config.c
Original file line number Diff line number Diff line change
Expand Up @@ -421,11 +421,16 @@ static void validateAndFixConfig(void)
if (systemConfig()->configurationState == CONFIGURATION_STATE_UNCONFIGURED) {
// enable some compiled-in features by default
uint32_t autoFeatures =
FEATURE_OSD | FEATURE_LED_STRIP
#if defined(SOFTSERIAL1_RX_PIN) || defined(SOFTSERIAL2_RX_PIN) || defined(SOFTSERIAL1_TX_PIN) || defined(SOFTSERIAL2_TX_PIN)
| FEATURE_SOFTSERIAL
FEATURE_OSD | FEATURE_LED_STRIP;
#if defined(USE_SOFTSERIAL)
// enable softserial if at least one pin is configured
for (unsigned i = RESOURCE_SOFTSERIAL_OFFSET; i < RESOURCE_SOFTSERIAL_OFFSET + RESOURCE_SOFTSERIAL_COUNT; i++) {
if (serialPinConfig()->ioTagTx[i] || serialPinConfig()->ioTagRx[i]) {
autoFeatures |= FEATURE_SOFTSERIAL;
break;
}
}
#endif
;
featureEnableImmediate(autoFeatures & featuresSupportedByBuild);
}

Expand Down Expand Up @@ -535,12 +540,11 @@ static void validateAndFixConfig(void)
// Find the first serial port on which MSP Displayport is enabled
displayPortMspSetSerial(SERIAL_PORT_NONE);

for (uint8_t serialPort = 0; serialPort < SERIAL_PORT_COUNT; serialPort++) {
const serialPortConfig_t *portConfig = &serialConfig()->portConfigs[serialPort];

if (portConfig &&
(portConfig->identifier != SERIAL_PORT_USB_VCP) &&
((portConfig->functionMask & (FUNCTION_VTX_MSP | FUNCTION_MSP)) == (FUNCTION_VTX_MSP | FUNCTION_MSP))) {
for (const serialPortConfig_t *portConfig = serialConfig()->portConfigs;
portConfig < ARRAYEND(serialConfig()->portConfigs);
portConfig++) {
if ((portConfig->identifier != SERIAL_PORT_USB_VCP)
&& ((portConfig->functionMask & (FUNCTION_VTX_MSP | FUNCTION_MSP)) == (FUNCTION_VTX_MSP | FUNCTION_MSP))) {
displayPortMspSetSerial(portConfig->identifier);
break;
}
Expand Down
15 changes: 13 additions & 2 deletions src/main/drivers/at32/dma_reqmap_mcu.c
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
#include "drivers/dma_reqmap.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"

#include "drivers/serial_uart_impl.h"
#include "pg/timerio.h"

typedef struct dmaPeripheralMapping_s {
Expand Down Expand Up @@ -97,17 +97,28 @@ static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
REQMAP(ADC, 3),
#endif

#ifdef USE_UART
// UARTDEV_x enum value exists only when coresponding UART is enabled
#ifdef USE_UART1
REQMAP_DIR(UART, 1, TX),
REQMAP_DIR(UART, 1, RX),
#endif
#ifdef USE_UART2
REQMAP_DIR(UART, 2, TX),
REQMAP_DIR(UART, 2, RX),
#endif
#ifdef USE_UART3
REQMAP_DIR(UART, 3, TX),
REQMAP_DIR(UART, 3, RX),
#endif
#ifdef USE_UART4
REQMAP_DIR(UART, 4, TX),
REQMAP_DIR(UART, 4, RX),
#endif
#ifdef USE_UART5
REQMAP_DIR(UART, 5, TX),
REQMAP_DIR(UART, 5, RX),
#endif
#ifdef USE_UART6
REQMAP_DIR(UART, 6, TX),
REQMAP_DIR(UART, 6, RX),
#endif
Expand Down
43 changes: 6 additions & 37 deletions src/main/drivers/at32/serial_uart_at32bsp.c
Original file line number Diff line number Diff line change
Expand Up @@ -48,40 +48,9 @@
#include "drivers/serial_uart.h"
#include "drivers/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
#endif
}

static uartDevice_t *uartFindDevice(uartPort_t *uartPort)
{
for (uint32_t i = 0; i < UARTDEV_COUNT_MAX; i++) {
uartDevice_t *candidate = uartDevmap[i];

if (&candidate->port == uartPort) {
return candidate;
}
}
return NULL;
}

static void uartConfigurePinSwap(uartPort_t *uartPort)
{
uartDevice_t *uartDevice = uartFindDevice(uartPort);
if (!uartDevice) {
return;
}

uartDevice_t *uartDevice = container_of(uartPort, uartDevice_t, port);
if (uartDevice->pinSwap) {
usart_transmit_receive_pin_swap(uartDevice->port.USARTx, TRUE);
}
Expand All @@ -107,15 +76,15 @@ void uartReconfigure(uartPort_t *uartPort)
if (uartPort->port.mode & MODE_RX) {
usart_receiver_enable(uartPort->USARTx, TRUE);
}

if (uartPort->port.mode & MODE_TX) {
usart_transmitter_enable(uartPort->USARTx, TRUE);
}

//config pin inverter
usartConfigurePinInversion(uartPort);
// config external pin inverter (no internal pin inversion available)
uartConfigureExternalPinInversion(uartPort);

//config pin swap
// config pin swap
uartConfigurePinSwap(uartPort);

if (uartPort->port.options & SERIAL_BIDIR) {
Expand Down Expand Up @@ -328,7 +297,7 @@ void uartIrqHandler(uartPort_t *s)
if (usart_flag_get(s->USARTx, USART_ROERR_FLAG) == SET) {
usart_flag_clear(s->USARTx, USART_ROERR_FLAG);
}

if (usart_flag_get(s->USARTx, USART_IDLEF_FLAG) == SET) {
if (s->port.idleCallback) {
s->port.idleCallback();
Expand Down
91 changes: 8 additions & 83 deletions src/main/drivers/at32/serial_uart_at32f43x.c
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#ifdef USE_UART1
{
.device = UARTDEV_1,
.identifier = SERIAL_PORT_USART1,
.reg = USART1,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_USART1_RX,
Expand Down Expand Up @@ -120,7 +120,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {

#ifdef USE_UART2
{
.device = UARTDEV_2,
.identifier = SERIAL_PORT_USART2,
.reg = USART2,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_USART2_RX,
Expand Down Expand Up @@ -151,7 +151,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {

#ifdef USE_UART3
{
.device = UARTDEV_3,
.identifier = SERIAL_PORT_USART3,
.reg = USART3,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_USART3_RX,
Expand Down Expand Up @@ -182,7 +182,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {

#ifdef USE_UART4
{
.device = UARTDEV_4,
.identifier = SERIAL_PORT_UART4,
.reg = UART4,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_UART4_RX,
Expand Down Expand Up @@ -213,7 +213,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {

#ifdef USE_UART5
{
.device = UARTDEV_5,
.identifier = SERIAL_PORT_UART5,
.reg = UART5,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_UART5_RX,
Expand Down Expand Up @@ -246,7 +246,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {

#ifdef USE_UART6
{
.device = UARTDEV_6,
.identifier = SERIAL_PORT_USART6,
.reg = USART6,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_USART6_RX,
Expand Down Expand Up @@ -279,7 +279,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {

#ifdef USE_UART7
{
.device = UARTDEV_7,
.identifier = SERIAL_PORT_UART7,
.reg = UART7,
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_UART7_RX,
Expand Down Expand Up @@ -313,7 +313,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {

#ifdef USE_UART8
{
.device = UARTDEV_8,
.identifier = SERIAL_PORT_UART8,
.reg = UART8, //USE UART8 FOR PIN CONFIG
#ifdef USE_DMA
.rxDMAMuxId = DMAMUX_DMAREQ_ID_UART8_RX,
Expand Down Expand Up @@ -348,79 +348,4 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {

};

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;

s->port.rxBuffer = hardware->rxBuffer;
s->port.txBuffer = hardware->txBuffer;
s->port.rxBufferSize = hardware->rxBufferSize;
s->port.txBufferSize = hardware->txBufferSize;

s->checkUsartTxOutput = checkUsartTxOutput;

#ifdef USE_DMA
uartConfigureDma(uartdev);
#endif

if (hardware->rcc) {
RCC_ClockCmd(hardware->rcc, ENABLE);
}

IO_t txIO = IOGetByTag(uartdev->tx.pin);
IO_t rxIO = IOGetByTag(uartdev->rx.pin);

uartdev->txPinState = TX_PIN_IGNORE;

if ((options & SERIAL_BIDIR) && txIO) {
//mode,speed,otype,pupd
ioConfig_t ioCfg = IO_CONFIG(
GPIO_MODE_MUX,
GPIO_DRIVE_STRENGTH_STRONGER,
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_OUTPUT_PUSH_PULL : GPIO_OUTPUT_OPEN_DRAIN,
(options & SERIAL_INVERTED) ? GPIO_PULL_DOWN : GPIO_PULL_UP
);
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));

if (((options & SERIAL_INVERTED) == SERIAL_NOT_INVERTED) && !(options & SERIAL_BIDIR_PP_PD)) {
uartdev->txPinState = TX_PIN_ACTIVE;
// Switch TX to an input with pullup so it's state can be monitored
uartTxMonitor(s);
} else {
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 (!s->rxDMAResource)
#endif
{
nvic_irq_enable(hardware->irqn,NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
}

return s;
}
#endif // USE_UART