Browse Source

GCS_MAVLink: flush parameters on reboot

mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
5de49aa5aa
  1. 6
      libraries/GCS_MAVLink/GCS_Common.cpp

6
libraries/GCS_MAVLink/GCS_Common.cpp

@ -1852,8 +1852,12 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa @@ -1852,8 +1852,12 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
// force safety on
hal.rcout->force_safety_on();
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
const bool hold_in_bootloader = is_equal(packet.param1, 3.0f);
hal.scheduler->reboot(hold_in_bootloader);

Loading…
Cancel
Save