mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
AP_InternalError: move methods for stack overflow and memguard to AP_HAL/Util
This commit is contained in:
parent
dd5b5847f6
commit
6b668d0113
@ -113,32 +113,4 @@ AP_InternalError &internalerror()
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
// stack overflow hook for low level RTOS code, C binding
|
||||
void AP_stack_overflow(const char *thread_name)
|
||||
{
|
||||
static bool done_stack_overflow;
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::stack_overflow);
|
||||
if (!done_stack_overflow) {
|
||||
// we don't want to record the thread name more than once, as
|
||||
// first overflow can trigger a 2nd
|
||||
strncpy_noterm(hal.util->persistent_data.thread_name4, thread_name, 4);
|
||||
done_stack_overflow = true;
|
||||
}
|
||||
hal.util->persistent_data.fault_type = 42; // magic value
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
AP_HAL::panic("stack overflow %s", 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", unsigned(size));
|
||||
}
|
||||
}
|
||||
|
||||
#endif // AP_INTERNALERROR_ENABLED
|
||||
|
@ -110,11 +110,6 @@ namespace AP {
|
||||
AP_InternalError &internalerror();
|
||||
};
|
||||
|
||||
extern "C" {
|
||||
void AP_stack_overflow(const char *thread_name);
|
||||
void AP_memory_guard_error(uint32_t size);
|
||||
}
|
||||
|
||||
#define INTERNAL_ERROR(error_number) \
|
||||
AP::internalerror().error(error_number, __AP_LINE__);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user