From c93c773de292eaa55c86a044afec0fbdcc3f603d Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 1 May 2015 23:26:34 -0700 Subject: [PATCH] AP_Math: change is_equal and is_zero to static class for better visability --- libraries/AP_Math/AP_Math.h | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index 0eadd9a34e..c225a9aa68 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -75,11 +75,15 @@ AP_PARAMDEFV(Matrix3f, Matrix3f, AP_PARAM_MATRIX3F); AP_PARAMDEFV(Vector3f, Vector3f, AP_PARAM_VECTOR3F); -// are two floats equal -inline bool is_equal(const float fVal1, const float fVal2) { return fabsf(fVal1 - fVal2) < FLT_EPSILON ? true : false; } +class AP_Math { -// are two floats equal -inline bool is_zero(const float fVal1) { return fabsf(fVal1) < FLT_EPSILON ? true : false; } +public: + // are two floats equal + static inline bool is_equal(const float fVal1, const float fVal2) { return fabsf(fVal1 - fVal2) < FLT_EPSILON ? true : false; } + + // is a float is zero + static inline bool is_zero(const float fVal1) { return fabsf(fVal1) < FLT_EPSILON ? true : false; } +}; // a varient of asin() that always gives a valid answer. float safe_asin(float v);