From 168e860f70cd87670a0bf61a0840dd52725d853f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 9 Jul 2021 14:03:04 +1000 Subject: [PATCH] AP_Math: fixed a few more single precision calls --- libraries/AP_Math/tests/test_vector2.cpp | 2 +- libraries/AP_Math/vector2.cpp | 2 +- libraries/AP_Math/vector3.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Math/tests/test_vector2.cpp b/libraries/AP_Math/tests/test_vector2.cpp index c695e0d599..e0b460a9ce 100644 --- a/libraries/AP_Math/tests/test_vector2.cpp +++ b/libraries/AP_Math/tests/test_vector2.cpp @@ -109,7 +109,7 @@ TEST(Vector2Test, angle) { EXPECT_FLOAT_EQ(M_PI/2, Vector2f(0, 1).angle()); EXPECT_FLOAT_EQ(M_PI/4, Vector2f(1, 1).angle()); - EXPECT_FLOAT_EQ(0.0f, Vector2f(1, 0).angle()); + EXPECT_FLOAT_EQ(0.0f, Vector2d(1, 0).angle()); EXPECT_FLOAT_EQ(M_PI*5/4, Vector2f(-1, -1).angle()); EXPECT_FLOAT_EQ(M_PI*5/4, Vector2f(-5, -5).angle()); diff --git a/libraries/AP_Math/vector2.cpp b/libraries/AP_Math/vector2.cpp index 7bd72ce7d4..35d4826597 100644 --- a/libraries/AP_Math/vector2.cpp +++ b/libraries/AP_Math/vector2.cpp @@ -161,7 +161,7 @@ T Vector2::angle(const Vector2 &v2) const template T Vector2::angle(void) const { - return M_PI_2 + atan2f(-x, y); + return M_PI_2 + atan2F(-x, y); } // find the intersection between two line segments diff --git a/libraries/AP_Math/vector3.cpp b/libraries/AP_Math/vector3.cpp index 0457579010..4e842b31aa 100644 --- a/libraries/AP_Math/vector3.cpp +++ b/libraries/AP_Math/vector3.cpp @@ -418,7 +418,7 @@ T Vector3::angle(const Vector3 &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);