mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Math: fixed expo_curve()
doesn't make sense as constexpr
This commit is contained in:
parent
aa5e74a5d9
commit
0b76a17e65
@ -118,7 +118,7 @@ float linear_interpolate(float low_output, float high_output,
|
|||||||
* alpha range: [0,1] min to max expo
|
* alpha range: [0,1] min to max expo
|
||||||
* input range: [-1,1]
|
* 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;
|
return (1.0f - alpha) * x + alpha * x * x * x;
|
||||||
}
|
}
|
||||||
|
@ -271,7 +271,7 @@ float linear_interpolate(float low_output, float high_output,
|
|||||||
* alpha range: [0,1] min to max expo
|
* alpha range: [0,1] min to max expo
|
||||||
* input range: [-1,1]
|
* input range: [-1,1]
|
||||||
*/
|
*/
|
||||||
constexpr float expo_curve(float alpha, float input);
|
float expo_curve(float alpha, float input);
|
||||||
|
|
||||||
/* throttle curve generator
|
/* throttle curve generator
|
||||||
* thr_mid: output at mid stick
|
* thr_mid: output at mid stick
|
||||||
|
Loading…
Reference in New Issue
Block a user