mirror of https://github.com/ArduPilot/ardupilot
AP_InternalError: change panic to return error code as string in SITL
This commit is contained in:
parent
6c3612b51d
commit
0ae1536e4a
|
@ -17,7 +17,9 @@ void AP_InternalError::error(const AP_InternalError::error_t e, uint16_t line) {
|
|||
// don't panic on these to facilitate watchdog testing
|
||||
break;
|
||||
default:
|
||||
AP_HAL::panic("internal error %u", unsigned(e));
|
||||
char buffer[50];
|
||||
AP::internalerror().error_to_string(buffer, ARRAY_SIZE(buffer), e);
|
||||
AP_HAL::panic("AP_InternalError::error_t::%s", buffer);
|
||||
}
|
||||
#endif
|
||||
internal_errors |= uint32_t(e);
|
||||
|
@ -29,43 +31,49 @@ void AP_InternalError::error(const AP_InternalError::error_t e, uint16_t line) {
|
|||
hal.util->persistent_data.internal_error_last_line = line;
|
||||
}
|
||||
|
||||
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
|
||||
"panic",
|
||||
"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
|
||||
"imu_reset", // imu_reset
|
||||
"gpio_isr",
|
||||
"mem_guard",
|
||||
"dma_fail",
|
||||
"params_restored",
|
||||
"invalid arguments",
|
||||
};
|
||||
|
||||
static_assert((1U<<(ARRAY_SIZE(error_bit_descriptions))) == uint32_t(AP_InternalError::error_t::__LAST__), "too few descriptions for bits");
|
||||
|
||||
void AP_InternalError::error_to_string(char *buffer, const uint16_t len, error_t error_code) const
|
||||
{
|
||||
uint32_t temp = log2f(int(error_code));
|
||||
strncpy(buffer, error_bit_descriptions[temp], len - 1);
|
||||
}
|
||||
|
||||
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
|
||||
"panic",
|
||||
"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
|
||||
"imu_reset", // imu_reset
|
||||
"gpio_isr",
|
||||
"mem_guard",
|
||||
"dma_fail",
|
||||
"params_restored",
|
||||
"invalid arguments",
|
||||
};
|
||||
|
||||
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++) {
|
||||
|
|
|
@ -83,6 +83,9 @@ public:
|
|||
// internal errors. buffer will always be null-terminated.
|
||||
void errors_as_string(uint8_t *buffer, uint16_t len) const;
|
||||
|
||||
// convert an error code to a string
|
||||
void error_to_string(char *buffer, uint16_t len, error_t error_code) const;
|
||||
|
||||
uint32_t count() const { return total_error_count; }
|
||||
|
||||
// internal_errors - return mask of internal errors seen
|
||||
|
|
Loading…
Reference in New Issue