mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: do not process commands after we have decided to reboot
This commit is contained in:
parent
34b17d0993
commit
e4621e6921
|
@ -2645,8 +2645,13 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
|
||||||
// flush pending parameter writes
|
// flush pending parameter writes
|
||||||
AP_Param::flush();
|
AP_Param::flush();
|
||||||
|
|
||||||
|
// do not process incoming mavlink messages while we delay:
|
||||||
|
hal.scheduler->register_delay_callback(nullptr, 5);
|
||||||
|
|
||||||
|
// 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);
|
hal.scheduler->delay(200);
|
||||||
|
|
||||||
// when packet.param1 == 3 we reboot to hold in bootloader
|
// when packet.param1 == 3 we reboot to hold in bootloader
|
||||||
const bool hold_in_bootloader = is_equal(packet.param1, 3.0f);
|
const bool hold_in_bootloader = is_equal(packet.param1, 3.0f);
|
||||||
hal.scheduler->reboot(hold_in_bootloader);
|
hal.scheduler->reboot(hold_in_bootloader);
|
||||||
|
|
Loading…
Reference in New Issue