GCS_MAVLink: allow forcing reboot via mavlink with parameter

This commit is contained in:
Peter Barker 2019-02-26 15:19:33 +11:00 committed by Andrew Tridgell
parent 289f76ac9c
commit fbeb9aa3fd

View File

@ -3011,9 +3011,13 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa
#endif
}
// refuse reboot when armed:
if (hal.util->get_soft_armed()) {
// refuse reboot when armed
return MAV_RESULT_FAILED;
/// but allow it if forced:
const float magic_force_reboot_value = 20190226;
if (!is_equal(packet.param6, magic_force_reboot_value)) {
return MAV_RESULT_FAILED;
}
}
if (!(is_equal(packet.param1, 1.0f) || is_equal(packet.param1, 3.0f))) {