mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Math: the windows arduino build is missing acosf()
This commit is contained in:
parent
0bdce404a5
commit
468dfe3faa
@ -6,6 +6,7 @@
|
||||
// Assorted useful math operations for ArduPilot(Mega)
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <math.h>
|
||||
#include <stdint.h>
|
||||
#include "rotations.h"
|
||||
#include "vector2.h"
|
||||
@ -13,7 +14,6 @@
|
||||
#include "matrix3.h"
|
||||
#include "quaternion.h"
|
||||
#include "polygon.h"
|
||||
#include <math.h>
|
||||
|
||||
// define AP_Param types AP_Vector3f and Ap_Matrix3f
|
||||
AP_PARAMDEFV(Matrix3f, Matrix3f, AP_PARAM_MATRIX3F);
|
||||
|
@ -140,15 +140,15 @@ struct Vector2
|
||||
|
||||
// computes the angle between 2 arbitrary vectors
|
||||
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
|
||||
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
|
||||
T angle_normalized(const Vector2<T> &v1, const Vector2<T> &v2)
|
||||
{ return (T)acosf(v1*v2); }
|
||||
{ return (T)acos(v1*v2); }
|
||||
|
||||
};
|
||||
|
||||
|
@ -165,15 +165,15 @@ public:
|
||||
|
||||
// computes the angle between 2 arbitrary vectors
|
||||
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
|
||||
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
|
||||
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
|
||||
bool is_nan(void)
|
||||
|
Loading…
Reference in New Issue
Block a user