mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: remove calls to save_fault_watchdog if on bootloader
This commit is contained in:
parent
dc803a5691
commit
21836d792a
|
@ -16,6 +16,10 @@
|
|||
|
||||
#include "hal.h"
|
||||
|
||||
#ifndef AP_WATCHDOG_SAVE_FAULT_ENABLED
|
||||
#define AP_WATCHDOG_SAVE_FAULT_ENABLED 1
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
@ -156,7 +160,10 @@ typedef enum {
|
|||
} FaultType;
|
||||
|
||||
// Record information about a fault
|
||||
#if AP_WATCHDOG_SAVE_FAULT_ENABLED
|
||||
void save_fault_watchdog(uint16_t line, FaultType fault_type, uint32_t fault_addr, uint32_t lr);
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Generates a block of random values, returns total values generated
|
||||
* if nonblocking, for blocking returns if successful or not
|
||||
|
|
|
@ -3066,6 +3066,10 @@ def add_bootloader_defaults(f):
|
|||
#define AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED 0
|
||||
#endif
|
||||
|
||||
#ifndef AP_WATCHDOG_SAVE_FAULT_ENABLED
|
||||
#define AP_WATCHDOG_SAVE_FAULT_ENABLED 0
|
||||
#endif
|
||||
|
||||
// end AP_Bootloader defaults
|
||||
''')
|
||||
|
||||
|
|
|
@ -92,7 +92,9 @@ void HardFault_Handler(void) {
|
|||
(void)isFaultAddressValid;
|
||||
#endif // #if AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED
|
||||
|
||||
#if AP_WATCHDOG_SAVE_FAULT_ENABLED
|
||||
save_fault_watchdog(__LINE__, faultType, faultAddress, (uint32_t)ctx.lr_thd);
|
||||
#endif
|
||||
|
||||
#ifdef HAL_GPIO_PIN_FAULT
|
||||
while (true) {
|
||||
|
@ -140,6 +142,7 @@ void UsageFault_Handler(void) {
|
|||
FaultType faultType = (FaultType)__get_IPSR();
|
||||
(void)faultType;
|
||||
uint32_t faultAddress = SCB->BFAR;
|
||||
(void)faultAddress;
|
||||
#if AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED
|
||||
//Flags about hardfault / busfault
|
||||
//See http://infocenter.arm.com/help/index.jsp?topic=/com.arm.doc.dui0552a/Cihdjcfc.html for reference
|
||||
|
@ -157,7 +160,9 @@ void UsageFault_Handler(void) {
|
|||
(void)isDivideByZeroFault;
|
||||
#endif // AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED
|
||||
|
||||
#if AP_WATCHDOG_SAVE_FAULT_ENABLED
|
||||
save_fault_watchdog(__LINE__, faultType, faultAddress, (uint32_t)ctx.lr_thd);
|
||||
#endif
|
||||
|
||||
//Cause debugger to stop. Ignored if no debugger is attached
|
||||
while(1) {}
|
||||
|
@ -175,8 +180,8 @@ void MemManage_Handler(void) {
|
|||
(void)faultType;
|
||||
//For HardFault/BusFault this is the address that was accessed causing the error
|
||||
uint32_t faultAddress = SCB->MMFAR;
|
||||
#if AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED
|
||||
(void)faultAddress;
|
||||
#if AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED
|
||||
//Flags about hardfault / busfault
|
||||
//See http://infocenter.arm.com/help/index.jsp?topic=/com.arm.doc.dui0552a/Cihdjcfc.html for reference
|
||||
bool isInstructionAccessViolation = ((SCB->CFSR >> SCB_CFSR_MEMFAULTSR_Pos) & (1 << 0) ? true : false);
|
||||
|
@ -191,7 +196,9 @@ void MemManage_Handler(void) {
|
|||
(void)isFaultAddressValid;
|
||||
#endif // AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED
|
||||
|
||||
#if AP_WATCHDOG_SAVE_FAULT_ENABLED
|
||||
save_fault_watchdog(__LINE__, faultType, faultAddress, (uint32_t)ctx.lr_thd);
|
||||
#endif
|
||||
|
||||
while(1) {}
|
||||
}
|
||||
|
@ -214,12 +221,14 @@ void MemManage_Handler(void) {
|
|||
HardFault_Handler();
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#if AP_WATCHDOG_SAVE_FAULT_ENABLED
|
||||
/*
|
||||
save watchdog data for a hard fault
|
||||
*/
|
||||
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;
|
||||
|
@ -241,8 +250,8 @@ void save_fault_watchdog(uint16_t line, FaultType fault_type, uint32_t fault_add
|
|||
}
|
||||
stm32_watchdog_save((uint32_t *)&hal.util->persistent_data, (sizeof(hal.util->persistent_data)+3)/4);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#endif // AP_WATCHDOG_SAVE_FAULT_ENABLED
|
||||
|
||||
void *__dso_handle;
|
||||
|
||||
|
|
Loading…
Reference in New Issue