mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 22:35:23 +03:00
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
This commit is contained in:
parent
cbaf9b0265
commit
4dc04d6a33
11 changed files with 239 additions and 28 deletions
|
@ -177,11 +177,44 @@ void uartReconfigure(uartPort_t *uartPort)
|
||||||
} else {
|
} else {
|
||||||
usart_interrupt_enable(uartPort->USARTx, USART_TDBE_INT, TRUE);
|
usart_interrupt_enable(uartPort->USARTx, USART_TDBE_INT, TRUE);
|
||||||
}
|
}
|
||||||
|
usart_interrupt_enable(uartPort->USARTx, USART_TDC_INT, TRUE);
|
||||||
}
|
}
|
||||||
|
|
||||||
usart_enable(uartPort->USARTx,TRUE);
|
usart_enable(uartPort->USARTx,TRUE);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
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);
|
||||||
|
}
|
||||||
|
|
||||||
#ifdef USE_DMA
|
#ifdef USE_DMA
|
||||||
void uartTryStartTxDMA(uartPort_t *s)
|
void uartTryStartTxDMA(uartPort_t *s)
|
||||||
{
|
{
|
||||||
|
@ -228,7 +261,14 @@ void uartTryStartTxDMA(uartPort_t *s)
|
||||||
|
|
||||||
static void handleUsartTxDma(uartPort_t *s)
|
static void handleUsartTxDma(uartPort_t *s)
|
||||||
{
|
{
|
||||||
|
uartDevice_t *uart = container_of(s, uartDevice_t, port);
|
||||||
|
|
||||||
uartTryStartTxDMA(s);
|
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)
|
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
|
||||||
|
@ -258,6 +298,14 @@ void uartIrqHandler(uartPort_t *s)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// UART transmission completed
|
||||||
|
if ((usart_flag_get(s->USARTx, USART_TDC_FLAG) != RESET)) {
|
||||||
|
usart_flag_clear(s->USARTx, USART_TDC_FLAG);
|
||||||
|
|
||||||
|
// Switch TX to an input with pull-up so it's state can be monitored
|
||||||
|
uartTxMonitor(s);
|
||||||
|
}
|
||||||
|
|
||||||
if (!s->txDMAResource && (usart_flag_get(s->USARTx, USART_TDBE_FLAG) == SET)) {
|
if (!s->txDMAResource && (usart_flag_get(s->USARTx, USART_TDBE_FLAG) == SET)) {
|
||||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||||
usart_data_transmit(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
|
usart_data_transmit(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
|
||||||
|
|
|
@ -286,6 +286,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
|
||||||
s->port.rxBufferSize = hardware->rxBufferSize;
|
s->port.rxBufferSize = hardware->rxBufferSize;
|
||||||
s->port.txBufferSize = hardware->txBufferSize;
|
s->port.txBufferSize = hardware->txBufferSize;
|
||||||
|
|
||||||
|
s->checkUsartTxOutput = checkUsartTxOutput;
|
||||||
|
|
||||||
#ifdef USE_DMA
|
#ifdef USE_DMA
|
||||||
uartConfigureDma(uartdev);
|
uartConfigureDma(uartdev);
|
||||||
#endif
|
#endif
|
||||||
|
@ -297,6 +299,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
|
||||||
IO_t txIO = IOGetByTag(uartdev->tx.pin);
|
IO_t txIO = IOGetByTag(uartdev->tx.pin);
|
||||||
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
|
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
|
||||||
|
|
||||||
|
uartdev->txPinState = TX_PIN_IGNORE;
|
||||||
|
|
||||||
if ((options & SERIAL_BIDIR) && txIO) {
|
if ((options & SERIAL_BIDIR) && txIO) {
|
||||||
//mode,speed,otype,pupd
|
//mode,speed,otype,pupd
|
||||||
ioConfig_t ioCfg = IO_CONFIG(
|
ioConfig_t ioCfg = IO_CONFIG(
|
||||||
|
@ -310,7 +314,14 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
|
||||||
} else {
|
} else {
|
||||||
if ((mode & MODE_TX) && txIO) {
|
if ((mode & MODE_TX) && txIO) {
|
||||||
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
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) {
|
if ((mode & MODE_RX) && rxIO) {
|
||||||
|
|
|
@ -267,6 +267,12 @@ static void uartWrite(serialPort_t *instance, uint8_t ch)
|
||||||
{
|
{
|
||||||
uartPort_t *uartPort = (uartPort_t *)instance;
|
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;
|
uartPort->port.txBuffer[uartPort->port.txBufferHead] = ch;
|
||||||
|
|
||||||
if (uartPort->port.txBufferHead + 1 >= uartPort->port.txBufferSize) {
|
if (uartPort->port.txBufferHead + 1 >= uartPort->port.txBufferSize) {
|
||||||
|
|
|
@ -76,6 +76,8 @@ typedef struct uartPort_s {
|
||||||
#endif
|
#endif
|
||||||
USART_TypeDef *USARTx;
|
USART_TypeDef *USARTx;
|
||||||
bool txDMAEmpty;
|
bool txDMAEmpty;
|
||||||
|
|
||||||
|
bool (* checkUsartTxOutput)(struct uartPort_s *s);
|
||||||
} uartPort_t;
|
} uartPort_t;
|
||||||
|
|
||||||
void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig);
|
void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig);
|
||||||
|
|
|
@ -217,6 +217,12 @@ extern const uartHardware_t uartHardware[];
|
||||||
// uartDevice_t is an actual device instance.
|
// uartDevice_t is an actual device instance.
|
||||||
// XXX Instances are allocated for uarts defined by USE_UARTx atm.
|
// 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 {
|
typedef struct uartDevice_s {
|
||||||
uartPort_t port;
|
uartPort_t port;
|
||||||
const uartHardware_t *hardware;
|
const uartHardware_t *hardware;
|
||||||
|
@ -227,6 +233,7 @@ typedef struct uartDevice_s {
|
||||||
#if !defined(STM32F4) // Don't support pin swap.
|
#if !defined(STM32F4) // Don't support pin swap.
|
||||||
bool pinSwap;
|
bool pinSwap;
|
||||||
#endif
|
#endif
|
||||||
|
txPinState_t txPinState;
|
||||||
} uartDevice_t;
|
} uartDevice_t;
|
||||||
|
|
||||||
extern uartDevice_t *uartDevmap[];
|
extern uartDevice_t *uartDevmap[];
|
||||||
|
@ -245,6 +252,9 @@ void uartConfigureDma(uartDevice_t *uartdev);
|
||||||
|
|
||||||
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor);
|
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor);
|
||||||
|
|
||||||
|
bool checkUsartTxOutput(uartPort_t *s);
|
||||||
|
void uartTxMonitor(uartPort_t *s);
|
||||||
|
|
||||||
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||||
#define UART_REG_RXD(base) ((base)->RDR)
|
#define UART_REG_RXD(base) ((base)->RDR)
|
||||||
#define UART_REG_TXD(base) ((base)->TDR)
|
#define UART_REG_TXD(base) ((base)->TDR)
|
||||||
|
|
|
@ -231,11 +231,46 @@ void uartReconfigure(uartPort_t *uartPort)
|
||||||
|
|
||||||
/* Enable the UART Transmit Data Register Empty Interrupt */
|
/* Enable the UART Transmit Data Register Empty Interrupt */
|
||||||
SET_BIT(uartPort->USARTx->CR1, USART_CR1_TXEIE);
|
SET_BIT(uartPort->USARTx->CR1, USART_CR1_TXEIE);
|
||||||
|
SET_BIT(uartPort->USARTx->CR1, USART_CR1_TCIE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return;
|
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
|
#ifdef USE_DMA
|
||||||
void uartTryStartTxDMA(uartPort_t *s)
|
void uartTryStartTxDMA(uartPort_t *s)
|
||||||
{
|
{
|
||||||
|
@ -275,7 +310,14 @@ void uartTryStartTxDMA(uartPort_t *s)
|
||||||
|
|
||||||
static void handleUsartTxDma(uartPort_t *s)
|
static void handleUsartTxDma(uartPort_t *s)
|
||||||
{
|
{
|
||||||
|
uartDevice_t *uart = container_of(s, uartDevice_t, port);
|
||||||
|
|
||||||
uartTryStartTxDMA(s);
|
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)
|
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);
|
__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 (
|
if (
|
||||||
#ifdef USE_DMA
|
#ifdef USE_DMA
|
||||||
|
@ -351,33 +405,19 @@ FAST_IRQ_HANDLER void uartIrqHandler(uartPort_t *s)
|
||||||
#endif
|
#endif
|
||||||
(__HAL_UART_GET_IT(huart, UART_IT_TXE) != RESET)) {
|
(__HAL_UART_GET_IT(huart, UART_IT_TXE) != RESET)) {
|
||||||
/* Check that a Tx process is ongoing */
|
/* Check that a Tx process is ongoing */
|
||||||
if (huart->gState != HAL_UART_STATE_BUSY_TX) {
|
if (s->port.txBufferTail == s->port.txBufferHead) {
|
||||||
if (s->port.txBufferTail == s->port.txBufferHead) {
|
/* Disable the UART Transmit Data Register Empty Interrupt */
|
||||||
huart->TxXferCount = 0;
|
CLEAR_BIT(huart->Instance->CR1, USART_CR1_TXEIE);
|
||||||
/* Disable the UART Transmit Data Register Empty Interrupt */
|
} else {
|
||||||
CLEAR_BIT(huart->Instance->CR1, USART_CR1_TXEIE);
|
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 {
|
} else {
|
||||||
if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) {
|
huart->Instance->TDR = (uint8_t)(s->port.txBuffer[s->port.txBufferTail]);
|
||||||
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;
|
|
||||||
}
|
}
|
||||||
|
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
|
// UART reception idle detected
|
||||||
|
|
||||||
if (__HAL_UART_GET_IT(huart, UART_IT_IDLE)) {
|
if (__HAL_UART_GET_IT(huart, UART_IT_IDLE)) {
|
||||||
|
|
|
@ -180,6 +180,8 @@ void uartReconfigure(uartPort_t *uartPort)
|
||||||
} else {
|
} else {
|
||||||
USART_ITConfig(uartPort->USARTx, USART_IT_TXE, ENABLE);
|
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);
|
USART_Cmd(uartPort->USARTx, ENABLE);
|
||||||
|
|
|
@ -26,6 +26,7 @@
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
#ifdef USE_UART
|
#ifdef USE_UART
|
||||||
|
|
||||||
|
@ -217,9 +218,48 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
|
||||||
#endif
|
#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)
|
static void handleUsartTxDma(uartPort_t *s)
|
||||||
{
|
{
|
||||||
|
uartDevice_t *uart = container_of(s, uartDevice_t, port);
|
||||||
|
|
||||||
uartTryStartTxDMA(s);
|
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)
|
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->USARTx = hardware->reg;
|
||||||
|
|
||||||
|
s->checkUsartTxOutput = checkUsartTxOutput;
|
||||||
|
|
||||||
#ifdef USE_DMA
|
#ifdef USE_DMA
|
||||||
uartConfigureDma(uart);
|
uartConfigureDma(uart);
|
||||||
#endif
|
#endif
|
||||||
|
@ -279,13 +321,22 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
|
||||||
RCC_ClockCmd(hardware->rcc, ENABLE);
|
RCC_ClockCmd(hardware->rcc, ENABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uart->txPinState = TX_PIN_IGNORE;
|
||||||
|
|
||||||
if (options & SERIAL_BIDIR) {
|
if (options & SERIAL_BIDIR) {
|
||||||
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
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);
|
IOConfigGPIOAF(txIO, ((options & SERIAL_BIDIR_PP) || (options & SERIAL_BIDIR_PP_PD)) ? IOCFG_AF_PP : IOCFG_AF_OD, hardware->af);
|
||||||
} else {
|
} else {
|
||||||
if ((mode & MODE_TX) && txIO) {
|
if ((mode & MODE_TX) && txIO) {
|
||||||
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
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) {
|
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->txDMAResource && (USART_GetITStatus(s->USARTx, USART_IT_TXE) == SET)) {
|
||||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||||
USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
|
USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
|
||||||
|
|
|
@ -345,6 +345,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
|
||||||
s->port.rxBufferSize = hardware->rxBufferSize;
|
s->port.rxBufferSize = hardware->rxBufferSize;
|
||||||
s->port.txBufferSize = hardware->txBufferSize;
|
s->port.txBufferSize = hardware->txBufferSize;
|
||||||
|
|
||||||
|
s->checkUsartTxOutput = checkUsartTxOutput;
|
||||||
|
|
||||||
#ifdef USE_DMA
|
#ifdef USE_DMA
|
||||||
uartConfigureDma(uartdev);
|
uartConfigureDma(uartdev);
|
||||||
#endif
|
#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 txIO = IOGetByTag(uartdev->tx.pin);
|
||||||
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
|
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
|
||||||
|
|
||||||
|
uartdev->txPinState = TX_PIN_IGNORE;
|
||||||
|
|
||||||
if ((options & SERIAL_BIDIR) && txIO) {
|
if ((options & SERIAL_BIDIR) && txIO) {
|
||||||
ioConfig_t ioCfg = IO_CONFIG(
|
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,
|
((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 {
|
else {
|
||||||
if ((mode & MODE_TX) && txIO) {
|
if ((mode & MODE_TX) && txIO) {
|
||||||
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
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) {
|
if ((mode & MODE_RX) && rxIO) {
|
||||||
|
|
|
@ -279,6 +279,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
|
||||||
s->port.rxBufferSize = hardware->rxBufferSize;
|
s->port.rxBufferSize = hardware->rxBufferSize;
|
||||||
s->port.txBufferSize = hardware->txBufferSize;
|
s->port.txBufferSize = hardware->txBufferSize;
|
||||||
|
|
||||||
|
s->checkUsartTxOutput = checkUsartTxOutput;
|
||||||
|
|
||||||
#ifdef USE_DMA
|
#ifdef USE_DMA
|
||||||
uartConfigureDma(uartdev);
|
uartConfigureDma(uartdev);
|
||||||
#endif
|
#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 txIO = IOGetByTag(uartdev->tx.pin);
|
||||||
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
|
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
|
||||||
|
|
||||||
|
uartdev->txPinState = TX_PIN_IGNORE;
|
||||||
|
|
||||||
if ((options & SERIAL_BIDIR) && txIO) {
|
if ((options & SERIAL_BIDIR) && txIO) {
|
||||||
ioConfig_t ioCfg = IO_CONFIG(
|
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,
|
((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 {
|
} else {
|
||||||
if ((mode & MODE_TX) && txIO) {
|
if ((mode & MODE_TX) && txIO) {
|
||||||
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
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) {
|
if ((mode & MODE_RX) && rxIO) {
|
||||||
|
|
|
@ -456,6 +456,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_e mode,
|
||||||
s->port.rxBufferSize = hardware->rxBufferSize;
|
s->port.rxBufferSize = hardware->rxBufferSize;
|
||||||
s->port.txBufferSize = hardware->txBufferSize;
|
s->port.txBufferSize = hardware->txBufferSize;
|
||||||
|
|
||||||
|
s->checkUsartTxOutput = checkUsartTxOutput;
|
||||||
|
|
||||||
#ifdef USE_DMA
|
#ifdef USE_DMA
|
||||||
uartConfigureDma(uartdev);
|
uartConfigureDma(uartdev);
|
||||||
#endif
|
#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 txIO = IOGetByTag(uartdev->tx.pin);
|
||||||
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
|
IO_t rxIO = IOGetByTag(uartdev->rx.pin);
|
||||||
|
|
||||||
|
uartdev->txPinState = TX_PIN_IGNORE;
|
||||||
|
|
||||||
if ((options & SERIAL_BIDIR) && txIO) {
|
if ((options & SERIAL_BIDIR) && txIO) {
|
||||||
ioConfig_t ioCfg = IO_CONFIG(
|
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,
|
((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 {
|
} else {
|
||||||
if ((mode & MODE_TX) && txIO) {
|
if ((mode & MODE_TX) && txIO) {
|
||||||
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
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) {
|
if ((mode & MODE_RX) && rxIO) {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue