Browse Source

HAL_ChibiOS: check for already allocated TX dma in UART driver

mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
dd8115c9b4
  1. 4
      libraries/AP_HAL_ChibiOS/UARTDriver.cpp

4
libraries/AP_HAL_ChibiOS/UARTDriver.cpp

@ -314,7 +314,9 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
void UARTDriver::dma_tx_allocate(Shared_DMA *ctx) void UARTDriver::dma_tx_allocate(Shared_DMA *ctx)
{ {
#if HAL_USE_SERIAL == TRUE #if HAL_USE_SERIAL == TRUE
osalDbgAssert(txdma == nullptr, "double DMA allocation"); if (txdma != nullptr) {
return;
}
chSysLock(); chSysLock();
txdma = dmaStreamAllocI(sdef.dma_tx_stream_id, txdma = dmaStreamAllocI(sdef.dma_tx_stream_id,
12, //IRQ Priority 12, //IRQ Priority

Loading…
Cancel
Save