mirror of https://github.com/ArduPilot/ardupilot
AP_InternalError: make constraining NaNs an internal error
This commit is contained in:
parent
381bb41a5e
commit
5c6c153467
|
@ -43,6 +43,7 @@ public:
|
|||
logger_bad_current_block = (1U << 7),
|
||||
logger_blockcount_mismatch = (1U << 8),
|
||||
logger_dequeue_failure = (1U << 9),
|
||||
constraining_nan = (1U << 10),
|
||||
};
|
||||
|
||||
void error(const AP_InternalError::error_t error);
|
||||
|
|
Loading…
Reference in New Issue