mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Math: do not use internal_error() on iofirmware
This commit is contained in:
parent
73aed28be7
commit
eacc29e81e
@ -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
|
// errors through any function that uses constrain_value(). The normal
|
||||||
// float semantics already handle -Inf and +Inf
|
// float semantics already handle -Inf and +Inf
|
||||||
if (isnan(amt)) {
|
if (isnan(amt)) {
|
||||||
|
#if !defined(IOMCU_FW)
|
||||||
AP::internalerror().error(AP_InternalError::error_t::constraining_nan, line);
|
AP::internalerror().error(AP_InternalError::error_t::constraining_nan, line);
|
||||||
|
#endif
|
||||||
return (low + high) / 2;
|
return (low + high) / 2;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user