1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 21:35:44 +03:00

Merge pull request #3349 from jflyper/bfdev-fix-dma-corruption-updated

F4 Fix UART TX DMA corruption
This commit is contained in:
jflyper 2017-07-19 22:59:43 +09:00 committed by GitHub
commit dbbd7aef4b
7 changed files with 94 additions and 45 deletions

View file

@ -11,6 +11,7 @@
#define NVIC_PRIO_MPU_INT_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_MAG_INT_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_WS2811_DMA NVIC_BUILD_PRIORITY(1, 2) // TODO - is there some reason to use high priority? (or to use DMA IRQ at all?)
#define NVIC_PRIO_SERIALUART_TXDMA NVIC_BUILD_PRIORITY(1, 1) // Highest of all SERIALUARTx_TXDMA
#define NVIC_PRIO_SERIALUART1_TXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART1_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART1 NVIC_BUILD_PRIORITY(1, 1)

View file

@ -28,10 +28,14 @@
#include "platform.h"
#include "build/build_config.h"
#include "build/atomic.h"
#include "common/utils.h"
#include "drivers/dma.h"
#include "drivers/gpio.h"
#include "drivers/inverter.h"
#include "drivers/nvic.h"
#include "drivers/rcc.h"
#include "drivers/serial.h"
@ -52,10 +56,36 @@ void uartSetMode(serialPort_t *instance, portMode_t mode)
uartReconfigure(uartPort);
}
void uartStartTxDMA(uartPort_t *s)
void uartTryStartTxDMA(uartPort_t *s)
{
// uartTryStartTxDMA must be protected, since it is called from
// uartWrite and handleUsartTxDma (an ISR).
ATOMIC_BLOCK(NVIC_PRIO_SERIALUART_TXDMA) {
#ifdef STM32F4
DMA_Cmd(s->txDMAStream, DISABLE);
if (s->txDMAStream->CR & 1) {
// DMA is already in progress
return;
}
// For F4 (and F1), there are cases that NDTR (CNDTR for F1) is non-zero upon TC interrupt.
// We couldn't find out the root cause, so mask the case here.
if (s->txDMAStream->NDTR) {
// Possible premature TC case.
goto reenable;
}
// DMA_Cmd(s->txDMAStream, DISABLE); // XXX It's already disabled.
if (s->port.txBufferHead == s->port.txBufferTail) {
// No more data to transmit.
s->txDMAEmpty = true;
return;
}
// Start a new transaction.
DMA_MemoryTargetConfig(s->txDMAStream, (uint32_t)&s->port.txBuffer[s->port.txBufferTail], DMA_Memory_0);
//s->txDMAStream->M0AR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail];
if (s->port.txBufferHead > s->port.txBufferTail) {
@ -67,8 +97,32 @@ void uartStartTxDMA(uartPort_t *s)
s->port.txBufferTail = 0;
}
s->txDMAEmpty = false;
reenable:
DMA_Cmd(s->txDMAStream, ENABLE);
#else
if (s->txDMAChannel->CCR & 1) {
// DMA is already in progress
return;
}
// For F1 (and F4), there are cases that CNDTR (NDTR for F4) is non-zero upon TC interrupt.
// We couldn't find out the root cause, so mask the case here.
// F3 is not confirmed to be vulnerable, but not excluded as a safety.
if (s->txDMAChannel->CNDTR) {
// Possible premature TC case.
goto reenable;
}
if (s->port.txBufferHead == s->port.txBufferTail) {
// No more data to transmit.
s->txDMAEmpty = true;
return;
}
// Start a new transaction.
s->txDMAChannel->CMAR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail];
if (s->port.txBufferHead > s->port.txBufferTail) {
s->txDMAChannel->CNDTR = s->port.txBufferHead - s->port.txBufferTail;
@ -78,8 +132,11 @@ void uartStartTxDMA(uartPort_t *s)
s->port.txBufferTail = 0;
}
s->txDMAEmpty = false;
reenable:
DMA_Cmd(s->txDMAChannel, ENABLE);
#endif
}
}
uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance)
@ -198,13 +255,12 @@ void uartWrite(serialPort_t *instance, uint8_t ch)
}
#ifdef STM32F4
if (s->txDMAStream) {
if (!(s->txDMAStream->CR & 1))
if (s->txDMAStream)
#else
if (s->txDMAChannel) {
if (!(s->txDMAChannel->CCR & 1))
if (s->txDMAChannel)
#endif
uartStartTxDMA(s);
{
uartTryStartTxDMA(s);
} else {
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
}

View file

@ -161,7 +161,11 @@ extern uartDevice_t *uartDevmap[];
extern const struct serialPortVTable uartVTable[];
#ifdef USE_HAL_DRIVER
void uartStartTxDMA(uartPort_t *s);
#else
void uartTryStartTxDMA(uartPort_t *s);
#endif
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options);

View file

@ -109,12 +109,9 @@ void uart_tx_dma_IRQHandler(dmaChannelDescriptor_t* descriptor)
{
uartPort_t *s = (uartPort_t*)(descriptor->userParam);
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
DMA_Cmd(descriptor->ref, DISABLE);
DMA_Cmd(descriptor->ref, DISABLE); // XXX F1 needs this!!!
if (s->port.txBufferHead != s->port.txBufferTail)
uartStartTxDMA(s);
else
s->txDMAEmpty = true;
uartTryStartTxDMA(s);
}
// XXX Should serialUART be consolidated?

View file

@ -170,10 +170,7 @@ static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor)
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
DMA_Cmd(descriptor->ref, DISABLE);
if (s->port.txBufferHead != s->port.txBufferTail)
uartStartTxDMA(s);
else
s->txDMAEmpty = true;
uartTryStartTxDMA(s);
}
void serialUARTInitIO(IO_t txIO, IO_t rxIO, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index)

View file

@ -166,12 +166,7 @@ const uartHardware_t uartHardware[UARTDEV_COUNT] = {
static void handleUsartTxDma(uartPort_t *s)
{
DMA_Cmd(s->txDMAStream, DISABLE);
if (s->port.txBufferHead != s->port.txBufferTail)
uartStartTxDMA(s);
else
s->txDMAEmpty = true;
uartTryStartTxDMA(s);
}
void dmaIRQHandler(dmaChannelDescriptor_t* descriptor)

View file

@ -149,7 +149,6 @@
#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_UART3
#define UART3_RX_PIN PB11