#include "AP_Math.h" #include /* * is_equal(): Integer implementation, provided for convenience and * compatibility with old code. Expands to the same as comparing the values * directly */ template typename std::enable_if::type>::value ,bool>::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2) { typedef typename std::common_type::type common_type; return static_cast(v_1) == static_cast(v_2); } /* * is_equal(): double/float implementation - takes into account * std::numeric_limits::epsilon() to return if 2 values are equal. */ template typename std::enable_if::type>::value, bool>::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2) { typedef typename std::common_type::type common_type; typedef typename std::remove_cv::type common_type_nonconst; if (std::is_same::value) { return fabs(v_1 - v_2) < std::numeric_limits::epsilon(); } return fabsf(v_1 - v_2) < std::numeric_limits::epsilon(); } template bool is_equal(const int v_1, const int v_2); template bool is_equal(const short v_1, const short v_2); template bool is_equal(const float v_1, const float v_2); template bool is_equal(const double v_1, const double v_2); template float safe_asin(const T v) { const float f = static_cast(v); if (isnan(f)) { return 0.0f; } if (f >= 1.0f) { return static_cast(M_PI_2); } if (f <= -1.0f) { return static_cast(-M_PI_2); } return asinf(f); } template float safe_asin(const int v); template float safe_asin(const short v); template float safe_asin(const float v); template float safe_asin(const double v); template float safe_sqrt(const T v) { float ret = sqrtf(static_cast(v)); if (isnan(ret)) { return 0; } return ret; } template float safe_sqrt(const int v); template float safe_sqrt(const short v); template float safe_sqrt(const float v); template float safe_sqrt(const double v); /* linear interpolation based on a variable in a range */ float linear_interpolate(float low_output, float high_output, float var_value, float var_low, float var_high) { if (var_value <= var_low) { return low_output; } if (var_value >= var_high) { return high_output; } float p = (var_value - var_low) / (var_high - var_low); return low_output + p * (high_output - low_output); } template float wrap_180(const T angle, float unit_mod) { auto res = wrap_360(angle, unit_mod); if (res > 180.f * unit_mod) { res -= 360.f * unit_mod; } return res; } template float wrap_180(const int angle, float unit_mod); template float wrap_180(const short angle, float unit_mod); template float wrap_180(const float angle, float unit_mod); template float wrap_180(const double angle, float unit_mod); template auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f)) { return wrap_180(angle, 100.f); } template auto wrap_180_cd(const float angle) -> decltype(wrap_180(angle, 100.f)); template auto wrap_180_cd(const int angle) -> decltype(wrap_180(angle, 100.f)); template auto wrap_180_cd(const short angle) -> decltype(wrap_180(angle, 100.f)); template auto wrap_180_cd(const double angle) -> decltype(wrap_360(angle, 100.f)); template float wrap_360(const T angle, float unit_mod) { const float ang_360 = 360.f * unit_mod; float res = fmodf(static_cast(angle), ang_360); if (res < 0) { res += ang_360; } return res; } template float wrap_360(const int angle, float unit_mod); template float wrap_360(const short angle, float unit_mod); template float wrap_360(const float angle, float unit_mod); template float wrap_360(const double angle, float unit_mod); template auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f)) { return wrap_360(angle, 100.f); } template auto wrap_360_cd(const float angle) -> decltype(wrap_360(angle, 100.f)); template auto wrap_360_cd(const int angle) -> decltype(wrap_360(angle, 100.f)); template auto wrap_360_cd(const short angle) -> decltype(wrap_360(angle, 100.f)); template auto wrap_360_cd(const double angle) -> decltype(wrap_360(angle, 100.f)); template float wrap_PI(const T radian) { auto res = wrap_2PI(radian); if (res > M_PI) { res -= M_2PI; } return res; } template float wrap_PI(const int radian); template float wrap_PI(const short radian); template float wrap_PI(const float radian); template float wrap_PI(const double radian); template float wrap_2PI(const T radian) { float res = fmodf(static_cast(radian), M_2PI); if (res < 0) { res += M_2PI; } return res; } template float wrap_2PI(const int radian); template float wrap_2PI(const short radian); template float wrap_2PI(const float radian); template float wrap_2PI(const double radian); template T constrain_value(const T amt, const T low, const T high) { // the check for NaN as a float prevents propagation of floating point // errors through any function that uses constrain_value(). The normal // float semantics already handle -Inf and +Inf if (isnan(amt)) { return (low + high) / 2; } if (amt < low) { return low; } if (amt > high) { return high; } return amt; } template int constrain_value(const int amt, const int low, const int high); template short constrain_value(const short amt, const short low, const short high); template float constrain_value(const float amt, const float low, const float high); template double constrain_value(const double amt, const double low, const double high); /* simple 16 bit random number generator */ uint16_t get_random16(void) { static uint32_t m_z = 1234; static uint32_t m_w = 76542; m_z = 36969 * (m_z & 0xFFFFu) + (m_z >> 16); m_w = 18000 * (m_w & 0xFFFFu) + (m_w >> 16); return ((m_z << 16) + m_w) & 0xFFFF; }