mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
HAL_ChibiOS: added DMAMUX channel assignment calls
This commit is contained in:
parent
f4e31ce65b
commit
071d5e01af
@ -823,6 +823,9 @@ void RCOutput::dma_allocate(Shared_DMA *ctx)
|
||||
chSysLock();
|
||||
group.dma = dmaStreamAllocI(group.dma_up_stream_id, 10, dma_irq_callback, &group);
|
||||
chSysUnlock();
|
||||
#if STM32_DMA_SUPPORTS_DMAMUX
|
||||
dmaSetRequestSource(group.dma, group.dma_up_channel);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -44,6 +44,9 @@ bool SoftSigReader::attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan,
|
||||
(void *)this);
|
||||
osalDbgAssert(dma, "stream allocation failed");
|
||||
chSysUnlock();
|
||||
#if STM32_DMA_SUPPORTS_DMAMUX
|
||||
dmaSetRequestSource(dma, dma_channel);
|
||||
#endif
|
||||
//setup address for full word transfer from Timer
|
||||
dmaStreamSetPeripheral(dma, &icu_drv->tim->DMAR);
|
||||
|
||||
|
@ -239,6 +239,9 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
#else
|
||||
dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->DR);
|
||||
#endif // STM32F7
|
||||
#if STM32_DMA_SUPPORTS_DMAMUX
|
||||
dmaSetRequestSource(rxdma, sdef.dma_rx_channel_id);
|
||||
#endif
|
||||
}
|
||||
if (sdef.dma_tx) {
|
||||
// we only allow for sharing of the TX DMA channel, not the RX
|
||||
@ -330,6 +333,9 @@ void UARTDriver::dma_tx_allocate(Shared_DMA *ctx)
|
||||
#else
|
||||
dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->DR);
|
||||
#endif // STM32F7
|
||||
#if STM32_DMA_SUPPORTS_DMAMUX
|
||||
dmaSetRequestSource(txdma, sdef.dma_tx_channel_id);
|
||||
#endif
|
||||
#endif // HAL_USE_SERIAL
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user