mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_Math: use inline wrappers for constrain_* functions
This avoids some warnings about "constrain_float defined but not used" in some compilers.
This commit is contained in:
parent
3bae8373e6
commit
aa974399d0
@ -111,9 +111,20 @@ float wrap_2PI(const T radian);
|
||||
template <class T>
|
||||
T constrain_value(const T amt, const T low, const T high);
|
||||
|
||||
auto const constrain_float = &constrain_value<float>;
|
||||
auto const constrain_int16 = &constrain_value<int16_t>;
|
||||
auto const constrain_int32 = &constrain_value<int32_t>;
|
||||
inline float constrain_float(const float amt, const float low, const float high)
|
||||
{
|
||||
return constrain_value(amt, low, high);
|
||||
}
|
||||
|
||||
inline int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
|
||||
{
|
||||
return constrain_value(amt, low, high);
|
||||
}
|
||||
|
||||
inline int32_t constrain_int32(const int32_t amt, const int32_t low, const int32_t high)
|
||||
{
|
||||
return constrain_value(amt, low, high);
|
||||
}
|
||||
|
||||
// degrees -> radians
|
||||
static inline float radians(float deg)
|
||||
|
Loading…
Reference in New Issue
Block a user