mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Sub: Remove pressure constraint on preflight baro calibration
This commit is contained in:
parent
7137d13817
commit
4ee6d8e980
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user