HAL_ChibiOS: fix DTCM size in stm32f745 mcu

This commit is contained in:
Alexander Malishev 2018-07-26 01:51:06 +04:00 committed by Andrew Tridgell
parent c6ac1bf95a
commit 06434a48c3

View File

@ -23,7 +23,7 @@
#if defined(STM32F7) && STM32_DMA_CACHE_HANDLING == TRUE
// on F7 we check we are in the DTCM region, and 16 bit aligned
#define IS_DMA_SAFE(addr) ((((uint32_t)(addr)) & 0xFFFE0001) == 0x20000000)
#define IS_DMA_SAFE(addr) ((((uint32_t)(addr)) & ((0xFFFFFFFF & ~(DTCM_RAM_SIZE_KB*1024U-1)) | 1U)) == 0x20000000)
#else
// this checks an address is in main memory and 16 bit aligned
#define IS_DMA_SAFE(addr) ((((uint32_t)(addr)) & 0xF0000001) == 0x20000000)