AP_InternalError: added invalid_arguments failure

this is intended to catch problems where we have unexpectedly received
invalid arguments.  For example an out-of-bounds target speed that
should have been caught somewhere else.

running out of bits so we use a single bit to capture invalid inputs to or output from a calculation
This commit is contained in:
Randy Mackay 2021-02-05 13:57:49 +09:00
parent f0094bac40
commit 67f2c79717
2 changed files with 3 additions and 1 deletions

View File

@ -61,6 +61,7 @@ void AP_InternalError::errors_as_string(uint8_t *buffer, const uint16_t len) con
"mem_guard",
"dma_fail",
"params_restored",
"invalid arguments",
};
static_assert((1U<<(ARRAY_SIZE(error_bit_descriptions))) == uint32_t(AP_InternalError::error_t::__LAST__), "too few descriptions for bits");

View File

@ -66,7 +66,8 @@ public:
mem_guard = (1U << 26), //0x4000000 67108864
dma_fail = (1U << 27), //0x8000000 134217728
params_restored = (1U << 28), //0x10000000 268435456
__LAST__ = (1U << 29), // used only for sanity check
invalid_arg_or_result = (1U << 29), //0x20000000 536870912
__LAST__ = (1U << 30), // used only for sanity check
};
// if you've changed __LAST__ to be 32, then you will want to