GCS_MAVLink: Alert GCS if user tries calibration while vehicle is armed
This commit is contained in:
parent
cbccdfa8a3
commit
f3e66055e5
@ -3537,6 +3537,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_calibration(const mavlink_comma
|
||||
{
|
||||
if (hal.util->get_soft_armed()) {
|
||||
// *preflight*, remember?
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE, "Disarm to allow calibration");
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
// now call subclass methods:
|
||||
|
Loading…
Reference in New Issue
Block a user