mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
HAL_ChibiOS: fixed a race and null ptr deref in dshot
if a dshot is cancelled then the waiter can be nullptr
This commit is contained in:
parent
013415eb31
commit
eec05c1f48
@ -1360,8 +1360,11 @@ void RCOutput::dma_unlock(void *p)
|
||||
pwm_group *group = (pwm_group *)p;
|
||||
|
||||
group->dshot_state = DshotState::IDLE;
|
||||
// tell the waiting process we've done the DMA
|
||||
chEvtSignalI(group->dshot_waiter, group->dshot_event_mask);
|
||||
if (group->dshot_waiter != nullptr) {
|
||||
// tell the waiting process we've done the DMA. Note that
|
||||
// dshot_waiter can be null if we have cancelled the send
|
||||
chEvtSignalI(group->dshot_waiter, group->dshot_event_mask);
|
||||
}
|
||||
chSysUnlockFromISR();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user