1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 08:15:30 +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

@ -85,9 +85,11 @@ static void uartReconfigure(uartPort_t *uartPort)
if (uartPort->port.mode & MODE_TX) if (uartPort->port.mode & MODE_TX)
uartPort->Handle.Init.Mode |= UART_MODE_TX; uartPort->Handle.Init.Mode |= UART_MODE_TX;
SET_BIT(uartPort->USARTx->CR3, USART_CR3_OVRDIS);
usartConfigurePinInversion(uartPort); usartConfigurePinInversion(uartPort);
HAL_UART_IRQHandler(&uartPort->Handle);
if(uartPort->port.options & SERIAL_BIDIR) if(uartPort->port.options & SERIAL_BIDIR)
{ {
status = HAL_HalfDuplex_Init(&uartPort->Handle); status = HAL_HalfDuplex_Init(&uartPort->Handle);
@ -96,6 +98,86 @@ static void uartReconfigure(uartPort_t *uartPort)
{ {
status = HAL_UART_Init(&uartPort->Handle); status = HAL_UART_Init(&uartPort->Handle);
} }
// Receive DMA or IRQ
if (uartPort->port.mode & MODE_RX)
{
if (uartPort->rxDMAStream)
{
uartPort->rxDMAHandle.Instance = uartPort->rxDMAStream;
uartPort->rxDMAHandle.Init.Channel = uartPort->rxDMAChannel;
uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
uartPort->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
uartPort->rxDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
uartPort->rxDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
uartPort->rxDMAHandle.Init.Mode = DMA_CIRCULAR;
uartPort->rxDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
uartPort->rxDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
uartPort->rxDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
uartPort->rxDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
HAL_DMA_DeInit(&uartPort->rxDMAHandle);
HAL_DMA_Init(&uartPort->rxDMAHandle);
/* Associate the initialized DMA handle to the UART handle */
__HAL_LINKDMA(&uartPort->Handle, hdmarx, uartPort->rxDMAHandle);
HAL_UART_Receive_DMA(&uartPort->Handle, (uint8_t*)uartPort->port.rxBuffer, uartPort->port.rxBufferSize);
uartPort->rxDMAPos = __HAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle);
}
else
{
//__HAL_UART_ENABLE_IT(&s->Handle, UART_IT_RXNE);
/* Enable the UART Parity Error Interrupt */
SET_BIT(uartPort->USARTx->CR1, USART_CR1_PEIE);
/* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */
SET_BIT(uartPort->USARTx->CR3, USART_CR3_EIE);
/* Enable the UART Data Register not empty Interrupt */
SET_BIT(uartPort->USARTx->CR1, USART_CR1_RXNEIE);
//HAL_UART_Receive_IT(&s->Handle, (uint8_t*)s->port.rxBuffer, 1);
}
}
// Transmit DMA or IRQ
if (uartPort->port.mode & MODE_TX) {
if (uartPort->txDMAStream) {
uartPort->txDMAHandle.Instance = uartPort->txDMAStream;
uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel;
uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH;
uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
uartPort->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
uartPort->txDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
uartPort->txDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
uartPort->txDMAHandle.Init.Mode = DMA_NORMAL;
uartPort->txDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
uartPort->txDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
uartPort->txDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
uartPort->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
HAL_DMA_DeInit(&uartPort->txDMAHandle);
HAL_StatusTypeDef status = HAL_DMA_Init(&uartPort->txDMAHandle);
if(status != HAL_OK)
{
while(1);
}
/* Associate the initialized DMA handle to the UART handle */
__HAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle);
// __HAL_DMA_ENABLE_IT(s->txDMAHandle, DMA_IT_TC|DMA_IT_FE|DMA_IT_TE|DMA_IT_DME);
__HAL_DMA_SET_COUNTER(&uartPort->txDMAHandle, 0);
} else {
__HAL_UART_ENABLE_IT(&uartPort->Handle, UART_IT_TXE);
}
}
return; return;
} }
@ -151,79 +233,6 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
uartReconfigure(s); uartReconfigure(s);
// Receive DMA or IRQ
if (mode & MODE_RX)
{
if (s->rxDMAStream)
{
s->rxDMAHandle.Instance = s->rxDMAStream;
s->rxDMAHandle.Init.Channel = s->rxDMAChannel;
s->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
s->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
s->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
s->rxDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
s->rxDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
s->rxDMAHandle.Init.Mode = DMA_CIRCULAR;
s->rxDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
s->rxDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
s->rxDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
s->rxDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
s->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
HAL_DMA_DeInit(&s->rxDMAHandle);
HAL_DMA_Init(&s->rxDMAHandle);
/* Associate the initialized DMA handle to the UART handle */
__HAL_LINKDMA(&s->Handle, hdmarx, s->rxDMAHandle);
HAL_UART_Receive_DMA(&s->Handle, (uint8_t*)s->port.rxBuffer, s->port.rxBufferSize);
s->rxDMAPos = __HAL_DMA_GET_COUNTER(&s->rxDMAHandle);
}
else
{
// __HAL_UART_CLEAR_IT(&cfg.uartport->Handle, UART_FLAG_RXNE);
// __HAL_UART_ENABLE_IT(&cfg.uartport->Handle, UART_IT_RXNE);
HAL_UART_Receive_IT(&s->Handle, (uint8_t*)s->port.rxBuffer, s->port.rxBufferSize);
}
}
// Transmit DMA or IRQ
if (mode & MODE_TX) {
if (s->txDMAStream) {
s->txDMAHandle.Instance = s->txDMAStream;
s->txDMAHandle.Init.Channel = s->txDMAChannel;
s->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH;
s->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
s->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
s->txDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
s->txDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
s->txDMAHandle.Init.Mode = DMA_NORMAL;
s->txDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
s->txDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
s->txDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
s->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
s->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
HAL_DMA_DeInit(&s->txDMAHandle);
HAL_StatusTypeDef status = HAL_DMA_Init(&s->txDMAHandle);
if(status != HAL_OK)
{
while(1);
}
/* Associate the initialized DMA handle to the UART handle */
__HAL_LINKDMA(&s->Handle, hdmatx, s->txDMAHandle);
// __HAL_DMA_ENABLE_IT(s->txDMAHandle, DMA_IT_TC|DMA_IT_FE|DMA_IT_TE|DMA_IT_DME);
__HAL_DMA_SET_COUNTER(&s->txDMAHandle, 0);
} else {
__HAL_UART_ENABLE_IT(&s->Handle, UART_IT_TXE);
}
}
return (serialPort_t *)s; return (serialPort_t *)s;
} }
@ -243,23 +252,21 @@ void uartSetMode(serialPort_t *instance, portMode_t mode)
void uartStartTxDMA(uartPort_t *s) void uartStartTxDMA(uartPort_t *s)
{ {
HAL_UART_StateTypeDef state = HAL_UART_GetState(&s->Handle);
if((state & HAL_UART_STATE_BUSY_TX) == HAL_UART_STATE_BUSY_TX)
return;
uint16_t size = 0; uint16_t size = 0;
// HAL_UART_DMAStop(&s->Handle); uint32_t fromwhere=0;
//HAL_UART_DMAStop(&s->Handle);
if (s->port.txBufferHead > s->port.txBufferTail) { if (s->port.txBufferHead > s->port.txBufferTail) {
size = s->port.txBufferHead - s->port.txBufferTail; size = s->port.txBufferHead - s->port.txBufferTail;
HAL_UART_Transmit_DMA(&s->Handle, (uint8_t *)&s->port.txBuffer[s->port.txBufferTail], size); fromwhere = s->port.txBufferTail;
s->port.txBufferTail = s->port.txBufferHead; s->port.txBufferTail = s->port.txBufferHead;
} else { } else {
size = s->port.txBufferSize - s->port.txBufferTail; size = s->port.txBufferSize - s->port.txBufferTail;
HAL_UART_Transmit_DMA(&s->Handle, (uint8_t *)&s->port.txBuffer[s->port.txBufferTail], size); fromwhere = s->port.txBufferTail;
s->port.txBufferTail = 0; s->port.txBufferTail = 0;
} }
s->txDMAEmpty = false; s->txDMAEmpty = false;
HAL_UART_Transmit_DMA(&s->Handle, (uint8_t *)&s->port.txBuffer[fromwhere], size);
} }
uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance) uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance)

View file

@ -236,8 +236,8 @@ static uartDevice_t uart8 =
#endif #endif
.txDMAStream = DMA1_Stream0, .txDMAStream = DMA1_Stream0,
.dev = UART8, .dev = UART8,
.rx = IO_TAG(UART6_RX_PIN), .rx = IO_TAG(UART8_RX_PIN),
.tx = IO_TAG(UART6_TX_PIN), .tx = IO_TAG(UART8_TX_PIN),
.af = GPIO_AF8_UART8, .af = GPIO_AF8_UART8,
#ifdef UART8_AHB1_PERIPHERALS #ifdef UART8_AHB1_PERIPHERALS
.rcc_ahb1 = UART8_AHB1_PERIPHERALS, .rcc_ahb1 = UART8_AHB1_PERIPHERALS,
@ -297,48 +297,67 @@ static uartDevice_t* uartHardwareMap[] = {
void uartIrqHandler(uartPort_t *s) 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) { 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(rbyte);
s->port.callback(s->USARTx->RDR);
s->Handle.pRxBuffPtr = (uint8_t *)s->port.rxBuffer;
} else { } 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->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 /* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */
s->Handle.RxXferCount = s->Handle.RxXferSize; CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE);
uint32_t errorcode = HAL_UART_GetError(&s->Handle); __HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST);
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);
}
}
} }
if (!s->txDMAStream && (s->Handle.TxXferCount == 0)) { /* UART parity error interrupt occurred -------------------------------------*/
if (s->port.txBufferTail != s->port.txBufferHead) { if((__HAL_UART_GET_IT(huart, UART_IT_PE) != RESET))
// 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); __HAL_UART_CLEAR_IT(huart, UART_CLEAR_PEF);
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
}
} }
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); handleUsartTxDma(s);
} }*/
} }
static void handleUsartTxDma(uartPort_t *s) static void handleUsartTxDma(uartPort_t *s)
@ -348,34 +367,15 @@ static void handleUsartTxDma(uartPort_t *s)
else else
{ {
s->txDMAEmpty = true; s->txDMAEmpty = true;
s->Handle.TxXferSize = 0; s->Handle.gState = HAL_UART_STATE_READY;
} }
} }
void dmaIRQHandler(dmaChannelDescriptor_t* descriptor) void dmaIRQHandler(dmaChannelDescriptor_t* descriptor)
{ {
uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port); uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
HAL_DMA_IRQHandler(&s->txDMAHandle); HAL_DMA_IRQHandler(&s->txDMAHandle);
handleUsartTxDma(s);
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);
}
} }
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options) 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 tx = IOGetByTag(uart->tx);
IO_t rx = IOGetByTag(uart->rx); IO_t rx = IOGetByTag(uart->rx);
// clocks
if (options & SERIAL_BIDIR) { if (options & SERIAL_BIDIR) {
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device)); IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device));
IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af); 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) void USART1_IRQHandler(void)
{ {
uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port); uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s); uartIrqHandler(s);
} }
#endif #endif
@ -470,7 +467,6 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option
void USART2_IRQHandler(void) void USART2_IRQHandler(void)
{ {
uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port); uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s); uartIrqHandler(s);
} }
#endif #endif
@ -485,7 +481,6 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option
void USART3_IRQHandler(void) void USART3_IRQHandler(void)
{ {
uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port); uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s); uartIrqHandler(s);
} }
#endif #endif
@ -500,7 +495,6 @@ uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t option
void UART4_IRQHandler(void) void UART4_IRQHandler(void)
{ {
uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port); uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s); uartIrqHandler(s);
} }
#endif #endif
@ -515,7 +509,6 @@ uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t option
void UART5_IRQHandler(void) void UART5_IRQHandler(void)
{ {
uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port); uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s); uartIrqHandler(s);
} }
#endif #endif
@ -530,7 +523,6 @@ uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t option
void USART6_IRQHandler(void) void USART6_IRQHandler(void)
{ {
uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port); uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s); uartIrqHandler(s);
} }
#endif #endif
@ -545,7 +537,6 @@ uartPort_t *serialUART7(uint32_t baudRate, portMode_t mode, portOptions_t option
void UART7_IRQHandler(void) void UART7_IRQHandler(void)
{ {
uartPort_t *s = &(uartHardwareMap[UARTDEV_7]->port); uartPort_t *s = &(uartHardwareMap[UARTDEV_7]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s); uartIrqHandler(s);
} }
#endif #endif
@ -560,7 +551,6 @@ uartPort_t *serialUART8(uint32_t baudRate, portMode_t mode, portOptions_t option
void UART8_IRQHandler(void) void UART8_IRQHandler(void)
{ {
uartPort_t *s = &(uartHardwareMap[UARTDEV_8]->port); uartPort_t *s = &(uartHardwareMap[UARTDEV_8]->port);
HAL_UART_IRQHandler(&s->Handle);
uartIrqHandler(s); uartIrqHandler(s);
} }
#endif #endif

View file

@ -526,7 +526,7 @@ void init(void)
#if defined(LED_STRIP) && defined(WS2811_DMA_CHANNEL) #if defined(LED_STRIP) && defined(WS2811_DMA_CHANNEL)
// Ensure the SPI Tx DMA doesn't overlap with the led strip // Ensure the SPI Tx DMA doesn't overlap with the led strip
#ifdef STM32F4 #if defined(STM32F4) || defined(STM32F7)
sdcardUseDMA = !feature(FEATURE_LED_STRIP) || SDCARD_DMA_CHANNEL_TX != WS2811_DMA_STREAM; sdcardUseDMA = !feature(FEATURE_LED_STRIP) || SDCARD_DMA_CHANNEL_TX != WS2811_DMA_STREAM;
#else #else
sdcardUseDMA = !feature(FEATURE_LED_STRIP) || SDCARD_DMA_CHANNEL_TX != WS2811_DMA_CHANNEL; sdcardUseDMA = !feature(FEATURE_LED_STRIP) || SDCARD_DMA_CHANNEL_TX != WS2811_DMA_CHANNEL;

View file

@ -45,7 +45,7 @@
#define MPU_INT_EXTI PC4 #define MPU_INT_EXTI PC4
#define USE_EXTI #define USE_EXTI
//#define MAG #define MAG
//#define USE_MAG_HMC5883 //#define USE_MAG_HMC5883
//#define HMC5883_BUS I2C_DEVICE_EXT //#define HMC5883_BUS I2C_DEVICE_EXT
//#define MAG_HMC5883_ALIGN CW270_DEG_FLIP //#define MAG_HMC5883_ALIGN CW270_DEG_FLIP

View file

@ -268,10 +268,10 @@ void SystemInit(void)
#endif #endif
/* Enable I-Cache */ /* Enable I-Cache */
SCB_EnableICache(); //SCB_EnableICache();
/* Enable D-Cache */ /* Enable D-Cache */
SCB_EnableDCache(); //SCB_EnableDCache();
/* Configure the system clock to 216 MHz */ /* Configure the system clock to 216 MHz */
SystemClock_Config(); SystemClock_Config();