AP_InternalError: persist internal error values

This commit is contained in:
Andrew Tridgell 2019-05-09 21:15:00 +10:00
parent 45d5e7f6d2
commit b217771dbf
2 changed files with 11 additions and 1 deletions

View File

@ -1,15 +1,24 @@
#include "AP_InternalError.h" #include "AP_InternalError.h"
extern const AP_HAL::HAL &hal;
// actually create the instance: // actually create the instance:
static AP_InternalError instance; static AP_InternalError instance;
void AP_InternalError::error(const AP_InternalError::error_t e) { void AP_InternalError::error(const AP_InternalError::error_t e) {
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (e != AP_InternalError::error_t::watchdog_reset) { switch (e) {
case AP_InternalError::error_t::watchdog_reset:
case AP_InternalError::error_t::main_loop_stuck:
// don't panic on these to facilitate watchdog testing
break;
default:
AP_HAL::panic("internal error %u", unsigned(e)); AP_HAL::panic("internal error %u", unsigned(e));
} }
#endif #endif
internal_errors |= uint32_t(e); internal_errors |= uint32_t(e);
hal.util->persistent_data.internal_errors = internal_errors;
hal.util->persistent_data.internal_error_count++;
} }

View File

@ -48,6 +48,7 @@ public:
iomcu_reset = (1U << 12), iomcu_reset = (1U << 12),
iomcu_fail = (1U << 13), iomcu_fail = (1U << 13),
spi_fail = (1U << 14), spi_fail = (1U << 14),
main_loop_stuck = (1U << 15),
}; };
void error(const AP_InternalError::error_t error); void error(const AP_InternalError::error_t error);