mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: allow double allocate call in RCOutput
This commit is contained in:
parent
c02a271c8a
commit
d96142a37e
|
@ -819,8 +819,7 @@ void RCOutput::dma_allocate(Shared_DMA *ctx)
|
||||||
{
|
{
|
||||||
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
|
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
|
||||||
pwm_group &group = pwm_group_list[i];
|
pwm_group &group = pwm_group_list[i];
|
||||||
if (group.dma_handle == ctx) {
|
if (group.dma_handle == ctx && group.dma == nullptr) {
|
||||||
osalDbgAssert(group.dma == nullptr, "double DMA allocation");
|
|
||||||
chSysLock();
|
chSysLock();
|
||||||
group.dma = dmaStreamAllocI(group.dma_up_stream_id, 10, dma_irq_callback, &group);
|
group.dma = dmaStreamAllocI(group.dma_up_stream_id, 10, dma_irq_callback, &group);
|
||||||
chSysUnlock();
|
chSysUnlock();
|
||||||
|
|
Loading…
Reference in New Issue