diff --git a/libraries/AP_HAL_ChibiOS/Util.cpp b/libraries/AP_HAL_ChibiOS/Util.cpp index 9f7eede326..f8b9a2218e 100644 --- a/libraries/AP_HAL_ChibiOS/Util.cpp +++ b/libraries/AP_HAL_ChibiOS/Util.cpp @@ -722,10 +722,9 @@ void Util::log_stack_info(void) #endif } -#if !defined(HAL_BOOTLOADER_BUILD) +#if AP_CRASHDUMP_ENABLED size_t Util::last_crash_dump_size() const { -#if HAL_CRASHDUMP_ENABLE // get dump size uint32_t size = stm32_crash_dump_size(); char* dump_start = (char*)stm32_crash_dump_addr(); @@ -738,22 +737,16 @@ size_t Util::last_crash_dump_size() const size = stm32_crash_dump_max_size(); } return size; -#endif - return 0; } void* Util::last_crash_dump_ptr() const { -#if HAL_CRASHDUMP_ENABLE if (last_crash_dump_size() == 0) { return nullptr; } return (void*)stm32_crash_dump_addr(); -#else - return nullptr; -#endif } -#endif // HAL_BOOTLOADER_BUILD +#endif // AP_CRASHDUMP_ENABLED // set armed state void Util::set_soft_armed(const bool b) diff --git a/libraries/AP_HAL_ChibiOS/Util.h b/libraries/AP_HAL_ChibiOS/Util.h index d5072477e2..66bd560984 100644 --- a/libraries/AP_HAL_ChibiOS/Util.h +++ b/libraries/AP_HAL_ChibiOS/Util.h @@ -146,7 +146,7 @@ private: // log info on stack usage void log_stack_info(void) override; -#if !defined(HAL_BOOTLOADER_BUILD) +#if AP_CRASHDUMP_ENABLED // get last crash dump size_t last_crash_dump_size() const override; void* last_crash_dump_ptr() const override; diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 869148a932..a63d61841f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -972,10 +972,10 @@ def write_mcu_config(f): if flash_size >= 2048 and not args.bootloader: # lets pick a flash sector for Crash log - f.write('#define HAL_CRASHDUMP_ENABLE 1\n') + f.write('#define AP_CRASHDUMP_ENABLED 1\n') env_vars['ENABLE_CRASHDUMP'] = 1 else: - f.write('#define HAL_CRASHDUMP_ENABLE 0\n') + f.write('#define AP_CRASHDUMP_ENABLED 0\n') env_vars['ENABLE_CRASHDUMP'] = 0 if args.bootloader: diff --git a/libraries/AP_HAL_ChibiOS/system.cpp b/libraries/AP_HAL_ChibiOS/system.cpp index b4b3b3b4c7..c1f943921e 100644 --- a/libraries/AP_HAL_ChibiOS/system.cpp +++ b/libraries/AP_HAL_ChibiOS/system.cpp @@ -23,7 +23,7 @@ #include "hwdef/common/watchdog.h" #include "hwdef/common/stm32_util.h" #include -#if HAL_CRASHDUMP_ENABLE +#if AP_CRASHDUMP_ENABLED #include #endif #include @@ -52,7 +52,7 @@ extern "C" { #define bkpt() __asm volatile("BKPT #0\n") -#if !HAL_CRASHDUMP_ENABLE +#if !AP_CRASHDUMP_ENABLED // do legacy hardfault handling void HardFault_Handler(void); void HardFault_Handler(void) {