mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed a race in DShot code
this fixes a problem found by Daniel Met with the copter 3.6 beta release
This commit is contained in:
parent
62f997d73c
commit
4a1348a432
|
@ -805,7 +805,9 @@ void RCOutput::dma_allocate(Shared_DMA *ctx)
|
|||
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
|
||||
pwm_group &group = pwm_group_list[i];
|
||||
if (group.dma_handle == ctx) {
|
||||
chSysLock();
|
||||
dmaStreamAllocate(group.dma, 10, dma_irq_callback, &group);
|
||||
chSysUnlock();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -818,7 +820,9 @@ void RCOutput::dma_deallocate(Shared_DMA *ctx)
|
|||
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
|
||||
pwm_group &group = pwm_group_list[i];
|
||||
if (group.dma_handle == ctx) {
|
||||
chSysLock();
|
||||
dmaStreamRelease(group.dma);
|
||||
chSysUnlock();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue