HAL_ChibiOS: skip compiling last_crash_dump if bootloader and GCS disabled

This commit is contained in:
bugobliterator 2021-10-27 12:12:03 +05:30 committed by Andrew Tridgell
parent 8651d99de6
commit a28bf358d1
2 changed files with 4 additions and 2 deletions

View File

@ -699,9 +699,10 @@ void Util::log_stack_info(void)
#endif
}
#if defined(HAL_CRASH_DUMP_FLASHPAGE)
#if defined(HAL_CRASH_DUMP_FLASHPAGE) && !defined(HAL_BOOTLOADER_BUILD)
void Util::last_crash_dump(ExpandingString &str) const
{
#if HAL_GCS_ENABLED
// get dump size
uint32_t size = stm32_crash_dump_size();
char* dump_start = (char*)stm32_flash_getpageaddr(HAL_CRASH_DUMP_FLASHPAGE);
@ -715,5 +716,6 @@ void Util::last_crash_dump(ExpandingString &str) const
size = stm32_flash_getpagesize(HAL_CRASH_DUMP_FLASHPAGE);
}
str.append(dump_start, size);
#endif
}
#endif

View File

@ -136,7 +136,7 @@ private:
// log info on stack usage
void log_stack_info(void) override;
#if defined(HAL_CRASH_DUMP_FLASHPAGE)
#if defined(HAL_CRASH_DUMP_FLASHPAGE) && !defined(HAL_BOOTLOADER_BUILD)
// get last crash dump
void last_crash_dump(ExpandingString &str) const override;
#endif