AP_Math: Add missing constexpr
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
c9f2b9ff87
commit
1635054c4f
@ -103,7 +103,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]
|
||||||
*/
|
*/
|
||||||
float expo_curve(float alpha, float x)
|
constexpr 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;
|
||||||
}
|
}
|
||||||
|
@ -215,32 +215,32 @@ static inline auto MAX(const A &one, const B &two) -> decltype(one > two ? one :
|
|||||||
return one > two ? one : two;
|
return one > two ? one : two;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint32_t hz_to_nsec(uint32_t freq)
|
inline constexpr uint32_t hz_to_nsec(uint32_t freq)
|
||||||
{
|
{
|
||||||
return AP_NSEC_PER_SEC / freq;
|
return AP_NSEC_PER_SEC / freq;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint32_t nsec_to_hz(uint32_t nsec)
|
inline constexpr uint32_t nsec_to_hz(uint32_t nsec)
|
||||||
{
|
{
|
||||||
return AP_NSEC_PER_SEC / nsec;
|
return AP_NSEC_PER_SEC / nsec;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint32_t usec_to_nsec(uint32_t usec)
|
inline constexpr uint32_t usec_to_nsec(uint32_t usec)
|
||||||
{
|
{
|
||||||
return usec * AP_NSEC_PER_USEC;
|
return usec * AP_NSEC_PER_USEC;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint32_t nsec_to_usec(uint32_t nsec)
|
inline constexpr uint32_t nsec_to_usec(uint32_t nsec)
|
||||||
{
|
{
|
||||||
return nsec / AP_NSEC_PER_USEC;
|
return nsec / AP_NSEC_PER_USEC;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint32_t hz_to_usec(uint32_t freq)
|
inline constexpr uint32_t hz_to_usec(uint32_t freq)
|
||||||
{
|
{
|
||||||
return AP_USEC_PER_SEC / freq;
|
return AP_USEC_PER_SEC / freq;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline uint32_t usec_to_hz(uint32_t usec)
|
inline constexpr uint32_t usec_to_hz(uint32_t usec)
|
||||||
{
|
{
|
||||||
return AP_USEC_PER_SEC / usec;
|
return AP_USEC_PER_SEC / usec;
|
||||||
}
|
}
|
||||||
@ -256,7 +256,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]
|
||||||
*/
|
*/
|
||||||
float expo_curve(float alpha, float input);
|
constexpr 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