Browse Source

AP_Math: fixed expo_curve()

doesn't make sense as constexpr
zr-v5.1
Andrew Tridgell 4 years ago committed by Randy Mackay
parent
commit
0b76a17e65
  1. 2
      libraries/AP_Math/AP_Math.cpp
  2. 2
      libraries/AP_Math/AP_Math.h

2
libraries/AP_Math/AP_Math.cpp

@ -118,7 +118,7 @@ float linear_interpolate(float low_output, float high_output, @@ -118,7 +118,7 @@ float linear_interpolate(float low_output, float high_output,
* alpha range: [0,1] min to max expo
* input range: [-1,1]
*/
constexpr float expo_curve(float alpha, float x)
float expo_curve(float alpha, float x)
{
return (1.0f - alpha) * x + alpha * x * x * x;
}

2
libraries/AP_Math/AP_Math.h

@ -271,7 +271,7 @@ float linear_interpolate(float low_output, float high_output, @@ -271,7 +271,7 @@ float linear_interpolate(float low_output, float high_output,
* alpha range: [0,1] min to max expo
* input range: [-1,1]
*/
constexpr float expo_curve(float alpha, float input);
float expo_curve(float alpha, float input);
/* throttle curve generator
* thr_mid: output at mid stick

Loading…
Cancel
Save