From ca12a4c611408e3b2b1f8320bf9ea30abb20b156 Mon Sep 17 00:00:00 2001 From: Mark Haslinghuis Date: Thu, 11 May 2023 10:25:40 +0200 Subject: [PATCH] =?utf8?q?[4.4.2]=20Tri-state=20USART=20TX=20output=20if?= =?utf8?q?=20load=20due=20to=20powered=20down=20peripheral=20is=20d?= =?utf8?q?=E2=80=A6=20(#12782)?= MIME-Version: 1.0 Content-Type: text/plain; charset=utf8 Content-Transfer-Encoding: 8bit Tri-state USART TX output if load due to powered down peripheral is detected (#12760) Tri-state USART TX output if loaded due to powered down peripheral being detected Co-authored-by: Steve Evans --- src/main/drivers/serial_uart.c | 6 +++ src/main/drivers/serial_uart.h | 2 + src/main/drivers/serial_uart_hal.c | 86 +++++++++++++++++++++++--------- src/main/drivers/serial_uart_impl.h | 10 ++++ src/main/drivers/serial_uart_stdperiph.c | 2 + src/main/drivers/serial_uart_stm32f4xx.c | 61 +++++++++++++++++++++- src/main/drivers/serial_uart_stm32f7xx.c | 13 ++++- src/main/drivers/serial_uart_stm32g4xx.c | 13 ++++- src/main/drivers/serial_uart_stm32h7xx.c | 13 ++++- 9 files changed, 179 insertions(+), 27 deletions(-) diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index b03b80a0e..94d753898 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -267,6 +267,12 @@ static void uartWrite(serialPort_t *instance, uint8_t ch) { uartPort_t *uartPort = (uartPort_t *)instance; + // Check if the TX line is being pulled low by an unpowered peripheral + if (uartPort->checkUsartTxOutput && !uartPort->checkUsartTxOutput(uartPort)) { + // TX line is being pulled low, so don't transmit + return; + } + uartPort->port.txBuffer[uartPort->port.txBufferHead] = ch; if (uartPort->port.txBufferHead + 1 >= uartPort->port.txBufferSize) { diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h index b9351355a..8fc78b019 100644 --- a/src/main/drivers/serial_uart.h +++ b/src/main/drivers/serial_uart.h @@ -72,6 +72,8 @@ typedef struct uartPort_s { #endif USART_TypeDef *USARTx; bool txDMAEmpty; + + bool (* checkUsartTxOutput)(struct uartPort_s *s); } uartPort_t; void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig); diff --git a/src/main/drivers/serial_uart_hal.c b/src/main/drivers/serial_uart_hal.c index 53e85a525..30360777a 100644 --- a/src/main/drivers/serial_uart_hal.c +++ b/src/main/drivers/serial_uart_hal.c @@ -231,11 +231,46 @@ void uartReconfigure(uartPort_t *uartPort) /* Enable the UART Transmit Data Register Empty Interrupt */ SET_BIT(uartPort->USARTx->CR1, USART_CR1_TXEIE); + SET_BIT(uartPort->USARTx->CR1, USART_CR1_TCIE); } } return; } +bool checkUsartTxOutput(uartPort_t *s) +{ + uartDevice_t *uart = container_of(s, uartDevice_t, port); + IO_t txIO = IOGetByTag(uart->tx.pin); + + if ((uart->txPinState == TX_PIN_MONITOR) && txIO) { + if (IORead(txIO)) { + // TX is high so we're good to transmit + + // Enable USART TX output + uart->txPinState = TX_PIN_ACTIVE; + IOConfigGPIOAF(txIO, IOCFG_AF_PP, uart->tx.af); + return true; + } else { + // TX line is pulled low so don't enable USART TX + return false; + } + } + + return true; +} + +void uartTxMonitor(uartPort_t *s) +{ + uartDevice_t *uart = container_of(s, uartDevice_t, port); + IO_t txIO = IOGetByTag(uart->tx.pin); + + if (uart->txPinState == TX_PIN_ACTIVE) { + // Switch TX to an input with pullup so it's state can be monitored + uart->txPinState = TX_PIN_MONITOR; + IOConfigGPIO(txIO, IOCFG_IPU); + } +} + #ifdef USE_DMA void uartTryStartTxDMA(uartPort_t *s) { @@ -275,7 +310,14 @@ void uartTryStartTxDMA(uartPort_t *s) static void handleUsartTxDma(uartPort_t *s) { + uartDevice_t *uart = container_of(s, uartDevice_t, port); + uartTryStartTxDMA(s); + + if (s->txDMAEmpty && (uart->txPinState != TX_PIN_IGNORE)) { + // Switch TX to an input with pullup so it's state can be monitored + uartTxMonitor(s); + } } void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor) @@ -343,7 +385,19 @@ FAST_IRQ_HANDLER void uartIrqHandler(uartPort_t *s) __HAL_UART_CLEAR_IT(huart, UART_CLEAR_OREF); } - // UART transmitter in interrupting mode, tx buffer empty + // UART transmission completed + if ((__HAL_UART_GET_IT(huart, UART_IT_TC) != RESET)) { + __HAL_UART_CLEAR_IT(huart, UART_CLEAR_TCF); + + // Switch TX to an input with pull-up so it's state can be monitored + uartTxMonitor(s); + +#ifdef USE_DMA + if (s->txDMAResource) { + handleUsartTxDma(s); + } +#endif + } if ( #ifdef USE_DMA @@ -351,33 +405,19 @@ FAST_IRQ_HANDLER void uartIrqHandler(uartPort_t *s) #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); + if (s->port.txBufferTail == s->port.txBufferHead) { + /* 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 { - 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; + huart->Instance->TDR = (uint8_t)(s->port.txBuffer[s->port.txBufferTail]); } + s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize; } } - // UART transmitter in DMA mode, transmission completed - - if ((__HAL_UART_GET_IT(huart, UART_IT_TC) != RESET)) { - HAL_UART_IRQHandler(huart); -#ifdef USE_DMA - if (s->txDMAResource) { - handleUsartTxDma(s); - } -#endif - } - // UART reception idle detected if (__HAL_UART_GET_IT(huart, UART_IT_IDLE)) { diff --git a/src/main/drivers/serial_uart_impl.h b/src/main/drivers/serial_uart_impl.h index 87e55230c..bc6e0e427 100644 --- a/src/main/drivers/serial_uart_impl.h +++ b/src/main/drivers/serial_uart_impl.h @@ -197,6 +197,12 @@ extern const uartHardware_t uartHardware[]; // uartDevice_t is an actual device instance. // XXX Instances are allocated for uarts defined by USE_UARTx atm. +typedef enum { + TX_PIN_ACTIVE, + TX_PIN_MONITOR, + TX_PIN_IGNORE +} txPinState_t; + typedef struct uartDevice_s { uartPort_t port; const uartHardware_t *hardware; @@ -207,6 +213,7 @@ typedef struct uartDevice_s { #if !defined(STM32F4) // Don't support pin swap. bool pinSwap; #endif + txPinState_t txPinState; } uartDevice_t; extern uartDevice_t *uartDevmap[]; @@ -225,6 +232,9 @@ void uartConfigureDma(uartDevice_t *uartdev); 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) diff --git a/src/main/drivers/serial_uart_stdperiph.c b/src/main/drivers/serial_uart_stdperiph.c index ab6a9142a..2d3255e0f 100644 --- a/src/main/drivers/serial_uart_stdperiph.c +++ b/src/main/drivers/serial_uart_stdperiph.c @@ -180,6 +180,8 @@ void uartReconfigure(uartPort_t *uartPort) } else { USART_ITConfig(uartPort->USARTx, USART_IT_TXE, ENABLE); } + // Enable the interrupt so completion of the transmission will be signalled + USART_ITConfig(uartPort->USARTx, USART_IT_TC, ENABLE); } USART_Cmd(uartPort->USARTx, ENABLE); diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index 0f1dc8dbb..0c3ba9e5f 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -26,6 +26,7 @@ #include #include "platform.h" +#include "build/debug.h" #ifdef USE_UART @@ -217,9 +218,48 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = { #endif }; +bool checkUsartTxOutput(uartPort_t *s) +{ + uartDevice_t *uart = container_of(s, uartDevice_t, port); + IO_t txIO = IOGetByTag(uart->tx.pin); + + if ((uart->txPinState == TX_PIN_MONITOR) && txIO) { + if (IORead(txIO)) { + // TX is high so we're good to transmit + + // Enable USART TX output + uart->txPinState = TX_PIN_ACTIVE; + IOConfigGPIOAF(txIO, IOCFG_AF_PP, uart->hardware->af); + return true; + } else { + // TX line is pulled low so don't enable USART TX + return false; + } + } + + return true; +} + +void uartTxMonitor(uartPort_t *s) +{ + uartDevice_t *uart = container_of(s, uartDevice_t, port); + IO_t txIO = IOGetByTag(uart->tx.pin); + + // Switch TX to an input with pullup so it's state can be monitored + uart->txPinState = TX_PIN_MONITOR; + IOConfigGPIO(txIO, IOCFG_IPU); +} + static void handleUsartTxDma(uartPort_t *s) { + uartDevice_t *uart = container_of(s, uartDevice_t, port); + uartTryStartTxDMA(s); + + if (s->txDMAEmpty && (uart->txPinState != TX_PIN_IGNORE)) { + // Switch TX to an input with pullup so it's state can be monitored + uartTxMonitor(s); + } } void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor) @@ -268,6 +308,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, s->USARTx = hardware->reg; + s->checkUsartTxOutput = checkUsartTxOutput; + #ifdef USE_DMA uartConfigureDma(uart); #endif @@ -279,13 +321,22 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, RCC_ClockCmd(hardware->rcc, ENABLE); } + uart->txPinState = TX_PIN_IGNORE; + if (options & SERIAL_BIDIR) { IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device)); IOConfigGPIOAF(txIO, ((options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? IOCFG_AF_PP : IOCFG_AF_OD, hardware->af); } else { if ((mode & MODE_TX) && txIO) { IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device)); - IOConfigGPIOAF(txIO, IOCFG_AF_PP_UP, hardware->af); + + if ((options & SERIAL_INVERTED) == SERIAL_NOT_INVERTED) { + uart->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, hardware->af); + } } if ((mode & MODE_RX) && rxIO) { @@ -320,6 +371,14 @@ void uartIrqHandler(uartPort_t *s) } } + // Detect completion of transmission + if (USART_GetITStatus(s->USARTx, USART_IT_TC) == SET) { + // Switch TX to an input with pullup so it's state can be monitored + uartTxMonitor(s); + + USART_ClearITPendingBit(s->USARTx, USART_IT_TC); + } + if (!s->txDMAResource && (USART_GetITStatus(s->USARTx, USART_IT_TXE) == SET)) { if (s->port.txBufferTail != s->port.txBufferHead) { USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail]); diff --git a/src/main/drivers/serial_uart_stm32f7xx.c b/src/main/drivers/serial_uart_stm32f7xx.c index ef3c81daa..e8ae7ab85 100644 --- a/src/main/drivers/serial_uart_stm32f7xx.c +++ b/src/main/drivers/serial_uart_stm32f7xx.c @@ -345,6 +345,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, s->port.rxBufferSize = hardware->rxBufferSize; s->port.txBufferSize = hardware->txBufferSize; + s->checkUsartTxOutput = checkUsartTxOutput; + #ifdef USE_DMA uartConfigureDma(uartdev); #endif @@ -358,6 +360,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, IO_t txIO = IOGetByTag(uartdev->tx.pin); IO_t rxIO = IOGetByTag(uartdev->rx.pin); + uartdev->txPinState = TX_PIN_IGNORE; + if ((options & SERIAL_BIDIR) && txIO) { ioConfig_t ioCfg = IO_CONFIG( ((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_MODE_AF_PP : GPIO_MODE_AF_OD, @@ -371,7 +375,14 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, else { if ((mode & MODE_TX) && txIO) { IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device)); - IOConfigGPIOAF(txIO, IOCFG_AF_PP, uartdev->tx.af); + + if ((options & SERIAL_INVERTED) == SERIAL_NOT_INVERTED) { + 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) { diff --git a/src/main/drivers/serial_uart_stm32g4xx.c b/src/main/drivers/serial_uart_stm32g4xx.c index 2c9197692..d8a87c792 100644 --- a/src/main/drivers/serial_uart_stm32g4xx.c +++ b/src/main/drivers/serial_uart_stm32g4xx.c @@ -279,6 +279,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, s->port.rxBufferSize = hardware->rxBufferSize; s->port.txBufferSize = hardware->txBufferSize; + s->checkUsartTxOutput = checkUsartTxOutput; + #ifdef USE_DMA uartConfigureDma(uartdev); #endif @@ -292,6 +294,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, IO_t txIO = IOGetByTag(uartdev->tx.pin); IO_t rxIO = IOGetByTag(uartdev->rx.pin); + uartdev->txPinState = TX_PIN_IGNORE; + if ((options & SERIAL_BIDIR) && txIO) { ioConfig_t ioCfg = IO_CONFIG( ((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_MODE_AF_PP : GPIO_MODE_AF_OD, @@ -304,7 +308,14 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, } else { if ((mode & MODE_TX) && txIO) { IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device)); - IOConfigGPIOAF(txIO, IOCFG_AF_PP, uartdev->tx.af); + + if ((options & SERIAL_INVERTED) == SERIAL_NOT_INVERTED) { + 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) { diff --git a/src/main/drivers/serial_uart_stm32h7xx.c b/src/main/drivers/serial_uart_stm32h7xx.c index 09011bb76..e3b3962b9 100644 --- a/src/main/drivers/serial_uart_stm32h7xx.c +++ b/src/main/drivers/serial_uart_stm32h7xx.c @@ -456,6 +456,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, s->port.rxBufferSize = hardware->rxBufferSize; s->port.txBufferSize = hardware->txBufferSize; + s->checkUsartTxOutput = checkUsartTxOutput; + #ifdef USE_DMA uartConfigureDma(uartdev); #endif @@ -469,6 +471,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, IO_t txIO = IOGetByTag(uartdev->tx.pin); IO_t rxIO = IOGetByTag(uartdev->rx.pin); + uartdev->txPinState = TX_PIN_IGNORE; + if ((options & SERIAL_BIDIR) && txIO) { ioConfig_t ioCfg = IO_CONFIG( ((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? GPIO_MODE_AF_PP : GPIO_MODE_AF_OD, @@ -481,7 +485,14 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode, } else { if ((mode & MODE_TX) && txIO) { IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device)); - IOConfigGPIOAF(txIO, IOCFG_AF_PP, uartdev->tx.af); + + if ((options & SERIAL_INVERTED) == SERIAL_NOT_INVERTED) { + 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) { -- 2.11.4.GIT