Browse Source

GCS_MAVLink: disable reboot when armed

this prevents reboot on vehicles that have ARMING_REQUIRE=0, which
applies to some planes, but those vehicles tend to not use MAVLink
reboot anyway.
mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
778b88cba2
  1. 5
      libraries/GCS_MAVLink/GCS_Common.cpp

5
libraries/GCS_MAVLink/GCS_Common.cpp

@ -2507,6 +2507,11 @@ void GCS_MAVLINK::zero_rc_outputs() @@ -2507,6 +2507,11 @@ void GCS_MAVLINK::zero_rc_outputs()
*/
MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &packet)
{
if (hal.util->get_soft_armed()) {
// refuse reboot when armed
return MAV_RESULT_FAILED;
}
if (!(is_equal(packet.param1, 1.0f) || is_equal(packet.param1, 3.0f))) {
// param1 must be 1 or 3 - 1 being reboot, 3 being reboot-to-bootloader
return MAV_RESULT_UNSUPPORTED;

Loading…
Cancel
Save