Browse Source

HAL_ChibiOS: improve reliability of reboot

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

8
libraries/AP_HAL_ChibiOS/Scheduler.cpp

@ -245,11 +245,11 @@ void Scheduler::reboot(bool hold_in_bootloader)
// 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 // disable interrupts
delay(500); disable_interrupts_save();
// disable interrupts during reboot // wait for 1ms to ensure all pending DMAs are complete
chSysDisable(); delay_microseconds(1000);
// reboot // reboot
NVIC_SystemReset(); NVIC_SystemReset();

Loading…
Cancel
Save