Browse Source

AP_InternalError: sync with master

added params_restored error
copter407
Andrew Tridgell 4 years ago
parent
commit
0a7588e451
  1. 4
      libraries/AP_InternalError/AP_InternalError.cpp
  2. 5
      libraries/AP_InternalError/AP_InternalError.h

4
libraries/AP_InternalError/AP_InternalError.cpp

@ -12,6 +12,7 @@ void AP_InternalError::error(const AP_InternalError::error_t e, uint16_t line) { @@ -12,6 +12,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:
@ -56,6 +57,9 @@ void AP_InternalError::errors_as_string(uint8_t *buffer, const uint16_t len) con @@ -56,6 +57,9 @@ void AP_InternalError::errors_as_string(uint8_t *buffer, const uint16_t len) con
"stack_ovrflw", // stack_overflow
"imu_reset", // imu_reset
"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");

5
libraries/AP_InternalError/AP_InternalError.h

@ -63,7 +63,10 @@ public: @@ -63,7 +63,10 @@ public:
stack_overflow = (1U << 23), //0x800000 8388608
imu_reset = (1U << 24), //0x1000000 16777216
gpio_isr = (1U << 25), //0x2000000 33554432
__LAST__ = (1U << 26), // used only for sanity check
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
};
// if you've changed __LAST__ to be 32, then you will want to

Loading…
Cancel
Save