mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_HAL_ChibiOS: do not gate AP_CRASHDUMP_ENABLED on bootloader
Also rename from HAL_CRASHDUMP_ENABLE Removes code based on define rather than creating empty functions. Makes it clearer what's going on in the callers.
This commit is contained in:
parent
680d158f59
commit
4ca0f35943
@ -722,10 +722,9 @@ void Util::log_stack_info(void)
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#if !defined(HAL_BOOTLOADER_BUILD)
|
#if AP_CRASHDUMP_ENABLED
|
||||||
size_t Util::last_crash_dump_size() const
|
size_t Util::last_crash_dump_size() const
|
||||||
{
|
{
|
||||||
#if HAL_CRASHDUMP_ENABLE
|
|
||||||
// get dump size
|
// get dump size
|
||||||
uint32_t size = stm32_crash_dump_size();
|
uint32_t size = stm32_crash_dump_size();
|
||||||
char* dump_start = (char*)stm32_crash_dump_addr();
|
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();
|
size = stm32_crash_dump_max_size();
|
||||||
}
|
}
|
||||||
return size;
|
return size;
|
||||||
#endif
|
|
||||||
return 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void* Util::last_crash_dump_ptr() const
|
void* Util::last_crash_dump_ptr() const
|
||||||
{
|
{
|
||||||
#if HAL_CRASHDUMP_ENABLE
|
|
||||||
if (last_crash_dump_size() == 0) {
|
if (last_crash_dump_size() == 0) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
return (void*)stm32_crash_dump_addr();
|
return (void*)stm32_crash_dump_addr();
|
||||||
#else
|
|
||||||
return nullptr;
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
#endif // HAL_BOOTLOADER_BUILD
|
#endif // AP_CRASHDUMP_ENABLED
|
||||||
|
|
||||||
// set armed state
|
// set armed state
|
||||||
void Util::set_soft_armed(const bool b)
|
void Util::set_soft_armed(const bool b)
|
||||||
|
@ -146,7 +146,7 @@ private:
|
|||||||
// log info on stack usage
|
// log info on stack usage
|
||||||
void log_stack_info(void) override;
|
void log_stack_info(void) override;
|
||||||
|
|
||||||
#if !defined(HAL_BOOTLOADER_BUILD)
|
#if AP_CRASHDUMP_ENABLED
|
||||||
// get last crash dump
|
// get last crash dump
|
||||||
size_t last_crash_dump_size() const override;
|
size_t last_crash_dump_size() const override;
|
||||||
void* last_crash_dump_ptr() const override;
|
void* last_crash_dump_ptr() const override;
|
||||||
|
@ -972,10 +972,10 @@ def write_mcu_config(f):
|
|||||||
|
|
||||||
if flash_size >= 2048 and not args.bootloader:
|
if flash_size >= 2048 and not args.bootloader:
|
||||||
# lets pick a flash sector for Crash log
|
# 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
|
env_vars['ENABLE_CRASHDUMP'] = 1
|
||||||
else:
|
else:
|
||||||
f.write('#define HAL_CRASHDUMP_ENABLE 0\n')
|
f.write('#define AP_CRASHDUMP_ENABLED 0\n')
|
||||||
env_vars['ENABLE_CRASHDUMP'] = 0
|
env_vars['ENABLE_CRASHDUMP'] = 0
|
||||||
|
|
||||||
if args.bootloader:
|
if args.bootloader:
|
||||||
|
@ -23,7 +23,7 @@
|
|||||||
#include "hwdef/common/watchdog.h"
|
#include "hwdef/common/watchdog.h"
|
||||||
#include "hwdef/common/stm32_util.h"
|
#include "hwdef/common/stm32_util.h"
|
||||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||||
#if HAL_CRASHDUMP_ENABLE
|
#if AP_CRASHDUMP_ENABLED
|
||||||
#include <CrashCatcher.h>
|
#include <CrashCatcher.h>
|
||||||
#endif
|
#endif
|
||||||
#include <ch.h>
|
#include <ch.h>
|
||||||
@ -52,7 +52,7 @@ extern "C"
|
|||||||
{
|
{
|
||||||
#define bkpt() __asm volatile("BKPT #0\n")
|
#define bkpt() __asm volatile("BKPT #0\n")
|
||||||
|
|
||||||
#if !HAL_CRASHDUMP_ENABLE
|
#if !AP_CRASHDUMP_ENABLED
|
||||||
// do legacy hardfault handling
|
// do legacy hardfault handling
|
||||||
void HardFault_Handler(void);
|
void HardFault_Handler(void);
|
||||||
void HardFault_Handler(void) {
|
void HardFault_Handler(void) {
|
||||||
|
Loading…
Reference in New Issue
Block a user