mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 19:40:31 +03:00
G4 LPUART rework (#11821)
* Extracted SOTSERIAL_TX & RX resources * Fixed LPUART1 on G4
This commit is contained in:
parent
7b39d3d296
commit
b8855d3a71
14 changed files with 120 additions and 47 deletions
|
@ -5027,6 +5027,10 @@ const cliResourceValue_t resourceTable[] = {
|
|||
#ifdef USE_INVERTER
|
||||
DEFA( OWNER_INVERTER, PG_SERIAL_PIN_CONFIG, serialPinConfig_t, ioTagInverter[0], SERIAL_PORT_MAX_INDEX ),
|
||||
#endif
|
||||
#if defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)
|
||||
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 ),
|
||||
#endif
|
||||
#ifdef USE_I2C
|
||||
DEFW( OWNER_I2C_SCL, PG_I2C_CONFIG, i2cConfig_t, ioTagScl, I2CDEV_COUNT ),
|
||||
DEFW( OWNER_I2C_SDA, PG_I2C_CONFIG, i2cConfig_t, ioTagSda, I2CDEV_COUNT ),
|
||||
|
|
|
@ -111,4 +111,6 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
|||
"SWD",
|
||||
"RX_SPI_EXPRESSLRS_RESET",
|
||||
"RX_SPI_EXPRESSLRS_BUSY",
|
||||
"SOFTSERIAL_TX",
|
||||
"SOFTSERIAL_RX",
|
||||
};
|
||||
|
|
|
@ -109,6 +109,8 @@ typedef enum {
|
|||
OWNER_SWD,
|
||||
OWNER_RX_SPI_EXPRESSLRS_RESET,
|
||||
OWNER_RX_SPI_EXPRESSLRS_BUSY,
|
||||
OWNER_SOFTSERIAL_TX,
|
||||
OWNER_SOFTSERIAL_RX,
|
||||
OWNER_TOTAL_COUNT
|
||||
} resourceOwner_e;
|
||||
|
||||
|
@ -120,4 +122,5 @@ typedef struct resourceOwner_s {
|
|||
extern const char * const ownerNames[OWNER_TOTAL_COUNT];
|
||||
|
||||
#define RESOURCE_INDEX(x) (x + 1)
|
||||
// TODO(hertz@): only used by vtx_rtc6707_soft_spi and probably for display purposes
|
||||
#define RESOURCE_SOFT_OFFSET 10
|
||||
|
|
|
@ -23,6 +23,8 @@
|
|||
#include "drivers/io.h"
|
||||
#include "drivers/io_types.h"
|
||||
#include "drivers/resource.h"
|
||||
// TODO(hertz@): uncomment and use UARTDevice_e::MAX_UARTDEV
|
||||
// #include "drivers/serial_uart.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
|
||||
|
@ -88,14 +90,18 @@ typedef struct serialPort_s {
|
|||
uint8_t identifier;
|
||||
} serialPort_t;
|
||||
|
||||
// TODO(hertz@): adjust this to include all the UARTDevice_e elements + necessary SOFTSERIALS
|
||||
// # define SERIAL_PORT_MAX_INDEX MAX_UARTDEV
|
||||
# define SERIAL_PORT_MAX_INDEX 11
|
||||
#if defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)
|
||||
# ifdef USE_SOFTSERIAL2
|
||||
# define SERIAL_PORT_MAX_INDEX (RESOURCE_SOFT_OFFSET + 2)
|
||||
# define SOFTSERIAL_COUNT 2
|
||||
# else
|
||||
# define SERIAL_PORT_MAX_INDEX (RESOURCE_SOFT_OFFSET + 1)
|
||||
# define SOFTSERIAL_COUNT 1
|
||||
# endif
|
||||
#else
|
||||
# define SERIAL_PORT_MAX_INDEX RESOURCE_SOFT_OFFSET
|
||||
// avoid zero-sized arrays when no software serials are enabled
|
||||
# define SOFTSERIAL_COUNT 1
|
||||
#endif
|
||||
|
||||
typedef struct serialPinConfig_s {
|
||||
|
@ -106,6 +112,13 @@ typedef struct serialPinConfig_s {
|
|||
|
||||
PG_DECLARE(serialPinConfig_t, serialPinConfig);
|
||||
|
||||
typedef struct softDSserialPinConfig_s {
|
||||
ioTag_t ioTagTx[SOFTSERIAL_COUNT];
|
||||
ioTag_t ioTagRx[SOFTSERIAL_COUNT];
|
||||
} softSerialPinConfig_t;
|
||||
|
||||
PG_DECLARE(softSerialPinConfig_t, softSerialPinConfig);
|
||||
|
||||
struct serialPortVTable {
|
||||
void (*serialWrite)(serialPort_t *instance, uint8_t ch);
|
||||
|
||||
|
|
|
@ -228,12 +228,6 @@ static const serialDefaultPin_t serialDefaultPin[] = {
|
|||
#ifdef USE_LPUART1
|
||||
{ SERIAL_PORT_LPUART1, IO_TAG(LPUART1_RX_PIN), IO_TAG(LPUART1_TX_PIN), IO_TAG(INVERTER_PIN_LPUART1) },
|
||||
#endif
|
||||
#ifdef USE_SOFTSERIAL1
|
||||
{ SERIAL_PORT_SOFTSERIAL1, IO_TAG(SOFTSERIAL1_RX_PIN), IO_TAG(SOFTSERIAL1_TX_PIN), IO_TAG(NONE) },
|
||||
#endif
|
||||
#ifdef USE_SOFTSERIAL2
|
||||
{ SERIAL_PORT_SOFTSERIAL2, IO_TAG(SOFTSERIAL2_RX_PIN), IO_TAG(SOFTSERIAL2_TX_PIN), IO_TAG(NONE) },
|
||||
#endif
|
||||
};
|
||||
|
||||
PG_REGISTER_WITH_RESET_FN(serialPinConfig_t, serialPinConfig, PG_SERIAL_PIN_CONFIG, 0);
|
||||
|
@ -247,5 +241,33 @@ void pgResetFn_serialPinConfig(serialPinConfig_t *serialPinConfig)
|
|||
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->inverterIO;
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL1)
|
||||
typedef struct softSerialDefaultPin_s {
|
||||
serialPortIdentifier_e ident;
|
||||
ioTag_t rxIO, txIO;
|
||||
} softSerialDefaultPin_t;
|
||||
|
||||
static const softSerialDefaultPin_t softSerialDefaultPin[SOFTSERIAL_COUNT] = {
|
||||
#ifdef USE_SOFTSERIAL1
|
||||
{ SERIAL_PORT_SOFTSERIAL1, IO_TAG(SOFTSERIAL1_RX_PIN), IO_TAG(SOFTSERIAL1_TX_PIN) },
|
||||
#endif
|
||||
#ifdef USE_SOFTSERIAL2
|
||||
{ SERIAL_PORT_SOFTSERIAL2, IO_TAG(SOFTSERIAL2_RX_PIN), IO_TAG(SOFTSERIAL2_TX_PIN) },
|
||||
#endif
|
||||
};
|
||||
|
||||
PG_REGISTER_WITH_RESET_FN(softSerialPinConfig_t, softSerialPinConfig, PG_SOFTSERIAL_PIN_CONFIG, 0);
|
||||
|
||||
void pgResetFn_softSerialPinConfig(softSerialPinConfig_t *softSerialPinConfig)
|
||||
{
|
||||
for (size_t index = 0 ; index < ARRAYLEN(softSerialDefaultPin) ; index++) {
|
||||
const softSerialDefaultPin_t *defpin = &softSerialDefaultPin[index];
|
||||
softSerialPinConfig->ioTagRx[SOFTSERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->rxIO;
|
||||
softSerialPinConfig->ioTagTx[SOFTSERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->txIO;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
|
|
@ -219,13 +219,11 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
|
|||
{
|
||||
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
|
||||
|
||||
int pinCfgIndex = portIndex + RESOURCE_SOFT_OFFSET;
|
||||
ioTag_t tagRx = softSerialPinConfig()->ioTagRx[portIndex];
|
||||
ioTag_t tagTx = softSerialPinConfig()->ioTagTx[portIndex];
|
||||
|
||||
ioTag_t tagRx = serialPinConfig()->ioTagRx[pinCfgIndex];
|
||||
ioTag_t tagTx = serialPinConfig()->ioTagTx[pinCfgIndex];
|
||||
|
||||
const timerHardware_t *timerTx = timerAllocate(tagTx, OWNER_SERIAL_TX, RESOURCE_INDEX(portIndex + RESOURCE_SOFT_OFFSET));
|
||||
const timerHardware_t *timerRx = (tagTx == tagRx) ? timerTx : timerAllocate(tagRx, OWNER_SERIAL_RX, RESOURCE_INDEX(portIndex + RESOURCE_SOFT_OFFSET));
|
||||
const timerHardware_t *timerTx = timerAllocate(tagTx, OWNER_SOFTSERIAL_TX, RESOURCE_INDEX(portIndex));
|
||||
const timerHardware_t *timerRx = (tagTx == tagRx) ? timerTx : timerAllocate(tagRx, OWNER_SOFTSERIAL_RX, RESOURCE_INDEX(portIndex));
|
||||
|
||||
IO_t rxIO = IOGetByTag(tagRx);
|
||||
IO_t txIO = IOGetByTag(tagTx);
|
||||
|
@ -241,7 +239,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
|
|||
softSerial->timerHardware = timerTx;
|
||||
softSerial->txIO = txIO;
|
||||
softSerial->rxIO = txIO;
|
||||
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(portIndex + RESOURCE_SOFT_OFFSET));
|
||||
IOInit(txIO, OWNER_SOFTSERIAL_TX, RESOURCE_INDEX(portIndex));
|
||||
} else {
|
||||
if (mode & MODE_RX) {
|
||||
// Need a pin & a timer on RX. Channel should not be N-Channel.
|
||||
|
@ -252,7 +250,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
|
|||
softSerial->rxIO = rxIO;
|
||||
softSerial->timerHardware = timerRx;
|
||||
if (!((mode & MODE_TX) && rxIO == txIO)) {
|
||||
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(portIndex + RESOURCE_SOFT_OFFSET));
|
||||
IOInit(rxIO, OWNER_SOFTSERIAL_RX, RESOURCE_INDEX(portIndex));
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -272,7 +270,7 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
|
|||
// Duplex
|
||||
softSerial->exTimerHardware = timerTx;
|
||||
}
|
||||
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(portIndex + RESOURCE_SOFT_OFFSET));
|
||||
IOInit(txIO, OWNER_SOFTSERIAL_TX, RESOURCE_INDEX(portIndex));
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -394,47 +394,56 @@ void uartConfigureDma(uartDevice_t *uartdev)
|
|||
}
|
||||
#endif
|
||||
|
||||
#define UART_IRQHandler(type, number, dev) \
|
||||
FAST_IRQ_HANDLER void type ## number ## _IRQHandler(void) \
|
||||
{ \
|
||||
uartPort_t *uartPort = &(uartDevmap[UARTDEV_ ## dev]->port); \
|
||||
uartIrqHandler(uartPort); \
|
||||
#define UART_IRQHandler(type, number, dev) \
|
||||
FAST_IRQ_HANDLER void type ## number ## _IRQHandler(void) \
|
||||
{ \
|
||||
uartPort_t *uartPort = &(uartDevmap[dev]->port); \
|
||||
uartIrqHandler(uartPort); \
|
||||
}
|
||||
|
||||
#ifdef USE_UART1
|
||||
UART_IRQHandler(USART, 1, 1) // USART1 Rx/Tx IRQ Handler
|
||||
UART_IRQHandler(USART, 1, UARTDEV_1) // USART1 Rx/Tx IRQ Handler
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART2
|
||||
UART_IRQHandler(USART, 2, 2) // USART2 Rx/Tx IRQ Handler
|
||||
UART_IRQHandler(USART, 2, UARTDEV_2) // USART2 Rx/Tx IRQ Handler
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART3
|
||||
UART_IRQHandler(USART, 3, 3) // USART3 Rx/Tx IRQ Handler
|
||||
UART_IRQHandler(USART, 3, UARTDEV_3) // USART3 Rx/Tx IRQ Handler
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART4
|
||||
UART_IRQHandler(UART, 4, 4) // UART4 Rx/Tx IRQ Handler
|
||||
UART_IRQHandler(UART, 4, UARTDEV_4) // UART4 Rx/Tx IRQ Handler
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART5
|
||||
UART_IRQHandler(UART, 5, 5) // UART5 Rx/Tx IRQ Handler
|
||||
UART_IRQHandler(UART, 5, UARTDEV_5) // UART5 Rx/Tx IRQ Handler
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART6
|
||||
UART_IRQHandler(USART, 6, 6) // USART6 Rx/Tx IRQ Handler
|
||||
UART_IRQHandler(USART, 6, UARTDEV_6) // USART6 Rx/Tx IRQ Handler
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART7
|
||||
UART_IRQHandler(UART, 7, 7) // UART7 Rx/Tx IRQ Handler
|
||||
UART_IRQHandler(UART, 7, UARTDEV_7) // UART7 Rx/Tx IRQ Handler
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART8
|
||||
UART_IRQHandler(UART, 8, 8) // UART8 Rx/Tx IRQ Handler
|
||||
UART_IRQHandler(UART, 8, UARTDEV_8) // UART8 Rx/Tx IRQ Handler
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART9
|
||||
UART_IRQHandler(LPUART, 1, 9) // UART9 (implemented with LPUART1) Rx/Tx IRQ Handler
|
||||
UART_IRQHandler(UART, 9, UARTDEV_9) // UART9 Rx/Tx IRQ Handler
|
||||
#endif
|
||||
|
||||
#ifdef USE_UART10
|
||||
UART_IRQHandler(UART, 10, UARTDEV_10) // UART10 Rx/Tx IRQ Handler
|
||||
#endif
|
||||
|
||||
#ifdef USE_LPUART1
|
||||
UART_IRQHandler(LPUART, 1, LPUARTDEV_1) // LPUART1 Rx/Tx IRQ Handler
|
||||
#endif
|
||||
|
||||
|
||||
#endif // USE_UART
|
||||
|
|
|
@ -41,6 +41,8 @@ typedef enum {
|
|||
UARTDEV_9 = 8,
|
||||
UARTDEV_10 = 9,
|
||||
LPUARTDEV_1 = 10,
|
||||
|
||||
MAX_UARTDEV = LPUARTDEV_1,
|
||||
} UARTDevice_e;
|
||||
|
||||
typedef struct uartPort_s {
|
||||
|
|
|
@ -67,11 +67,11 @@
|
|||
#ifndef UART5_RX_DMA_CHANNEL
|
||||
#define UART5_RX_DMA_CHANNEL NULL
|
||||
#endif
|
||||
#ifndef UART9_TX_DMA_CHANNEL
|
||||
#define UART9_TX_DMA_CHANNEL NULL
|
||||
#ifndef LPUART1_TX_DMA_CHANNEL
|
||||
#define LPUART1_TX_DMA_CHANNEL NULL
|
||||
#endif
|
||||
#ifndef UART9_RX_DMA_CHANNEL
|
||||
#define UART9_RX_DMA_CHANNEL NULL
|
||||
#ifndef LPUART1_RX_DMA_CHANNEL
|
||||
#define LPUART1_RX_DMA_CHANNEL NULL
|
||||
#endif
|
||||
|
||||
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
|
||||
|
@ -228,9 +228,9 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
|
|||
.reg = LPUART1,
|
||||
#ifdef USE_DMA
|
||||
.rxDMAChannel = DMA_REQUEST_LPUART1_RX,
|
||||
.rxDMAResource = (dmaResource_t *)UART9_RX_DMA_CHANNEL,
|
||||
.rxDMAResource = (dmaResource_t *)LPUART1_RX_DMA_CHANNEL,
|
||||
.txDMAChannel = DMA_REQUEST_LPUART1_TX,
|
||||
.txDMAResource = (dmaResource_t *)UART9_TX_DMA_CHANNEL,
|
||||
.txDMAResource = (dmaResource_t *)LPUART1_TX_DMA_CHANNEL,
|
||||
#endif
|
||||
.rxPins = {
|
||||
{ DEFIO_TAG_E(PA3), GPIO_AF12_LPUART1 },
|
||||
|
|
|
@ -498,13 +498,13 @@ void serialInit(bool softserialEnabled, serialPortIdentifier_e serialPortToDisab
|
|||
#endif
|
||||
else if ((serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL1
|
||||
#ifdef USE_SOFTSERIAL1
|
||||
&& !(softserialEnabled && (serialPinConfig()->ioTagTx[RESOURCE_SOFT_OFFSET + SOFTSERIAL1] ||
|
||||
serialPinConfig()->ioTagRx[RESOURCE_SOFT_OFFSET + SOFTSERIAL1]))
|
||||
&& !(softserialEnabled && (softSerialPinConfig()->ioTagTx[SOFTSERIAL1] ||
|
||||
softSerialPinConfig()->ioTagRx[SOFTSERIAL1]))
|
||||
#endif
|
||||
) || (serialPortUsageList[index].identifier == SERIAL_PORT_SOFTSERIAL2
|
||||
#ifdef USE_SOFTSERIAL2
|
||||
&& !(softserialEnabled && (serialPinConfig()->ioTagTx[RESOURCE_SOFT_OFFSET + SOFTSERIAL2] ||
|
||||
serialPinConfig()->ioTagRx[RESOURCE_SOFT_OFFSET + SOFTSERIAL2]))
|
||||
&& !(softserialEnabled && (softSerialPinConfig()->ioTagTx[SOFTSERIAL2] ||
|
||||
softSerialPinConfig()->ioTagRx[SOFTSERIAL2]))
|
||||
#endif
|
||||
)) {
|
||||
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
|
||||
|
|
|
@ -92,6 +92,7 @@ typedef enum {
|
|||
SERIAL_PORT_USART8,
|
||||
SERIAL_PORT_UART9,
|
||||
SERIAL_PORT_USART10,
|
||||
SERIAL_PORT_USART_MAX = SERIAL_PORT_USART10,
|
||||
SERIAL_PORT_USB_VCP = 20,
|
||||
SERIAL_PORT_SOFTSERIAL1 = 30,
|
||||
SERIAL_PORT_SOFTSERIAL2,
|
||||
|
@ -101,9 +102,21 @@ typedef enum {
|
|||
|
||||
extern const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT];
|
||||
|
||||
#define SERIAL_PORT_IDENTIFIER_TO_INDEX(x) (((x) < RESOURCE_SOFT_OFFSET) ? (x) : (RESOURCE_SOFT_OFFSET + ((x) - SERIAL_PORT_SOFTSERIAL1)))
|
||||
#define SOFTSERIAL_PORT_IDENTIFIER_TO_INDEX(x) ((x) - SERIAL_PORT_SOFTSERIAL1)
|
||||
|
||||
#if defined(USE_LPUART1)
|
||||
|
||||
#define SERIAL_PORT_IDENTIFIER_TO_INDEX(x) \
|
||||
(((x) <= SERIAL_PORT_USART_MAX) ? ((x) - SERIAL_PORT_USART1) : ((x) - SERIAL_PORT_LPUART1) + LPUARTDEV_1)
|
||||
#define SERIAL_PORT_IDENTIFIER_TO_UARTDEV(x) \
|
||||
(((x) <= SERIAL_PORT_USART_MAX) ? ((x) - SERIAL_PORT_USART1 + UARTDEV_1) : ((x) - SERIAL_PORT_LPUART1) + LPUARTDEV_1)
|
||||
|
||||
#else
|
||||
|
||||
#define SERIAL_PORT_IDENTIFIER_TO_INDEX(x) ((x) - SERIAL_PORT_USART1)
|
||||
#define SERIAL_PORT_IDENTIFIER_TO_UARTDEV(x) ((x) - SERIAL_PORT_USART1 + UARTDEV_1)
|
||||
|
||||
#endif
|
||||
//
|
||||
// runtime
|
||||
//
|
||||
|
|
|
@ -155,7 +155,8 @@
|
|||
#define PG_RX_EXPRESSLRS_SPI_CONFIG 555
|
||||
#define PG_SCHEDULER_CONFIG 556
|
||||
#define PG_MSP_CONFIG 557
|
||||
#define PG_BETAFLIGHT_END 557
|
||||
#define PG_SOFTSERIAL_PIN_CONFIG 558
|
||||
#define PG_BETAFLIGHT_END 558
|
||||
|
||||
|
||||
// OSD configuration (subject to change)
|
||||
|
|
|
@ -35,6 +35,7 @@
|
|||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
|
||||
// TODO(hertz@): UARTDEV_CONFIG_MAX is measured to be exactly 8, which cannot accomodate even all the UARTs below
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(serialUartConfig_t, UARTDEV_CONFIG_MAX, serialUartConfig, PG_SERIAL_UART_CONFIG, 0);
|
||||
|
||||
typedef struct uartDmaopt_s {
|
||||
|
@ -74,13 +75,16 @@ static uartDmaopt_t uartDmaopt[] = {
|
|||
#ifdef USE_UART10
|
||||
{ UARTDEV_10, UART10_TX_DMA_OPT, UART10_RX_DMA_OPT },
|
||||
#endif
|
||||
#ifdef USE_LPUART1
|
||||
{ LPUARTDEV_1, DMA_OPT_UNUSED, DMA_OPT_UNUSED },
|
||||
#endif
|
||||
};
|
||||
|
||||
void pgResetFn_serialUartConfig(serialUartConfig_t *config)
|
||||
{
|
||||
for (unsigned i = 0; i < UARTDEV_CONFIG_MAX; i++) {
|
||||
config[i].txDmaopt = -1;
|
||||
config[i].rxDmaopt = -1;
|
||||
config[i].txDmaopt = DMA_OPT_UNUSED;
|
||||
config[i].rxDmaopt = DMA_OPT_UNUSED;
|
||||
}
|
||||
|
||||
for (unsigned i = 0; i < ARRAYLEN(uartDmaopt); i++) {
|
||||
|
|
|
@ -27,7 +27,9 @@
|
|||
#include "drivers/io_types.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
|
||||
#define UARTDEV_CONFIG_MAX 8 // Alternative to UARTDEV_COUNT_MAX, which requires serial_uart_imp.h
|
||||
|
||||
// TODO(hertz@): this alternative got out of sync
|
||||
#define UARTDEV_CONFIG_MAX 11 // Alternative to UARTDEV_COUNT_MAX, which requires serial_uart_imp.h
|
||||
|
||||
typedef struct serialUartConfig_s {
|
||||
int8_t txDmaopt;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue