Browse Source

AP_NavEKF: float to double promotion via tan instead of tanf

mission-4.1.18
Tom Pittenger 10 years ago committed by Andrew Tridgell
parent
commit
e987173ffb
  1. 2
      libraries/AP_NavEKF/AP_SmallEKF.cpp

2
libraries/AP_NavEKF/AP_SmallEKF.cpp

@ -727,7 +727,7 @@ void SmallEKF::fuseCompass() @@ -727,7 +727,7 @@ void SmallEKF::fuseCompass()
float t5757 = magX*t5756;
float t5758 = t5747-t5752+t5757;
float t5759 = t5742*t5758;
float t5723 = tan(t5759);
float t5723 = tanf(t5759);
float t5760 = sq(t5723);
float t5761 = t5760+1.0f;
float t5762 = 1.0f/sq(t5741);

Loading…
Cancel
Save