Skip to content

Commit

Permalink
AP_HAL_ChibiOS: increase the number of memory regions for crashdump
Browse files Browse the repository at this point in the history
also checks num region overruns for bss and heap
  • Loading branch information
bugobliterator authored and robertlong13 committed Oct 14, 2024
1 parent 7dd1f9b commit b9f342a
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions libraries/AP_HAL_ChibiOS/hwdef/common/crashdump.c
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ const CrashCatcherMemoryRegion* CrashCatcher_GetMemoryRegions(void);
const CrashCatcherMemoryRegion* CrashCatcher_GetMemoryRegions(void)
{
// do a full dump if on serial
static CrashCatcherMemoryRegion regions[60] = {
static CrashCatcherMemoryRegion regions[80] = {
{(uint32_t)&__ram0_start__, (uint32_t)&__ram0_end__, CRASH_CATCHER_BYTE},
{(uint32_t)&ch_system, (uint32_t)&ch_system + sizeof(ch_system), CRASH_CATCHER_BYTE}};
uint32_t total_dump_size = dump_size + buf_off + REMAINDER_MEM_REGION_SIZE;
Expand Down Expand Up @@ -138,7 +138,7 @@ const CrashCatcherMemoryRegion* CrashCatcher_GetMemoryRegions(void)
// log statically alocated memory
int32_t bss_size = ((uint32_t)&__bss_end__) - ((uint32_t)&__bss_base__);
int32_t available_space = stm32_crash_dump_max_size() - total_dump_size;
if (available_space < 0) {
if (available_space < 0 || curr_region >= (ARRAY_SIZE(regions) - 1)) {
// we can't log anymore than this
goto finalise;
}
Expand All @@ -157,7 +157,7 @@ const CrashCatcherMemoryRegion* CrashCatcher_GetMemoryRegions(void)
// dump the Heap as well as much as we can
int32_t heap_size = ((uint32_t)&__heap_end__) - ((uint32_t)&__heap_base__);
available_space = stm32_crash_dump_max_size() - total_dump_size;
if (available_space < 0) {
if (available_space < 0 || curr_region >= (ARRAY_SIZE(regions) - 1)) {
// we can't log anymore than this
goto finalise;
}
Expand Down

0 comments on commit b9f342a

Please sign in to comment.