mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Math: fixed inefficient sq() function
This commit is contained in:
parent
b290148ed0
commit
ecbe67a0fe
@ -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…
Reference in New Issue
Block a user