HAL_ChibiOS: check for already allocated TX dma in UART driver

This commit is contained in:
Andrew Tridgell 2019-02-10 21:05:23 +11:00
parent a4687930b0
commit dd8115c9b4
1 changed files with 3 additions and 1 deletions

View File

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