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:
Andrew Tridgell 2021-02-24 12:48:39 +11:00
parent 013415eb31
commit eec05c1f48
1 changed files with 5 additions and 2 deletions

View File

@ -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();
}