mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: added params restored internal error
This commit is contained in:
parent
4d58bcb321
commit
9e15efcbb5
|
@ -13,6 +13,7 @@ void AP_InternalError::error(const AP_InternalError::error_t e, uint16_t line) {
|
|||
switch (e) {
|
||||
case AP_InternalError::error_t::watchdog_reset:
|
||||
case AP_InternalError::error_t::main_loop_stuck:
|
||||
case AP_InternalError::error_t::params_restored:
|
||||
// don't panic on these to facilitate watchdog testing
|
||||
break;
|
||||
default:
|
||||
|
@ -59,6 +60,7 @@ void AP_InternalError::errors_as_string(uint8_t *buffer, const uint16_t len) con
|
|||
"gpio_isr",
|
||||
"mem_guard",
|
||||
"dma_fail",
|
||||
"params_restored",
|
||||
};
|
||||
|
||||
static_assert((1U<<(ARRAY_SIZE(error_bit_descriptions))) == uint32_t(AP_InternalError::error_t::__LAST__), "too few descriptions for bits");
|
||||
|
|
|
@ -65,7 +65,8 @@ public:
|
|||
gpio_isr = (1U << 25), //0x2000000 33554432
|
||||
mem_guard = (1U << 26), //0x4000000 67108864
|
||||
dma_fail = (1U << 27), //0x8000000 134217728
|
||||
__LAST__ = (1U << 28), // used only for sanity check
|
||||
params_restored = (1U << 28), //0x10000000 268435456
|
||||
__LAST__ = (1U << 29), // used only for sanity check
|
||||
};
|
||||
|
||||
// if you've changed __LAST__ to be 32, then you will want to
|
||||
|
|
Loading…
Reference in New Issue