AP_Soaring: change TRIM_ARSPD_CM to AIRSPEED_CRUISE

This commit is contained in:
Andrew Tridgell 2024-01-18 13:34:22 +11:00
parent ed13b97526
commit ed9180154a
1 changed files with 1 additions and 1 deletions

View File

@ -21,7 +21,7 @@ void Variometer::update(const float thermal_bank)
float aspd = 0;
if (!_ahrs.airspeed_estimate(aspd)) {
aspd = _aparm.airspeed_cruise_cm * 0.01f;
aspd = _aparm.airspeed_cruise;
}
float aspd_filt = _sp_filter.apply(aspd);