mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Math: create double versions of is_zero, is_positive and is_negative
Seeks to prevent Thread 1 "ardurover" received signal SIGFPE, Arithmetic exception. is_positive<double> (fVal1=9.6315720352771873e+44) at ../../libraries/AP_Math/AP_Math.h:66 66 return (static_cast<float>(fVal1) >= FLT_EPSILON);
This commit is contained in:
parent
c6c285b5a2
commit
2205b95c99
@ -78,6 +78,27 @@ inline bool is_negative(const T fVal1) {
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* @brief: Check whether a double is zero
|
||||
*/
|
||||
inline bool is_zero(const double fVal1) {
|
||||
return (fabsf(fVal1) < static_cast<double>(FLT_EPSILON));
|
||||
}
|
||||
|
||||
/*
|
||||
* @brief: Check whether a double is greater than zero
|
||||
*/
|
||||
inline bool is_positive(const double fVal1) {
|
||||
return (fVal1 >= static_cast<double>(FLT_EPSILON));
|
||||
}
|
||||
|
||||
/*
|
||||
* @brief: Check whether a double is less than zero
|
||||
*/
|
||||
inline bool is_negative(const double fVal1) {
|
||||
return (fVal1 <= static_cast<double>((-1.0 * FLT_EPSILON)));
|
||||
}
|
||||
|
||||
/*
|
||||
* A variant of asin() that checks the input ranges and ensures a valid angle
|
||||
* as output. If nan is given as input then zero is returned.
|
||||
|
Loading…
Reference in New Issue
Block a user