diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index ddc8b3f900..41d2e8693d 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -82,6 +82,16 @@ template float safe_sqrt(const short v); template float safe_sqrt(const float v); template float safe_sqrt(const double v); +/* + replacement for std::swap() needed for STM32 + */ +static void swap_float(float &f1, float &f2) +{ + float tmp = f1; + f1 = f2; + f2 = tmp; +} + /* * linear interpolation based on a variable in a range */ @@ -89,6 +99,11 @@ float linear_interpolate(float low_output, float high_output, float var_value, float var_low, float var_high) { + if (var_low > var_high) { + // support either polarity + swap_float(var_low, var_high); + swap_float(low_output, high_output); + } if (var_value <= var_low) { return low_output; } diff --git a/libraries/AP_Math/AP_Math.h b/libraries/AP_Math/AP_Math.h index bd5ad2292a..7af6e999bd 100644 --- a/libraries/AP_Math/AP_Math.h +++ b/libraries/AP_Math/AP_Math.h @@ -248,6 +248,9 @@ inline constexpr uint32_t usec_to_hz(uint32_t usec) /* linear interpolation based on a variable in a range + return value will be in the range [var_low,var_high] + + Either polarity is supported, so var_low can be higher than var_high */ float linear_interpolate(float low_output, float high_output, float var_value,