AP_Math: do not use internal_error() on iofirmware

This commit is contained in:
Andy Piper 2023-05-22 15:15:11 +01:00 committed by Andrew Tridgell
parent 73aed28be7
commit eacc29e81e
1 changed files with 2 additions and 0 deletions

View File

@ -270,7 +270,9 @@ T constrain_value_line(const T amt, const T low, const T high, uint32_t line)
// errors through any function that uses constrain_value(). The normal
// float semantics already handle -Inf and +Inf
if (isnan(amt)) {
#if !defined(IOMCU_FW)
AP::internalerror().error(AP_InternalError::error_t::constraining_nan, line);
#endif
return (low + high) / 2;
}