AP_HAL_ChibiOS: allow flash to be write-protected/unprotected on reboot

control protection support via HAL_FLASH_PROTECTION
provide support for flash protection on SPRacingH7
SPRacingH7 bootloader needs to use w25q-dtr
This commit is contained in:
Andy Piper 2022-02-18 21:31:53 +00:00 committed by Peter Barker
parent b32638b29e
commit ed952a0ea0
7 changed files with 198 additions and 1 deletions

View File

@ -241,6 +241,15 @@ static void main_loop()
utilInstance.apply_persistent_params();
#endif
#ifdef HAL_FLASH_PROTECTION
if (AP_BoardConfig::unlock_flash()) {
stm32_flash_unprotect_flash();
} else {
stm32_flash_protect_flash(false, AP_BoardConfig::protect_flash());
stm32_flash_protect_flash(true, AP_BoardConfig::protect_bootloader());
}
#endif
#if !defined(DISABLE_WATCHDOG)
#ifdef IOMCU_FW
stm32_watchdog_init();

View File

@ -47,10 +47,11 @@ PB10 QUADSPI_BK1_NCS QUADSPI1
PB2 QUADSPI_CLK QUADSPI1
# IFace Device Name Bus QSPI Mode Clk Freq Size (Pow2) NCS Delay
QSPIDEV w25q QUADSPI1 MODE3 120*MHZ 24 2
QSPIDEV w25q-dtr QUADSPI1 MODE3 120*MHZ 24 2
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Add CS pins to ensure they are high in bootloader
PB12 ICM20602_2_CS CS

View File

@ -18,6 +18,7 @@ STM32_ST_USE_TIMER 2
# internal flash is off limits
FLASH_SIZE_KB 128
FLASH_RESERVE_START_KB 0
define HAL_FLASH_PROTECTION 1
EXT_FLASH_SIZE_MB 16
EXT_FLASH_RESERVE_START_KB 1024

View File

@ -148,6 +148,7 @@ SECTIONS
lib/lib*.a:vector2.*(.text* .rodata*)
lib/lib*.a:quaternion.*(.text* .rodata*)
lib/lib*.a:polygon.*(.text* .rodata*)
lib/lib*.a:flash.*(.text* .rodata*) /* flash ops in RAM so that both banks can be erased */
/* uncomment these to test CPUInfo in FLASH_RAM */
/*Tools/CPUInfo/CPUInfo.*(.text* .rodata*)
Tools/CPUInfo/EKF_Maths.*(.text* .rodata*)*/

View File

@ -161,6 +161,12 @@ static bool flash_keep_unlocked;
#ifndef FLASH_KEY2
#define FLASH_KEY2 0xCDEF89AB
#endif
#ifndef FLASH_OPTKEY1
#define FLASH_OPTKEY1 0x08192A3B
#endif
#ifndef FLASH_OPTKEY2
#define FLASH_OPTKEY2 0x4C5D6E7F
#endif
/* Some compiler options will convert short loads and stores into byte loads
* and stores. We don't want this to happen for IO reads and writes!
@ -278,7 +284,48 @@ void stm32_flash_lock(void)
#endif
}
#if defined(STM32H7) && defined(HAL_FLASH_PROTECTION)
static void stm32_flash_wait_opt_idle(void)
{
__DSB();
while (FLASH->OPTSR_CUR & FLASH_OPTSR_OPT_BUSY) {
// nop
}
}
static void stm32_flash_opt_clear_errors(void)
{
FLASH->OPTCCR = FLASH_OPTCCR_CLR_OPTCHANGEERR;
}
static bool stm32_flash_unlock_options(void)
{
stm32_flash_wait_opt_idle();
if (FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) {
/* Unlock sequence */
FLASH->OPTKEYR = FLASH_OPTKEY1;
FLASH->OPTKEYR = FLASH_OPTKEY2;
}
if (FLASH->OPTSR_CUR & FLASH_OPTSR_OPTCHANGEERR) {
return false;
}
return true;
}
static bool stm32_flash_lock_options(void)
{
stm32_flash_wait_opt_idle();
FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK;
if (FLASH->OPTSR_CUR & FLASH_OPTSR_OPTCHANGEERR) {
return false;
}
return true;
}
#endif
/*
get the memory address of a page
@ -803,6 +850,139 @@ void stm32_flash_keep_unlocked(bool set)
}
}
/**
* @brief write protect the main flash or bootloader sectors
*/
void stm32_flash_protect_flash(bool bootloader, bool protect)
{
(void)bootloader;
(void)protect;
#if defined(STM32H7) && !defined(HAL_BOOTLOADER_BUILD) && defined(HAL_FLASH_PROTECTION)
uint32_t prg1 = FLASH->WPSN_CUR1;
uint32_t prg2 = FLASH->WPSN_CUR2;
#ifndef STORAGE_FLASH_PAGE
const uint32_t storage_page = 0xFF;
#else
const uint32_t storage_page = STORAGE_FLASH_PAGE;
#endif
const uint32_t reserve_page = (FLASH_LOAD_ADDRESS - 0x08000000) / (1024 * 128);
if (bootloader) { // only lock the reserved section
for (uint32_t i = 0; i < reserve_page; i++) {
if (protect) {
prg1 &= ~(1U<<i);
} else {
prg1 |= 1U<<i;
}
}
} else {
for (uint32_t i = reserve_page; i < 8; i++) {
if (i != storage_page && i != storage_page+1 && protect) {
prg1 &= ~(1U<<i);
} else {
prg1 |= 1U<<i;
}
}
for (uint32_t i = 0; i < 8; i++) {
if (i+8 != storage_page && i+8 != storage_page+1 && protect) {
prg2 &= ~(1U<<i);
} else {
prg2 |= 1U<<i;
}
}
}
// check if any changes to be made
if (prg1 == FLASH->WPSN_CUR1 && prg2 == FLASH->WPSN_CUR2) {
return;
}
stm32_flash_opt_clear_errors();
stm32_flash_clear_errors();
if (stm32_flash_unlock_options()) {
FLASH->WPSN_PRG1 = prg1;
FLASH->WPSN_PRG2 = prg2;
FLASH->OPTCR |= FLASH_OPTCR_OPTSTART;
stm32_flash_wait_opt_idle();
stm32_flash_lock_options();
}
#endif
}
/*
* remove all protections from flash banks
* this is a destructive operation requiring bank erasure
* see H743 reference manual 4.3.10 - flash bank erase with protection removal
*/
void stm32_flash_unprotect_flash()
{
#if defined(STM32H7) && defined(HAL_FLASH_PROTECTION)
stm32_flash_opt_clear_errors();
stm32_flash_clear_errors();
if ((FLASH->PRAR_CUR2 & 0xFFF) <= ((FLASH->PRAR_CUR2 >> 16) & 0xFFF)
|| (FLASH->SCAR_CUR2 & 0xFFF) <= ((FLASH->SCAR_CUR2 >> 16) & 0xFFF)) {
if (stm32_flash_unlock_options()) {
const uint32_t start_addr = 0x00;
const uint32_t end_addr = 0xFF;
const uint32_t prg = (1 << 31) | ((start_addr << 16) | end_addr);
FLASH->PRAR_PRG2 = prg;
FLASH->SCAR_PRG2 = prg;
FLASH->WPSN_PRG2 = 0xFF;
stm32_flash_unlock();
FLASH->CR2 |= FLASH_CR_BER; // bank 2 erase
FLASH->CR2 |= FLASH_CR_START;
stm32_flash_wait_idle();
stm32_flash_lock();
}
}
if ((FLASH->PRAR_CUR1 & 0xFFF) <= ((FLASH->PRAR_CUR1 >> 16) & 0xFFF)
|| (FLASH->SCAR_CUR1 & 0xFFF) <= ((FLASH->SCAR_CUR1 >> 16) & 0xFFF)) {
if (stm32_flash_unlock_options()) {
const uint32_t start_addr = 0x00;
const uint32_t end_addr = 0xFF;
const uint32_t prg = (1 << 31) | ((start_addr << 16) | end_addr);
FLASH->PRAR_PRG1 = prg;
FLASH->SCAR_PRG1 = prg;
FLASH->WPSN_PRG1 = 0xFF;
stm32_flash_unlock();
FLASH->CR1 |= FLASH_CR_BER; // bank 1 erase
FLASH->CR1 |= FLASH_CR_START;
stm32_flash_wait_idle();
stm32_flash_lock();
}
}
// remove write protection from banks 1&2
if ((FLASH->WPSN_CUR2 & 0xFF) != 0xFF
|| (FLASH->WPSN_CUR1 & 0xFF) != 0xFF) {
if (stm32_flash_unlock_options()) {
FLASH->WPSN_PRG1 = 0xFF;
FLASH->WPSN_PRG2 = 0xFF;
FLASH->OPTCR |= FLASH_OPTCR_OPTSTART;
stm32_flash_wait_opt_idle();
stm32_flash_lock_options();
}
}
#endif
}
#ifndef HAL_BOOTLOADER_BUILD
/*
return true if we had a recent erase

View File

@ -27,6 +27,8 @@ bool stm32_flash_erasepage(uint32_t page);
bool stm32_flash_write(uint32_t addr, const void *buf, uint32_t count);
void stm32_flash_keep_unlocked(bool set);
bool stm32_flash_ispageerased(uint32_t page);
void stm32_flash_protect_flash(bool bootloader, bool protect);
void stm32_flash_unprotect_flash(void);
#ifndef HAL_BOOTLOADER_BUILD
bool stm32_flash_recent_erase(void);
#endif

View File

@ -161,6 +161,9 @@ bool stm32_rand_generate_blocking(unsigned char* output, unsigned int sz, uint32
unsigned int stm32_rand_generate_nonblocking(unsigned char* output, unsigned int sz);
#endif
void stm32_flash_protect_flash(bool bootloader, bool protect);
void stm32_flash_unprotect_flash(void);
// allow stack view code to show free ISR stack
extern uint32_t __main_stack_base__;
extern uint32_t __main_stack_end__;