AP_Math: fix uses of single precision

This commit is contained in:
Andrew Tridgell 2021-07-22 15:54:45 +10:00 committed by Randy Mackay
parent 92008ebb8f
commit 7f3bc8ba1f
3 changed files with 6 additions and 6 deletions

View File

@ -52,10 +52,10 @@ void Matrix3<T>::to_euler(T *roll, T *pitch, T *yaw) const
*pitch = -safe_asin(c.x);
}
if (roll != nullptr) {
*roll = atan2f(c.y, c.z);
*roll = atan2F(c.y, c.z);
}
if (yaw != nullptr) {
*yaw = atan2f(b.x, a.x);
*yaw = atan2F(b.x, a.x);
}
}
@ -81,8 +81,8 @@ template <typename T>
Vector3<T> Matrix3<T>::to_euler312() const
{
return Vector3<T>(asinF(c.y),
atan2f(-c.x, c.z),
atan2f(-a.y, b.y));
atan2F(-c.x, c.z),
atan2F(-a.y, b.y));
}
/*

View File

@ -161,7 +161,7 @@ T Vector2<T>::angle(const Vector2<T> &v2) const
template <typename T>
T Vector2<T>::angle(void) const
{
return M_PI_2 + atan2f(-x, y);
return M_PI_2 + atan2F(-x, y);
}
// find the intersection between two line segments

View File

@ -418,7 +418,7 @@ T Vector3<T>::angle(const Vector3<T> &v2) const
return 0.0f;
}
const T cosv = ((*this)*v2) / len;
if (fabsf(cosv) >= 1) {
if (fabsF(cosv) >= 1) {
return 0.0f;
}
return acosF(cosv);