AP_Math: the windows arduino build is missing acosf()

This commit is contained in:
Andrew Tridgell 2012-07-04 14:14:58 +10:00
parent 0bdce404a5
commit 468dfe3faa
3 changed files with 7 additions and 7 deletions

View File

@ -6,6 +6,7 @@
// Assorted useful math operations for ArduPilot(Mega) // Assorted useful math operations for ArduPilot(Mega)
#include <AP_Common.h> #include <AP_Common.h>
#include <math.h>
#include <stdint.h> #include <stdint.h>
#include "rotations.h" #include "rotations.h"
#include "vector2.h" #include "vector2.h"
@ -13,7 +14,6 @@
#include "matrix3.h" #include "matrix3.h"
#include "quaternion.h" #include "quaternion.h"
#include "polygon.h" #include "polygon.h"
#include <math.h>
// define AP_Param types AP_Vector3f and Ap_Matrix3f // define AP_Param types AP_Vector3f and Ap_Matrix3f
AP_PARAMDEFV(Matrix3f, Matrix3f, AP_PARAM_MATRIX3F); AP_PARAMDEFV(Matrix3f, Matrix3f, AP_PARAM_MATRIX3F);

View File

@ -140,15 +140,15 @@ struct Vector2
// computes the angle between 2 arbitrary vectors // computes the angle between 2 arbitrary vectors
T angle(const Vector2<T> &v1, const Vector2<T> &v2) T angle(const Vector2<T> &v1, const Vector2<T> &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 // computes the angle between this vector and another vector
T angle(const Vector2<T> &v2) T angle(const Vector2<T> &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 // computes the angle between 2 normalized arbitrary vectors
T angle_normalized(const Vector2<T> &v1, const Vector2<T> &v2) T angle_normalized(const Vector2<T> &v1, const Vector2<T> &v2)
{ return (T)acosf(v1*v2); } { return (T)acos(v1*v2); }
}; };

View File

@ -165,15 +165,15 @@ public:
// computes the angle between 2 arbitrary vectors // computes the angle between 2 arbitrary vectors
T angle(const Vector3<T> &v1, const Vector3<T> &v2) T angle(const Vector3<T> &v1, const Vector3<T> &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 // computes the angle between this vector and another vector
T angle(const Vector3<T> &v2) T angle(const Vector3<T> &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 // computes the angle between 2 arbitrary normalized vectors
T angle_normalized(const Vector3<T> &v1, const Vector3<T> &v2) T angle_normalized(const Vector3<T> &v1, const Vector3<T> &v2)
{ return (T)acosf(v1*v2); } { return (T)acos(v1*v2); }
// check if any elements are NAN // check if any elements are NAN
bool is_nan(void) bool is_nan(void)