Skip to content

Commit

Permalink
Merge pull request #5210 from DieHertz/f4-overclock-subset
Browse files Browse the repository at this point in the history
Adjustable overclock for F405 and F411
  • Loading branch information
mikeller committed Feb 18, 2018
2 parents 08281c1 + ac26c97 commit f07bf40
Show file tree
Hide file tree
Showing 11 changed files with 94 additions and 48 deletions.
2 changes: 1 addition & 1 deletion src/main/drivers/max7456.c
Expand Up @@ -432,7 +432,7 @@ void max7456Init(const max7456Config_t *max7456Config, const vcdProfile_t *pVcdP
max7456DeviceType = MAX7456_DEVICE_TYPE_MAX;
}

#if defined(STM32F4) && !defined(DISABLE_OVERCLOCK)
#if defined(USE_OVERCLOCK)
// Determine SPI clock divisor based on config and the device type.

switch (max7456Config->clockConfig) {
Expand Down
2 changes: 1 addition & 1 deletion src/main/fc/config.c
Expand Up @@ -78,7 +78,7 @@ PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
.activeRateProfile = 0,
.debug_mode = DEBUG_MODE,
.task_statistics = true,
.cpu_overclock = false,
.cpu_overclock = 0,
.powerOnArmingGraceTime = 5,
.boardIdentifier = TARGET_BOARD_IDENTIFIER
);
Expand Down
14 changes: 2 additions & 12 deletions src/main/fc/fc_init.c
Expand Up @@ -353,18 +353,8 @@ void init(void)
}
#endif

#if defined(STM32F4) && !defined(DISABLE_OVERCLOCK)
// If F4 Overclocking is set and System core clock is not correct a reset is forced
if (systemConfig()->cpu_overclock && SystemCoreClock != OC_FREQUENCY_HZ) {
*((uint32_t *)0x2001FFF8) = 0xBABEFACE; // 128KB SRAM STM32F4XX
__disable_irq();
NVIC_SystemReset();
} else if (!systemConfig()->cpu_overclock && SystemCoreClock == OC_FREQUENCY_HZ) {
*((uint32_t *)0x2001FFF8) = 0x0; // 128KB SRAM STM32F4XX
__disable_irq();
NVIC_SystemReset();
}

#ifdef USE_OVERCLOCK
OverclockRebootIfNecessary(systemConfig()->cpu_overclock);
#endif

delay(100);
Expand Down
18 changes: 16 additions & 2 deletions src/main/interface/settings.c
Expand Up @@ -274,6 +274,17 @@ static const char * const lookupTableRatesType[] = {
"BETAFLIGHT", "RACEFLIGHT"
};

#ifdef USE_OVERCLOCK
static const char * const lookupOverclock[] = {
"OFF",
#if defined(STM32F40_41xxx)
"192MHZ", "216MHZ", "240MHZ"
#elif defined(STM32F411xE)
"108MHZ", "120MHZ"
#endif
};
#endif

const lookupTableEntry_t lookupTables[] = {
{ lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
{ lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
Expand Down Expand Up @@ -326,6 +337,9 @@ const lookupTableEntry_t lookupTables[] = {
{ lookupTableGyroOverflowCheck, sizeof(lookupTableGyroOverflowCheck) / sizeof(char *) },
#endif
{ lookupTableRatesType, sizeof(lookupTableRatesType) / sizeof(char *) },
#ifdef USE_OVERCLOCK
{ lookupOverclock, sizeof(lookupOverclock) / sizeof(char *) },
#endif
};

const clivalue_t valueTable[] = {
Expand Down Expand Up @@ -792,8 +806,8 @@ const clivalue_t valueTable[] = {
#endif
{ "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DEBUG }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, debug_mode) },
{ "rate_6pos_switch", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, rateProfile6PosSwitch) },
#if defined(STM32F4) && !defined(DISABLE_OVERCLOCK)
{ "cpu_overclock", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, cpu_overclock) },
#ifdef USE_OVERCLOCK
{ "cpu_overclock", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OVERCLOCK }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, cpu_overclock) },
#endif
{ "pwr_on_arm_grace", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 30 }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, powerOnArmingGraceTime) },

Expand Down
3 changes: 3 additions & 0 deletions src/main/interface/settings.h
Expand Up @@ -74,6 +74,9 @@ typedef enum {
TABLE_GYRO_OVERFLOW_CHECK,
#endif
TABLE_RATES_TYPE,
#ifdef USE_OVERCLOCK
TABLE_OVERCLOCK,
#endif
LOOKUP_TABLE_COUNT
} lookupTableIndex_e;

Expand Down
10 changes: 1 addition & 9 deletions src/main/startup/startup_stm32f411xe.s
Expand Up @@ -71,14 +71,6 @@ defined in linker script */
.weak Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
// Enable CCM
// RCC->AHB1ENR |= RCC_AHB1ENR_CCMDATARAMEN;
ldr r0, =0x40023800 // RCC_BASE
ldr r1, [r0, #0x30] // AHB1ENR
orr r1, r1, 0x00100000 // RCC_AHB1ENR_CCMDATARAMEN
str r1, [r0, #0x30]
dsb

// Check for bootloader reboot
ldr r0, =0x2001FFFC // mj666
ldr r1, =0xDEADBEEF // mj666
Expand Down Expand Up @@ -135,7 +127,7 @@ LoopMarkHeapStack:
str r1,[r0]

/* Call the clock system intitialization function.*/
bl SystemInit
bl SystemInitOC

/* Call the application's entry point.*/
bl main
Expand Down
8 changes: 0 additions & 8 deletions src/main/startup/startup_stm32f446xx.s
Expand Up @@ -71,14 +71,6 @@ defined in linker script */
.weak Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
// Enable CCM
// RCC->AHB1ENR |= RCC_AHB1ENR_CCMDATARAMEN;
ldr r0, =0x40023800 // RCC_BASE
ldr r1, [r0, #0x30] // AHB1ENR
orr r1, r1, 0x00100000 // RCC_AHB1ENR_CCMDATARAMEN
str r1, [r0, #0x30]
dsb

// Check for bootloader reboot
ldr r0, =0x2001FFFC // mj666
ldr r1, =0xDEADBEEF // mj666
Expand Down
5 changes: 5 additions & 0 deletions src/main/target/common_fc_pre.h
Expand Up @@ -51,6 +51,11 @@
#define USE_GYRO_DATA_ANALYSE
#define USE_ADC
#define USE_ADC_INTERNAL

#if defined(STM32F40_41xxx) || defined(STM32F411xE)
#define USE_OVERCLOCK
#endif

#endif // STM32F4

#ifdef STM32F722xx
Expand Down
5 changes: 3 additions & 2 deletions src/main/target/link/stm32_flash_split.ld
Expand Up @@ -12,7 +12,8 @@
ENTRY(Reset_Handler)

/* Highest address of the user mode stack */
_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM); /* end of RAM */
_Hot_Reboot_Flags_Size = 16;
_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - _Hot_Reboot_Flags_Size; /* end of RAM */

/* Base address where the config is stored. */
__config_start = ORIGIN(FLASH_CONFIG);
Expand Down Expand Up @@ -136,7 +137,7 @@ SECTIONS
} >FASTRAM

/* User_heap_stack section, used to check that there is enough RAM left */
_heap_stack_end = ORIGIN(STACKRAM)+LENGTH(STACKRAM) - 8; /* 8 bytes to allow for alignment */
_heap_stack_end = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - _Hot_Reboot_Flags_Size;
_heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size;
. = _heap_stack_begin;
._user_heap_stack :
Expand Down
69 changes: 61 additions & 8 deletions src/main/target/system_stm32f4xx.c
Expand Up @@ -502,21 +502,74 @@ void SystemInit(void)
#endif
}

typedef struct pllConfig_s {
uint16_t n;
uint16_t p;
uint16_t q;
} pllConfig_t;

static const pllConfig_t overclockLevels[] = {
{ PLL_N, PLL_P, PLL_Q }, // default

#if defined(STM32F40_41xxx)
{ 384, 2, 8 }, // 192 MHz
{ 432, 2, 9 }, // 216 MHz
{ 480, 2, 10 } // 240 MHz
#elif defined(STM32F411xE)
{ 432, 4, 9 }, // 108 MHz
{ 480, 4, 10 }, // 120 MHz
#endif

// XXX Doesn't work for F446 with this configuration.
// XXX Need to use smaller M to reduce N?
};

// 8 bytes of memory located at the very end of RAM, expected to be unoccupied
#define REQUEST_OVERCLOCK (*(__IO uint32_t *) 0x2001FFF8)
#define CURRENT_OVERCLOCK_LEVEL (*(__IO uint32_t *) 0x2001FFF4)
#define REQUEST_OVERCLOCK_MAGIC_COOKIE 0xBABEFACE

void SystemInitOC(void)
{
#if !defined(STM32F446xxx)
// XXX Doesn't work for F446 with this configuration.
// XXX Need to use smaller M to reduce N?

/* PLL setting for overclocking */
pll_n = PLL_N_OC;
pll_p = PLL_P_OC;
pll_q = PLL_Q_OC;
#ifdef STM32F411xE
if (REQUEST_OVERCLOCK_MAGIC_COOKIE == REQUEST_OVERCLOCK) {
#endif
const uint32_t overclockLevel = CURRENT_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;
}

#ifdef STM32F411xE
REQUEST_OVERCLOCK = 0;
}
#endif

SystemInit();
}

void OverclockRebootIfNecessary(uint32_t overclockLevel)
{
if (overclockLevel >= ARRAYLEN(overclockLevels)) {
return;
}

const pllConfig_t * const pll = overclockLevels + overclockLevel;

// Reboot to adjust overclock frequency
if (SystemCoreClock != (pll->n / pll->p) * 1000000) {
REQUEST_OVERCLOCK = REQUEST_OVERCLOCK_MAGIC_COOKIE;
CURRENT_OVERCLOCK_LEVEL = overclockLevel;
__disable_irq();
NVIC_SystemReset();
}
}

/**
* @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock (HCLK), it can
Expand Down
6 changes: 1 addition & 5 deletions src/main/target/system_stm32f4xx.h
Expand Up @@ -32,15 +32,11 @@
extern "C" {
#endif

#define PLL_N_OC 480
#define PLL_P_OC 2
#define PLL_Q_OC 10
#define OC_FREQUENCY_HZ (1000000*PLL_N_OC/PLL_P_OC)

extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
extern void SystemInit(void);
extern void SystemInitOC(void);
extern void SystemCoreClockUpdate(void);
extern void OverclockRebootIfNecessary(uint32_t overclockLevel);

#ifdef __cplusplus
}
Expand Down

0 comments on commit f07bf40

Please sign in to comment.