Browse Source

AP_Vehicle: ensure reboot command ACK is written out in SITL

zr-v5.1
Peter Barker 4 years ago committed by Andrew Tridgell
parent
commit
749d4c997b
  1. 5
      libraries/AP_Vehicle/AP_Vehicle.cpp

5
libraries/AP_Vehicle/AP_Vehicle.cpp

@ -334,6 +334,11 @@ void AP_Vehicle::reboot(bool hold_in_bootloader) @@ -334,6 +334,11 @@ void AP_Vehicle::reboot(bool hold_in_bootloader)
// do not process incoming mavlink messages while we delay:
hal.scheduler->register_delay_callback(nullptr, 5);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// need to ensure the ack goes out:
hal.serial(0)->flush();
#endif
// delay to give the ACK a chance to get out, the LEDs to flash,
// the IO board safety to be forced on, the parameters to flush, ...
hal.scheduler->delay(200);

Loading…
Cancel
Save