Browse Source

AP_InternalError: implement AP_stack_overflow() C binding

allow low level HAL code to report a stack overflow to
AP_InternalError
zr-v5.1
Andrew Tridgell 5 years ago
parent
commit
7d6e5fa8a5
  1. 18
      libraries/AP_InternalError/AP_InternalError.cpp
  2. 6
      libraries/AP_InternalError/AP_InternalError.h

18
libraries/AP_InternalError/AP_InternalError.cpp

@ -25,7 +25,6 @@ void AP_InternalError::error(const AP_InternalError::error_t e) { @@ -25,7 +25,6 @@ void AP_InternalError::error(const AP_InternalError::error_t e) {
hal.util->persistent_data.internal_error_count = total_error_count;
}
namespace AP {
AP_InternalError &internalerror()
@ -34,3 +33,20 @@ AP_InternalError &internalerror() @@ -34,3 +33,20 @@ 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;
AP::internalerror().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(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\n", thread_name);
}
}

6
libraries/AP_InternalError/AP_InternalError.h

@ -56,6 +56,7 @@ public: @@ -56,6 +56,7 @@ public:
flow_of_control = (1U << 20), //0x100000 1048576 for generic we-should-never-get-here situations
switch_full_sector_recursion= (1U << 21), //0x200000 2097152
bad_rotation = (1U << 22), //0x400000 4194304
stack_overflow = (1U << 23), //0x800000 8388608
};
void error(const AP_InternalError::error_t error);
@ -77,3 +78,8 @@ private: @@ -77,3 +78,8 @@ private:
namespace AP {
AP_InternalError &internalerror();
};
extern "C" {
void AP_stack_overflow(const char *thread_name);
}

Loading…
Cancel
Save