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

Reworked reboot flags for F4 partially (#5193)

This commit is contained in:
Andrey Mironov 2018-04-03 16:08:36 +03:00 committed by Michael Keller
parent 07cce64572
commit aede46288b
13 changed files with 118 additions and 171 deletions

View file

@ -45,9 +45,9 @@ void failureMode(failureMode_e mode);
// bootloader/IAP // bootloader/IAP
void systemReset(void); void systemReset(void);
void systemResetToBootloader(void); void systemResetToBootloader(void);
void checkForBootLoaderRequest(void);
bool isMPUSoftReset(void); bool isMPUSoftReset(void);
void cycleCounterInit(void); void cycleCounterInit(void);
void checkForBootLoaderRequest(void);
void enableGPIOPowerUsageAndNoiseReductions(void); void enableGPIOPowerUsageAndNoiseReductions(void);
// current crystal frequency - 8 or 12MHz // current crystal frequency - 8 or 12MHz

View file

@ -39,18 +39,43 @@ void systemReset(void)
NVIC_SystemReset(); NVIC_SystemReset();
} }
PERSISTENT uint32_t bootloaderRequest = 0;
#define BOOTLOADER_REQUEST_COOKIE 0xDEADBEEF
void systemResetToBootloader(void) void systemResetToBootloader(void)
{ {
if (mpuResetFn) { if (mpuResetFn) {
mpuResetFn(); mpuResetFn();
} }
*((uint32_t *)0x2001FFFC) = 0xDEADBEEF; // 128KB SRAM STM32F4XX bootloaderRequest = BOOTLOADER_REQUEST_COOKIE;
__disable_irq(); __disable_irq();
NVIC_SystemReset(); NVIC_SystemReset();
} }
typedef void resetHandler_t(void);
typedef struct isrVector_s {
__I uint32_t stackEnd;
resetHandler_t *resetHandler;
} isrVector_t;
void checkForBootLoaderRequest(void)
{
if (bootloaderRequest != BOOTLOADER_REQUEST_COOKIE) {
return;
}
bootloaderRequest = 0;
extern isrVector_t system_isr_vector_table_base;
__set_MSP(system_isr_vector_table_base.stackEnd);
system_isr_vector_table_base.resetHandler();
while (1);
}
void enableGPIOPowerUsageAndNoiseReductions(void) void enableGPIOPowerUsageAndNoiseReductions(void)
{ {
@ -160,8 +185,6 @@ bool isMPUSoftReset(void)
void systemInit(void) void systemInit(void)
{ {
checkForBootLoaderRequest();
SetSysClock(); SetSysClock();
// Configure NVIC preempt/priority groups // Configure NVIC preempt/priority groups
@ -185,19 +208,3 @@ void systemInit(void)
// SysTick // SysTick
SysTick_Config(SystemCoreClock / 1000); SysTick_Config(SystemCoreClock / 1000);
} }
void(*bootJump)(void);
void checkForBootLoaderRequest(void)
{
if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) {
*((uint32_t *)0x2001FFFC) = 0x0;
__enable_irq();
__set_MSP(*((uint32_t *)0x1FFF0000));
bootJump = (void(*)(void))(*((uint32_t *) 0x1FFF0004));
bootJump();
while (1);
}
}

View file

@ -79,21 +79,8 @@ Reset_Handler:
str r1, [r0, #0x30] str r1, [r0, #0x30]
dsb dsb
// Check for bootloader reboot // Defined in C code
ldr r0, =0x2001FFFC // mj666 bl checkForBootLoaderRequest
ldr r1, =0xDEADBEEF // mj666
ldr r2, [r0, #0] // mj666
str r0, [r0, #0] // mj666
cmp r2, r1 // mj666
beq Reboot_Loader // mj666
// Check for overclocking request
ldr r0, =0x2001FFF8 // Faduf
ldr r1, =0xBABEFACE // Faduf
ldr r2, [r0, #0] // Faduf
str r0, [r0, #0] // Faduf
cmp r2, r1 // Faduf
beq Boot_OC // Faduf
/* Copy the data segment initializers from flash to SRAM */ /* Copy the data segment initializers from flash to SRAM */
movs r1, #0 movs r1, #0
@ -153,71 +140,6 @@ LoopMarkHeapStack:
LoopForever: LoopForever:
b LoopForever b LoopForever
Boot_OC:
/* Copy the data segment initializers from flash to SRAM */
movs r1, #0
b LoopCopyDataInitOC
CopyDataInitOC:
ldr r3, =_sidata
ldr r3, [r3, r1]
str r3, [r0, r1]
adds r1, r1, #4
LoopCopyDataInitOC:
ldr r0, =_sdata
ldr r3, =_edata
adds r2, r0, r1
cmp r2, r3
bcc CopyDataInitOC
ldr r2, =_sbss
b LoopFillZerobssOC
/* Zero fill the bss segment. */
FillZerobssOC:
movs r3, #0
str r3, [r2], #4
LoopFillZerobssOC:
ldr r3, = _ebss
cmp r2, r3
bcc FillZerobssOC
/* Mark the heap and stack */
ldr r2, =_heap_stack_begin
b LoopMarkHeapStackOC
MarkHeapStackOC:
movs r3, 0xa5a5a5a5
str r3, [r2], #4
LoopMarkHeapStackOC:
ldr r3, = _heap_stack_end
cmp r2, r3
bcc MarkHeapStackOC
/*FPU settings*/
ldr r0, =0xE000ED88 /* Enable CP10,CP11 */
ldr r1,[r0]
orr r1,r1,#(0xF << 20)
str r1,[r0]
/* Call the clock system intitialization function.*/
/* Done in system_stm32f4xx.c */
bl SystemInitOC
/* Call the application's entry point.*/
bl main
bx lr
Reboot_Loader: // mj666
// Reboot to ROM // mj666
ldr r0, =0x1FFF0000 // mj666
ldr sp,[r0, #0] // mj666
ldr r0,[r0, #4] // mj666
bx r0 // mj666
.size Reset_Handler, .-Reset_Handler .size Reset_Handler, .-Reset_Handler
/** /**

View file

@ -127,7 +127,7 @@ LoopMarkHeapStack:
str r1,[r0] str r1,[r0]
/* Call the clock system intitialization function.*/ /* Call the clock system intitialization function.*/
bl SystemInitOC bl SystemInit
/* Call the application's entry point.*/ /* Call the application's entry point.*/
bl main bl main

View file

@ -102,6 +102,10 @@
#define FAST_RAM #define FAST_RAM
#endif // USE_FAST_RAM #endif // USE_FAST_RAM
#ifdef STM32F4
// Data in RAM which is guaranteed to not be reset on hot reboot
#define PERSISTENT __attribute__ ((section(".persistent_data"), aligned(4)))
#endif
#define USE_CLI #define USE_CLI
#define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values #define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values

View file

@ -26,6 +26,8 @@ MEMORY
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 992K FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 992K
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
CCM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K CCM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
BACKUP_SRAM (rwx) : ORIGIN = 0x40024000, LENGTH = 4K BACKUP_SRAM (rwx) : ORIGIN = 0x40024000, LENGTH = 4K

View file

@ -27,6 +27,8 @@ MEMORY
FLASH_CONFIG (r): ORIGIN = 0x08008000, LENGTH = 16K FLASH_CONFIG (r): ORIGIN = 0x08008000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x0800C000, LENGTH = 976K FLASH1 (rx) : ORIGIN = 0x0800C000, LENGTH = 976K
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
CCM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K CCM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K

View file

@ -26,6 +26,8 @@ MEMORY
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
} }

View file

@ -27,6 +27,8 @@ MEMORY
FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 16K FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x0800C000, LENGTH = 464K FLASH1 (rx) : ORIGIN = 0x0800C000, LENGTH = 464K
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
} }

View file

@ -26,6 +26,8 @@ MEMORY
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
} }

View file

@ -35,6 +35,15 @@ SECTIONS
. = ALIGN(4); . = ALIGN(4);
} >FLASH } >FLASH
/* System memory (read-only bootloader) interrupt vector */
.system_isr_vector (NOLOAD) :
{
. = ALIGN(4);
PROVIDE (system_isr_vector_table_base = .);
KEEP(*(.system_isr_vector)) /* Bootloader code */
. = ALIGN(4);
} >SYSTEM_MEMORY
/* The program code and other data goes into FLASH */ /* The program code and other data goes into FLASH */
.text : .text :
{ {
@ -113,7 +122,7 @@ SECTIONS
/* Uninitialized data section */ /* Uninitialized data section */
. = ALIGN(4); . = ALIGN(4);
.bss : .bss (NOLOAD) :
{ {
/* This is used by the startup in order to initialize the .bss secion */ /* This is used by the startup in order to initialize the .bss secion */
_sbss = .; /* define a global symbol at bss start */ _sbss = .; /* define a global symbol at bss start */
@ -136,6 +145,14 @@ SECTIONS
__fastram_bss_end__ = .; __fastram_bss_end__ = .;
} >FASTRAM } >FASTRAM
.persistent_data (NOLOAD) :
{
__persistent_data_start__ = .;
*(.persistent_data)
. = ALIGN(4);
__persistent_data_end__ = .;
} >RAM
/* User_heap_stack section, used to check that there is enough RAM left */ /* User_heap_stack section, used to check that there is enough RAM left */
_heap_stack_end = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - _Hot_Reboot_Flags_Size; _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 = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size;

View file

@ -458,8 +458,64 @@ static void SystemInit_ExtMemCtl(void);
uint32_t SystemCoreClock; uint32_t SystemCoreClock;
uint32_t pll_p = PLL_P, pll_n = PLL_N, pll_q = PLL_Q; uint32_t pll_p = PLL_P, pll_n = PLL_N, pll_q = PLL_Q;
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?
};
static PERSISTENT uint32_t currentOverclockLevel = 0;
void SystemInitOC(void)
{
/* PLL setting for overclocking */
if (currentOverclockLevel >= ARRAYLEN(overclockLevels)) {
return;
}
const pllConfig_t * const pll = overclockLevels + currentOverclockLevel;
pll_n = pll->n;
pll_p = pll->p;
pll_q = pll->q;
}
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) {
currentOverclockLevel = overclockLevel;
__disable_irq();
NVIC_SystemReset();
}
}
void SystemInit(void) void SystemInit(void)
{ {
SystemInitOC();
/* core clock is simply a mhz of PLL_N / PLL_P */ /* core clock is simply a mhz of PLL_N / PLL_P */
SystemCoreClock = (pll_n / pll_p) * 1000000; SystemCoreClock = (pll_n / pll_p) * 1000000;
@ -502,74 +558,6 @@ void SystemInit(void)
#endif #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)
{
#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. * @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock (HCLK), it can * The SystemCoreClock variable contains the core clock (HCLK), it can

View file

@ -34,7 +34,6 @@
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
extern void SystemInit(void); extern void SystemInit(void);
extern void SystemInitOC(void);
extern void SystemCoreClockUpdate(void); extern void SystemCoreClockUpdate(void);
extern void OverclockRebootIfNecessary(uint32_t overclockLevel); extern void OverclockRebootIfNecessary(uint32_t overclockLevel);