mirror of https://github.com/ArduPilot/ardupilot
Sub: better check and text message for baro calibration failure
This commit is contained in:
parent
dce3b615b5
commit
00bc528729
|
@ -1315,7 +1315,7 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
|
|||
result = MAV_RESULT_FAILED;
|
||||
}
|
||||
} else if (is_equal(packet.param3,1.0f)) {
|
||||
if (!sub.sensor_health.depth || sub.motors.armed()) {
|
||||
if (!sub.control_check_barometer() || sub.motors.armed()) {
|
||||
result = MAV_RESULT_FAILED;
|
||||
} else {
|
||||
sub.init_barometer(true);
|
||||
|
|
Loading…
Reference in New Issue