mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 10:13:57 -04:00
AP_NavEKF: changed sqrt to sqrtf
This commit is contained in:
parent
1f0b4b02d0
commit
9d375da550
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user