AP_Math: fixed inefficient sq() function

This commit is contained in:
Andrew Tridgell 2019-02-23 14:10:10 +11:00
parent b290148ed0
commit ecbe67a0fe

View File

@ -174,7 +174,8 @@ static inline constexpr float degrees(float rad)
template<typename T> template<typename T>
float sq(const T val) float sq(const T val)
{ {
return powf(static_cast<float>(val), 2); float v = static_cast<float>(val);
return v*v;
} }
/* /*