MPU configuration service (#8595)

MPU configuration service
This commit is contained in:
Michael Keller 2019-07-27 16:06:40 +12:00 committed by GitHub
commit f6870e4189
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
11 changed files with 327 additions and 113 deletions

View File

@ -163,6 +163,7 @@ DEVICE_FLAGS += -DSTM32H743xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h743_2m.ld
STARTUP_SRC = startup_stm32h743xx.s
TARGET_FLASH := 2048
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
else ifeq ($(TARGET),$(filter $(TARGET),$(H750xB_TARGETS)))
DEVICE_FLAGS += -DSTM32H750xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_128k.ld
@ -181,6 +182,13 @@ TARGET_FLASH := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_exst.ld
endif
ifeq ($(EXST),yes)
# Upper 8 regions are reserved for a boot loader in EXST environment
DEVICE_FLAGS += -DMAX_MPU_REGIONS=8
else
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
endif
ifneq ($(DEBUG),GDB)
OPTIMISE_DEFAULT := -Os
OPTIMISE_SPEED := -Os
@ -230,6 +238,8 @@ MCU_COMMON_SRC = \
drivers/persistent.c \
drivers/transponder_ir_io_hal.c \
drivers/audio_stm32h7xx.c \
drivers/memprot_hal.c \
drivers/memprot_stm32h7xx.c \
#drivers/accgyro/accgyro_mpu.c \
MCU_EXCLUDES = \

View File

@ -224,13 +224,40 @@ SECTIONS
.DMA_RAM (NOLOAD) :
{
. = ALIGN(32);
PROVIDE(dmaram_start = .);
_sdmaram = .;
_dmaram_start__ = _sdmaram;
KEEP(*(.DMA_RAM))
PROVIDE(dmaram_end = .);
_edmaram = .;
_dmaram_end__ = _edmaram;
} >D2_RAM
.DMA_RW_D2 (NOLOAD) :
{
. = ALIGN(32);
PROVIDE(dmarw_start = .);
_sdmarw = .;
_dmarw_start__ = _sdmarw;
KEEP(*(.DMA_RW))
PROVIDE(dmarw_end = .);
_edmarw = .;
_dmarw_end__ = _edmarw;
} >D2_RAM
.DMA_RW_AXI (NOLOAD) :
{
. = ALIGN(32);
PROVIDE(dmarwaxi_start = .);
_sdmarwaxi = .;
_dmarwaxi_start__ = _sdmarwaxi;
KEEP(*(.DMA_RW_AXI))
PROVIDE(dmarwaxi_end = .);
_edmarwaxi = .;
_dmarwaxi_end__ = _edmarwaxi;
} >RAM
.persistent_data (NOLOAD) :
{
__persistent_data_start__ = .;

View File

@ -226,6 +226,30 @@ SECTIONS
_dmaram_end__ = _edmaram;
} >D2_RAM
.DMA_RW_D2 (NOLOAD) :
{
. = ALIGN(32);
PROVIDE(dmarw_start = .);
_sdmarw = .;
_dmarw_start__ = _sdmarw;
KEEP(*(.DMA_RW))
PROVIDE(dmarw_end = .);
_edmarw = .;
_dmarw_end__ = _edmarw;
} >D2_RAM
.DMA_RW_AXI (NOLOAD) :
{
. = ALIGN(32);
PROVIDE(dmarwaxi_start = .);
_sdmarwaxi = .;
_dmarwaxi_start__ = _sdmarwaxi;
KEEP(*(.DMA_RW_AXI))
PROVIDE(dmarwaxi_end = .);
_edmarwaxi = .;
_dmarwaxi_end__ = _edmarwaxi;
} >RAM
.persistent_data (NOLOAD) :
{
__persistent_data_start__ = .;

View File

@ -241,13 +241,40 @@ SECTIONS
.DMA_RAM (NOLOAD) :
{
. = ALIGN(32);
PROVIDE(dmaram_start = .);
_sdmaram = .;
_dmaram_start__ = _sdmaram;
KEEP(*(.DMA_RAM))
PROVIDE(dmaram_end = .);
_edmaram = .;
_dmaram_end__ = _edmaram;
} >D2_RAM
.DMA_RW_D2 (NOLOAD) :
{
. = ALIGN(32);
PROVIDE(dmarw_start = .);
_sdmarw = .;
_dmarw_start__ = _sdmarw;
KEEP(*(.DMA_RW))
PROVIDE(dmarw_end = .);
_edmarw = .;
_dmarw_end__ = _edmarw;
} >D2_RAM
.DMA_RW_AXI (NOLOAD) :
{
. = ALIGN(32);
PROVIDE(dmarwaxi_start = .);
_sdmarwaxi = .;
_dmarwaxi_start__ = _sdmarwaxi;
KEEP(*(.DMA_RW_AXI))
PROVIDE(dmarwaxi_end = .);
_edmarwaxi = .;
_dmarwaxi_end__ = _edmarwaxi;
} >RAM
.persistent_data (NOLOAD) :
{
__persistent_data_start__ = .;

View File

@ -0,0 +1,38 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
typedef struct mpuRegion_s {
uint32_t start;
uint32_t end; // Zero if determined by size member (MPU_REGION_SIZE_xxx)
uint8_t size; // Zero if determined from linker symbols
uint8_t perm;
uint8_t exec;
uint8_t shareable;
uint8_t cacheable;
uint8_t bufferable;
} mpuRegion_t;
extern mpuRegion_t mpuRegions[];
extern unsigned mpuRegionCount;
void memProtReset(void);
void memProtConfigure(mpuRegion_t *mpuRegions, unsigned regionCount);

View File

@ -0,0 +1,107 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <string.h>
#include "platform.h"
#include "memprot.h"
static void memProtConfigError(void)
{
for (;;) {}
}
void memProtConfigure(mpuRegion_t *regions, unsigned regionCount)
{
MPU_Region_InitTypeDef MPU_InitStruct;
if (regionCount > MAX_MPU_REGIONS) {
memProtConfigError();
}
HAL_MPU_Disable();
// Setup common members
MPU_InitStruct.Enable = MPU_REGION_ENABLE;
MPU_InitStruct.SubRegionDisable = 0x00;
MPU_InitStruct.TypeExtField = MPU_TEX_LEVEL0;
for (unsigned number = 0; number < regionCount; number++) {
mpuRegion_t *region = &regions[number];
if (region->end == 0 && region->size == 0) {
memProtConfigError();
}
MPU_InitStruct.Number = number;
MPU_InitStruct.BaseAddress = region->start;
if (region->size) {
MPU_InitStruct.Size = region->size;
} else {
// Adjust start of the region to align with cache line size.
uint32_t start = region->start & ~0x1F;
uint32_t length = region->end - start;
if (length < 32) {
// This will also prevent flsl from returning negative (case length == 0)
length = 32;
}
int msbpos = flsl(length) - 1;
if (length == (1U << msbpos)) {
msbpos += 1;
}
MPU_InitStruct.Size = msbpos;
}
// Copy per region attributes
MPU_InitStruct.AccessPermission = region->perm;
MPU_InitStruct.DisableExec = region->exec;
MPU_InitStruct.IsShareable = region->shareable;
MPU_InitStruct.IsCacheable = region->cacheable;
MPU_InitStruct.IsBufferable = region->bufferable;
HAL_MPU_ConfigRegion(&MPU_InitStruct);
}
HAL_MPU_Enable(MPU_PRIVILEGED_DEFAULT);
}
void memProtReset(void)
{
MPU_Region_InitTypeDef MPU_InitStruct;
/* Disable the MPU */
HAL_MPU_Disable();
// Disable existing regions
for (uint8_t region = 0; region <= MAX_MPU_REGIONS; region++) {
MPU_InitStruct.Enable = MPU_REGION_DISABLE;
MPU_InitStruct.Number = region;
HAL_MPU_ConfigRegion(&MPU_InitStruct);
}
HAL_MPU_Enable(MPU_PRIVILEGED_DEFAULT);
}

View File

@ -0,0 +1,77 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
#include "memprot.h"
// Defined in linker script
extern uint8_t dmaram_start;
extern uint8_t dmaram_end;
extern uint8_t dmarwaxi_start;
extern uint8_t dmarwaxi_end;
mpuRegion_t mpuRegions[] = {
#ifdef USE_ITCM_RAM
{
// Mark ITCM-RAM as read-only
// "For Cortex®-M7, TCMs memories always behave as Non-cacheable, Non-shared normal memories, irrespectiveof the memory type attributes defined in the MPU for a memory region containing addresses held in the TCM"
// See AN4838
.start = 0x00000000,
.end = 0, // Size defined by "size"
.size = MPU_REGION_SIZE_64KB,
.perm = MPU_REGION_PRIV_RO_URO,
.exec = MPU_INSTRUCTION_ACCESS_ENABLE,
.shareable = MPU_ACCESS_NOT_SHAREABLE,
.cacheable = MPU_ACCESS_NOT_CACHEABLE,
.bufferable = MPU_ACCESS_BUFFERABLE,
},
#endif
{
// DMA transmit buffer in D2 SRAM1
// Reading needs cache coherence operation
.start = (uint32_t)&dmaram_start,
.end = (uint32_t)&dmaram_end,
.size = 0, // Size determined by ".end"
.perm = MPU_REGION_FULL_ACCESS,
.exec = MPU_INSTRUCTION_ACCESS_ENABLE,
.shareable = MPU_ACCESS_SHAREABLE,
.cacheable = MPU_ACCESS_CACHEABLE,
.bufferable = MPU_ACCESS_NOT_BUFFERABLE,
},
#ifdef USE_SDCARD_SDIO
{
// A region in AXI RAM accessible from SDIO internal DMA
.start = (uint32_t)&dmarwaxi_start,
.end = (uint32_t)&dmarwaxi_end,
.size = 0, // Size determined by ".end"
.perm = MPU_REGION_FULL_ACCESS,
.exec = MPU_INSTRUCTION_ACCESS_ENABLE,
.shareable = MPU_ACCESS_NOT_SHAREABLE,
.cacheable = MPU_ACCESS_CACHEABLE,
.bufferable = MPU_ACCESS_NOT_BUFFERABLE,
},
#endif
};
unsigned mpuRegionCount = ARRAYLEN(mpuRegions);
STATIC_ASSERT(ARRAYLEN(mpuRegions) <= MAX_MPU_REGIONS, MPU_region_count_exceeds_limit);

View File

@ -176,31 +176,6 @@ bool isMPUSoftReset(void)
void systemInit(void)
{
#ifdef USE_ITCM_RAM
// Mark ITCM-RAM as read-only
HAL_MPU_Disable();
// "For Cortex®-M7, TCMs memories always behave as Non-cacheable, Non-shared normal memories, irrespective of the memory type attributes defined in the MPU for a memory region containing addresses held in the TCM"
// See AN4838
MPU_Region_InitTypeDef MPU_InitStruct;
MPU_InitStruct.Enable = MPU_REGION_ENABLE;
MPU_InitStruct.BaseAddress = 0x00000000;
MPU_InitStruct.Size = MPU_REGION_SIZE_64KB;
MPU_InitStruct.AccessPermission = MPU_REGION_PRIV_RO_URO;
MPU_InitStruct.IsBufferable = MPU_ACCESS_BUFFERABLE;
MPU_InitStruct.IsCacheable = MPU_ACCESS_NOT_CACHEABLE;
MPU_InitStruct.IsShareable = MPU_ACCESS_NOT_SHAREABLE;
MPU_InitStruct.Number = MPU_REGION_NUMBER0;
MPU_InitStruct.TypeExtField = MPU_TEX_LEVEL0;
MPU_InitStruct.SubRegionDisable = 0x00;
MPU_InitStruct.DisableExec = MPU_INSTRUCTION_ACCESS_ENABLE;
HAL_MPU_ConfigRegion(&MPU_InitStruct);
HAL_MPU_Enable(MPU_PRIVILEGED_DEFAULT);
#endif
// Configure NVIC preempt/priority groups
HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITY_GROUPING);

View File

@ -457,9 +457,8 @@ typedef struct afatfs_t {
} initState;
#endif
#ifdef STM32H7
uint8_t cache[AFATFS_SECTOR_SIZE * AFATFS_NUM_CACHE_SECTORS] __attribute__((aligned(32)));
uint8_t *cache;
#else
uint8_t cache[AFATFS_SECTOR_SIZE * AFATFS_NUM_CACHE_SECTORS];
#endif
@ -512,6 +511,10 @@ typedef struct afatfs_t {
uint32_t rootDirectorySectors; // Zero on FAT32, for FAT16 the number of sectors that the root directory occupies
} afatfs_t;
#ifdef STM32H7
static DMA_RW_AXI uint8_t afatfs_cache[AFATFS_SECTOR_SIZE * AFATFS_NUM_CACHE_SECTORS] __attribute__((aligned(32)));
#endif
static afatfs_t afatfs;
static void afatfs_fileOperationContinue(afatfsFile_t *file);
@ -3609,6 +3612,9 @@ afatfsError_e afatfs_getLastError(void)
void afatfs_init(void)
{
#ifdef STM32H7
afatfs.cache = afatfs_cache;
#endif
afatfs.filesystemState = AFATFS_FILESYSTEM_STATE_INITIALIZATION;
afatfs.initPhase = AFATFS_INITIALIZATION_READ_MBR;
afatfs.lastClusterAllocated = FAT_SMALLEST_LEGAL_CLUSTER_NUMBER;

View File

@ -64,6 +64,8 @@
#include "stm32h7xx.h"
#include "drivers/system.h"
#include "platform.h"
#include "string.h"
#include "common/utils.h"
#include "build/debug.h"
@ -508,96 +510,15 @@ void CRS_IRQHandler(void)
}
#endif
void MPU_Config()
{
MPU_Region_InitTypeDef MPU_InitStruct;
#include "build/debug.h"
HAL_MPU_Disable();
void systemCheckResetReason(void);
MPU_InitStruct.Enable = MPU_REGION_ENABLE;
// XXX FIXME Entire D2 SRAM1 region is setup as non-bufferable (write-through) and non-cachable.
// Ideally, DMA buffer region should be prepared based on read and write activities,
// and DMA buffers should be assigned to different region based on read/write activity on
// the buffer.
// XXX FIXME Further more, sizes of DMA buffer regions should tracked and size set as appropriate
// using _<REGION>_start__ and _<REGION>_end__.
MPU_InitStruct.BaseAddress = 0x30000000;
MPU_InitStruct.Size = MPU_REGION_SIZE_128KB;
MPU_InitStruct.AccessPermission = MPU_REGION_FULL_ACCESS;
// As described in p.10 of AN4838.
// Write through & no-cache config
MPU_InitStruct.TypeExtField = MPU_TEX_LEVEL0;
MPU_InitStruct.IsCacheable = MPU_ACCESS_NOT_CACHEABLE;
MPU_InitStruct.IsBufferable = MPU_ACCESS_NOT_BUFFERABLE;
MPU_InitStruct.IsShareable = MPU_ACCESS_SHAREABLE;
MPU_InitStruct.Number = MPU_REGION_NUMBER1;
MPU_InitStruct.SubRegionDisable = 0x00;
MPU_InitStruct.DisableExec = MPU_INSTRUCTION_ACCESS_ENABLE;
HAL_MPU_ConfigRegion(&MPU_InitStruct);
#ifdef USE_SDCARD_SDIO
// The Base Address 0x24000000 is the SRAM1 accessible by the SDIO internal DMA.
MPU_InitStruct.Enable = MPU_REGION_ENABLE;
MPU_InitStruct.BaseAddress = 0x24000000;
#if defined(USE_EXST)
MPU_InitStruct.Size = MPU_REGION_SIZE_64KB;
#else
MPU_InitStruct.Size = MPU_REGION_SIZE_512KB;
#endif
MPU_InitStruct.AccessPermission = MPU_REGION_FULL_ACCESS;
MPU_InitStruct.IsBufferable = MPU_ACCESS_NOT_BUFFERABLE;
MPU_InitStruct.IsCacheable = MPU_ACCESS_CACHEABLE;
MPU_InitStruct.IsShareable = MPU_ACCESS_NOT_SHAREABLE;
MPU_InitStruct.Number = MPU_REGION_NUMBER2;
MPU_InitStruct.TypeExtField = MPU_TEX_LEVEL0;
MPU_InitStruct.SubRegionDisable = 0x00;
MPU_InitStruct.DisableExec = MPU_INSTRUCTION_ACCESS_ENABLE;
HAL_MPU_ConfigRegion(&MPU_InitStruct);
#endif
HAL_MPU_Enable(MPU_PRIVILEGED_DEFAULT);
}
/**
* @brief Setup the microcontroller system
* Initialize the FPU setting, vector table location and External memory
* configuration.
* @param None
* @retval None
*/
void resetMPU(void)
{
MPU_Region_InitTypeDef MPU_InitStruct;
/* Disable the MPU */
HAL_MPU_Disable();
#if !defined(USE_EXST)
uint8_t highestRegion = MPU_REGION_NUMBER15;
#else
uint8_t highestRegion = MPU_REGION_NUMBER7;// currently 8-15 reserved by bootloader. Bootloader may write-protect the firmware region, this firmware can examine and undo this at it's peril.
#endif
// disable all existing regions
for (uint8_t region = MPU_REGION_NUMBER0; region <= highestRegion; region++) {
MPU_InitStruct.Enable = MPU_REGION_DISABLE;
MPU_InitStruct.Number = region;
HAL_MPU_ConfigRegion(&MPU_InitStruct);
}
HAL_MPU_Enable(MPU_PRIVILEGED_DEFAULT);
}
#include "drivers/memprot.h"
void SystemInit (void)
{
resetMPU();
memProtReset();
initialiseMemorySections();
@ -692,7 +613,7 @@ void SystemInit (void)
// Configure MPU
MPU_Config();
memProtConfigure(mpuRegions, mpuRegionCount);
// Enable CPU L1-Cache
SCB_EnableICache();

View File

@ -151,8 +151,10 @@
#ifdef USE_DMA_RAM
#define DMA_RAM __attribute__((section(".DMA_RAM")))
#define DMA_RW_AXI __attribute__((section(".DMA_AXI_RW")))
#else
#define DMA_RAM
#define DMA_RW_AXI
#endif
#define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot