From b8e82a56f36949378e78b1051eb9b9596b94a918 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 4 Feb 2021 09:04:15 +1100 Subject: [PATCH] HAL_ChibiOS: don't start rout ticks till after full system init this prevents an occasional boot hang on systems with DShot enabled. We shouldn't be starting DShot output till after setup() is complete as the outputs are still being configured --- libraries/AP_HAL_ChibiOS/Scheduler.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 21978ac27a..be0e10ed60 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -321,7 +321,9 @@ void Scheduler::_timer_thread(void *arg) sched->_run_timers(); // process any pending RC output requests - hal.rcout->timer_tick(); + if (sched->is_system_initialized()) { + hal.rcout->timer_tick(); + } if (sched->in_expected_delay()) { sched->watchdog_pat();