mirror of https://github.com/ArduPilot/ardupilot
AP_InternalError: create and use INTERNAL_ERROR macro so we get line numbers
This commit is contained in:
parent
5f8a9d1e15
commit
a30cdabb34
|
@ -7,7 +7,7 @@ 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, uint16_t line) {
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
switch (e) {
|
switch (e) {
|
||||||
case AP_InternalError::error_t::watchdog_reset:
|
case AP_InternalError::error_t::watchdog_reset:
|
||||||
|
@ -20,9 +20,11 @@ void AP_InternalError::error(const AP_InternalError::error_t e) {
|
||||||
#endif
|
#endif
|
||||||
internal_errors |= uint32_t(e);
|
internal_errors |= uint32_t(e);
|
||||||
total_error_count++;
|
total_error_count++;
|
||||||
|
last_line = line;
|
||||||
|
|
||||||
hal.util->persistent_data.internal_errors = internal_errors;
|
hal.util->persistent_data.internal_errors = internal_errors;
|
||||||
hal.util->persistent_data.internal_error_count = total_error_count;
|
hal.util->persistent_data.internal_error_count = total_error_count;
|
||||||
|
hal.util->persistent_data.internal_error_last_line = line;
|
||||||
}
|
}
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
|
@ -38,7 +40,7 @@ AP_InternalError &internalerror()
|
||||||
void AP_stack_overflow(const char *thread_name)
|
void AP_stack_overflow(const char *thread_name)
|
||||||
{
|
{
|
||||||
static bool done_stack_overflow;
|
static bool done_stack_overflow;
|
||||||
AP::internalerror().error(AP_InternalError::error_t::stack_overflow);
|
INTERNAL_ERROR(AP_InternalError::error_t::stack_overflow);
|
||||||
if (!done_stack_overflow) {
|
if (!done_stack_overflow) {
|
||||||
// we don't want to record the thread name more than once, as
|
// we don't want to record the thread name more than once, as
|
||||||
// first overflow can trigger a 2nd
|
// first overflow can trigger a 2nd
|
||||||
|
|
|
@ -59,7 +59,9 @@ public:
|
||||||
stack_overflow = (1U << 23), //0x800000 8388608
|
stack_overflow = (1U << 23), //0x800000 8388608
|
||||||
};
|
};
|
||||||
|
|
||||||
void error(const AP_InternalError::error_t error);
|
uint16_t last_error_line() const { return last_line; }
|
||||||
|
|
||||||
|
void error(const AP_InternalError::error_t error, uint16_t line);
|
||||||
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
|
||||||
|
@ -73,6 +75,7 @@ private:
|
||||||
uint32_t internal_errors;
|
uint32_t internal_errors;
|
||||||
|
|
||||||
uint32_t total_error_count;
|
uint32_t total_error_count;
|
||||||
|
uint16_t last_line;
|
||||||
};
|
};
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
|
@ -83,3 +86,5 @@ extern "C" {
|
||||||
void AP_stack_overflow(const char *thread_name);
|
void AP_stack_overflow(const char *thread_name);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#define INTERNAL_ERROR(error_number) \
|
||||||
|
AP::internalerror().error(error_number, __LINE__);
|
||||||
|
|
Loading…
Reference in New Issue