AP_Soaring: Fix use of double precision sqrt.

This commit is contained in:
Samuel Tabor 2019-06-23 15:12:45 +01:00 committed by Andrew Tridgell
parent 7d3ff28974
commit 17f1fa9600

View File

@ -34,7 +34,7 @@ void Variometer::update(const float polar_K, const float polar_Cd0, const float
_aspd_filt = _sp_filter.apply(aspd);
// Constrained airspeed.
const float minV = sqrt(polar_K/1.5);
const float minV = sqrtf(polar_K/1.5);
_aspd_filt_constrained = _aspd_filt>minV ? _aspd_filt : minV;