From eec05c1f48a2e5cd050fc7c02fe36d0be33cc19c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 24 Feb 2021 12:48:39 +1100 Subject: [PATCH] HAL_ChibiOS: fixed a race and null ptr deref in dshot if a dshot is cancelled then the waiter can be nullptr --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index c625238aad..40da4eb60a 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -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(); }