mirror of https://github.com/ArduPilot/ardupilot
HAL_CbibiOS: get crash dump info for main thread lockups
This commit is contained in:
parent
c8fc238e62
commit
5afabf7bfb
|
@ -443,6 +443,17 @@ void Scheduler::_monitor_thread(void *arg)
|
|||
INTERNAL_ERROR(AP_InternalError::error_t::main_loop_stuck);
|
||||
}
|
||||
|
||||
#if AP_CRASHDUMP_ENABLED
|
||||
if (loop_delay >= 1800 && using_watchdog) {
|
||||
// we are about to watchdog, better to trigger a hardfault
|
||||
// now and get a crash dump file
|
||||
void *ptr = (void*)0xE000FFFF;
|
||||
typedef void (*fptr)();
|
||||
fptr gptr = (fptr) (void *)ptr;
|
||||
gptr();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
if (log_wd_counter++ == 10 && hal.util->was_watchdog_reset()) {
|
||||
log_wd_counter = 0;
|
||||
|
|
Loading…
Reference in New Issue