AP_Soaring: Change from division to multiplication

This commit is contained in:
murata 2022-03-12 02:38:04 +09:00 committed by Andrew Tridgell
parent af3fbac118
commit a1a46b54e9

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 / 100.0f;
aspd = _aparm.airspeed_cruise_cm * 0.01f;
}
float aspd_filt = _sp_filter.apply(aspd);