AP_Soaring: move to airspeed_estimate with pointer

This commit is contained in:
Peter Hall 2020-01-07 00:50:54 +00:00 committed by WickedShell
parent d16de83e3f
commit 850eee2f84

View File

@ -22,7 +22,7 @@ void Variometer::update(const float polar_K, const float polar_B, const float po
// Both filtered total energy rates and unfiltered are computed for the thermal switching logic and the EKF // Both filtered total energy rates and unfiltered are computed for the thermal switching logic and the EKF
float aspd = 0; float aspd = 0;
float roll = _ahrs.roll; float roll = _ahrs.roll;
if (!_ahrs.airspeed_estimate(&aspd)) { if (!_ahrs.airspeed_estimate(aspd)) {
aspd = _aparm.airspeed_cruise_cm / 100.0f; aspd = _aparm.airspeed_cruise_cm / 100.0f;
} }
_aspd_filt = ASPD_FILT * aspd + (1 - ASPD_FILT) * _aspd_filt; _aspd_filt = ASPD_FILT * aspd + (1 - ASPD_FILT) * _aspd_filt;