Sub: add armed check to preflight baro calibration

This commit is contained in:
Jacob Walser 2018-04-22 11:37:03 -04:00
parent 00bc528729
commit abf1a09909

View File

@ -1315,7 +1315,10 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
result = MAV_RESULT_FAILED;
}
} else if (is_equal(packet.param3,1.0f)) {
if (!sub.control_check_barometer() || sub.motors.armed()) {
if (sub.motors.armed()) {
sub.gcs_send_text(MAV_SEVERITY_INFO, "Disarm before calibration.");
result = MAV_RESULT_FAILED;
} else if (!sub.control_check_barometer()) {
result = MAV_RESULT_FAILED;
} else {
sub.init_barometer(true);