Skip to content

Commit

Permalink
Added idle interrupt callback to UART driver
Browse files Browse the repository at this point in the history
  • Loading branch information
MiguelFAlvarez committed Jul 22, 2019
1 parent 0f230c4 commit 38013a8
Show file tree
Hide file tree
Showing 7 changed files with 49 additions and 8 deletions.
3 changes: 3 additions & 0 deletions src/main/drivers/serial.h
Expand Up @@ -59,6 +59,7 @@ typedef enum {
#define CTRL_LINE_STATE_RTS (1 << 1)

typedef void (*serialReceiveCallbackPtr)(uint16_t data, void *rxCallbackData); // used by serial drivers to return frames to app
typedef void (*serialIdleCallbackPtr)();

typedef struct serialPort_s {

Expand All @@ -81,6 +82,8 @@ typedef struct serialPort_s {
serialReceiveCallbackPtr rxCallback;
void *rxCallbackData;

serialIdleCallbackPtr idleCallback;

uint8_t identifier;
} serialPort_t;

Expand Down
4 changes: 3 additions & 1 deletion src/main/drivers/serial_uart_hal.c
Expand Up @@ -147,7 +147,6 @@ void uartReconfigure(uartPort_t *uartPort)
HAL_UART_Receive_DMA(&uartPort->Handle, (uint8_t*)uartPort->port.rxBuffer, uartPort->port.rxBufferSize);

uartPort->rxDMAPos = __HAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle);

} else
#endif
{
Expand All @@ -159,6 +158,9 @@ void uartReconfigure(uartPort_t *uartPort)

/* Enable the UART Data Register not empty Interrupt */
SET_BIT(uartPort->USARTx->CR1, USART_CR1_RXNEIE);

/* Enable Idle Line detection */
SET_BIT(uartPort->USARTx->CR1, USART_CR1_IDLEIE);
}
}

Expand Down
1 change: 1 addition & 0 deletions src/main/drivers/serial_uart_init.c
Expand Up @@ -189,6 +189,7 @@ serialPort_t *uartOpen(UARTDevice_e device, serialReceiveCallbackPtr rxCallback,
} else {
USART_ClearITPendingBit(s->USARTx, USART_IT_RXNE);
USART_ITConfig(s->USARTx, USART_IT_RXNE, ENABLE);
USART_ITConfig(s->USARTx, USART_IT_IDLE, ENABLE);
}
}

Expand Down
8 changes: 8 additions & 0 deletions src/main/drivers/serial_uart_stm32f10x.c
Expand Up @@ -214,5 +214,13 @@ void uartIrqHandler(uartPort_t *s)
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
}
}
if (SR & USART_FLAG_IDLE) {
if (s->port.idleCallback) {
s->port.idleCallback();
}

const uint32_t read_to_clear = s->USARTx->DR;
(void) read_to_clear;
}
}
#endif // USE_UART
10 changes: 9 additions & 1 deletion src/main/drivers/serial_uart_stm32f30x.c
Expand Up @@ -285,7 +285,15 @@ void uartIrqHandler(uartPort_t *s)

if (ISR & USART_FLAG_ORE)
{
USART_ClearITPendingBit (s->USARTx, USART_IT_ORE);
USART_ClearITPendingBit(s->USARTx, USART_IT_ORE);
}

if (ISR & USART_FLAG_IDLE) {
if (s->port.idleCallback) {
s->port.idleCallback();
}

USART_ClearITPendingBit(s->USARTx, USART_IT_IDLE);
}
}
#endif // USE_UART
15 changes: 12 additions & 3 deletions src/main/drivers/serial_uart_stm32f4xx.c
Expand Up @@ -289,9 +289,18 @@ void uartIrqHandler(uartPort_t *s)
}
}

if (USART_GetITStatus(s->USARTx, USART_IT_ORE) == SET)
{
USART_ClearITPendingBit (s->USARTx, USART_IT_ORE);
if (USART_GetITStatus(s->USARTx, USART_IT_ORE) == SET) {
USART_ClearITPendingBit(s->USARTx, USART_IT_ORE);
}

if (USART_GetITStatus(s->USARTx, USART_IT_IDLE) == SET) {
if (s->port.idleCallback) {
s->port.idleCallback();
}

// clear
(void) s->USARTx->SR;
(void) s->USARTx->DR;
}
}
#endif
16 changes: 13 additions & 3 deletions src/main/drivers/serial_uart_stm32f7xx.c
Expand Up @@ -39,6 +39,8 @@
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"

#include "stm32f7xx_ll_usart.h"

static void handleUsartTxDma(uartPort_t *s);

const uartHardware_t uartHardware[UARTDEV_COUNT] = {
Expand Down Expand Up @@ -150,15 +152,15 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
#endif
.rxPins = {
{ DEFIO_TAG_E(PA1), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PC11), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PC11), GPIO_AF8_UART4 },
#ifdef STM32F765xx
{ DEFIO_TAG_E(PA11), GPIO_AF6_UART4 },
{ DEFIO_TAG_E(PD0), GPIO_AF8_UART4 }
{ DEFIO_TAG_E(PD0), GPIO_AF8_UART4 }
#endif
},
.txPins = {
{ DEFIO_TAG_E(PA0), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PC10), GPIO_AF8_UART4 },
{ DEFIO_TAG_E(PC10), GPIO_AF8_UART4 },
#ifdef STM32F765xx
{ DEFIO_TAG_E(PA12), GPIO_AF6_UART4 },
{ DEFIO_TAG_E(PD1), GPIO_AF8_UART4 }
Expand Down Expand Up @@ -372,6 +374,14 @@ void uartIrqHandler(uartPort_t *s)
handleUsartTxDma(s);
}
}

if (__HAL_UART_GET_IT(huart, UART_IT_IDLE)) {
if (s->port.idleCallback) {
s->port.idleCallback();
}

__HAL_UART_CLEAR_IDLEFLAG(huart);
}
}

static void handleUsartTxDma(uartPort_t *s)
Expand Down

0 comments on commit 38013a8

Please sign in to comment.