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
This commit is contained in:
parent
a09bdcdda1
commit
b8e82a56f3
@ -321,7 +321,9 @@ void Scheduler::_timer_thread(void *arg)
|
|||||||
sched->_run_timers();
|
sched->_run_timers();
|
||||||
|
|
||||||
// process any pending RC output requests
|
// process any pending RC output requests
|
||||||
hal.rcout->timer_tick();
|
if (sched->is_system_initialized()) {
|
||||||
|
hal.rcout->timer_tick();
|
||||||
|
}
|
||||||
|
|
||||||
if (sched->in_expected_delay()) {
|
if (sched->in_expected_delay()) {
|
||||||
sched->watchdog_pat();
|
sched->watchdog_pat();
|
||||||
|
Loading…
Reference in New Issue
Block a user