1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 15:25:36 +03:00

Rework uart rx interrupt, DMA TX still not working

# Conflicts:
#	src/main/drivers/serial_uart_hal.c
#	src/main/io/gps.c
This commit is contained in:
Sami Korhonen 2016-10-08 22:06:07 +03:00
parent 4fd046470b
commit a70da02c58
5 changed files with 145 additions and 148 deletions

View file

@ -236,8 +236,8 @@ static uartDevice_t uart8 =
#endif
.txDMAStream = DMA1_Stream0,
.dev = UART8,
.rx = IO_TAG(UART6_RX_PIN),
.tx = IO_TAG(UART6_TX_PIN),
.rx = IO_TAG(UART8_RX_PIN),
.tx = IO_TAG(UART8_TX_PIN),
.af = GPIO_AF8_UART8,
#ifdef UART8_AHB1_PERIPHERALS
.rcc_ahb1 = UART8_AHB1_PERIPHERALS,
@ -297,48 +297,67 @@ static uartDevice_t* uartHardwareMap[] = {
void uartIrqHandler(uartPort_t *s)
{
/// TODO: This implmentation is kind of a hack to reduce overhead otherwise generated by the HAL, there might be a better solution
UART_HandleTypeDef *huart = &s->Handle;
/* UART in mode Receiver ---------------------------------------------------*/
if((__HAL_UART_GET_IT(huart, UART_IT_RXNE) != RESET))
{
uint8_t rbyte = (uint8_t)(huart->Instance->RDR & (uint8_t)0xff);
if (!s->rxDMAStream && (s->Handle.RxXferSize != s->Handle.RxXferCount)) {
if (s->port.callback) {
// The HAL has already stored the last received byte in the receive buffer we have tell it where to put the next
s->port.callback(s->USARTx->RDR);
s->Handle.pRxBuffPtr = (uint8_t *)s->port.rxBuffer;
s->port.callback(rbyte);
} else {
// The HAL has already stored the last received byte in the receive buffer we have tell it where to put the next
s->port.rxBuffer[s->port.rxBufferHead] = rbyte;
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
s->Handle.pRxBuffPtr = (uint8_t *)&s->port.rxBuffer[s->port.rxBufferHead];
}
//__HAL_UART_CLEAR_IT(huart, UART_IT_RXNE);
CLEAR_BIT(huart->Instance->CR1, (USART_CR1_PEIE));
// We override the rx transfer counter to keep it going without disabling interrupts
s->Handle.RxXferCount = s->Handle.RxXferSize;
/* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */
CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE);
uint32_t errorcode = HAL_UART_GetError(&s->Handle);
if(errorcode != HAL_UART_ERROR_NONE)
{
if(!s->rxDMAStream)
{
HAL_UART_Receive_IT(&s->Handle, (uint8_t *)s->port.rxBuffer, s->port.rxBufferSize);
}
else
{
HAL_UART_Receive_DMA(&s->Handle, (uint8_t *)s->port.rxBuffer, s->port.rxBufferSize);
}
}
__HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST);
}
if (!s->txDMAStream && (s->Handle.TxXferCount == 0)) {
if (s->port.txBufferTail != s->port.txBufferHead) {
// very inefficient but will most likely never be used anyway as TX dma is enabled by default.
HAL_UART_Transmit_IT(&s->Handle, (uint8_t *)&s->port.txBuffer[s->port.txBufferTail], 1);
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
}
/* UART parity error interrupt occurred -------------------------------------*/
if((__HAL_UART_GET_IT(huart, UART_IT_PE) != RESET))
{
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_PEF);
}
else if(s->txDMAStream && (s->Handle.TxXferCount == 0) && (s->Handle.TxXferSize != 0))
/* UART frame error interrupt occurred --------------------------------------*/
if((__HAL_UART_GET_IT(huart, UART_IT_FE) != RESET))
{
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_FEF);
}
/* UART noise error interrupt occurred --------------------------------------*/
if((__HAL_UART_GET_IT(huart, UART_IT_NE) != RESET))
{
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_NEF);
}
/* UART Over-Run interrupt occurred -----------------------------------------*/
if((__HAL_UART_GET_IT(huart, UART_IT_ORE) != RESET))
{
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_OREF);
}
/* UART in mode Transmitter ------------------------------------------------*/
if((__HAL_UART_GET_IT(huart, UART_IT_TXE) != RESET))
{
//UART_Transmit_IT(huart);
}
/* UART in mode Transmitter (transmission end) -----------------------------*/
if((__HAL_UART_GET_IT(huart, UART_IT_TC) != RESET))
{
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_TCF);
}
/*if(s->txDMAStream && (s->Handle.TxXferCount == 0) && (s->Handle.TxXferSize != 0))
{
handleUsartTxDma(s);
}
}*/
}
static void handleUsartTxDma(uartPort_t *s)
@ -348,34 +367,15 @@ static void handleUsartTxDma(uartPort_t *s)
else
{
s->txDMAEmpty = true;
s->Handle.TxXferSize = 0;
s->Handle.gState = HAL_UART_STATE_READY;
}
}
void dmaIRQHandler(dmaChannelDescriptor_t* descriptor)
{
uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
HAL_DMA_IRQHandler(&s->txDMAHandle);
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF))
{
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF);
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_FEIF))
{
DMA_CLEAR_FLAG(descriptor, DMA_IT_FEIF);
}
handleUsartTxDma(s);
}
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF))
{
DMA_CLEAR_FLAG(descriptor, DMA_IT_TEIF);
}
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_DMEIF))
{
DMA_CLEAR_FLAG(descriptor, DMA_IT_DMEIF);
}
handleUsartTxDma(s);
}
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
@ -411,8 +411,6 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
IO_t tx = IOGetByTag(uart->tx);
IO_t rx = IOGetByTag(uart->rx);
// clocks
if (options & SERIAL_BIDIR) {
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device));
IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af);
@ -455,7 +453,6 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option
void USART1_IRQHandler(void)
{
uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s);
}
#endif
@ -470,7 +467,6 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option
void USART2_IRQHandler(void)
{
uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s);
}
#endif
@ -485,7 +481,6 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option
void USART3_IRQHandler(void)
{
uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s);
}
#endif
@ -500,7 +495,6 @@ uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t option
void UART4_IRQHandler(void)
{
uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s);
}
#endif
@ -515,7 +509,6 @@ uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t option
void UART5_IRQHandler(void)
{
uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s);
}
#endif
@ -530,7 +523,6 @@ uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t option
void USART6_IRQHandler(void)
{
uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s);
}
#endif
@ -545,7 +537,6 @@ uartPort_t *serialUART7(uint32_t baudRate, portMode_t mode, portOptions_t option
void UART7_IRQHandler(void)
{
uartPort_t *s = &(uartHardwareMap[UARTDEV_7]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s);
}
#endif
@ -560,7 +551,6 @@ uartPort_t *serialUART8(uint32_t baudRate, portMode_t mode, portOptions_t option
void UART8_IRQHandler(void)
{
uartPort_t *s = &(uartHardwareMap[UARTDEV_8]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s);
}
#endif