mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 05:15:25 +03:00
Merge pull request #7166 from jflyper/bfdev-use-RTC-backup-register-for-persistent-data
[SYSTEM] Use RTC backup register for persistent storage
This commit is contained in:
commit
2e81109be1
18 changed files with 217 additions and 74 deletions
|
@ -37,7 +37,6 @@ EXCLUDES = stm32f4xx_crc.c \
|
||||||
stm32f4xx_cryp_aes.c \
|
stm32f4xx_cryp_aes.c \
|
||||||
stm32f4xx_hash_md5.c \
|
stm32f4xx_hash_md5.c \
|
||||||
stm32f4xx_cryp_des.c \
|
stm32f4xx_cryp_des.c \
|
||||||
stm32f4xx_rtc.c \
|
|
||||||
stm32f4xx_hash.c \
|
stm32f4xx_hash.c \
|
||||||
stm32f4xx_dbgmcu.c \
|
stm32f4xx_dbgmcu.c \
|
||||||
stm32f4xx_cryp_tdes.c \
|
stm32f4xx_cryp_tdes.c \
|
||||||
|
@ -183,7 +182,8 @@ MCU_COMMON_SRC = \
|
||||||
drivers/serial_uart_init.c \
|
drivers/serial_uart_init.c \
|
||||||
drivers/serial_uart_stm32f4xx.c \
|
drivers/serial_uart_stm32f4xx.c \
|
||||||
drivers/system_stm32f4xx.c \
|
drivers/system_stm32f4xx.c \
|
||||||
drivers/timer_stm32f4xx.c
|
drivers/timer_stm32f4xx.c \
|
||||||
|
drivers/persistent.c
|
||||||
|
|
||||||
ifeq ($(PERIPH_DRIVER), HAL)
|
ifeq ($(PERIPH_DRIVER), HAL)
|
||||||
VCP_SRC = \
|
VCP_SRC = \
|
||||||
|
|
|
@ -41,8 +41,6 @@ EXCLUDES = stm32f7xx_hal_can.c \
|
||||||
stm32f7xx_hal_nor.c \
|
stm32f7xx_hal_nor.c \
|
||||||
stm32f7xx_hal_qspi.c \
|
stm32f7xx_hal_qspi.c \
|
||||||
stm32f7xx_hal_rng.c \
|
stm32f7xx_hal_rng.c \
|
||||||
stm32f7xx_hal_rtc.c \
|
|
||||||
stm32f7xx_hal_rtc_ex.c \
|
|
||||||
stm32f7xx_hal_sai.c \
|
stm32f7xx_hal_sai.c \
|
||||||
stm32f7xx_hal_sai_ex.c \
|
stm32f7xx_hal_sai_ex.c \
|
||||||
stm32f7xx_hal_sd.c \
|
stm32f7xx_hal_sd.c \
|
||||||
|
@ -179,6 +177,7 @@ MCU_COMMON_SRC = \
|
||||||
drivers/light_ws2811strip_hal.c \
|
drivers/light_ws2811strip_hal.c \
|
||||||
drivers/transponder_ir_io_hal.c \
|
drivers/transponder_ir_io_hal.c \
|
||||||
drivers/bus_spi_ll.c \
|
drivers/bus_spi_ll.c \
|
||||||
|
drivers/persistent.c \
|
||||||
drivers/pwm_output_dshot_hal.c \
|
drivers/pwm_output_dshot_hal.c \
|
||||||
drivers/timer_hal.c \
|
drivers/timer_hal.c \
|
||||||
drivers/timer_stm32f7xx.c \
|
drivers/timer_stm32f7xx.c \
|
||||||
|
|
109
src/main/drivers/persistent.c
Normal file
109
src/main/drivers/persistent.c
Normal file
|
@ -0,0 +1,109 @@
|
||||||
|
/*
|
||||||
|
* 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/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
* An implementation of persistent data storage utilizing RTC backup data register.
|
||||||
|
* Retains values written across software resets and boot loader activities.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "drivers/persistent.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
#define PERSISTENT_OBJECT_MAGIC_VALUE (('B' << 24)|('e' << 16)|('f' << 8)|('1' << 0))
|
||||||
|
|
||||||
|
#ifdef USE_HAL_DRIVER
|
||||||
|
|
||||||
|
uint32_t persistentObjectRead(persistentObjectId_e id)
|
||||||
|
{
|
||||||
|
RTC_HandleTypeDef rtcHandle = { .Instance = RTC };
|
||||||
|
|
||||||
|
uint32_t value = HAL_RTCEx_BKUPRead(&rtcHandle, id);
|
||||||
|
|
||||||
|
return value;
|
||||||
|
}
|
||||||
|
|
||||||
|
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(); // Enable Access to PWR
|
||||||
|
HAL_PWR_EnableBkUpAccess(); // Disable backup domain protection
|
||||||
|
|
||||||
|
#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
|
||||||
|
|
||||||
|
// 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
|
||||||
|
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); // Enable Access to PWR
|
||||||
|
PWR_BackupAccessCmd(ENABLE); // Disable backup domain protection
|
||||||
|
|
||||||
|
// We don't need a clock source for RTC itself. Skip it.
|
||||||
|
|
||||||
|
RTC_WriteProtectionCmd(ENABLE); // Reset sequence
|
||||||
|
RTC_WriteProtectionCmd(DISABLE); // Apply sequence
|
||||||
|
}
|
||||||
|
#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);
|
||||||
|
}
|
||||||
|
}
|
38
src/main/drivers/persistent.h
Normal file
38
src/main/drivers/persistent.h
Normal 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
|
||||||
|
|
||||||
|
// 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);
|
|
@ -52,6 +52,8 @@ void checkForBootLoaderRequest(void);
|
||||||
bool isMPUSoftReset(void);
|
bool isMPUSoftReset(void);
|
||||||
void cycleCounterInit(void);
|
void cycleCounterInit(void);
|
||||||
|
|
||||||
|
#define BOOTLOADER_REQUEST_COOKIE 0xDEADBEEF
|
||||||
|
|
||||||
void enableGPIOPowerUsageAndNoiseReductions(void);
|
void enableGPIOPowerUsageAndNoiseReductions(void);
|
||||||
// current crystal frequency - 8 or 12MHz
|
// current crystal frequency - 8 or 12MHz
|
||||||
|
|
||||||
|
|
|
@ -27,6 +27,7 @@
|
||||||
#include "drivers/exti.h"
|
#include "drivers/exti.h"
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
#include "drivers/persistent.h"
|
||||||
|
|
||||||
|
|
||||||
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
|
#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
|
||||||
|
@ -38,12 +39,9 @@ void systemReset(void)
|
||||||
NVIC_SystemReset();
|
NVIC_SystemReset();
|
||||||
}
|
}
|
||||||
|
|
||||||
PERSISTENT uint32_t bootloaderRequest = 0;
|
|
||||||
#define BOOTLOADER_REQUEST_COOKIE 0xDEADBEEF
|
|
||||||
|
|
||||||
void systemResetToBootloader(void)
|
void systemResetToBootloader(void)
|
||||||
{
|
{
|
||||||
bootloaderRequest = BOOTLOADER_REQUEST_COOKIE;
|
persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, BOOTLOADER_REQUEST_COOKIE);
|
||||||
|
|
||||||
__disable_irq();
|
__disable_irq();
|
||||||
NVIC_SystemReset();
|
NVIC_SystemReset();
|
||||||
|
@ -58,12 +56,14 @@ typedef struct isrVector_s {
|
||||||
|
|
||||||
void checkForBootLoaderRequest(void)
|
void checkForBootLoaderRequest(void)
|
||||||
{
|
{
|
||||||
|
uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_BOOTLOADER_REQUEST);
|
||||||
|
|
||||||
|
persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, 0);
|
||||||
|
|
||||||
if (bootloaderRequest != BOOTLOADER_REQUEST_COOKIE) {
|
if (bootloaderRequest != BOOTLOADER_REQUEST_COOKIE) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
bootloaderRequest = 0;
|
|
||||||
|
|
||||||
extern isrVector_t system_isr_vector_table_base;
|
extern isrVector_t system_isr_vector_table_base;
|
||||||
|
|
||||||
__set_MSP(system_isr_vector_table_base.stackEnd);
|
__set_MSP(system_isr_vector_table_base.stackEnd);
|
||||||
|
|
|
@ -29,6 +29,7 @@
|
||||||
#include "drivers/exti.h"
|
#include "drivers/exti.h"
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
#include "drivers/persistent.h"
|
||||||
|
|
||||||
#include "stm32f7xx_ll_cortex.h"
|
#include "stm32f7xx_ll_cortex.h"
|
||||||
|
|
||||||
|
@ -44,8 +45,7 @@ void systemReset(void)
|
||||||
|
|
||||||
void systemResetToBootloader(void)
|
void systemResetToBootloader(void)
|
||||||
{
|
{
|
||||||
(*(__IO uint32_t *) (BKPSRAM_BASE + 4)) = 0xDEADBEEF; // flag that will be readable after reboot
|
persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, BOOTLOADER_REQUEST_COOKIE);
|
||||||
|
|
||||||
__disable_irq();
|
__disable_irq();
|
||||||
NVIC_SystemReset();
|
NVIC_SystemReset();
|
||||||
}
|
}
|
||||||
|
@ -188,27 +188,28 @@ void systemInit(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
void(*bootJump)(void);
|
void(*bootJump)(void);
|
||||||
|
|
||||||
void checkForBootLoaderRequest(void)
|
void checkForBootLoaderRequest(void)
|
||||||
{
|
{
|
||||||
uint32_t bt;
|
uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_BOOTLOADER_REQUEST);
|
||||||
__PWR_CLK_ENABLE();
|
|
||||||
__BKPSRAM_CLK_ENABLE();
|
|
||||||
HAL_PWR_EnableBkUpAccess();
|
|
||||||
|
|
||||||
bt = (*(__IO uint32_t *) (BKPSRAM_BASE + 4)) ;
|
persistentObjectWrite(PERSISTENT_OBJECT_BOOTLOADER_REQUEST, 0);
|
||||||
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));
|
|
||||||
|
|
||||||
void (*SysMemBootJump)(void);
|
if (bootloaderRequest != BOOTLOADER_REQUEST_COOKIE) {
|
||||||
__SYSCFG_CLK_ENABLE();
|
return;
|
||||||
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);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
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 default values
|
||||||
|
|
||||||
|
SysMemBootJump = (void (*)(void)) (*((uint32_t *) 0x1ff00004)); // Point the PC to the System Memory reset vector (+4)
|
||||||
|
SysMemBootJump();
|
||||||
|
|
||||||
|
while (1);
|
||||||
}
|
}
|
||||||
|
|
|
@ -84,6 +84,7 @@ Reset_Handler:
|
||||||
dsb
|
dsb
|
||||||
|
|
||||||
// Defined in C code
|
// Defined in C code
|
||||||
|
bl persistentObjectInit
|
||||||
bl checkForBootLoaderRequest
|
bl checkForBootLoaderRequest
|
||||||
|
|
||||||
/* Copy the data segment initializers from flash to SRAM */
|
/* Copy the data segment initializers from flash to SRAM */
|
||||||
|
|
|
@ -72,6 +72,7 @@ defined in linker script */
|
||||||
.type Reset_Handler, %function
|
.type Reset_Handler, %function
|
||||||
Reset_Handler:
|
Reset_Handler:
|
||||||
// Defined in C code
|
// Defined in C code
|
||||||
|
bl persistentObjectInit
|
||||||
bl checkForBootLoaderRequest
|
bl checkForBootLoaderRequest
|
||||||
|
|
||||||
/* Copy the data segment initializers from flash to SRAM */
|
/* Copy the data segment initializers from flash to SRAM */
|
||||||
|
|
|
@ -71,13 +71,9 @@ defined in linker script */
|
||||||
.weak Reset_Handler
|
.weak Reset_Handler
|
||||||
.type Reset_Handler, %function
|
.type Reset_Handler, %function
|
||||||
Reset_Handler:
|
Reset_Handler:
|
||||||
// Check for bootloader reboot
|
// Defined in C code
|
||||||
ldr r0, =0x2001FFFC // mj666
|
bl persistentObjectInit
|
||||||
ldr r1, =0xDEADBEEF // mj666
|
bl checkForBootLoaderRequest
|
||||||
ldr r2, [r0, #0] // mj666
|
|
||||||
str r0, [r0, #0] // mj666
|
|
||||||
cmp r2, r1 // mj666
|
|
||||||
beq Reboot_Loader // mj666
|
|
||||||
|
|
||||||
/* Copy the data segment initializers from flash to SRAM */
|
/* Copy the data segment initializers from flash to SRAM */
|
||||||
movs r1, #0
|
movs r1, #0
|
||||||
|
|
|
@ -83,6 +83,8 @@ defined in linker script */
|
||||||
Reset_Handler:
|
Reset_Handler:
|
||||||
ldr sp, =_estack /* set stack pointer */
|
ldr sp, =_estack /* set stack pointer */
|
||||||
|
|
||||||
|
bl persistentObjectInit
|
||||||
|
|
||||||
/* Copy the data segment initializers from flash to SRAM */
|
/* Copy the data segment initializers from flash to SRAM */
|
||||||
movs r1, #0
|
movs r1, #0
|
||||||
b LoopCopyDataInit
|
b LoopCopyDataInit
|
||||||
|
|
|
@ -83,6 +83,8 @@ defined in linker script */
|
||||||
Reset_Handler:
|
Reset_Handler:
|
||||||
ldr sp, =_estack /* set stack pointer */
|
ldr sp, =_estack /* set stack pointer */
|
||||||
|
|
||||||
|
bl persistentObjectInit
|
||||||
|
|
||||||
/* Copy the data segment initializers from flash to SRAM */
|
/* Copy the data segment initializers from flash to SRAM */
|
||||||
movs r1, #0
|
movs r1, #0
|
||||||
b LoopCopyDataInit
|
b LoopCopyDataInit
|
||||||
|
|
|
@ -83,6 +83,8 @@ defined in linker script */
|
||||||
Reset_Handler:
|
Reset_Handler:
|
||||||
ldr sp, =_estack /* set stack pointer */
|
ldr sp, =_estack /* set stack pointer */
|
||||||
|
|
||||||
|
bl persistentObjectInit
|
||||||
|
|
||||||
/* Copy the data segment initializers from flash to SRAM */
|
/* Copy the data segment initializers from flash to SRAM */
|
||||||
movs r1, #0
|
movs r1, #0
|
||||||
b LoopCopyDataInit
|
b LoopCopyDataInit
|
||||||
|
|
|
@ -83,6 +83,8 @@ defined in linker script */
|
||||||
Reset_Handler:
|
Reset_Handler:
|
||||||
ldr sp, =_estack /* set stack pointer */
|
ldr sp, =_estack /* set stack pointer */
|
||||||
|
|
||||||
|
bl persistentObjectInit
|
||||||
|
|
||||||
/* Copy the data segment initializers from flash to SRAM */
|
/* Copy the data segment initializers from flash to SRAM */
|
||||||
movs r1, #0
|
movs r1, #0
|
||||||
b LoopCopyDataInit
|
b LoopCopyDataInit
|
||||||
|
|
|
@ -69,7 +69,7 @@
|
||||||
/* #define HAL_LTDC_MODULE_ENABLED */
|
/* #define HAL_LTDC_MODULE_ENABLED */
|
||||||
/* #define HAL_QSPI_MODULE_ENABLED */
|
/* #define HAL_QSPI_MODULE_ENABLED */
|
||||||
/* #define HAL_RNG_MODULE_ENABLED */
|
/* #define HAL_RNG_MODULE_ENABLED */
|
||||||
/* #define HAL_RTC_MODULE_ENABLED */
|
#define HAL_RTC_MODULE_ENABLED
|
||||||
/* #define HAL_SAI_MODULE_ENABLED */
|
/* #define HAL_SAI_MODULE_ENABLED */
|
||||||
/* #define HAL_SD_MODULE_ENABLED */
|
/* #define HAL_SD_MODULE_ENABLED */
|
||||||
/* #define HAL_MMC_MODULE_ENABLED */
|
/* #define HAL_MMC_MODULE_ENABLED */
|
||||||
|
|
|
@ -317,6 +317,8 @@
|
||||||
#include "stm32f4xx.h"
|
#include "stm32f4xx.h"
|
||||||
#include "system_stm32f4xx.h"
|
#include "system_stm32f4xx.h"
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
#include "drivers/persistent.h"
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @}
|
* @}
|
||||||
|
@ -459,12 +461,12 @@ static const pllConfig_t overclockLevels[] = {
|
||||||
#define PLL_R 7 // PLL_R output is not used, can be any descent number
|
#define PLL_R 7 // PLL_R output is not used, can be any descent number
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static PERSISTENT uint32_t currentOverclockLevel = 0;
|
|
||||||
static PERSISTENT uint32_t hse_value = 8000000;
|
|
||||||
|
|
||||||
void SystemInitPLLParameters(void)
|
void SystemInitPLLParameters(void)
|
||||||
{
|
{
|
||||||
/* PLL setting for overclocking */
|
/* PLL setting for overclocking */
|
||||||
|
|
||||||
|
uint32_t currentOverclockLevel = persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL);
|
||||||
|
|
||||||
if (currentOverclockLevel >= ARRAYLEN(overclockLevels)) {
|
if (currentOverclockLevel >= ARRAYLEN(overclockLevels)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -486,7 +488,7 @@ void OverclockRebootIfNecessary(uint32_t overclockLevel)
|
||||||
|
|
||||||
// Reboot to adjust overclock frequency
|
// Reboot to adjust overclock frequency
|
||||||
if (SystemCoreClock != pll->mhz * 1000000U) {
|
if (SystemCoreClock != pll->mhz * 1000000U) {
|
||||||
currentOverclockLevel = overclockLevel;
|
persistentObjectWrite(PERSISTENT_OBJECT_OVERCLOCK_LEVEL, overclockLevel);
|
||||||
__disable_irq();
|
__disable_irq();
|
||||||
NVIC_SystemReset();
|
NVIC_SystemReset();
|
||||||
}
|
}
|
||||||
|
@ -494,8 +496,10 @@ void OverclockRebootIfNecessary(uint32_t overclockLevel)
|
||||||
|
|
||||||
void systemClockSetHSEValue(uint32_t frequency)
|
void systemClockSetHSEValue(uint32_t frequency)
|
||||||
{
|
{
|
||||||
|
uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE);
|
||||||
|
|
||||||
if (hse_value != frequency) {
|
if (hse_value != frequency) {
|
||||||
hse_value = frequency;
|
persistentObjectWrite(PERSISTENT_OBJECT_HSE_VALUE, frequency);
|
||||||
__disable_irq();
|
__disable_irq();
|
||||||
NVIC_SystemReset();
|
NVIC_SystemReset();
|
||||||
}
|
}
|
||||||
|
@ -503,11 +507,6 @@ void systemClockSetHSEValue(uint32_t frequency)
|
||||||
|
|
||||||
void SystemInit(void)
|
void SystemInit(void)
|
||||||
{
|
{
|
||||||
if (!(RCC->CSR & RCC_CSR_SFTRSTF)) {
|
|
||||||
currentOverclockLevel = 0;
|
|
||||||
hse_value = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* FPU settings ------------------------------------------------------------*/
|
/* FPU settings ------------------------------------------------------------*/
|
||||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||||
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
||||||
|
@ -587,6 +586,8 @@ void SystemInit(void)
|
||||||
*/
|
*/
|
||||||
void SystemCoreClockUpdate(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;
|
uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
|
||||||
#if defined(STM32F446xx)
|
#if defined(STM32F446xx)
|
||||||
uint32_t pllr = 2;
|
uint32_t pllr = 2;
|
||||||
|
@ -672,6 +673,7 @@ static int StartHSx(uint32_t onBit, uint32_t readyBit, int maxWaitCount)
|
||||||
*/
|
*/
|
||||||
void SetSysClock(void)
|
void SetSysClock(void)
|
||||||
{
|
{
|
||||||
|
uint32_t hse_value = persistentObjectRead(PERSISTENT_OBJECT_HSE_VALUE);
|
||||||
uint32_t hse_mhz = hse_value / 1000000;
|
uint32_t hse_mhz = hse_value / 1000000;
|
||||||
|
|
||||||
// Switch to HSI during clock manipulation
|
// Switch to HSI during clock manipulation
|
||||||
|
|
|
@ -66,6 +66,7 @@
|
||||||
#include "stm32f7xx.h"
|
#include "stm32f7xx.h"
|
||||||
#include "system_stm32f7xx.h"
|
#include "system_stm32f7xx.h"
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
#include "drivers/persistent.h"
|
||||||
|
|
||||||
#if !defined (HSE_VALUE)
|
#if !defined (HSE_VALUE)
|
||||||
#define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz */
|
#define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz */
|
||||||
|
@ -259,30 +260,19 @@ static const pllConfig_t overclockLevels[] = {
|
||||||
{ 480, RCC_PLLP_DIV2, 10 }, // 240 MHz
|
{ 480, RCC_PLLP_DIV2, 10 }, // 240 MHz
|
||||||
};
|
};
|
||||||
|
|
||||||
// 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
|
|
||||||
|
|
||||||
void SystemInitOC(void) {
|
void SystemInitOC(void) {
|
||||||
__PWR_CLK_ENABLE();
|
uint32_t currentOverclockLevel = persistentObjectRead(PERSISTENT_OBJECT_OVERCLOCK_LEVEL);
|
||||||
__BKPSRAM_CLK_ENABLE();
|
|
||||||
HAL_PWR_EnableBkUpAccess();
|
|
||||||
|
|
||||||
if (REQUEST_OVERCLOCK_MAGIC_COOKIE == REQUEST_OVERCLOCK) {
|
if (currentOverclockLevel >= ARRAYLEN(overclockLevels)) {
|
||||||
const uint32_t overclockLevel = CURRENT_OVERCLOCK_LEVEL;
|
return;
|
||||||
|
|
||||||
/* 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;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* 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)
|
void OverclockRebootIfNecessary(uint32_t overclockLevel)
|
||||||
|
@ -295,8 +285,7 @@ void OverclockRebootIfNecessary(uint32_t overclockLevel)
|
||||||
|
|
||||||
// Reboot to adjust overclock frequency
|
// Reboot to adjust overclock frequency
|
||||||
if (SystemCoreClock != (pll->n / pll->p) * 1000000U) {
|
if (SystemCoreClock != (pll->n / pll->p) * 1000000U) {
|
||||||
REQUEST_OVERCLOCK = REQUEST_OVERCLOCK_MAGIC_COOKIE;
|
persistentObjectWrite(PERSISTENT_OBJECT_OVERCLOCK_LEVEL, overclockLevel);
|
||||||
CURRENT_OVERCLOCK_LEVEL = overclockLevel;
|
|
||||||
__disable_irq();
|
__disable_irq();
|
||||||
NVIC_SystemReset();
|
NVIC_SystemReset();
|
||||||
}
|
}
|
||||||
|
|
|
@ -83,9 +83,6 @@ void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev)
|
||||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
|
||||||
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, ENABLE) ;
|
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, ENABLE) ;
|
||||||
|
|
||||||
/* enable the PWR clock */
|
|
||||||
RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE);
|
|
||||||
|
|
||||||
EXTI_ClearITPendingBit(EXTI_Line0);
|
EXTI_ClearITPendingBit(EXTI_Line0);
|
||||||
}
|
}
|
||||||
/**
|
/**
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue