Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Math: Add missing constexpr #13726

Merged
merged 1 commit into from Mar 16, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
2 changes: 1 addition & 1 deletion libraries/AP_Math/AP_Math.cpp
Expand Up @@ -103,7 +103,7 @@ float linear_interpolate(float low_output, float high_output,
* alpha range: [0,1] min to max expo
* 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;
}
Expand Down
14 changes: 7 additions & 7 deletions libraries/AP_Math/AP_Math.h
Expand Up @@ -215,32 +215,32 @@ static inline auto MAX(const A &one, const B &two) -> decltype(one > two ? one :
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;
}

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

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

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

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

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;
}
Expand All @@ -256,7 +256,7 @@ float linear_interpolate(float low_output, float high_output,
* alpha range: [0,1] min to max expo
* input range: [-1,1]
*/
float expo_curve(float alpha, float input);
constexpr float expo_curve(float alpha, float input);

/* throttle curve generator
* thr_mid: output at mid stick
Expand Down