Sub: Remove pressure constraint on preflight baro calibration

This commit is contained in:
Jacob Walser 2017-08-22 14:09:29 -04:00 committed by jaxxzer
parent 7137d13817
commit 4ee6d8e980

View File

@ -1123,7 +1123,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() || sub.barometer.get_pressure() > 110000) {
if (!sub.sensor_health.depth || sub.motors.armed()) {
result = MAV_RESULT_FAILED;
} else {
sub.init_barometer(true);