From 99fde1a0ff769121db6a8d25c3f8973f3dc8a952 Mon Sep 17 00:00:00 2001 From: jflyper Date: Mon, 3 Dec 2018 09:45:36 +0900 Subject: [PATCH 1/8] Use RTC backup register for persistent storage --- make/mcu/STM32F4.mk | 4 +- src/main/drivers/persistent.c | 107 +++++++++++++++++++++++++ src/main/drivers/persistent.h | 38 +++++++++ src/main/drivers/system_stm32f4xx.c | 10 ++- src/main/startup/startup_stm32f40xx.s | 1 + src/main/startup/startup_stm32f411xe.s | 1 + src/main/startup/startup_stm32f446xx.s | 10 +-- src/main/target/system_stm32f4xx.c | 22 ++--- src/main/vcpf4/usb_bsp.c | 3 - 9 files changed, 170 insertions(+), 26 deletions(-) create mode 100644 src/main/drivers/persistent.c create mode 100644 src/main/drivers/persistent.h diff --git a/make/mcu/STM32F4.mk b/make/mcu/STM32F4.mk index a7abfb7efd..206bb6d569 100644 --- a/make/mcu/STM32F4.mk +++ b/make/mcu/STM32F4.mk @@ -37,7 +37,6 @@ EXCLUDES = stm32f4xx_crc.c \ stm32f4xx_cryp_aes.c \ stm32f4xx_hash_md5.c \ stm32f4xx_cryp_des.c \ - stm32f4xx_rtc.c \ stm32f4xx_hash.c \ stm32f4xx_dbgmcu.c \ stm32f4xx_cryp_tdes.c \ @@ -183,7 +182,8 @@ MCU_COMMON_SRC = \ drivers/serial_uart_init.c \ drivers/serial_uart_stm32f4xx.c \ drivers/system_stm32f4xx.c \ - drivers/timer_stm32f4xx.c + drivers/timer_stm32f4xx.c \ + drivers/persistent.c ifeq ($(PERIPH_DRIVER), HAL) VCP_SRC = \ diff --git a/src/main/drivers/persistent.c b/src/main/drivers/persistent.c new file mode 100644 index 0000000000..682c7a7187 --- /dev/null +++ b/src/main/drivers/persistent.c @@ -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 . + */ + +/* + * An implementation of persistent data storage utilizing RTC backup data register. + * Retains values written across software resets and boot loader activities. + */ + +#include +#include "platform.h" + +#include "drivers/persistent.h" + +#define PERSISTENT_OBJECT_MAGIC_VALUE (('B' << 24)|('e' << 16)|('f' << 8)|('1' << 0)) + +#ifdef USE_HAL_DRIVER + +static RTC_HandleTypeDef rtcHandle = { .Instance = RTC } ; + +uint32_t persistentObjectRead(persistentObjectId_e id) +{ + uint32_t value = HAL_RTCEx_BKUPRead(&rtcHandle, id); + + return value; +} + +void persistentObjectWrite(persistentObjectId_e id, uint32_t value) +{ + HAL_RTCEx_BKUPWrite(&rtcHandle, id, value); +} + +void persistentObjectRTCEnable(void) +{ + __HAL_RCC_PWR_CLK_ENABLE(); + HAL_PWR_EnableBkUpAccess(); + + __HAL_RCC_LSI_ENABLE(); + while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET); + + __HAL_RCC_RTC_CONFIG(RCC_RTCCLKSOURCE_LSI); + __HAL_RCC_RTC_ENABLE(); + + __HAL_RTC_WRITEPROTECTION_ENABLE(&rtcHandle); + __HAL_RTC_WRITEPROTECTION_DISABLE(&rtcHandle); +} + +#else +uint32_t persistentObjectRead(persistentObjectId_e id) +{ + uint32_t value = RTC_ReadBackupRegister(id); + + return value; +} + +void persistentObjectWrite(persistentObjectId_e id, uint32_t value) +{ + RTC_WriteBackupRegister(id, value); +} + +void persistentObjectRTCEnable(void) +{ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE); + PWR_BackupAccessCmd(ENABLE); + + RCC_LSICmd(ENABLE); + while (RCC_GetFlagStatus(RCC_FLAG_LSIRDY) == RESET); + + RCC_RTCCLKConfig(RCC_RTCCLKSource_LSI); + RCC_RTCCLKCmd(ENABLE); + + RTC_WriteProtectionCmd(ENABLE); + RTC_WriteProtectionCmd(DISABLE); +} +#endif + +void persistentObjectInit(void) +{ + // Configure and enable RTC for backup register access + + persistentObjectRTCEnable(); + + // Magic value checking may be sufficient + + if (!(RCC->CSR & RCC_CSR_SFTRSTF) || (persistentObjectRead(PERSISTENT_OBJECT_MAGIC) != PERSISTENT_OBJECT_MAGIC_VALUE)) { + for (int i = 1; i < PERSISTENT_OBJECT_COUNT; i++) { + persistentObjectWrite(i, 0); + } + persistentObjectWrite(PERSISTENT_OBJECT_MAGIC, PERSISTENT_OBJECT_MAGIC_VALUE); + } +} diff --git a/src/main/drivers/persistent.h b/src/main/drivers/persistent.h new file mode 100644 index 0000000000..90f0568d3f --- /dev/null +++ b/src/main/drivers/persistent.h @@ -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 . + */ + +#pragma once + +// Available RTC backup registers (4-byte words) per MCU type +// F4: 20 words +// F7: 32 words +// H7: 32 words + +typedef enum { + PERSISTENT_OBJECT_MAGIC = 0, + PERSISTENT_OBJECT_HSE_VALUE, + PERSISTENT_OBJECT_OVERCLOCK_LEVEL, + PERSISTENT_OBJECT_BOOTLOADER_REQUEST, + PERSISTENT_OBJECT_COUNT, +} persistentObjectId_e; + +void persistentObjectInit(void); +uint32_t persistentObjectRead(persistentObjectId_e id); +void persistentObjectWrite(persistentObjectId_e id, uint32_t value); diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index 535445170b..52039bcf8b 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -27,6 +27,7 @@ #include "drivers/exti.h" #include "drivers/nvic.h" #include "drivers/system.h" +#include "drivers/persistent.h" #define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) @@ -38,12 +39,11 @@ void systemReset(void) NVIC_SystemReset(); } -PERSISTENT uint32_t bootloaderRequest = 0; #define BOOTLOADER_REQUEST_COOKIE 0xDEADBEEF void systemResetToBootloader(void) { - bootloaderRequest = BOOTLOADER_REQUEST_COOKIE; + persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, BOOTLOADER_REQUEST_COOKIE); __disable_irq(); NVIC_SystemReset(); @@ -58,12 +58,14 @@ typedef struct isrVector_s { void checkForBootLoaderRequest(void) { + uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_BOOTLOADER_REQUEST); + + persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, 0); + if (bootloaderRequest != BOOTLOADER_REQUEST_COOKIE) { return; } - bootloaderRequest = 0; - extern isrVector_t system_isr_vector_table_base; __set_MSP(system_isr_vector_table_base.stackEnd); diff --git a/src/main/startup/startup_stm32f40xx.s b/src/main/startup/startup_stm32f40xx.s index f28a3f1586..08bcfc6c19 100644 --- a/src/main/startup/startup_stm32f40xx.s +++ b/src/main/startup/startup_stm32f40xx.s @@ -84,6 +84,7 @@ Reset_Handler: dsb // Defined in C code + bl persistentObjectInit bl checkForBootLoaderRequest /* Copy the data segment initializers from flash to SRAM */ diff --git a/src/main/startup/startup_stm32f411xe.s b/src/main/startup/startup_stm32f411xe.s index 591fc888a9..a3e38c12be 100644 --- a/src/main/startup/startup_stm32f411xe.s +++ b/src/main/startup/startup_stm32f411xe.s @@ -72,6 +72,7 @@ defined in linker script */ .type Reset_Handler, %function Reset_Handler: // Defined in C code + bl persistentObjectInit bl checkForBootLoaderRequest /* Copy the data segment initializers from flash to SRAM */ diff --git a/src/main/startup/startup_stm32f446xx.s b/src/main/startup/startup_stm32f446xx.s index 61c8ff4a4a..92b8eda3f0 100644 --- a/src/main/startup/startup_stm32f446xx.s +++ b/src/main/startup/startup_stm32f446xx.s @@ -71,13 +71,9 @@ defined in linker script */ .weak Reset_Handler .type Reset_Handler, %function Reset_Handler: - // Check for bootloader reboot - ldr r0, =0x2001FFFC // mj666 - ldr r1, =0xDEADBEEF // mj666 - ldr r2, [r0, #0] // mj666 - str r0, [r0, #0] // mj666 - cmp r2, r1 // mj666 - beq Reboot_Loader // mj666 + // Defined in C code + bl persistentObjectInit + bl checkForBootLoaderRequest /* Copy the data segment initializers from flash to SRAM */ movs r1, #0 diff --git a/src/main/target/system_stm32f4xx.c b/src/main/target/system_stm32f4xx.c index 377559d57a..5eac890951 100644 --- a/src/main/target/system_stm32f4xx.c +++ b/src/main/target/system_stm32f4xx.c @@ -317,6 +317,8 @@ #include "stm32f4xx.h" #include "system_stm32f4xx.h" #include "platform.h" +#include "drivers/persistent.h" + /** * @} @@ -460,12 +462,12 @@ static const pllConfig_t overclockLevels[] = { #define PLL_R 7 // PLL_R output is not used, can be any descent number #endif -static PERSISTENT uint32_t currentOverclockLevel = 0; -static PERSISTENT uint32_t hse_value = 8000000; - void SystemInitPLLParameters(void) { /* PLL setting for overclocking */ + + uint32_t currentOverclockLevel = persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL); + if (currentOverclockLevel >= ARRAYLEN(overclockLevels)) { return; } @@ -487,7 +489,7 @@ void OverclockRebootIfNecessary(uint32_t overclockLevel) // Reboot to adjust overclock frequency if (SystemCoreClock != pll->mhz * 1000000U) { - currentOverclockLevel = overclockLevel; + persistentObjectWrite(PERSISTENT_OBJECT_OVERCLOCK_LEVEL, overclockLevel); __disable_irq(); NVIC_SystemReset(); } @@ -495,8 +497,10 @@ void OverclockRebootIfNecessary(uint32_t overclockLevel) void systemClockSetHSEValue(uint32_t frequency) { + uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE); + if (hse_value != frequency) { - hse_value = frequency; + persistentObjectWrite(PERSISTENT_OBJECT_HSE_VALUE, frequency); __disable_irq(); NVIC_SystemReset(); } @@ -504,11 +508,6 @@ void systemClockSetHSEValue(uint32_t frequency) void SystemInit(void) { - if (!(RCC->CSR & RCC_CSR_SFTRSTF)) { - currentOverclockLevel = 0; - hse_value = 0; - } - /* FPU settings ------------------------------------------------------------*/ #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ @@ -588,6 +587,8 @@ void SystemInit(void) */ void SystemCoreClockUpdate(void) { + uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE); + uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2; #if defined(STM32F446xx) uint32_t pllr = 2; @@ -673,6 +674,7 @@ static int StartHSx(uint32_t onBit, uint32_t readyBit, int maxWaitCount) */ void SetSysClock(void) { + uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE); uint32_t hse_mhz = hse_value / 1000000; // Switch to HSI during clock manipulation diff --git a/src/main/vcpf4/usb_bsp.c b/src/main/vcpf4/usb_bsp.c index a3f3e4336f..27aa963b62 100644 --- a/src/main/vcpf4/usb_bsp.c +++ b/src/main/vcpf4/usb_bsp.c @@ -83,9 +83,6 @@ void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev) RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, ENABLE) ; - /* enable the PWR clock */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE); - EXTI_ClearITPendingBit(EXTI_Line0); } /** From c0d51a5f5571bd19a9a40ef38ab2ad91ca2dc898 Mon Sep 17 00:00:00 2001 From: jflyper Date: Mon, 3 Dec 2018 23:54:56 +0900 Subject: [PATCH 2/8] Convert F7s to use RTC backup register based persistent memory --- make/mcu/STM32F7.mk | 3 +- src/main/drivers/system_stm32f7xx.c | 38 +++++++++++--------------- src/main/startup/startup_stm32f722xx.s | 3 ++ src/main/startup/startup_stm32f745xx.s | 3 ++ src/main/startup/startup_stm32f746xx.s | 3 ++ src/main/startup/startup_stm32f765xx.s | 3 ++ src/main/target/stm32f7xx_hal_conf.h | 2 +- src/main/target/system_stm32f7xx.c | 30 ++++++++++---------- 8 files changed, 46 insertions(+), 39 deletions(-) diff --git a/make/mcu/STM32F7.mk b/make/mcu/STM32F7.mk index 2c5733415c..a76667fe02 100644 --- a/make/mcu/STM32F7.mk +++ b/make/mcu/STM32F7.mk @@ -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 \ diff --git a/src/main/drivers/system_stm32f7xx.c b/src/main/drivers/system_stm32f7xx.c index c5bed7df7d..d7f8ba4adf 100644 --- a/src/main/drivers/system_stm32f7xx.c +++ b/src/main/drivers/system_stm32f7xx.c @@ -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); } diff --git a/src/main/startup/startup_stm32f722xx.s b/src/main/startup/startup_stm32f722xx.s index d5f33a36bc..4deebf2b74 100644 --- a/src/main/startup/startup_stm32f722xx.s +++ b/src/main/startup/startup_stm32f722xx.s @@ -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 diff --git a/src/main/startup/startup_stm32f745xx.s b/src/main/startup/startup_stm32f745xx.s index eabae6d8bd..bb4fa6cb27 100644 --- a/src/main/startup/startup_stm32f745xx.s +++ b/src/main/startup/startup_stm32f745xx.s @@ -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 diff --git a/src/main/startup/startup_stm32f746xx.s b/src/main/startup/startup_stm32f746xx.s index bfc7ae95bf..f57a73cc0c 100644 --- a/src/main/startup/startup_stm32f746xx.s +++ b/src/main/startup/startup_stm32f746xx.s @@ -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 diff --git a/src/main/startup/startup_stm32f765xx.s b/src/main/startup/startup_stm32f765xx.s index 07f79cc0b6..99d129d0a2 100644 --- a/src/main/startup/startup_stm32f765xx.s +++ b/src/main/startup/startup_stm32f765xx.s @@ -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 diff --git a/src/main/target/stm32f7xx_hal_conf.h b/src/main/target/stm32f7xx_hal_conf.h index bc361b940e..c6c2504d9d 100644 --- a/src/main/target/stm32f7xx_hal_conf.h +++ b/src/main/target/stm32f7xx_hal_conf.h @@ -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 */ diff --git a/src/main/target/system_stm32f7xx.c b/src/main/target/system_stm32f7xx.c index 8c8d8900df..d064d3ac30 100644 --- a/src/main/target/system_stm32f7xx.c +++ b/src/main/target/system_stm32f7xx.c @@ -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(); } From 6bacdc71fffa5c5b5441f1c087e9bdc01e000e51 Mon Sep 17 00:00:00 2001 From: jflyper Date: Tue, 4 Dec 2018 00:17:44 +0900 Subject: [PATCH 3/8] Don't use variable initialization; it is referenced before it is initialized --- src/main/drivers/persistent.c | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/persistent.c b/src/main/drivers/persistent.c index 682c7a7187..ce6ec71433 100644 --- a/src/main/drivers/persistent.c +++ b/src/main/drivers/persistent.c @@ -32,10 +32,10 @@ #ifdef USE_HAL_DRIVER -static RTC_HandleTypeDef rtcHandle = { .Instance = RTC } ; - uint32_t persistentObjectRead(persistentObjectId_e id) { + RTC_HandleTypeDef rtcHandle = { .Instance = RTC }; + uint32_t value = HAL_RTCEx_BKUPRead(&rtcHandle, id); return value; @@ -43,11 +43,15 @@ uint32_t persistentObjectRead(persistentObjectId_e id) void persistentObjectWrite(persistentObjectId_e id, uint32_t value) { + RTC_HandleTypeDef rtcHandle = { .Instance = RTC }; + HAL_RTCEx_BKUPWrite(&rtcHandle, id, value); } void persistentObjectRTCEnable(void) { + RTC_HandleTypeDef rtcHandle = { .Instance = RTC }; + __HAL_RCC_PWR_CLK_ENABLE(); HAL_PWR_EnableBkUpAccess(); From a539997ffbec431e4db7e27a1f21f5e592460d1a Mon Sep 17 00:00:00 2001 From: jflyper Date: Tue, 4 Dec 2018 10:09:11 +0900 Subject: [PATCH 4/8] Change position of checkForBootloaderRequest (F745 working) --- src/main/drivers/system_stm32f7xx.c | 9 ++++++++- src/main/startup/startup_stm32f722xx.s | 1 - src/main/startup/startup_stm32f745xx.s | 1 - src/main/startup/startup_stm32f746xx.s | 1 - src/main/startup/startup_stm32f765xx.s | 1 - 5 files changed, 8 insertions(+), 5 deletions(-) diff --git a/src/main/drivers/system_stm32f7xx.c b/src/main/drivers/system_stm32f7xx.c index d7f8ba4adf..d899772668 100644 --- a/src/main/drivers/system_stm32f7xx.c +++ b/src/main/drivers/system_stm32f7xx.c @@ -154,6 +154,8 @@ 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); @@ -198,11 +200,16 @@ void checkForBootLoaderRequest(void) } 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 + + __set_MSP(p); //Set the main stack pointer to its default values + SysMemBootJump = (void (*)(void)) (*((uint32_t *) 0x1ff00004)); // Point the PC to the System Memory reset vector (+4) SysMemBootJump(); + while (1); } diff --git a/src/main/startup/startup_stm32f722xx.s b/src/main/startup/startup_stm32f722xx.s index 4deebf2b74..580a99205e 100644 --- a/src/main/startup/startup_stm32f722xx.s +++ b/src/main/startup/startup_stm32f722xx.s @@ -84,7 +84,6 @@ Reset_Handler: ldr sp, =_estack /* set stack pointer */ bl persistentObjectInit - bl checkForBootLoaderRequest /* Copy the data segment initializers from flash to SRAM */ movs r1, #0 diff --git a/src/main/startup/startup_stm32f745xx.s b/src/main/startup/startup_stm32f745xx.s index bb4fa6cb27..9d7f7b6063 100644 --- a/src/main/startup/startup_stm32f745xx.s +++ b/src/main/startup/startup_stm32f745xx.s @@ -84,7 +84,6 @@ Reset_Handler: ldr sp, =_estack /* set stack pointer */ bl persistentObjectInit - bl checkForBootLoaderRequest /* Copy the data segment initializers from flash to SRAM */ movs r1, #0 diff --git a/src/main/startup/startup_stm32f746xx.s b/src/main/startup/startup_stm32f746xx.s index f57a73cc0c..6f3fc401f9 100644 --- a/src/main/startup/startup_stm32f746xx.s +++ b/src/main/startup/startup_stm32f746xx.s @@ -84,7 +84,6 @@ Reset_Handler: ldr sp, =_estack /* set stack pointer */ bl persistentObjectInit - bl checkForBootLoaderRequest /* Copy the data segment initializers from flash to SRAM */ movs r1, #0 diff --git a/src/main/startup/startup_stm32f765xx.s b/src/main/startup/startup_stm32f765xx.s index 99d129d0a2..47bb4cf93c 100644 --- a/src/main/startup/startup_stm32f765xx.s +++ b/src/main/startup/startup_stm32f765xx.s @@ -84,7 +84,6 @@ Reset_Handler: ldr sp, =_estack /* set stack pointer */ bl persistentObjectInit - bl checkForBootLoaderRequest /* Copy the data segment initializers from flash to SRAM */ movs r1, #0 From 2446dafffdc88cc3ac896c3242558ef21476bdf7 Mon Sep 17 00:00:00 2001 From: jflyper Date: Tue, 4 Dec 2018 11:44:28 +0900 Subject: [PATCH 5/8] Kludge to do additional reset for F722 if RTC is invisible --- src/main/drivers/persistent.c | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/src/main/drivers/persistent.c b/src/main/drivers/persistent.c index ce6ec71433..963b1987c0 100644 --- a/src/main/drivers/persistent.c +++ b/src/main/drivers/persistent.c @@ -27,6 +27,7 @@ #include "platform.h" #include "drivers/persistent.h" +#include "drivers/system.h" #define PERSISTENT_OBJECT_MAGIC_VALUE (('B' << 24)|('e' << 16)|('f' << 8)|('1' << 0)) @@ -61,6 +62,21 @@ void persistentObjectRTCEnable(void) __HAL_RCC_RTC_CONFIG(RCC_RTCCLKSOURCE_LSI); __HAL_RCC_RTC_ENABLE(); +#if defined(STM32F722xx) + // F722 boot loader leaves RTC device in some unknown state that + // it is not visible at all; reads all zero and does not + // respond to any operations. + // + // Additional reset seems to clear this state, so we + // rely on ISR's reset value (0x7), which we don't manipulate + // throughout the code, to determine if the device is in the + // invisible state. + + if (RTC->ISR == 0) { + systemReset(); + } +#endif + __HAL_RTC_WRITEPROTECTION_ENABLE(&rtcHandle); __HAL_RTC_WRITEPROTECTION_DISABLE(&rtcHandle); } From 06882b6a2cbae31cc35994b62723dcd2f6d40a3b Mon Sep 17 00:00:00 2001 From: jflyper Date: Tue, 4 Dec 2018 23:02:42 +0900 Subject: [PATCH 6/8] Turn on RTC bus clock for applicable MCUs, drop time clock init --- src/main/drivers/persistent.c | 46 +++++++++++------------------------ 1 file changed, 14 insertions(+), 32 deletions(-) diff --git a/src/main/drivers/persistent.c b/src/main/drivers/persistent.c index 963b1987c0..0be8cdd52b 100644 --- a/src/main/drivers/persistent.c +++ b/src/main/drivers/persistent.c @@ -53,32 +53,18 @@ void persistentObjectRTCEnable(void) { RTC_HandleTypeDef rtcHandle = { .Instance = RTC }; - __HAL_RCC_PWR_CLK_ENABLE(); - HAL_PWR_EnableBkUpAccess(); + __HAL_RCC_PWR_CLK_ENABLE(); // Enable Access to PWR + HAL_PWR_EnableBkUpAccess(); // Disable backup domain protection - __HAL_RCC_LSI_ENABLE(); - while(__HAL_RCC_GET_FLAG(RCC_FLAG_LSIRDY) == RESET); - - __HAL_RCC_RTC_CONFIG(RCC_RTCCLKSOURCE_LSI); - __HAL_RCC_RTC_ENABLE(); - -#if defined(STM32F722xx) - // F722 boot loader leaves RTC device in some unknown state that - // it is not visible at all; reads all zero and does not - // respond to any operations. - // - // Additional reset seems to clear this state, so we - // rely on ISR's reset value (0x7), which we don't manipulate - // throughout the code, to determine if the device is in the - // invisible state. - - if (RTC->ISR == 0) { - systemReset(); - } +#if defined(__HAL_RCC_RTC_CLK_ENABLE) + // For those MCUs with RTCAPBEN bit in RCC clock enable register, turn it on. + __HAL_RCC_RTC_CLK_ENABLE(); // Enable RTC module #endif - __HAL_RTC_WRITEPROTECTION_ENABLE(&rtcHandle); - __HAL_RTC_WRITEPROTECTION_DISABLE(&rtcHandle); + // We don't need a clock source for RTC itself. Skip it. + + __HAL_RTC_WRITEPROTECTION_ENABLE(&rtcHandle); // Reset sequence + __HAL_RTC_WRITEPROTECTION_DISABLE(&rtcHandle); // Apply sequence } #else @@ -96,17 +82,13 @@ void persistentObjectWrite(persistentObjectId_e id, uint32_t value) void persistentObjectRTCEnable(void) { - RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE); - PWR_BackupAccessCmd(ENABLE); + RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE); // Enable Access to PWR + PWR_BackupAccessCmd(ENABLE); // Disable backup domain protection - RCC_LSICmd(ENABLE); - while (RCC_GetFlagStatus(RCC_FLAG_LSIRDY) == RESET); + // We don't need a clock source for RTC itself. Skip it. - RCC_RTCCLKConfig(RCC_RTCCLKSource_LSI); - RCC_RTCCLKCmd(ENABLE); - - RTC_WriteProtectionCmd(ENABLE); - RTC_WriteProtectionCmd(DISABLE); + RTC_WriteProtectionCmd(ENABLE); // Reset sequence + RTC_WriteProtectionCmd(DISABLE); // Apply sequence } #endif From 14bbc3ac0763cc6656a880db218801cb3ba383f6 Mon Sep 17 00:00:00 2001 From: jflyper Date: Tue, 4 Dec 2018 23:03:44 +0900 Subject: [PATCH 7/8] Code cleanup, remove old code and debug artifacts --- src/main/drivers/system.h | 2 ++ src/main/drivers/system_stm32f4xx.c | 2 -- src/main/drivers/system_stm32f7xx.c | 4 ++-- src/main/target/system_stm32f7xx.c | 13 ------------- 4 files changed, 4 insertions(+), 17 deletions(-) diff --git a/src/main/drivers/system.h b/src/main/drivers/system.h index 285aefdfb6..8f66593060 100644 --- a/src/main/drivers/system.h +++ b/src/main/drivers/system.h @@ -52,6 +52,8 @@ void checkForBootLoaderRequest(void); bool isMPUSoftReset(void); void cycleCounterInit(void); +#define BOOTLOADER_REQUEST_COOKIE 0xDEADBEEF + void enableGPIOPowerUsageAndNoiseReductions(void); // current crystal frequency - 8 or 12MHz diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index 52039bcf8b..17c1da9983 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -39,8 +39,6 @@ void systemReset(void) NVIC_SystemReset(); } -#define BOOTLOADER_REQUEST_COOKIE 0xDEADBEEF - void systemResetToBootloader(void) { persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, BOOTLOADER_REQUEST_COOKIE); diff --git a/src/main/drivers/system_stm32f7xx.c b/src/main/drivers/system_stm32f7xx.c index d899772668..d51fc9800e 100644 --- a/src/main/drivers/system_stm32f7xx.c +++ b/src/main/drivers/system_stm32f7xx.c @@ -45,7 +45,7 @@ void systemReset(void) void systemResetToBootloader(void) { - persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, 0xDEADBEEF); + persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, BOOTLOADER_REQUEST_COOKIE); __disable_irq(); NVIC_SystemReset(); } @@ -195,7 +195,7 @@ void checkForBootLoaderRequest(void) persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, 0xCAFEFEED); - if (bootloaderRequest != 0xDEADBEEF) { + if (bootloaderRequest != BOOTLOADER_REQUEST_COOKIE) { return; } diff --git a/src/main/target/system_stm32f7xx.c b/src/main/target/system_stm32f7xx.c index d064d3ac30..36cfea6760 100644 --- a/src/main/target/system_stm32f7xx.c +++ b/src/main/target/system_stm32f7xx.c @@ -260,20 +260,7 @@ 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 - uint32_t currentOverclockLevel = persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL); if (currentOverclockLevel >= ARRAYLEN(overclockLevels)) { From e8c194e5098975df5652798386ad0d64cfaa858f Mon Sep 17 00:00:00 2001 From: jflyper Date: Wed, 5 Dec 2018 03:16:42 +0900 Subject: [PATCH 8/8] Use zero instead of 0xCAFEFEED to indicate absence of boot loader request --- src/main/drivers/system_stm32f7xx.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/system_stm32f7xx.c b/src/main/drivers/system_stm32f7xx.c index d51fc9800e..6d0471be5f 100644 --- a/src/main/drivers/system_stm32f7xx.c +++ b/src/main/drivers/system_stm32f7xx.c @@ -193,7 +193,7 @@ void checkForBootLoaderRequest(void) { uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_BOOTLOADER_REQUEST); - persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, 0xCAFEFEED); + persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, 0); if (bootloaderRequest != BOOTLOADER_REQUEST_COOKIE) { return;