AP_InternalError: added an internal error for GPIO ISR overload

This commit is contained in:
Andrew Tridgell 2020-09-21 18:27:12 +10:00
parent c62b86e3c1
commit 965af98f4a
2 changed files with 3 additions and 1 deletions

View File

@ -55,6 +55,7 @@ void AP_InternalError::errors_as_string(uint8_t *buffer, const uint16_t len) con
"bad_rotation", "bad_rotation",
"stack_ovrflw", // stack_overflow "stack_ovrflw", // stack_overflow
"imu_reset", // imu_reset "imu_reset", // imu_reset
"gpio_isr",
}; };
static_assert((1U<<(ARRAY_SIZE(error_bit_descriptions))) == uint32_t(AP_InternalError::error_t::__LAST__), "too few descriptions for bits"); static_assert((1U<<(ARRAY_SIZE(error_bit_descriptions))) == uint32_t(AP_InternalError::error_t::__LAST__), "too few descriptions for bits");

View File

@ -62,7 +62,8 @@ public:
bad_rotation = (1U << 22), //0x400000 4194304 bad_rotation = (1U << 22), //0x400000 4194304
stack_overflow = (1U << 23), //0x800000 8388608 stack_overflow = (1U << 23), //0x800000 8388608
imu_reset = (1U << 24), //0x1000000 16777216 imu_reset = (1U << 24), //0x1000000 16777216
__LAST__ = (1U << 25), // used only for sanity check gpio_isr = (1U << 25), //0x2000000 33554432
__LAST__ = (1U << 26), // used only for sanity check
}; };
// if you've changed __LAST__ to be 32, then you will want to // if you've changed __LAST__ to be 32, then you will want to