HAL_ChibiOS: fixed bouncebuffer code on STM32F7

This commit is contained in:
Andrew Tridgell 2019-02-18 11:10:53 +11:00
parent ef3306d408
commit e92c66418d
2 changed files with 7 additions and 4 deletions

View File

@ -24,9 +24,10 @@
#if defined(STM32H7)
// always use a bouncebuffer on H7, to ensure alignment and padding
#define IS_DMA_SAFE(addr) false
#elif defined(DTCM_RAM_SIZE_KB)
// 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)
#elif defined(STM32F7)
// on F76x we only consider first half of DTCM memory as DMA safe, 2nd half is used as fast memory for EKF
// on F74x we only have 64k of DTCM
#define IS_DMA_SAFE(addr) ((((uint32_t)(addr)) & ((0xFFFFFFFF & ~(64*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)

View File

@ -35,7 +35,9 @@ mcu = {
# flags of 2 means faster memory for CPU intensive work
'RAM_MAP' : [
(0x20020000, 384, 0), # SRAM1/SRAM2
(0x20000000, 128, 1), # DTCM, DMA
# split DTCM in two to allow for fast checking of IS_DMA_SAFE in bouncebuffer code
(0x20000000, 64, 1), # DTCM, DMA safe
(0x20010000, 64, 2), # DTCM, 2nd half, used as fast memory. This lowers memory contention in the EKF code
]
}