Convert F7s to use RTC backup register based persistent memory

This commit is contained in:
jflyper 2018-12-03 23:54:56 +09:00
parent 99fde1a0ff
commit c0d51a5f55
8 changed files with 46 additions and 39 deletions

View File

@ -41,8 +41,6 @@ EXCLUDES = stm32f7xx_hal_can.c \
stm32f7xx_hal_nor.c \
stm32f7xx_hal_qspi.c \
stm32f7xx_hal_rng.c \
stm32f7xx_hal_rtc.c \
stm32f7xx_hal_rtc_ex.c \
stm32f7xx_hal_sai.c \
stm32f7xx_hal_sai_ex.c \
stm32f7xx_hal_sd.c \
@ -179,6 +177,7 @@ MCU_COMMON_SRC = \
drivers/light_ws2811strip_hal.c \
drivers/transponder_ir_io_hal.c \
drivers/bus_spi_ll.c \
drivers/persistent.c \
drivers/pwm_output_dshot_hal.c \
drivers/timer_hal.c \
drivers/timer_stm32f7xx.c \

View File

@ -29,6 +29,7 @@
#include "drivers/exti.h"
#include "drivers/nvic.h"
#include "drivers/system.h"
#include "drivers/persistent.h"
#include "stm32f7xx_ll_cortex.h"
@ -44,8 +45,7 @@ void systemReset(void)
void systemResetToBootloader(void)
{
(*(__IO uint32_t *) (BKPSRAM_BASE + 4)) = 0xDEADBEEF; // flag that will be readable after reboot
persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, 0xDEADBEEF);
__disable_irq();
NVIC_SystemReset();
}
@ -154,8 +154,6 @@ bool isMPUSoftReset(void)
void systemInit(void)
{
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);
@ -188,27 +186,23 @@ void systemInit(void)
}
void(*bootJump)(void);
void checkForBootLoaderRequest(void)
{
uint32_t bt;
__PWR_CLK_ENABLE();
__BKPSRAM_CLK_ENABLE();
HAL_PWR_EnableBkUpAccess();
uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_BOOTLOADER_REQUEST);
bt = (*(__IO uint32_t *) (BKPSRAM_BASE + 4)) ;
if ( bt == 0xDEADBEEF ) {
(*(__IO uint32_t *) (BKPSRAM_BASE + 4)) = 0xCAFEFEED; // Reset our trigger
// Backup SRAM is write-back by default, ensure value actually reaches memory
// Another solution would be marking BKPSRAM as write-through in Memory Protection Unit settings
SCB_CleanDCache_by_Addr((uint32_t *) (BKPSRAM_BASE + 4), sizeof(uint32_t));
persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, 0xCAFEFEED);
void (*SysMemBootJump)(void);
__SYSCFG_CLK_ENABLE();
SYSCFG->MEMRMP |= SYSCFG_MEM_BOOT_ADD0 ;
uint32_t p = (*((uint32_t *) 0x1ff00000));
__set_MSP(p); //Set the main stack pointer to its defualt values
SysMemBootJump = (void (*)(void)) (*((uint32_t *) 0x1ff00004)); // Point the PC to the System Memory reset vector (+4)
SysMemBootJump();
while (1);
if (bootloaderRequest != 0xDEADBEEF) {
return;
}
void (*SysMemBootJump)(void);
__SYSCFG_CLK_ENABLE();
SYSCFG->MEMRMP |= SYSCFG_MEM_BOOT_ADD0 ;
uint32_t p = (*((uint32_t *) 0x1ff00000));
__set_MSP(p); //Set the main stack pointer to its defualt values
SysMemBootJump = (void (*)(void)) (*((uint32_t *) 0x1ff00004)); // Point the PC to the System Memory reset vector (+4)
SysMemBootJump();
while (1);
}

View File

@ -83,6 +83,9 @@ defined in linker script */
Reset_Handler:
ldr sp, =_estack /* set stack pointer */
bl persistentObjectInit
bl checkForBootLoaderRequest
/* Copy the data segment initializers from flash to SRAM */
movs r1, #0
b LoopCopyDataInit

View File

@ -83,6 +83,9 @@ defined in linker script */
Reset_Handler:
ldr sp, =_estack /* set stack pointer */
bl persistentObjectInit
bl checkForBootLoaderRequest
/* Copy the data segment initializers from flash to SRAM */
movs r1, #0
b LoopCopyDataInit

View File

@ -83,6 +83,9 @@ defined in linker script */
Reset_Handler:
ldr sp, =_estack /* set stack pointer */
bl persistentObjectInit
bl checkForBootLoaderRequest
/* Copy the data segment initializers from flash to SRAM */
movs r1, #0
b LoopCopyDataInit

View File

@ -83,6 +83,9 @@ defined in linker script */
Reset_Handler:
ldr sp, =_estack /* set stack pointer */
bl persistentObjectInit
bl checkForBootLoaderRequest
/* Copy the data segment initializers from flash to SRAM */
movs r1, #0
b LoopCopyDataInit

View File

@ -69,7 +69,7 @@
/* #define HAL_LTDC_MODULE_ENABLED */
/* #define HAL_QSPI_MODULE_ENABLED */
/* #define HAL_RNG_MODULE_ENABLED */
/* #define HAL_RTC_MODULE_ENABLED */
#define HAL_RTC_MODULE_ENABLED
/* #define HAL_SAI_MODULE_ENABLED */
/* #define HAL_SD_MODULE_ENABLED */
/* #define HAL_MMC_MODULE_ENABLED */

View File

@ -66,6 +66,7 @@
#include "stm32f7xx.h"
#include "system_stm32f7xx.h"
#include "platform.h"
#include "drivers/persistent.h"
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz */
@ -259,30 +260,32 @@ static const pllConfig_t overclockLevels[] = {
{ 480, RCC_PLLP_DIV2, 10 }, // 240 MHz
};
#if 0
// 8 bytes of memory located at the very end of RAM, expected to be unoccupied
#define REQUEST_OVERCLOCK (*(__IO uint32_t *) (BKPSRAM_BASE + 8))
#define CURRENT_OVERCLOCK_LEVEL (*(__IO uint32_t *) (BKPSRAM_BASE + 12))
#define REQUEST_OVERCLOCK_MAGIC_COOKIE 0xBABEFACE
#endif
void SystemInitOC(void) {
#if 0
__PWR_CLK_ENABLE();
__BKPSRAM_CLK_ENABLE();
HAL_PWR_EnableBkUpAccess();
#endif
if (REQUEST_OVERCLOCK_MAGIC_COOKIE == REQUEST_OVERCLOCK) {
const uint32_t overclockLevel = CURRENT_OVERCLOCK_LEVEL;
uint32_t currentOverclockLevel = persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL);
/* PLL setting for overclocking */
if (overclockLevel < ARRAYLEN(overclockLevels)) {
const pllConfig_t * const pll = overclockLevels + overclockLevel;
pll_n = pll->n;
pll_p = pll->p;
pll_q = pll->q;
}
REQUEST_OVERCLOCK = 0;
if (currentOverclockLevel >= ARRAYLEN(overclockLevels)) {
return;
}
/* PLL setting for overclocking */
const pllConfig_t * const pll = overclockLevels + currentOverclockLevel;
pll_n = pll->n;
pll_p = pll->p;
pll_q = pll->q;
}
void OverclockRebootIfNecessary(uint32_t overclockLevel)
@ -295,8 +298,7 @@ void OverclockRebootIfNecessary(uint32_t overclockLevel)
// Reboot to adjust overclock frequency
if (SystemCoreClock != (pll->n / pll->p) * 1000000U) {
REQUEST_OVERCLOCK = REQUEST_OVERCLOCK_MAGIC_COOKIE;
CURRENT_OVERCLOCK_LEVEL = overclockLevel;
persistentObjectWrite(PERSISTENT_OBJECT_OVERCLOCK_LEVEL, overclockLevel);
__disable_irq();
NVIC_SystemReset();
}