HAL_ChibiOS: flush all memory on chSysHalt()

this makes debugging a lot easier, as gdb can see the values in dcache
This commit is contained in:
Andrew Tridgell 2018-06-04 10:55:34 +10:00
parent dc2a776985
commit 0e09dc75c0
2 changed files with 16 additions and 3 deletions

View File

@ -520,11 +520,13 @@
* @brief System halt hook.
* @details This hook is invoked in case to a system halting error before
* the system is halted.
*
* We flush all memory on STM32F7 to allow gdb to access variables currently
* in the dcache
*/
#define CH_CFG_SYSTEM_HALT_HOOK(reason) do { \
extern int printf(const char *fmt, ...); \
printf(reason); \
extern void memory_flush_all(void); \
memory_flush_all(); \
} while(0)
/**

View File

@ -17,6 +17,7 @@
#include <stdint.h>
#include <stdio.h>
#include <string.h>
#include <stm32_dma.h>
void stm32_timer_set_input_filter(stm32_tim_t *tim, uint8_t channel, uint8_t filter_mode)
{
@ -54,3 +55,13 @@ void show_stack_usage(void)
} while (tp != NULL);
}
#endif
/*
flush all memory. Used in chSysHalt()
*/
void memory_flush_all(void)
{
#if defined(STM32F7) && STM32_DMA_CACHE_HANDLING == TRUE
dmaBufferFlush(HAL_RAM_BASE_ADDRESS, HAL_RAM_SIZE_KB * 1024U);
#endif
}