GCS_MAVLink: do not process commands after we have decided to reboot

This commit is contained in:
Peter Barker 2020-06-16 14:21:40 +10:00 committed by Peter Barker
parent 34b17d0993
commit e4621e6921
1 changed files with 6 additions and 1 deletions

View File

@ -2645,8 +2645,13 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
// flush pending parameter writes
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);
// when packet.param1 == 3 we reboot to hold in bootloader
const bool hold_in_bootloader = is_equal(packet.param1, 3.0f);
hal.scheduler->reboot(hold_in_bootloader);