mirror of https://github.com/ArduPilot/ardupilot
AP_Math: fixed a few more single precision calls
This commit is contained in:
parent
56d9134e38
commit
168e860f70
|
@ -109,7 +109,7 @@ TEST(Vector2Test, angle)
|
||||||
{
|
{
|
||||||
EXPECT_FLOAT_EQ(M_PI/2, Vector2f(0, 1).angle());
|
EXPECT_FLOAT_EQ(M_PI/2, Vector2f(0, 1).angle());
|
||||||
EXPECT_FLOAT_EQ(M_PI/4, Vector2f(1, 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(-1, -1).angle());
|
||||||
EXPECT_FLOAT_EQ(M_PI*5/4, Vector2f(-5, -5).angle());
|
EXPECT_FLOAT_EQ(M_PI*5/4, Vector2f(-5, -5).angle());
|
||||||
|
|
||||||
|
|
|
@ -161,7 +161,7 @@ T Vector2<T>::angle(const Vector2<T> &v2) const
|
||||||
template <typename T>
|
template <typename T>
|
||||||
T Vector2<T>::angle(void) const
|
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
|
// find the intersection between two line segments
|
||||||
|
|
|
@ -418,7 +418,7 @@ T Vector3<T>::angle(const Vector3<T> &v2) const
|
||||||
return 0.0f;
|
return 0.0f;
|
||||||
}
|
}
|
||||||
const T cosv = ((*this)*v2) / len;
|
const T cosv = ((*this)*v2) / len;
|
||||||
if (fabsf(cosv) >= 1) {
|
if (fabsF(cosv) >= 1) {
|
||||||
return 0.0f;
|
return 0.0f;
|
||||||
}
|
}
|
||||||
return acosF(cosv);
|
return acosF(cosv);
|
||||||
|
|
Loading…
Reference in New Issue