diff --git a/ArduSub/control_surface.cpp b/ArduSub/control_surface.cpp index e6ffe645a6..3fc6170988 100644 --- a/ArduSub/control_surface.cpp +++ b/ArduSub/control_surface.cpp @@ -49,7 +49,7 @@ void Sub::surface_run() attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); // set target climb rate - float cmb_rate = constrain_float(abs(wp_nav.get_default_speed_up()), 1, pos_control.get_max_speed_up()); + float cmb_rate = constrain_float(fabsf(wp_nav.get_default_speed_up()), 1, pos_control.get_max_speed_up()); // record desired climb rate for logging desired_climb_rate = cmb_rate; diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index a2951c9665..9513644a5e 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -32,7 +32,12 @@ is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2) return fabs(v_1 - v_2) < std::numeric_limits::epsilon(); } #endif +#pragma clang diagnostic push +#pragma clang diagnostic ignored "-Wabsolute-value" + // clang doesn't realise we catch the double case above and warns + // about loss of precision here. return fabsf(v_1 - v_2) < std::numeric_limits::epsilon(); +#pragma clang diagnostic pop } template bool is_equal(const int v_1, const int v_2); @@ -124,60 +129,53 @@ float throttle_curve(float thr_mid, float alpha, float thr_in) } template -float wrap_180(const T angle, float unit_mod) +T wrap_180(const T angle, T unit_mod) { auto res = wrap_360(angle, unit_mod); - if (res > 180.f * unit_mod) { - res -= 360.f * unit_mod; + if (res > T(180) * unit_mod) { + res -= T(360) * 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 int wrap_180(const int angle, int unit_mod); +template short wrap_180(const short angle, short unit_mod); template float wrap_180(const float angle, float unit_mod); -template float wrap_180(const double angle, float unit_mod); +#ifdef ALLOW_DOUBLE_MATH_FUNCTIONS +template double wrap_180(const double angle, double unit_mod); +#endif -template -auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f)) +float wrap_360(const float angle, float unit_mod) { - 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 long 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); + const auto ang_360 = float(360) * unit_mod; + auto res = fmodf(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 long 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)) +#ifdef ALLOW_DOUBLE_MATH_FUNCTIONS +double wrap_360(const double angle, double unit_mod) { - return wrap_360(angle, 100.f); + const auto ang_360 = double(360) * unit_mod; + auto res = fmod(angle, ang_360); + if (res < 0) { + res += ang_360; + } + return res; } +#endif -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 long 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)); +int wrap_360(const int angle, int unit_mod) +{ + const int ang_360 = 360 * unit_mod; + int res = angle % ang_360; + if (res < 0) { + res += ang_360; + } + return res; +} template float wrap_PI(const T radian) diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index feff4f1afb..f5bd1696fc 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -99,27 +99,34 @@ bool inverse(float x[], float y[], uint16_t dim) WARN_IF_UNUSED; * 100 == centi. */ template -float wrap_180(const T angle, float unit_mod = 1); +T wrap_180(const T angle, T unit_mod = T(1)); /* * Wrap an angle in centi-degrees. See wrap_180(). */ -template -auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f)); +inline float wrap_180_cd(const float angle) { return wrap_180(angle, float(100)); } +inline int32_t wrap_180_cd(const int32_t angle) { return wrap_180(int(angle), int(100)); } +#ifdef ALLOW_DOUBLE_MATH_FUNCTIONS +inline double wrap_180_cd(const double angle) { return wrap_180(angle, double(100)); } +#endif /* * Constrain an euler angle to be within the range: 0 to 360 degrees. The * second parameter changes the units. Default: 1 == degrees, 10 == dezi, * 100 == centi. */ -template -float wrap_360(const T angle, float unit_mod = 1); +float wrap_360(const float angle, float unit_mod = 1); +#ifdef ALLOW_DOUBLE_MATH_FUNCTIONS +double wrap_360(const double angle, double unit_mod = 1); +#endif +int wrap_360(const int angle, int unit_mod = 1); + +inline int32_t wrap_360_cd(const int32_t angle) { return wrap_360(int(angle), int(100)); } +inline float wrap_360_cd(const float angle) { return wrap_360(angle, float(100)); } +#ifdef ALLOW_DOUBLE_MATH_FUNCTIONS +inline double wrap_360_cd(const double angle) { return wrap_360(angle, double(100)); } +#endif -/* - * Wrap an angle in centi-degrees. See wrap_360(). - */ -template -auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f)); /* wrap an angle in radians to -PI ~ PI (equivalent to +- 180 degrees)