mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 00:33:56 -04:00
Sub: Remove pressure constraint on preflight baro calibration
This commit is contained in:
parent
35c03717fc
commit
cf9626f568
@ -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);
|
||||||
|
Loading…
Reference in New Issue
Block a user