mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
SITL: use sinf() and cosf()
for some strange reason the double precision functions can crash
This commit is contained in:
parent
bb0eed5c14
commit
9e3bf685c2
@ -132,8 +132,8 @@ void SITL::convert_body_frame(double rollDeg, double pitchDeg,
|
||||
thetaDot = ToRad(pitchRate);
|
||||
psiDot = ToRad(yawRate);
|
||||
|
||||
*p = phiDot - psiDot*sin(theta);
|
||||
*q = cos(phi)*thetaDot + sin(phi)*psiDot*cos(theta);
|
||||
*r = cos(phi)*psiDot*cos(theta) - sin(phi)*thetaDot;
|
||||
*p = phiDot - psiDot*sinf(theta);
|
||||
*q = cosf(phi)*thetaDot + sinf(phi)*psiDot*cosf(theta);
|
||||
*r = cosf(phi)*psiDot*cosf(theta) - sinf(phi)*thetaDot;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user