mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
AP_HAL_ChibiOS: update last_crash_dump api
This commit is contained in:
parent
0c69ebc50e
commit
f02a7b560b
@ -700,7 +700,7 @@ void Util::log_stack_info(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
#if defined(HAL_CRASH_DUMP_FLASHPAGE) && !defined(HAL_BOOTLOADER_BUILD)
|
#if defined(HAL_CRASH_DUMP_FLASHPAGE) && !defined(HAL_BOOTLOADER_BUILD)
|
||||||
void Util::last_crash_dump(ExpandingString &str) const
|
size_t Util::last_crash_dump_size() const
|
||||||
{
|
{
|
||||||
#if HAL_GCS_ENABLED
|
#if HAL_GCS_ENABLED
|
||||||
// get dump size
|
// get dump size
|
||||||
@ -708,17 +708,26 @@ void Util::last_crash_dump(ExpandingString &str) const
|
|||||||
char* dump_start = (char*)stm32_flash_getpageaddr(HAL_CRASH_DUMP_FLASHPAGE);
|
char* dump_start = (char*)stm32_flash_getpageaddr(HAL_CRASH_DUMP_FLASHPAGE);
|
||||||
if (!(dump_start[0] == 0x63 && dump_start[1] == 0x43)) {
|
if (!(dump_start[0] == 0x63 && dump_start[1] == 0x43)) {
|
||||||
// there's no valid Crash Dump
|
// there's no valid Crash Dump
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "No Crash Detected!");
|
return 0;
|
||||||
return;
|
|
||||||
}
|
}
|
||||||
if (size == 0xFFFFFFFF) {
|
if (size == 0xFFFFFFFF) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Crash Dump incomplete, dumping what we got!");
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Crash Dump incomplete, dumping what we got!");
|
||||||
size = stm32_flash_getpagesize(HAL_CRASH_DUMP_FLASHPAGE);
|
size = stm32_flash_getpagesize(HAL_CRASH_DUMP_FLASHPAGE);
|
||||||
}
|
}
|
||||||
str.append(dump_start, size);
|
return size;
|
||||||
#endif
|
#endif
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
void* Util::last_crash_dump_ptr() const
|
||||||
|
{
|
||||||
|
if (last_crash_dump_size() == 0) {
|
||||||
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "No Crash Detected!");
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
return (void*)stm32_flash_getpageaddr(HAL_CRASH_DUMP_FLASHPAGE);
|
||||||
|
}
|
||||||
|
#endif // HAL_CRASH_DUMP_FLASHPAGE
|
||||||
|
|
||||||
// set armed state
|
// set armed state
|
||||||
void Util::set_soft_armed(const bool b)
|
void Util::set_soft_armed(const bool b)
|
||||||
|
@ -141,7 +141,8 @@ private:
|
|||||||
|
|
||||||
#if defined(HAL_CRASH_DUMP_FLASHPAGE) && !defined(HAL_BOOTLOADER_BUILD)
|
#if defined(HAL_CRASH_DUMP_FLASHPAGE) && !defined(HAL_BOOTLOADER_BUILD)
|
||||||
// get last crash dump
|
// get last crash dump
|
||||||
void last_crash_dump(ExpandingString &str) const override;
|
size_t last_crash_dump_size() const override;
|
||||||
|
void* last_crash_dump_ptr() const override;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user