mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
AP_InternalError: added mem_guard internal error
This commit is contained in:
parent
ce95b7e81a
commit
cc61e05d90
@ -1,6 +1,7 @@
|
|||||||
#include "AP_InternalError.h"
|
#include "AP_InternalError.h"
|
||||||
|
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
|
|
||||||
@ -56,6 +57,7 @@ void AP_InternalError::errors_as_string(uint8_t *buffer, const uint16_t len) con
|
|||||||
"stack_ovrflw", // stack_overflow
|
"stack_ovrflw", // stack_overflow
|
||||||
"imu_reset", // imu_reset
|
"imu_reset", // imu_reset
|
||||||
"gpio_isr",
|
"gpio_isr",
|
||||||
|
"mem_guard",
|
||||||
};
|
};
|
||||||
|
|
||||||
static_assert((1U<<(ARRAY_SIZE(error_bit_descriptions))) == uint32_t(AP_InternalError::error_t::__LAST__), "too few descriptions for bits");
|
static_assert((1U<<(ARRAY_SIZE(error_bit_descriptions))) == uint32_t(AP_InternalError::error_t::__LAST__), "too few descriptions for bits");
|
||||||
@ -110,3 +112,13 @@ void AP_stack_overflow(const char *thread_name)
|
|||||||
AP_HAL::panic("stack overflow %s\n", thread_name);
|
AP_HAL::panic("stack overflow %s\n", thread_name);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// hook for memory guard errors with --enable-memory-guard
|
||||||
|
void AP_memory_guard_error(uint32_t size)
|
||||||
|
{
|
||||||
|
INTERNAL_ERROR(AP_InternalError::error_t::mem_guard);
|
||||||
|
if (!hal.util->get_soft_armed()) {
|
||||||
|
::printf("memory guard error size=%u\n", unsigned(size));
|
||||||
|
AP_HAL::panic("memory guard size=%u\n", unsigned(size));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
@ -63,7 +63,8 @@ public:
|
|||||||
stack_overflow = (1U << 23), //0x800000 8388608
|
stack_overflow = (1U << 23), //0x800000 8388608
|
||||||
imu_reset = (1U << 24), //0x1000000 16777216
|
imu_reset = (1U << 24), //0x1000000 16777216
|
||||||
gpio_isr = (1U << 25), //0x2000000 33554432
|
gpio_isr = (1U << 25), //0x2000000 33554432
|
||||||
__LAST__ = (1U << 26), // used only for sanity check
|
mem_guard = (1U << 26), //0x4000000 67108864
|
||||||
|
__LAST__ = (1U << 27), // used only for sanity check
|
||||||
};
|
};
|
||||||
|
|
||||||
// if you've changed __LAST__ to be 32, then you will want to
|
// if you've changed __LAST__ to be 32, then you will want to
|
||||||
@ -101,6 +102,7 @@ namespace AP {
|
|||||||
|
|
||||||
extern "C" {
|
extern "C" {
|
||||||
void AP_stack_overflow(const char *thread_name);
|
void AP_stack_overflow(const char *thread_name);
|
||||||
|
void AP_memory_guard_error(uint32_t size);
|
||||||
}
|
}
|
||||||
|
|
||||||
#define INTERNAL_ERROR(error_number) \
|
#define INTERNAL_ERROR(error_number) \
|
||||||
|
Loading…
Reference in New Issue
Block a user