Browse Source

AP_Math: fixed inefficient sq() function

master
Andrew Tridgell 6 years ago
parent
commit
ecbe67a0fe
  1. 3
      libraries/AP_Math/AP_Math.h

3
libraries/AP_Math/AP_Math.h

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

Loading…
Cancel
Save