mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_InternalError: emit stringification of internal errors
This commit is contained in:
parent
75514dfdfe
commit
70a9abfaff
@ -783,7 +783,7 @@ bool AP_Arming::system_checks(bool report)
|
|||||||
if (AP::internalerror().errors() != 0) {
|
if (AP::internalerror().errors() != 0) {
|
||||||
uint8_t buffer[32];
|
uint8_t buffer[32];
|
||||||
AP::internalerror().errors_as_string(buffer, ARRAY_SIZE(buffer));
|
AP::internalerror().errors_as_string(buffer, ARRAY_SIZE(buffer));
|
||||||
check_failed(report, "Internal errors 0x%x l:%u (%s)", (unsigned int)AP::internalerror().errors(), AP::internalerror().last_error_line(), buffer);
|
check_failed(report, "Internal errors 0x%x l:%u %s", (unsigned int)AP::internalerror().errors(), AP::internalerror().last_error_line(), buffer);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -27,6 +27,62 @@ void AP_InternalError::error(const AP_InternalError::error_t e, uint16_t line) {
|
|||||||
hal.util->persistent_data.internal_error_last_line = line;
|
hal.util->persistent_data.internal_error_last_line = line;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void AP_InternalError::errors_as_string(uint8_t *buffer, const uint16_t len) const
|
||||||
|
{
|
||||||
|
static const char * const error_bit_descriptions[] {
|
||||||
|
"mapfailure", // logger_mapfailure
|
||||||
|
"miss_struct", // logger_missing_logstructure
|
||||||
|
"write_mssfmt", // logger_logwrite_missingfmt
|
||||||
|
"many_deletes", // logger_too_many_deletions
|
||||||
|
"bad_getfile", // logger_bad_getfilename
|
||||||
|
"unused1",
|
||||||
|
"flush_no_sem", // logger_flushing_without_sem
|
||||||
|
"bad_curr_blk", // logger_bad_current_block
|
||||||
|
"blkcnt_bad", // logger_blockcount_mismatch
|
||||||
|
"dq_failure", // logger_dequeue_failure
|
||||||
|
"cnstring_nan", // constraining_nan
|
||||||
|
"watchdog_rst", // watchdog_reset
|
||||||
|
"iomcu_reset",
|
||||||
|
"iomcu_fail",
|
||||||
|
"spi_fail",
|
||||||
|
"main_loop_stk", // main_loop_stuck
|
||||||
|
"gcs_bad_link", // gcs_bad_missionprotocol_link
|
||||||
|
"bitmask_range",
|
||||||
|
"gcs_offset",
|
||||||
|
"i2c_isr",
|
||||||
|
"flow_of_ctrl", // flow_of_control
|
||||||
|
"sfs_recursion", // switch_full_sector_recursion
|
||||||
|
"bad_rotation",
|
||||||
|
"stack_ovrflw", // stack_overflow
|
||||||
|
};
|
||||||
|
|
||||||
|
static_assert((1U<<(ARRAY_SIZE(error_bit_descriptions))) == uint32_t(AP_InternalError::error_t::__LAST__), "too few descriptions for bits");
|
||||||
|
|
||||||
|
buffer[0] = 0;
|
||||||
|
uint32_t buffer_used = 0;
|
||||||
|
for (uint8_t i=0; i<ARRAY_SIZE(error_bit_descriptions); i++) {
|
||||||
|
if (buffer_used >= len) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (internal_errors & (1U<<i)) {
|
||||||
|
const char *format;
|
||||||
|
if (i == 0) {
|
||||||
|
format = "%s";
|
||||||
|
} else {
|
||||||
|
format = ",%s";
|
||||||
|
}
|
||||||
|
const size_t written = hal.util->snprintf((char*)&buffer[buffer_used],
|
||||||
|
len-buffer_used,
|
||||||
|
format,
|
||||||
|
error_bit_descriptions[i]);
|
||||||
|
if (written <= 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
buffer_used += written;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
|
|
||||||
AP_InternalError &internalerror()
|
AP_InternalError &internalerror()
|
||||||
|
@ -57,11 +57,22 @@ public:
|
|||||||
switch_full_sector_recursion= (1U << 21), //0x200000 2097152
|
switch_full_sector_recursion= (1U << 21), //0x200000 2097152
|
||||||
bad_rotation = (1U << 22), //0x400000 4194304
|
bad_rotation = (1U << 22), //0x400000 4194304
|
||||||
stack_overflow = (1U << 23), //0x800000 8388608
|
stack_overflow = (1U << 23), //0x800000 8388608
|
||||||
|
__LAST__ = (1U << 24), // used only for sanity check
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// if you've changed __LAST__ to be 32, then you will want to
|
||||||
|
// rejig the way we do sanity checks as we don't want to move to a
|
||||||
|
// 64-bit type for error_t:
|
||||||
|
static_assert(sizeof(error_t) == 4, "error_t should be 32-bit type");
|
||||||
|
|
||||||
uint16_t last_error_line() const { return last_line; }
|
uint16_t last_error_line() const { return last_line; }
|
||||||
|
|
||||||
void error(const AP_InternalError::error_t error, uint16_t line);
|
void error(const AP_InternalError::error_t error, uint16_t line);
|
||||||
|
|
||||||
|
// fill buffer with a description of the exceptions present in
|
||||||
|
// internal errors. buffer will always be null-terminated.
|
||||||
|
void errors_as_string(uint8_t *buffer, uint16_t len) const;
|
||||||
|
|
||||||
uint32_t count() const { return total_error_count; }
|
uint32_t count() const { return total_error_count; }
|
||||||
|
|
||||||
// internal_errors - return mask of internal errors seen
|
// internal_errors - return mask of internal errors seen
|
||||||
|
Loading…
Reference in New Issue
Block a user