|
|
|
@ -56,16 +56,26 @@ void NMI_Handler(void) { while (1); }
@@ -56,16 +56,26 @@ void NMI_Handler(void) { while (1); }
|
|
|
|
|
/*
|
|
|
|
|
save watchdog data for a hard fault |
|
|
|
|
*/ |
|
|
|
|
static void save_fault_watchdog(uint16_t line, FaultType fault_type, uint32_t fault_addr, uint32_t lr) |
|
|
|
|
static void save_fault_watchdog(uint16_t line, FaultType fault_type, uint32_t fault_addr, uint32_t lr) |
|
|
|
|
{ |
|
|
|
|
#ifndef HAL_BOOTLOADER_BUILD |
|
|
|
|
bool using_watchdog = AP_BoardConfig::watchdog_enabled(); |
|
|
|
|
if (using_watchdog) { |
|
|
|
|
AP_HAL::Util::PersistentData &pd = hal.util->persistent_data; |
|
|
|
|
pd.fault_line = line; |
|
|
|
|
pd.fault_type = fault_type; |
|
|
|
|
if (pd.fault_type == 0) { |
|
|
|
|
// don't overwrite earlier fault
|
|
|
|
|
pd.fault_type = fault_type; |
|
|
|
|
} |
|
|
|
|
pd.fault_addr = fault_addr; |
|
|
|
|
pd.fault_thd_prio = chThdGetPriorityX(); |
|
|
|
|
thread_t *tp = chThdGetSelfX(); |
|
|
|
|
if (tp) { |
|
|
|
|
pd.fault_thd_prio = tp->prio; |
|
|
|
|
// get first 4 bytes of the name, but only of first fault
|
|
|
|
|
if (tp->name && pd.thread_name4[0] == 0) { |
|
|
|
|
strncpy(pd.thread_name4, tp->name, 4); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
pd.fault_icsr = SCB->ICSR; |
|
|
|
|
pd.fault_lr = lr; |
|
|
|
|
stm32_watchdog_save((uint32_t *)&hal.util->persistent_data, (sizeof(hal.util->persistent_data)+3)/4); |
|
|
|
|