AP_Math: fixed expo_curve()

doesn't make sense as constexpr
This commit is contained in:
Andrew Tridgell 2021-07-17 16:39:46 +10:00 committed by Randy Mackay
parent ed24af2709
commit 8268a59130
2 changed files with 2 additions and 2 deletions

View File

@ -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;
}

View File

@ -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