1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 14:25:20 +03:00

Enabled MPU for ITCM-RAM and MemManage_Handler

This commit is contained in:
Andrey Mironov 2018-07-24 12:59:16 +03:00
parent 805b2f4b1e
commit 134616ed32
3 changed files with 30 additions and 2 deletions

View file

@ -162,6 +162,10 @@ void systemInit(void)
{ {
checkForBootLoaderRequest(); checkForBootLoaderRequest();
// Mark ITCM-RAM as read-only
LL_MPU_ConfigRegion(LL_MPU_REGION_NUMBER0, 0, RAMITCM_BASE, LL_MPU_REGION_SIZE_16KB | LL_MPU_REGION_PRIV_RO_URO);
LL_MPU_Enable(LL_MPU_CTRL_PRIVILEGED_DEFAULT);
//SystemClock_Config(); //SystemClock_Config();
// Configure NVIC preempt/priority groups // Configure NVIC preempt/priority groups

View file

@ -31,6 +31,31 @@
#include "flight/mixer.h" #include "flight/mixer.h"
#ifdef STM32F7
void MemManage_Handler(void)
{
LED2_ON;
#ifdef USE_TRANSPONDER
// prevent IR LEDs from burning out.
uint8_t requiredStateForTransponder = SYSTEM_STATE_CONFIG_LOADED | SYSTEM_STATE_TRANSPONDER_ENABLED;
if ((systemState & requiredStateForTransponder) == requiredStateForTransponder) {
transponderIrDisable();
}
#endif
LED1_OFF;
LED0_OFF;
while (1) {
delay(500);
LED2_TOGGLE;
delay(50);
LED2_TOGGLE;
}
}
#endif
#ifdef DEBUG_HARDFAULTS #ifdef DEBUG_HARDFAULTS
//from: https://mcuoneclipse.com/2012/11/24/debugging-hard-faults-on-arm-cortex-m/ //from: https://mcuoneclipse.com/2012/11/24/debugging-hard-faults-on-arm-cortex-m/
/** /**
@ -116,10 +141,8 @@ void HardFault_Handler(void)
LED0_OFF; LED0_OFF;
while (1) { while (1) {
#ifdef LED2
delay(50); delay(50);
LED2_TOGGLE; LED2_TOGGLE;
#endif
} }
} }
#endif #endif

View file

@ -31,6 +31,7 @@
#include "stm32f7xx_hal.h" #include "stm32f7xx_hal.h"
#include "system_stm32f7xx.h" #include "system_stm32f7xx.h"
#include "stm32f7xx_ll_cortex.h"
#include "stm32f7xx_ll_spi.h" #include "stm32f7xx_ll_spi.h"
#include "stm32f7xx_ll_gpio.h" #include "stm32f7xx_ll_gpio.h"
#include "stm32f7xx_ll_dma.h" #include "stm32f7xx_ll_dma.h"