Sub: Remove pressure constraint on preflight baro calibration

This commit is contained in:
Jacob Walser 2017-08-22 14:09:29 -04:00
parent 35c03717fc
commit cf9626f568

View File

@ -1298,7 +1298,7 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
result = MAV_RESULT_FAILED; result = MAV_RESULT_FAILED;
} }
} else if (is_equal(packet.param3,1.0f)) { } 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; result = MAV_RESULT_FAILED;
} else { } else {
sub.init_barometer(true); sub.init_barometer(true);