Browse Source

HAL_ChibiOS: improve reliability of reboot

mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
79ca1e76c0
  1. 10
      libraries/AP_HAL_ChibiOS/Scheduler.cpp

10
libraries/AP_HAL_ChibiOS/Scheduler.cpp

@ -244,12 +244,12 @@ void Scheduler::reboot(bool hold_in_bootloader)
// lock all shared DMA channels. This has the effect of waiting // lock all shared DMA channels. This has the effect of waiting
// till the sensor buses are idle // till the sensor buses are idle
Shared_DMA::lock_all(); Shared_DMA::lock_all();
// delay to ensure the async force_saftey operation completes
delay(500);
// disable interrupts during reboot // disable interrupts
chSysDisable(); disable_interrupts_save();
// wait for 1ms to ensure all pending DMAs are complete
delay_microseconds(1000);
// reboot // reboot
NVIC_SystemReset(); NVIC_SystemReset();

Loading…
Cancel
Save