From 468dfe3faaf84c8336c29fe1bb089e041a2cf980 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 4 Jul 2012 14:14:58 +1000 Subject: [PATCH] AP_Math: the windows arduino build is missing acosf() --- libraries/AP_Math/AP_Math.h | 2 +- libraries/AP_Math/vector2.h | 6 +++--- libraries/AP_Math/vector3.h | 6 +++--- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index 7fb07c604d..a59bde2039 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -6,6 +6,7 @@ // Assorted useful math operations for ArduPilot(Mega) #include +#include #include #include "rotations.h" #include "vector2.h" @@ -13,7 +14,6 @@ #include "matrix3.h" #include "quaternion.h" #include "polygon.h" -#include // define AP_Param types AP_Vector3f and Ap_Matrix3f AP_PARAMDEFV(Matrix3f, Matrix3f, AP_PARAM_MATRIX3F); diff --git a/libraries/AP_Math/vector2.h b/libraries/AP_Math/vector2.h index eebb9d8d4d..e35e1f92ae 100644 --- a/libraries/AP_Math/vector2.h +++ b/libraries/AP_Math/vector2.h @@ -140,15 +140,15 @@ struct Vector2 // computes the angle between 2 arbitrary vectors T angle(const Vector2 &v1, const Vector2 &v2) - { return (T)acosf((v1*v2) / (v1.length()*v2.length())); } + { return (T)acos((v1*v2) / (v1.length()*v2.length())); } // computes the angle between this vector and another vector T angle(const Vector2 &v2) - { return (T)acosf(((*this)*v2) / (this->length()*v2.length())); } + { return (T)acos(((*this)*v2) / (this->length()*v2.length())); } // computes the angle between 2 normalized arbitrary vectors T angle_normalized(const Vector2 &v1, const Vector2 &v2) - { return (T)acosf(v1*v2); } + { return (T)acos(v1*v2); } }; diff --git a/libraries/AP_Math/vector3.h b/libraries/AP_Math/vector3.h index 5759d11787..8ad3becb41 100644 --- a/libraries/AP_Math/vector3.h +++ b/libraries/AP_Math/vector3.h @@ -165,15 +165,15 @@ public: // computes the angle between 2 arbitrary vectors T angle(const Vector3 &v1, const Vector3 &v2) - { return (T)acosf((v1*v2) / (v1.length()*v2.length())); } + { return (T)acos((v1*v2) / (v1.length()*v2.length())); } // computes the angle between this vector and another vector T angle(const Vector3 &v2) - { return (T)acosf(((*this)*v2) / (this->length()*v2.length())); } + { return (T)acos(((*this)*v2) / (this->length()*v2.length())); } // computes the angle between 2 arbitrary normalized vectors T angle_normalized(const Vector3 &v1, const Vector3 &v2) - { return (T)acosf(v1*v2); } + { return (T)acos(v1*v2); } // check if any elements are NAN bool is_nan(void)