GCS_MAVLink: flush parameters on reboot

This commit is contained in:
Andrew Tridgell 2018-08-06 19:41:58 +10:00
parent f1e10b0a8f
commit 5de49aa5aa
1 changed files with 5 additions and 1 deletions

View File

@ -1852,6 +1852,10 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
// force safety on // force safety on
hal.rcout->force_safety_on(); hal.rcout->force_safety_on();
hal.rcout->force_safety_no_wait(); hal.rcout->force_safety_no_wait();
// flush pending parameter writes
AP_Param::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