mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
HAL_ChibiOS: fixed H7 flash storage
this fixes the flash re-init problem when flash storage fills on H7. It was caused by rejecting writes where one or more of the 32 byte chunks was not all 0xff but was equal to the current data. That happens when writing to the sector header in AP_FlashStorage it also moves the interrupt disable inside the loop to allow for other interrupts to run between blocks
This commit is contained in:
parent
5a46280ce3
commit
f3c19575e9
@ -546,8 +546,15 @@ static bool stm32_flash_write_h7(uint32_t addr, const void *buf, uint32_t count)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
stm32_flash_unlock();
|
||||||
|
bool success = true;
|
||||||
|
|
||||||
|
while (count >= 32) {
|
||||||
|
const uint8_t *b2 = (const uint8_t *)addr;
|
||||||
|
// if the bytes already match then skip this chunk
|
||||||
|
if (memcmp(b, b2, 32) != 0) {
|
||||||
// check for erasure
|
// check for erasure
|
||||||
if (!stm32h7_check_all_ones(addr, count >> 2)) {
|
if (!stm32h7_check_all_ones(addr, 8)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -555,20 +562,22 @@ static bool stm32_flash_write_h7(uint32_t addr, const void *buf, uint32_t count)
|
|||||||
syssts_t sts = chSysGetStatusAndLockX();
|
syssts_t sts = chSysGetStatusAndLockX();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
stm32_flash_unlock();
|
bool ok = stm32h7_flash_write32(addr, b);
|
||||||
bool success = true;
|
|
||||||
|
|
||||||
while (count >= 32) {
|
#if STM32_FLASH_DISABLE_ISR
|
||||||
if (!stm32h7_flash_write32(addr, b)) {
|
chSysRestoreStatusX(sts);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (!ok) {
|
||||||
success = false;
|
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;
|
success = false;
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
addr += 32;
|
addr += 32;
|
||||||
count -= 32;
|
count -= 32;
|
||||||
@ -577,9 +586,6 @@ static bool stm32_flash_write_h7(uint32_t addr, const void *buf, uint32_t count)
|
|||||||
|
|
||||||
failed:
|
failed:
|
||||||
stm32_flash_lock();
|
stm32_flash_lock();
|
||||||
#if STM32_FLASH_DISABLE_ISR
|
|
||||||
chSysRestoreStatusX(sts);
|
|
||||||
#endif
|
|
||||||
return success;
|
return success;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user