Int flash fixes (#3089)
* STM32F7xx: flash write parallelism settings Datasheed allows 32bit program operation only for 2.7..3.0 While RM defines wider range... * Add parentheses to defines * intFlash: show all errors to user Currently only erase error was exported to user. Flash write error was silent. Also define few additional error codes and show it to user.
This commit is contained in:
parent
2b5b669807
commit
c091b18baf
|
@ -92,11 +92,17 @@ int eraseAndFlashCopy(flashaddr_t storageAddress, const TStorage& data) {
|
|||
|
||||
auto err = intFlashErase(storageAddress, sizeof(TStorage));
|
||||
if (FLASH_RETURN_SUCCESS != err) {
|
||||
firmwareError(OBD_PCM_Processor_Fault, "Failed to erase flash at 0x%08x", storageAddress);
|
||||
firmwareError(OBD_PCM_Processor_Fault, "Failed to erase flash at 0x%08x: %d", storageAddress, err);
|
||||
return err;
|
||||
}
|
||||
|
||||
return intFlashWrite(storageAddress, reinterpret_cast<const char*>(&data), sizeof(TStorage));
|
||||
err = intFlashWrite(storageAddress, reinterpret_cast<const char*>(&data), sizeof(TStorage));
|
||||
if (FLASH_RETURN_SUCCESS != err) {
|
||||
firmwareError(OBD_PCM_Processor_Fault, "Failed to write flash at 0x%08x: %d", storageAddress, err);
|
||||
return err;
|
||||
}
|
||||
|
||||
return err;
|
||||
}
|
||||
|
||||
void writeToFlashNow(void) {
|
||||
|
|
|
@ -15,6 +15,24 @@
|
|||
/** @brief Flash operation error because of denied access, corrupted memory.*/
|
||||
#define FLASH_RETURN_NO_PERMISSION -1
|
||||
|
||||
/** @brief Flash operation error */
|
||||
#define FLASH_RETURN_OPERROR -2
|
||||
|
||||
/** @brief Flash write protection error */
|
||||
#define FLASH_RETURN_WPERROR -3
|
||||
|
||||
/** @brief Flash alignment error */
|
||||
#define FLASH_RETURN_ALIGNERROR -4
|
||||
|
||||
/** @brief Flash programming parallelism error */
|
||||
#define FLASH_RETURN_PPARALLERROR -5
|
||||
|
||||
/** @brief Flash erase sequence error */
|
||||
#define FLASH_RETURN_ESEQERROR -6
|
||||
|
||||
/** @brief Flash programming sequence error */
|
||||
#define FLASH_RETURN_PSEQERROR -7
|
||||
|
||||
/** @brief Flash operation error because of bad flash, corrupted memory */
|
||||
#define FLASH_RETURN_BAD_FLASH -11
|
||||
|
||||
|
@ -35,8 +53,8 @@ extern "C" {
|
|||
* 11 to program 64 bits per step
|
||||
*/
|
||||
// Warning, flashdata_t must be unsigned!!!
|
||||
#if defined(STM32F4XX) || defined(STM32F7XX) || defined(STM32H7XX)
|
||||
#define FLASH_CR_PSIZE_MASK FLASH_CR_PSIZE_0 | FLASH_CR_PSIZE_1
|
||||
#if defined(STM32F4XX) || defined(STM32H7XX)
|
||||
#define FLASH_CR_PSIZE_MASK (FLASH_CR_PSIZE_0 | FLASH_CR_PSIZE_1)
|
||||
#if ((STM32_VDD >= 270) && (STM32_VDD <= 360))
|
||||
#define FLASH_CR_PSIZE_VALUE FLASH_CR_PSIZE_1
|
||||
typedef uint32_t flashdata_t;
|
||||
|
@ -52,7 +70,23 @@ typedef uint8_t flashdata_t;
|
|||
#else
|
||||
#error "invalid VDD voltage specified"
|
||||
#endif
|
||||
#endif /* defined(STM32F4XX) */
|
||||
#endif /* defined(STM32F4XX) || defined(STM32H7XX) */
|
||||
|
||||
#if defined(STM32F7XX)
|
||||
#define FLASH_CR_PSIZE_MASK (FLASH_CR_PSIZE_0 | FLASH_CR_PSIZE_1)
|
||||
#if ((STM32_VDD >= 270) && (STM32_VDD <= 300))
|
||||
#define FLASH_CR_PSIZE_VALUE FLASH_CR_PSIZE_1
|
||||
typedef uint32_t flashdata_t;
|
||||
#elif (STM32_VDD >= 210) && (STM32_VDD < 360)
|
||||
#define FLASH_CR_PSIZE_VALUE FLASH_CR_PSIZE_0
|
||||
typedef uint16_t flashdata_t;
|
||||
#elif (STM32_VDD >= 170) && (STM32_VDD < 360)
|
||||
#define FLASH_CR_PSIZE_VALUE ((uint32_t)0x00000000)
|
||||
typedef uint8_t flashdata_t;
|
||||
#else
|
||||
#error "invalid VDD voltage specified"
|
||||
#endif
|
||||
#endif /* defined(STM32F7XX) */
|
||||
|
||||
/** @brief Address in the flash memory */
|
||||
typedef uintptr_t flashaddr_t;
|
||||
|
|
|
@ -59,6 +59,45 @@ flashsector_t intFlashSectorAt(flashaddr_t address) {
|
|||
return sector;
|
||||
}
|
||||
|
||||
static void intFlashClearErrors(void)
|
||||
{
|
||||
#ifdef STM32H7XX
|
||||
FLASH->CCR2 = 0xffffffff;
|
||||
#else
|
||||
FLASH_SR = 0x0000ffff;
|
||||
#endif
|
||||
}
|
||||
|
||||
static int intFlashCheckErrors(void)
|
||||
{
|
||||
uint32_t sr = FLASH_SR;
|
||||
|
||||
#ifdef FLASH_SR_OPERR
|
||||
if (sr & FLASH_SR_OPERR)
|
||||
return FLASH_RETURN_OPERROR;
|
||||
#endif
|
||||
if (sr & FLASH_SR_WRPERR)
|
||||
return FLASH_RETURN_WPERROR;
|
||||
#ifdef FLASH_SR_PGAERR
|
||||
if (sr & FLASH_SR_PGAERR)
|
||||
return FLASH_RETURN_ALIGNERROR;
|
||||
#endif
|
||||
#ifdef FLASH_SR_PGPERR
|
||||
if (sr & FLASH_SR_PGPERR)
|
||||
return FLASH_RETURN_PPARALLERROR;
|
||||
#endif
|
||||
#ifdef FLASH_SR_ERSERR
|
||||
if (sr & FLASH_SR_ERSERR)
|
||||
return FLASH_RETURN_ESEQERROR;
|
||||
#endif
|
||||
#ifdef FLASH_SR_PGSERR
|
||||
if (sr & FLASH_SR_PGSERR)
|
||||
return FLASH_RETURN_PSEQERROR;
|
||||
#endif
|
||||
|
||||
return FLASH_RETURN_SUCCESS;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Unlock the flash memory for write access.
|
||||
* @return HAL_SUCCESS Unlock was successful.
|
||||
|
@ -92,6 +131,7 @@ static bool isDualBank(void) {
|
|||
#endif
|
||||
|
||||
int intFlashSectorErase(flashsector_t sector) {
|
||||
int ret;
|
||||
uint8_t sectorRegIdx = sector;
|
||||
#ifdef STM32F7XX
|
||||
// On dual bank STM32F7, sector index doesn't match register value.
|
||||
|
@ -114,6 +154,9 @@ int intFlashSectorErase(flashsector_t sector) {
|
|||
/* Wait for any busy flags. */
|
||||
intFlashWaitWhileBusy();
|
||||
|
||||
/* Clearing error status bits.*/
|
||||
intFlashClearErrors();
|
||||
|
||||
/* Setup parallelism before any program/erase */
|
||||
FLASH_CR &= ~FLASH_CR_PSIZE_MASK;
|
||||
FLASH_CR |= FLASH_CR_PSIZE_VALUE;
|
||||
|
@ -145,6 +188,10 @@ int intFlashSectorErase(flashsector_t sector) {
|
|||
intFlashLock()
|
||||
;
|
||||
|
||||
ret = intFlashCheckErrors();
|
||||
if (ret != FLASH_RETURN_SUCCESS)
|
||||
return ret;
|
||||
|
||||
/* Check deleted sector for errors */
|
||||
if (intFlashIsErased(intFlashSectorBegin(sector), flashSectorSize(sector)) == FALSE)
|
||||
return FLASH_RETURN_BAD_FLASH; /* Sector is not empty despite the erase cycle! */
|
||||
|
@ -283,7 +330,10 @@ int intFlashWrite(flashaddr_t address, const char* buffer, size_t size) {
|
|||
}
|
||||
|
||||
#else // not STM32H7XX
|
||||
static void intFlashWriteData(flashaddr_t address, const flashdata_t data) {
|
||||
static int intFlashWriteData(flashaddr_t address, const flashdata_t data) {
|
||||
/* Clearing error status bits.*/
|
||||
intFlashClearErrors();
|
||||
|
||||
/* Enter flash programming mode */
|
||||
FLASH->CR |= FLASH_CR_PG;
|
||||
|
||||
|
@ -301,9 +351,13 @@ static void intFlashWriteData(flashaddr_t address, const flashdata_t data) {
|
|||
|
||||
/* Exit flash programming mode */
|
||||
FLASH->CR &= ~FLASH_CR_PG;
|
||||
|
||||
return intFlashCheckErrors();
|
||||
}
|
||||
|
||||
int intFlashWrite(flashaddr_t address, const char* buffer, size_t size) {
|
||||
int ret = FLASH_RETURN_SUCCESS;
|
||||
|
||||
/* Unlock flash for write access */
|
||||
if (intFlashUnlock() == HAL_FAILED)
|
||||
return FLASH_RETURN_NO_PERMISSION;
|
||||
|
@ -337,7 +391,9 @@ int intFlashWrite(flashaddr_t address, const char* buffer, size_t size) {
|
|||
memcpy((char*) &tmp + alignOffset, buffer, chunkSize);
|
||||
|
||||
/* Write the new data in flash */
|
||||
intFlashWriteData(alignedFlashAddress, tmp);
|
||||
ret = intFlashWriteData(alignedFlashAddress, tmp);
|
||||
if (ret != FLASH_RETURN_SUCCESS)
|
||||
goto exit;
|
||||
|
||||
/* Advance */
|
||||
address += chunkSize;
|
||||
|
@ -350,7 +406,9 @@ int intFlashWrite(flashaddr_t address, const char* buffer, size_t size) {
|
|||
* copied requires special treatment. */
|
||||
while (size >= sizeof(flashdata_t)) {
|
||||
// print("flash write size=%d\r\n", size);
|
||||
intFlashWriteData(address, *(const flashdata_t*) buffer);
|
||||
ret = intFlashWriteData(address, *(const flashdata_t*) buffer);
|
||||
if (ret != FLASH_RETURN_SUCCESS)
|
||||
goto exit;
|
||||
address += sizeof(flashdata_t);
|
||||
buffer += sizeof(flashdata_t);
|
||||
size -= sizeof(flashdata_t);
|
||||
|
@ -363,14 +421,17 @@ int intFlashWrite(flashaddr_t address, const char* buffer, size_t size) {
|
|||
if (size > 0) {
|
||||
flashdata_t tmp = *(volatile flashdata_t*) address;
|
||||
memcpy(&tmp, buffer, size);
|
||||
intFlashWriteData(address, tmp);
|
||||
ret = intFlashWriteData(address, tmp);
|
||||
if (ret != FLASH_RETURN_SUCCESS)
|
||||
goto exit;
|
||||
}
|
||||
|
||||
exit:
|
||||
/* Lock flash again */
|
||||
intFlashLock()
|
||||
;
|
||||
|
||||
return FLASH_RETURN_SUCCESS;
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
Loading…
Reference in New Issue