HAL_ChibiOS: enable DMA checking on H7

This commit is contained in:
Andrew Tridgell 2019-02-07 08:03:47 +11:00
parent 51b4d54f70
commit ae448a6932
1 changed files with 2 additions and 2 deletions

View File

@ -21,8 +21,8 @@
#include <stdio.h>
#include "bouncebuffer.h"
#if defined(STM32F7) && STM32_DMA_CACHE_HANDLING == TRUE
// on F7 we check we are in the DTCM region, and 16 bit aligned
#if DTCM_RAM_SIZE_KB > 0
// on F7 and H7 we check we are in the DTCM region, and 16 bit aligned
#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