mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_Math: fix is_zero() after template conversion
This commit is contained in:
parent
6746b4227a
commit
1ac712fa65
@ -34,7 +34,7 @@ template <class T>
|
||||
inline bool is_zero(const T fVal1) {
|
||||
static_assert(std::is_floating_point<T>::value || std::is_base_of<T,AP_Float>::value,
|
||||
"Template parameter not of type float");
|
||||
return fabsf(fVal1) < std::numeric_limits<T>::epsilon() ? true : false;
|
||||
return fabsf(static_cast<float>(fVal1)) < FLT_EPSILON ? true : false;
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user