mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_Math: inline is_equal, add is_zero
This commit is contained in:
parent
726d7df710
commit
0392292489
@ -1,12 +1,6 @@
|
|||||||
#include "AP_Math.h"
|
#include "AP_Math.h"
|
||||||
#include <float.h>
|
#include <float.h>
|
||||||
|
|
||||||
// are two floats equal
|
|
||||||
bool is_equal(const float &fVal1, const float &fVal2)
|
|
||||||
{
|
|
||||||
return fabs(fVal1 - fVal2) < FLT_EPSILON ? true : false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// a varient of asin() that checks the input ranges and ensures a
|
// a varient of asin() that checks the input ranges and ensures a
|
||||||
// valid angle as output. If nan is given as input then zero is
|
// valid angle as output. If nan is given as input then zero is
|
||||||
// returned.
|
// returned.
|
||||||
|
@ -19,12 +19,13 @@
|
|||||||
#include "quaternion.h"
|
#include "quaternion.h"
|
||||||
#include "polygon.h"
|
#include "polygon.h"
|
||||||
#include "edc.h"
|
#include "edc.h"
|
||||||
|
#include "float.h"
|
||||||
|
|
||||||
#ifndef M_PI_F
|
#ifndef M_PI_F
|
||||||
#define M_PI_F 3.141592653589793f
|
#define M_PI_F 3.141592653589793f
|
||||||
#endif
|
#endif
|
||||||
#ifndef M_2PI_F
|
#ifndef M_2PI_F
|
||||||
#define M_2PI_F 2*M_PI_F
|
#define M_2PI_F (2*M_PI_F)
|
||||||
#endif
|
#endif
|
||||||
#ifndef PI
|
#ifndef PI
|
||||||
# define PI M_PI_F
|
# define PI M_PI_F
|
||||||
@ -75,7 +76,10 @@ AP_PARAMDEFV(Matrix3f, Matrix3f, AP_PARAM_MATRIX3F);
|
|||||||
AP_PARAMDEFV(Vector3f, Vector3f, AP_PARAM_VECTOR3F);
|
AP_PARAMDEFV(Vector3f, Vector3f, AP_PARAM_VECTOR3F);
|
||||||
|
|
||||||
// are two floats equal
|
// are two floats equal
|
||||||
bool is_equal(const float &fVal1, const float &fVal2);
|
inline bool is_equal(const float fVal1, const float fVal2) { return fabsf(fVal1 - fVal2) < FLT_EPSILON ? true : false; }
|
||||||
|
|
||||||
|
// are two floats equal
|
||||||
|
inline bool is_zero(const float fVal1) { return fabsf(fVal1) < FLT_EPSILON ? true : false; }
|
||||||
|
|
||||||
// a varient of asin() that always gives a valid answer.
|
// a varient of asin() that always gives a valid answer.
|
||||||
float safe_asin(float v);
|
float safe_asin(float v);
|
||||||
|
Loading…
Reference in New Issue
Block a user