mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_HAL_ChibiOS: never write bytes that have not been erased on H7
Be more careful about flash failure conditions on H7
This commit is contained in:
parent
78735a946e
commit
2823fa7245
@ -422,6 +422,19 @@ bool stm32_flash_erasepage(uint32_t page)
|
|||||||
|
|
||||||
|
|
||||||
#if defined(STM32H7)
|
#if defined(STM32H7)
|
||||||
|
// Check that the flash line is erased as writing to an un-erased line causes flash corruption
|
||||||
|
static bool stm32h7_check_all_ones(uint32_t addr, uint32_t words)
|
||||||
|
{
|
||||||
|
for (uint32_t i = 0; i < words; i++) {
|
||||||
|
// check that the byte was erased
|
||||||
|
if (getreg32(addr) != 0xFFFFFFFF) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
addr += 4;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
the H7 needs special handling, and only writes 32 bytes at a time
|
the H7 needs special handling, and only writes 32 bytes at a time
|
||||||
*/
|
*/
|
||||||
@ -438,12 +451,12 @@ static bool stm32h7_flash_write32(uint32_t addr, const void *buf)
|
|||||||
SR = &FLASH->SR2;
|
SR = &FLASH->SR2;
|
||||||
}
|
}
|
||||||
stm32_flash_wait_idle();
|
stm32_flash_wait_idle();
|
||||||
|
|
||||||
*CCR = ~0;
|
*CCR = ~0;
|
||||||
*CR |= FLASH_CR_PG;
|
*CR |= FLASH_CR_PG;
|
||||||
|
|
||||||
const uint32_t *v = (const uint32_t *)buf;
|
const uint32_t *v = (const uint32_t *)buf;
|
||||||
uint8_t i;
|
for (uint8_t i=0; i<8; i++) {
|
||||||
for (i=0; i<8; i++) {
|
|
||||||
while (*SR & (FLASH_SR_BSY|FLASH_SR_QW)) ;
|
while (*SR & (FLASH_SR_BSY|FLASH_SR_QW)) ;
|
||||||
putreg32(*v, addr);
|
putreg32(*v, addr);
|
||||||
v++;
|
v++;
|
||||||
@ -465,36 +478,41 @@ static bool stm32_flash_write_h7(uint32_t addr, const void *buf, uint32_t count)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check for erasure
|
||||||
|
if (!stm32h7_check_all_ones(addr, count >> 2)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
#if STM32_FLASH_DISABLE_ISR
|
#if STM32_FLASH_DISABLE_ISR
|
||||||
syssts_t sts = chSysGetStatusAndLockX();
|
syssts_t sts = chSysGetStatusAndLockX();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
stm32_flash_unlock();
|
stm32_flash_unlock();
|
||||||
|
bool success = true;
|
||||||
|
|
||||||
while (count >= 32) {
|
while (count >= 32) {
|
||||||
if (memcmp((void*)addr, b, 32) != 0 &&
|
if (!stm32h7_flash_write32(addr, b)) {
|
||||||
!stm32h7_flash_write32(addr, b)) {
|
success = false;
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
|
||||||
// check contents
|
// check contents
|
||||||
if (memcmp((void *)addr, b, 32) != 0) {
|
if (memcmp((void*)addr, b, 32) != 0) {
|
||||||
|
success = false;
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
|
||||||
addr += 32;
|
addr += 32;
|
||||||
count -= 32;
|
count -= 32;
|
||||||
b += 32;
|
b += 32;
|
||||||
}
|
}
|
||||||
stm32_flash_lock();
|
|
||||||
#if STM32_FLASH_DISABLE_ISR
|
|
||||||
chSysRestoreStatusX(sts);
|
|
||||||
#endif
|
|
||||||
return true;
|
|
||||||
|
|
||||||
failed:
|
failed:
|
||||||
stm32_flash_lock();
|
stm32_flash_lock();
|
||||||
#if STM32_FLASH_DISABLE_ISR
|
#if STM32_FLASH_DISABLE_ISR
|
||||||
chSysRestoreStatusX(sts);
|
chSysRestoreStatusX(sts);
|
||||||
#endif
|
#endif
|
||||||
return false;
|
return success;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // STM32H7
|
#endif // STM32H7
|
||||||
|
Loading…
Reference in New Issue
Block a user