AP_NavEKF: changed sqrt to sqrtf

This commit is contained in:
Paul Riseborough 2014-01-16 06:14:48 +11:00 committed by Andrew Tridgell
parent 1f0b4b02d0
commit 9d375da550

View File

@ -1814,7 +1814,7 @@ void NavEKF::FuseAirspeed()
if (VtasPred > 1.0f)
{
// Calculate observation jacobians
SH_TAS[0] = 1.0f/(sqrt(sq(ve - vwe) + sq(vn - vwn) + sq(vd)));
SH_TAS[0] = 1.0f/(sqrtf(sq(ve - vwe) + sq(vn - vwn) + sq(vd)));
SH_TAS[1] = (SH_TAS[0]*(2*ve - 2*vwe))/2;
SH_TAS[2] = (SH_TAS[0]*(2*vn - 2*vwn))/2;
for (uint8_t i=0; i<=21; i++) H_TAS[i] = 0.0f;