mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-01 11:13:58 -04:00
AP_Airspeed: fixed airspeed autocal
don't use negative pressures
This commit is contained in:
parent
a39cfda192
commit
5b4e57414d
@ -125,7 +125,7 @@ void AP_Airspeed::update_calibration(const Vector3f &vground, int16_t max_airspe
|
||||
_calibration.state.z = 1.0f / sqrtf(ratio);
|
||||
|
||||
// calculate true airspeed, assuming a airspeed ratio of 1.0
|
||||
float dpress = get_differential_pressure();
|
||||
float dpress = MAX(get_differential_pressure(), 0);
|
||||
float true_airspeed = sqrtf(dpress) * _EAS2TAS;
|
||||
|
||||
float zratio = _calibration.update(true_airspeed, vground, max_airspeed_allowed_during_cal);
|
||||
|
Loading…
Reference in New Issue
Block a user