mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_InternalError: added an internal error for GPIO ISR overload
This commit is contained in:
parent
2bdda6be71
commit
a77e5caeb9
@ -54,6 +54,8 @@ void AP_InternalError::errors_as_string(uint8_t *buffer, const uint16_t len) con
|
||||
"sfs_recursion", // switch_full_sector_recursion
|
||||
"bad_rotation",
|
||||
"stack_ovrflw", // stack_overflow
|
||||
"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");
|
||||
|
@ -61,7 +61,9 @@ public:
|
||||
switch_full_sector_recursion= (1U << 21), //0x200000 2097152
|
||||
bad_rotation = (1U << 22), //0x400000 4194304
|
||||
stack_overflow = (1U << 23), //0x800000 8388608
|
||||
__LAST__ = (1U << 24), // used only for sanity check
|
||||
imu_reset = (1U << 24), //0x1000000 16777216
|
||||
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
|
||||
|
Loading…
Reference in New Issue
Block a user