mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
GCS_MAVLink: flush parameters on reboot
This commit is contained in:
parent
f1e10b0a8f
commit
5de49aa5aa
@ -1852,8 +1852,12 @@ 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();
|
||||||
hal.scheduler->delay(200);
|
|
||||||
|
|
||||||
|
// flush pending parameter writes
|
||||||
|
AP_Param::flush();
|
||||||
|
|
||||||
|
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
Block a user