AP_Math: make constraining NaNs an internal error

This commit is contained in:
Peter Barker 2019-04-05 08:07:57 +11:00 committed by Andrew Tridgell
parent 0f7281fbb6
commit 381bb41a5e

View File

@ -2,6 +2,8 @@
#include <float.h>
#include <AP_InternalError/AP_InternalError.h>
/*
* is_equal(): Integer implementation, provided for convenience and
* compatibility with old code. Expands to the same as comparing the values
@ -185,6 +187,7 @@ T constrain_value(const T amt, const T low, const T high)
// errors through any function that uses constrain_value(). The normal
// float semantics already handle -Inf and +Inf
if (isnan(amt)) {
AP::internalerror().error(AP_InternalError::error_t::constraining_nan);
return (low + high) / 2;
}