1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 20:10:18 +03:00

Add booting into the flash boot loader as an option.

This commit is contained in:
mikeller 2019-06-15 19:47:47 +12:00
parent de60402840
commit 5cf42f40b6
14 changed files with 180 additions and 111 deletions

View file

@ -274,6 +274,11 @@ typedef enum dumpFlags_e {
typedef bool printFn(dumpFlags_t dumpMask, bool equalsDefault, const char *format, ...); typedef bool printFn(dumpFlags_t dumpMask, bool equalsDefault, const char *format, ...);
typedef enum {
REBOOT_TARGET_FIRMWARE,
REBOOT_TARGET_BOOTLOADER_ROM,
REBOOT_TARGET_BOOTLOADER_FLASH,
} rebootTarget_e;
static void backupPgConfig(const pgRegistry_t *pg) static void backupPgConfig(const pgRegistry_t *pg)
{ {
@ -3309,31 +3314,61 @@ static char *checkCommand(char *cmdline, const char *command)
} }
} }
static void cliRebootEx(bool bootLoader) static void cliRebootEx(rebootTarget_e rebootTarget)
{ {
cliPrint("\r\nRebooting"); cliPrint("\r\nRebooting");
bufWriterFlush(cliWriter); bufWriterFlush(cliWriter);
waitForSerialPortToFinishTransmitting(cliPort); waitForSerialPortToFinishTransmitting(cliPort);
stopPwmAllMotors(); stopPwmAllMotors();
if (bootLoader) { switch (rebootTarget) {
systemResetToBootloader(); case REBOOT_TARGET_BOOTLOADER_ROM:
return; systemResetToBootloader(BOOTLOADER_REQUEST_ROM);
}
break;
#if defined(USE_FLASH_BOOT_LOADER)
case REBOOT_TARGET_BOOTLOADER_FLASH:
systemResetToBootloader(BOATLOADER_REQUEST_FLASH);
break;
#endif
case REBOOT_TARGET_FIRMWARE:
default:
systemReset(); systemReset();
break;
}
} }
static void cliReboot(void) static void cliReboot(void)
{ {
cliRebootEx(false); cliRebootEx(REBOOT_TARGET_FIRMWARE);
} }
static void cliBootloader(char *cmdline) static void cliBootloader(char *cmdline)
{ {
UNUSED(cmdline); rebootTarget_e rebootTarget;
if (
#if !defined(USE_FLASH_BOOT_LOADER)
isEmpty(cmdline) ||
#endif
strncasecmp(cmdline, "rom", 3) == 0) {
rebootTarget = REBOOT_TARGET_BOOTLOADER_ROM;
cliPrintHashLine("restarting in bootloader mode"); cliPrintHashLine("restarting in ROM bootloader mode");
cliRebootEx(true); #if defined(USE_FLASH_BOOT_LOADER)
} else if (isEmpty(cmdline) || strncasecmp(cmdline, "flash", 5) == 0) {
rebootTarget = REBOOT_TARGET_BOOTLOADER_FLASH;
cliPrintHashLine("restarting in flash bootloader mode");
#endif
} else {
cliPrintErrorLinef("Invalid option");
return;
}
cliRebootEx(rebootTarget);
} }
static void cliExit(char *cmdline) static void cliExit(char *cmdline)
@ -5873,7 +5908,11 @@ const clicmd_t cmdTable[] = {
#ifdef USE_RX_SPI #ifdef USE_RX_SPI
CLI_COMMAND_DEF("bind_rx_spi", "initiate binding for RX SPI", NULL, cliRxSpiBind), CLI_COMMAND_DEF("bind_rx_spi", "initiate binding for RX SPI", NULL, cliRxSpiBind),
#endif #endif
CLI_COMMAND_DEF("bl", "reboot into bootloader", NULL, cliBootloader), #if defined(USE_FLASH_BOOT_LOADER)
CLI_COMMAND_DEF("bl", "reboot into bootloader", "[flash|rom]", cliBootloader),
#else
CLI_COMMAND_DEF("bl", "reboot into bootloader", "[rom]", cliBootloader),
#endif
#if defined(USE_BOARD_INFO) #if defined(USE_BOARD_INFO)
CLI_COMMAND_DEF("board_name", "get / set the name of the board model", "[board name]", cliBoardName), CLI_COMMAND_DEF("board_name", "get / set the name of the board model", "[board name]", cliBoardName),
#endif #endif

View file

@ -202,7 +202,7 @@ void failureMode(failureMode_e mode)
#ifdef DEBUG #ifdef DEBUG
systemReset(); systemReset();
#else #else
systemResetToBootloader(); systemResetToBootloader(BOOTLOADER_REQUEST_ROM);
#endif #endif
} }

View file

@ -50,16 +50,23 @@ typedef enum {
#define WARNING_CODE_DURATION_LONG_MS 250 #define WARNING_CODE_DURATION_LONG_MS 250
#define WARNING_CODE_DURATION_SHORT_MS 50 #define WARNING_CODE_DURATION_SHORT_MS 50
typedef enum {
BOOTLOADER_REQUEST_ROM,
BOATLOADER_REQUEST_FLASH,
} bootloaderRequestType_e;
// failure // failure
void indicateFailure(failureMode_e mode, int repeatCount); void indicateFailure(failureMode_e mode, int repeatCount);
void failureMode(failureMode_e mode); void failureMode(failureMode_e mode);
// bootloader/IAP // bootloader/IAP
void systemReset(void); void systemReset(void);
void systemResetToBootloader(void); void systemResetToBootloader(bootloaderRequestType_e requestType);
void checkForBootLoaderRequest(void);
bool isMPUSoftReset(void); bool isMPUSoftReset(void);
void cycleCounterInit(void); void cycleCounterInit(void);
#if defined(STM32H7)
void systemCheckResetReason(void);
#endif
void initialiseMemorySections(void); void initialiseMemorySections(void);

View file

@ -114,7 +114,7 @@ void systemInit(void)
SysTick_Config(SystemCoreClock / 1000); SysTick_Config(SystemCoreClock / 1000);
} }
void checkForBootLoaderRequest(void) static void checkForBootLoaderRequest(void)
{ {
void(*bootJump)(void); void(*bootJump)(void);

View file

@ -35,8 +35,9 @@ void systemReset(void)
SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04; SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04;
} }
void systemResetToBootloader(void) void systemResetToBootloader(bootloaderRequestType_e requestType)
{ {
UNUSED(requestType);
// 1FFFF000 -> 20000200 -> SP // 1FFFF000 -> 20000200 -> SP
// 1FFFF004 -> 1FFFF021 -> PC // 1FFFF004 -> 1FFFF021 -> PC
@ -83,6 +84,23 @@ bool isMPUSoftReset(void)
return false; return false;
} }
static void checkForBootLoaderRequest(void)
{
void(*bootJump)(void);
if (*((uint32_t *)0x20009FFC) == 0xDEADBEEF) {
*((uint32_t *)0x20009FFC) = 0x0;
__enable_irq();
__set_MSP(*((uint32_t *)0x1FFFD800));
bootJump = (void(*)(void))(*((uint32_t *) 0x1FFFD804));
bootJump();
while (1);
}
}
void systemInit(void) void systemInit(void)
{ {
checkForBootLoaderRequest(); checkForBootLoaderRequest();
@ -106,20 +124,3 @@ void systemInit(void)
// SysTick // SysTick
SysTick_Config(SystemCoreClock / 1000); SysTick_Config(SystemCoreClock / 1000);
} }
void checkForBootLoaderRequest(void)
{
void(*bootJump)(void);
if (*((uint32_t *)0x20009FFC) == 0xDEADBEEF) {
*((uint32_t *)0x20009FFC) = 0x0;
__enable_irq();
__set_MSP(*((uint32_t *)0x1FFFD800));
bootJump = (void(*)(void))(*((uint32_t *) 0x1FFFD804));
bootJump();
while (1);
}
}

View file

@ -39,10 +39,16 @@ void systemReset(void)
NVIC_SystemReset(); NVIC_SystemReset();
} }
void systemResetToBootloader(void) void systemResetToBootloader(bootloaderRequestType_e requestType)
{ {
switch (requestType) {
case BOOTLOADER_REQUEST_ROM:
default:
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST); persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST);
break;
}
__disable_irq(); __disable_irq();
NVIC_SystemReset(); NVIC_SystemReset();
} }
@ -54,6 +60,7 @@ typedef struct isrVector_s {
resetHandler_t *resetHandler; resetHandler_t *resetHandler;
} isrVector_t; } isrVector_t;
// Used in the startup files for F4
void checkForBootLoaderRequest(void) void checkForBootLoaderRequest(void)
{ {
uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON); uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON);

View file

@ -43,9 +43,16 @@ void systemReset(void)
NVIC_SystemReset(); NVIC_SystemReset();
} }
void systemResetToBootloader(void) void systemResetToBootloader(bootloaderRequestType_e requestType)
{ {
switch (requestType) {
case BOOTLOADER_REQUEST_ROM:
default:
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST); persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST);
break;
}
__disable_irq(); __disable_irq();
NVIC_SystemReset(); NVIC_SystemReset();
} }
@ -152,6 +159,30 @@ bool isMPUSoftReset(void)
return false; return false;
} }
static void checkForBootLoaderRequest(void)
{
uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON);
if (bootloaderRequest != RESET_BOOTLOADER_REQUEST) {
return;
}
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE);
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);
}
void systemInit(void) void systemInit(void)
{ {
checkForBootLoaderRequest(); checkForBootLoaderRequest();
@ -186,29 +217,3 @@ void systemInit(void)
HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK); HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
} }
void(*bootJump)(void);
void checkForBootLoaderRequest(void)
{
uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON);
if (bootloaderRequest != RESET_BOOTLOADER_REQUEST) {
return;
}
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE);
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);
}

View file

@ -230,14 +230,6 @@ void systemInit(void)
void systemReset(void) void systemReset(void)
{ {
#if 0
#ifdef USE_GYRO
if (mpuResetFn) {
mpuResetFn();
}
#endif
#endif
SCB_DisableDCache(); SCB_DisableDCache();
SCB_DisableICache(); SCB_DisableICache();
@ -253,36 +245,36 @@ void forcedSystemResetWithoutDisablingCaches(void)
NVIC_SystemReset(); NVIC_SystemReset();
} }
void systemResetToBootloader(void) void systemResetToBootloader(bootloaderRequestType_e requestType)
{ {
#if 0 switch (requestType) {
#ifdef USE_GYRO #if defined(USE_FLASH_BOOT_LOADER)
if (mpuResetFn) { case BOATLOADER_REQUEST_FLASH:
mpuResetFn();
}
#endif
#endif
#ifdef USE_EXST
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_FLASH_BOOTLOADER_REQUEST); persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_FLASH_BOOTLOADER_REQUEST);
#else
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST); break;
#endif #endif
case BOOTLOADER_REQUEST_ROM:
default:
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST);
break;
}
__disable_irq(); __disable_irq();
NVIC_SystemReset(); NVIC_SystemReset();
} }
static uint32_t bootloaderRequest; static uint32_t bootloaderRequest;
bool systemIsFlashBootloaderRequested(void)
{
return (bootloaderRequest == RESET_FLASH_BOOTLOADER_REQUEST);
}
void systemCheckResetReason(void) void systemCheckResetReason(void)
{ {
bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON); bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON);
switch (bootloaderRequest) { switch (bootloaderRequest) {
#if defined(USE_FLASH_BOOT_LOADER)
case BOATLOADER_REQUEST_FLASH:
#endif
case RESET_BOOTLOADER_REQUEST: case RESET_BOOTLOADER_REQUEST:
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_POST); persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_POST);
break; break;

View file

@ -140,9 +140,10 @@ static const char * const flightControllerIdentifier = BETAFLIGHT_IDENTIFIER; //
enum { enum {
MSP_REBOOT_FIRMWARE = 0, MSP_REBOOT_FIRMWARE = 0,
MSP_REBOOT_BOOTLOADER, MSP_REBOOT_BOOTLOADER_ROM,
MSP_REBOOT_MSC, MSP_REBOOT_MSC,
MSP_REBOOT_MSC_UTC, MSP_REBOOT_MSC_UTC,
MSP_REBOOT_BOOTLOADER_FLASH,
MSP_REBOOT_COUNT, MSP_REBOOT_COUNT,
}; };
@ -263,8 +264,8 @@ static void mspRebootFn(serialPort_t *serialPort)
systemReset(); systemReset();
break; break;
case MSP_REBOOT_BOOTLOADER: case MSP_REBOOT_BOOTLOADER_ROM:
systemResetToBootloader(); systemResetToBootloader(BOOTLOADER_REQUEST_ROM);
break; break;
#if defined(USE_USB_MSC) #if defined(USE_USB_MSC)
@ -279,6 +280,12 @@ static void mspRebootFn(serialPort_t *serialPort)
} }
break; break;
#endif #endif
#if defined(USE_FLASH_BOOT_LOADER)
case MSP_REBOOT_BOOTLOADER_FLASH:
systemResetToBootloader(BOOTLOADER_REQUEST_FLASH);
break;
#endif
default: default:
return; return;

View file

@ -425,16 +425,16 @@ static mspPostProcessFnPtr mspSerialProcessReceivedCommand(mspPort_t *msp, mspPr
static void mspEvaluateNonMspData(mspPort_t * mspPort, uint8_t receivedChar) static void mspEvaluateNonMspData(mspPort_t * mspPort, uint8_t receivedChar)
{ {
#ifdef USE_CLI
if (receivedChar == '#') {
mspPort->pendingRequest = MSP_PENDING_CLI;
return;
}
#endif
if (receivedChar == serialConfig()->reboot_character) { if (receivedChar == serialConfig()->reboot_character) {
mspPort->pendingRequest = MSP_PENDING_BOOTLOADER; mspPort->pendingRequest = MSP_PENDING_BOOTLOADER_ROM;
return; #ifdef USE_CLI
} else if (receivedChar == '#') {
mspPort->pendingRequest = MSP_PENDING_CLI;
#endif
#if defined(USE_FLASH_BOOT_LOADER)
} else if (receivedChar == 'F') {
mspPort->pendingRequest = MSP_PENDING_BOOTLOADER_FLASH;
#endif
} }
} }
@ -446,10 +446,16 @@ static void mspProcessPendingRequest(mspPort_t * mspPort)
} }
switch(mspPort->pendingRequest) { switch(mspPort->pendingRequest) {
case MSP_PENDING_BOOTLOADER: case MSP_PENDING_BOOTLOADER_ROM:
systemResetToBootloader(); systemResetToBootloader(BOOTLOADER_REQUEST_ROM);
break;
break;
#if defined(USE_FLASH_BOOT_LOADER)
case MSP_PENDING_BOOTLOADER_ROM:
systemResetToBootloader(BOATLOADER_REQUEST_FLASH);
break;
#endif
#ifdef USE_CLI #ifdef USE_CLI
case MSP_PENDING_CLI: case MSP_PENDING_CLI:
cliEnter(mspPort->port); cliEnter(mspPort->port);

View file

@ -59,8 +59,9 @@ typedef enum {
typedef enum { typedef enum {
MSP_PENDING_NONE, MSP_PENDING_NONE,
MSP_PENDING_BOOTLOADER, MSP_PENDING_BOOTLOADER_ROM,
MSP_PENDING_CLI MSP_PENDING_CLI,
MSP_PENDING_BOOTLOADER_FLASH,
} mspPendingSystemRequest_e; } mspPendingSystemRequest_e;
#define MSP_PORT_INBUF_SIZE 192 #define MSP_PORT_INBUF_SIZE 192

View file

@ -252,7 +252,9 @@ void systemReset(void){
pthread_join(udpWorker, NULL); pthread_join(udpWorker, NULL);
exit(0); exit(0);
} }
void systemResetToBootloader(void) { void systemResetToBootloader(bootloaderRequestType_e requestType) {
UNUSED(requestType);
printf("[system]ResetToBootloader!\n"); printf("[system]ResetToBootloader!\n");
workerRunning = false; workerRunning = false;
pthread_join(tcpWorker, NULL); pthread_join(tcpWorker, NULL);

View file

@ -352,3 +352,7 @@ extern uint8_t eepromData[EEPROM_SIZE];
extern uint8_t __config_start; // configured via linker script when building binaries. extern uint8_t __config_start; // configured via linker script when building binaries.
extern uint8_t __config_end; extern uint8_t __config_end;
#endif #endif
#if defined(USE_EXST)
#define USE_FLASH_BOOT_LOADER
#endif

View file

@ -572,8 +572,6 @@ void MPU_Config()
* @param None * @param None
* @retval None * @retval None
*/ */
void systemCheckResetReason(void);
void resetMPU(void) void resetMPU(void)
{ {
MPU_Region_InitTypeDef MPU_InitStruct; MPU_Region_InitTypeDef MPU_InitStruct;