mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: setup for recording crashdump at the remaining flash space
This commit is contained in:
parent
52c7886270
commit
ee35350129
|
@ -192,4 +192,13 @@ SECTIONS
|
|||
. = ORIGIN(HEAP_RAM) + LENGTH(HEAP_RAM);
|
||||
__heap_end__ = .;
|
||||
} > HEAP_RAM
|
||||
|
||||
/* The crash log uses the unused part of a flash section.*/
|
||||
.crash_log (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(32);
|
||||
__crash_log_base__ = .;
|
||||
. = ORIGIN(flash) + LENGTH(flash);
|
||||
__crash_log_end__ = .;
|
||||
} > flash
|
||||
}
|
||||
|
|
|
@ -23,12 +23,9 @@
|
|||
#include "stm32_util.h"
|
||||
#include "flash.h"
|
||||
|
||||
#if defined(HAL_CRASH_DUMP_FLASHPAGE) || defined(HAL_CRASH_SERIAL_PORT)
|
||||
CRASH_CATCHER_TEST_WRITEABLE CrashCatcherReturnCodes g_crashCatcherDumpEndReturn = CRASH_CATCHER_TRY_AGAIN;
|
||||
static CrashCatcherInfo g_info;
|
||||
#endif
|
||||
|
||||
#if defined(HAL_CRASH_DUMP_FLASHPAGE)
|
||||
static bool do_flash_crash_dump = true;
|
||||
static void* dump_start_address;
|
||||
static void* dump_end_address;
|
||||
|
@ -36,7 +33,6 @@ static void* dump_end_address;
|
|||
static void CrashCatcher_DumpStartFlash(const CrashCatcherInfo* pInfo);
|
||||
static CrashCatcherReturnCodes CrashCatcher_DumpEndFlash(void);
|
||||
static void CrashCatcher_DumpMemoryFlash(const void* pvMemory, CrashCatcherElementSizes elementSize, size_t elementCount);
|
||||
#endif // HAL_CRASH_DUMP_FLASHPAGE
|
||||
|
||||
#if defined(HAL_CRASH_SERIAL_PORT)
|
||||
static bool uart_initialised = false;
|
||||
|
@ -61,15 +57,33 @@ static CrashCatcherReturnCodes CrashCatcher_DumpEndHex(void);
|
|||
static void CrashCatcher_DumpMemoryHex(const void* pvMemory, CrashCatcherElementSizes elementSize, size_t elementCount);
|
||||
#endif // HAL_CRASH_SERIAL_PORT
|
||||
|
||||
extern uint32_t __crash_log_base__, __crash_log_end__;
|
||||
|
||||
uint32_t stm32_crash_dump_size(void)
|
||||
{
|
||||
#if defined(HAL_CRASH_DUMP_FLASHPAGE)
|
||||
uint32_t* page_addr = (uint32_t*)stm32_flash_getpageaddr(HAL_CRASH_DUMP_FLASHPAGE);
|
||||
uint32_t page_size = stm32_flash_getpagesize(HAL_CRASH_DUMP_FLASHPAGE);
|
||||
uint32_t* page_addr = (uint32_t*)&__crash_log_base__;
|
||||
uint32_t page_size = stm32_crash_dump_max_size();
|
||||
return page_addr[(page_size / sizeof(uint32_t)) - 1];
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
uint32_t stm32_crash_dump_max_size(void)
|
||||
{
|
||||
return (uint32_t)&__crash_log_end__ - (uint32_t)&__crash_log_base__;
|
||||
}
|
||||
|
||||
uint32_t stm32_crash_dump_addr(void)
|
||||
{
|
||||
return (uint32_t)&__crash_log_base__;
|
||||
}
|
||||
|
||||
bool stm32_crash_dump_region_erased(void)
|
||||
{
|
||||
for (uint32_t i = 0; i < stm32_crash_dump_max_size(); i += 4) {
|
||||
if (((uint32_t*)stm32_crash_dump_addr())[i / 4] != 0xFFFFFFFF) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
#define ARRAY_SIZE(X) (sizeof(X)/sizeof(X[0]))
|
||||
|
@ -121,13 +135,11 @@ const CrashCatcherMemoryRegion* CrashCatcher_GetMemoryRegions(void)
|
|||
regions[ARRAY_SIZE(regions) - 1].endAddress = 0xFFFFFFFF;
|
||||
}
|
||||
|
||||
#if defined(HAL_CRASH_DUMP_FLASHPAGE)
|
||||
if (do_flash_crash_dump) {
|
||||
// smaller dump if on flash
|
||||
regions[0].startAddress = (uint32_t)dump_start_address;
|
||||
regions[0].endAddress = (uint32_t)dump_end_address;
|
||||
}
|
||||
#endif
|
||||
return regions;
|
||||
}
|
||||
|
||||
|
@ -141,11 +153,9 @@ void CrashCatcher_DumpMemory(const void* pvMemory, CrashCatcherElementSizes elem
|
|||
CrashCatcher_DumpMemoryHex(pvMemory, elementSize, elementCount);
|
||||
}
|
||||
#endif
|
||||
#if defined(HAL_CRASH_DUMP_FLASHPAGE)
|
||||
if (do_flash_crash_dump) {
|
||||
CrashCatcher_DumpMemoryFlash(pvMemory, elementSize, elementCount);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
@ -155,19 +165,14 @@ void CrashCatcher_DumpStart(const CrashCatcherInfo* pInfo)
|
|||
struct port_extctx* ctx = (struct port_extctx*)pInfo->sp;
|
||||
FaultType faultType = (FaultType)__get_IPSR();
|
||||
save_fault_watchdog(__LINE__, faultType, pInfo->sp, ctx->lr_thd);
|
||||
#if !defined(HAL_CRASH_SERIAL_PORT) && !defined(HAL_CRASH_DUMP_FLASHPAGE)
|
||||
while(true) {} // Nothing to do
|
||||
#endif
|
||||
#if defined(HAL_CRASH_SERIAL_PORT)
|
||||
if (do_serial_crash_dump) {
|
||||
CrashCatcher_DumpStartHex(pInfo);
|
||||
}
|
||||
#endif
|
||||
#if defined(HAL_CRASH_DUMP_FLASHPAGE)
|
||||
if (do_flash_crash_dump) {
|
||||
CrashCatcher_DumpStartFlash(pInfo);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
CrashCatcherReturnCodes CrashCatcher_DumpEnd(void)
|
||||
|
@ -177,12 +182,10 @@ CrashCatcherReturnCodes CrashCatcher_DumpEnd(void)
|
|||
return CrashCatcher_DumpEndHex();
|
||||
}
|
||||
#endif
|
||||
#if defined(HAL_CRASH_DUMP_FLASHPAGE)
|
||||
if (do_flash_crash_dump) {
|
||||
return CrashCatcher_DumpEndFlash();
|
||||
}
|
||||
do_flash_crash_dump = false;
|
||||
#endif
|
||||
#if defined(HAL_CRASH_SERIAL_PORT)
|
||||
do_serial_crash_dump = true;
|
||||
#endif
|
||||
|
@ -190,8 +193,6 @@ CrashCatcherReturnCodes CrashCatcher_DumpEnd(void)
|
|||
}
|
||||
|
||||
// -------------- FlashDump Code --------------------
|
||||
#if defined(HAL_CRASH_DUMP_FLASHPAGE)
|
||||
|
||||
static uint32_t dump_size;
|
||||
static uint8_t dump_buffer[32]; // we need to maintain a dump buffer of 32bytes for H7
|
||||
static uint8_t buf_off;
|
||||
|
@ -224,7 +225,7 @@ static void CrashCatcher_DumpStartFlash(const CrashCatcherInfo* pInfo)
|
|||
dump_size = 0;
|
||||
buf_off = 0;
|
||||
// we expect crash dump flash page to already be empty
|
||||
if (!stm32_flash_ispageerased(HAL_CRASH_DUMP_FLASHPAGE)) {
|
||||
if (!stm32_crash_dump_region_erased()) {
|
||||
// stuff is already there, maybe last dump
|
||||
// so just do nothing
|
||||
do_flash_crash_dump = false;
|
||||
|
@ -238,7 +239,7 @@ static void CrashCatcher_DumpStartFlash(const CrashCatcherInfo* pInfo)
|
|||
static void flush_dump_buffer(void)
|
||||
{
|
||||
if (buf_off == sizeof(dump_buffer)) {
|
||||
uint32_t page_start = stm32_flash_getpageaddr(HAL_CRASH_DUMP_FLASHPAGE);
|
||||
uint32_t page_start = (uint32_t)stm32_crash_dump_addr();
|
||||
// write dump buffer to flash
|
||||
stm32_flash_write(page_start + dump_size, dump_buffer, sizeof(dump_buffer));
|
||||
dump_size += sizeof(dump_buffer);
|
||||
|
@ -254,7 +255,7 @@ static void CrashCatcher_DumpMemoryFlash(const void* pvMemory, CrashCatcherEleme
|
|||
const uint8_t* pv = (const uint8_t*)pvMemory;
|
||||
size_t cnt = 0;
|
||||
while (cnt < elementCount) {
|
||||
if (dump_size + buf_off + sizeof(dump_size) >= stm32_flash_getpagesize(HAL_CRASH_DUMP_FLASHPAGE)) {
|
||||
if (dump_size + buf_off + sizeof(dump_size) >= stm32_crash_dump_max_size()) {
|
||||
// when this happens, buf_off will be sizeof(buffer)-sizeof(dump_size)
|
||||
// 0xFF will be used to detect that we were in the middle of taking a dump
|
||||
memset(&dump_buffer[sizeof(dump_buffer)-sizeof(dump_size)], 0xFF, sizeof(dump_size));
|
||||
|
@ -289,20 +290,20 @@ static void CrashCatcher_DumpMemoryFlash(const void* pvMemory, CrashCatcherEleme
|
|||
static CrashCatcherReturnCodes CrashCatcher_DumpEndFlash(void)
|
||||
{
|
||||
// flush the buffer
|
||||
if (dump_size + buf_off + sizeof(dump_size) >= stm32_flash_getpagesize(HAL_CRASH_DUMP_FLASHPAGE)) {
|
||||
if (dump_size + buf_off + sizeof(dump_size) >= stm32_crash_dump_max_size()) {
|
||||
// when this happens, buf_off will be sizeof(buffer)-sizeof(dump_size)
|
||||
// 0xFF will be used to detect that we were in the middle of taking a dump
|
||||
memset(&dump_buffer[sizeof(dump_buffer)-sizeof(dump_size)], 0xFF, sizeof(dump_size));
|
||||
buf_off = sizeof(dump_buffer);
|
||||
}
|
||||
if (buf_off > 0) {
|
||||
if (dump_size + sizeof(dump_buffer) >= stm32_flash_getpagesize(HAL_CRASH_DUMP_FLASHPAGE) && buf_off < sizeof(dump_buffer)) {
|
||||
if (dump_size + sizeof(dump_buffer) >= stm32_crash_dump_max_size() && buf_off < sizeof(dump_buffer)) {
|
||||
// we have a partially full buffer towards the end, so we need to write the buffer
|
||||
// and then write the size of the buffer
|
||||
memcpy(&dump_buffer[sizeof(dump_buffer)-sizeof(dump_size)], &dump_size, sizeof(dump_size));
|
||||
buf_off = 32;
|
||||
}
|
||||
stm32_flash_write(stm32_flash_getpageaddr(HAL_CRASH_DUMP_FLASHPAGE) + dump_size, dump_buffer, 32);
|
||||
stm32_flash_write(stm32_crash_dump_addr() + dump_size, dump_buffer, 32);
|
||||
dump_size += buf_off;
|
||||
buf_off = 0;
|
||||
memset(dump_buffer, 0, sizeof(dump_buffer));
|
||||
|
@ -310,9 +311,9 @@ static CrashCatcherReturnCodes CrashCatcher_DumpEndFlash(void)
|
|||
}
|
||||
|
||||
// write size to buffer if not already written
|
||||
if (dump_size < stm32_flash_getpagesize(HAL_CRASH_DUMP_FLASHPAGE)) {
|
||||
if (dump_size < stm32_crash_dump_max_size()) {
|
||||
memcpy(&dump_buffer[sizeof(dump_buffer)-sizeof(dump_size)], &dump_size, sizeof(dump_size));
|
||||
stm32_flash_write(stm32_flash_getpageaddr(HAL_CRASH_DUMP_FLASHPAGE) + stm32_flash_getpagesize(HAL_CRASH_DUMP_FLASHPAGE) - sizeof(dump_buffer), dump_buffer, sizeof(dump_buffer));
|
||||
stm32_flash_write(stm32_crash_dump_addr() + stm32_crash_dump_max_size() - sizeof(dump_buffer), dump_buffer, sizeof(dump_buffer));
|
||||
stm32_watchdog_pat();
|
||||
}
|
||||
|
||||
|
@ -324,8 +325,6 @@ static CrashCatcherReturnCodes CrashCatcher_DumpEndFlash(void)
|
|||
return g_crashCatcherDumpEndReturn;
|
||||
}
|
||||
|
||||
#endif // HAL_USE_CRASH_CATCHER
|
||||
|
||||
// -------------- HexDump Code --------------------
|
||||
/* Copyright (C) 2018 Adam Green (https://github.com/adamgreen)
|
||||
|
||||
|
|
|
@ -145,10 +145,6 @@ static const uint32_t flash_memmap[STM32_FLASH_NPAGES] = { KB(32), KB(32), KB(32
|
|||
static_assert(STORAGE_FLASH_PAGE < STM32_FLASH_NPAGES,
|
||||
"STORAGE_FLASH_PAGE out of range");
|
||||
#endif
|
||||
#ifdef HAL_CRASH_DUMP_FLASH_PAGE
|
||||
static_assert(HAL_CRASH_DUMP_FLASH_PAGE < STM32_FLASH_NPAGES,
|
||||
"HAL_CRASH_DUMP_FLASH_PAGE out of range");
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// keep a cache of the page addresses
|
||||
|
|
|
@ -138,6 +138,8 @@ void* get_addr_mem_region_end_addr(void *addr);
|
|||
|
||||
// return the size of crash dump
|
||||
uint32_t stm32_crash_dump_size(void);
|
||||
uint32_t stm32_crash_dump_addr(void);
|
||||
uint32_t stm32_crash_dump_max_size(void);
|
||||
|
||||
typedef enum {
|
||||
Reset = 1,
|
||||
|
|
|
@ -856,17 +856,6 @@ def write_mcu_config(f):
|
|||
# lets pick a flash sector for Crash log
|
||||
f.write('#define HAL_CRASHDUMP_ENABLE 1\n')
|
||||
env_vars['ENABLE_CRASHDUMP'] = 1
|
||||
num_flash_pages = get_flash_npages()
|
||||
crash_dump_flash_page = get_config('CRASH_DUMP_FLASHPAGE', default=num_flash_pages-1, type=int)
|
||||
if crash_dump_flash_page >= num_flash_pages:
|
||||
raise Exception("CRASH_DUMP_FLASHPAGE cannot exceed number of available flash pages: %u" % num_flash_pages)
|
||||
if storage_flash_page is not None:
|
||||
while crash_dump_flash_page == storage_flash_page or crash_dump_flash_page == storage_flash_page+1:
|
||||
if crash_dump_flash_page > 0:
|
||||
crash_dump_flash_page -= 1
|
||||
else:
|
||||
raise Exception('Unable to find a Crash log flash page')
|
||||
f.write('#define HAL_CRASH_DUMP_FLASHPAGE %u\n' % crash_dump_flash_page)
|
||||
else:
|
||||
f.write('#define HAL_CRASHDUMP_ENABLE 0\n')
|
||||
env_vars['ENABLE_CRASHDUMP'] = 0
|
||||
|
|
Loading…
Reference in New Issue