Added non-blocking SPI DMA support for access to FLASH for BB

This commit is contained in:
Steve Evans 2021-04-20 19:45:56 +01:00
parent 83a98f743c
commit 432b80167f
12 changed files with 341 additions and 265 deletions

View File

@ -374,6 +374,11 @@ void blackboxEraseAll(void)
{
switch (blackboxConfig()->device) {
case BLACKBOX_DEVICE_FLASH:
/* Stop the recorder as if blackbox_mode = ALWAYS it will attempt to resume writing after
* the erase and leave a corrupted first log.
* Possible enhancement here is to restart logging after erase.
*/
blackboxInit();
flashfsEraseCompletely();
break;
default:

View File

@ -389,6 +389,8 @@ static int write_word(config_streamer_t *c, config_streamer_buffer_align_type_t
uint32_t flashSectorSize = flashGeometry->sectorSize;
uint32_t flashPageSize = flashGeometry->pageSize;
const uint8_t *buffers[1];
uint32_t bufferSizes[1];
bool onPageBoundary = (flashAddress % flashPageSize == 0);
if (onPageBoundary) {
@ -402,10 +404,13 @@ static int write_word(config_streamer_t *c, config_streamer_buffer_align_type_t
flashEraseSector(flashAddress);
}
flashPageProgramBegin(flashAddress);
flashPageProgramBegin(flashAddress, NULL);
}
flashPageProgramContinue((uint8_t *)buffer, CONFIG_STREAMER_BUFFER_SIZE);
buffers[0] = (uint8_t *)buffer;
bufferSizes[0] = CONFIG_STREAMER_BUFFER_SIZE;
flashPageProgramContinue(buffers, bufferSizes, 1);
#elif defined(CONFIG_IN_RAM) || defined(CONFIG_IN_SDCARD)
if (c->address == (uintptr_t)&eepromData[0]) {

View File

@ -252,31 +252,46 @@ void flashEraseCompletely(void)
flashDevice.vTable->eraseCompletely(&flashDevice);
}
void flashPageProgramBegin(uint32_t address)
/* The callback, if provided, will receive the totoal number of bytes transfered
* by each call to flashPageProgramContinue() once the transfer completes.
*/
void flashPageProgramBegin(uint32_t address, void (*callback)(uint32_t length))
{
flashDevice.callback = NULL;
flashDevice.vTable->pageProgramBegin(&flashDevice, address);
flashDevice.vTable->pageProgramBegin(&flashDevice, address, callback);
}
void flashPageProgramContinue(const uint8_t *data, int length)
uint32_t flashPageProgramContinue(const uint8_t **buffers, uint32_t *bufferSizes, uint32_t bufferCount)
{
flashDevice.callback = NULL;
flashDevice.vTable->pageProgramContinue(&flashDevice, data, length);
uint32_t maxBytesToWrite = flashDevice.geometry.pageSize - (flashDevice.currentWriteAddress % flashDevice.geometry.pageSize);
if (bufferCount == 0) {
return 0;
}
if (bufferSizes[0] >= maxBytesToWrite) {
bufferSizes[0] = maxBytesToWrite;
bufferCount = 1;
} else {
maxBytesToWrite -= bufferSizes[0];
if ((bufferCount == 2) && (bufferSizes[1] > maxBytesToWrite)) {
bufferSizes[1] = maxBytesToWrite;
}
}
return flashDevice.vTable->pageProgramContinue(&flashDevice, buffers, bufferSizes, bufferCount);
}
void flashPageProgramFinish(void)
{
flashDevice.callback = NULL;
flashDevice.vTable->pageProgramFinish(&flashDevice);
}
void flashPageProgram(uint32_t address, const uint8_t *data, int length)
void flashPageProgram(uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length))
{
flashDevice.callback = NULL;
flashDevice.vTable->pageProgram(&flashDevice, address, data, length);
flashDevice.vTable->pageProgram(&flashDevice, address, data, length, callback);
}
int flashReadBytes(uint32_t address, uint8_t *buffer, int length)
int flashReadBytes(uint32_t address, uint8_t *buffer, uint32_t length)
{
flashDevice.callback = NULL;
return flashDevice.vTable->readBytes(&flashDevice, address, buffer, length);

View File

@ -54,11 +54,11 @@ bool flashIsReady(void);
bool flashWaitForReady(void);
void flashEraseSector(uint32_t address);
void flashEraseCompletely(void);
void flashPageProgramBegin(uint32_t address);
void flashPageProgramContinue(const uint8_t *data, int length);
void flashPageProgramBegin(uint32_t address, void (*callback)(uint32_t arg));
uint32_t flashPageProgramContinue(const uint8_t **buffers, uint32_t *bufferSizes, uint32_t bufferCount);
void flashPageProgramFinish(void);
void flashPageProgram(uint32_t address, const uint8_t *data, int length);
int flashReadBytes(uint32_t address, uint8_t *buffer, int length);
void flashPageProgram(uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length));
int flashReadBytes(uint32_t address, uint8_t *buffer, uint32_t length);
void flashFlush(void);
const flashGeometry_t *flashGetGeometry(void);

View File

@ -25,6 +25,7 @@
#pragma once
#include "drivers/bus.h"
#include "drivers/dma.h"
struct flashVTable_s;
@ -64,11 +65,11 @@ typedef struct flashVTable_s {
bool (*waitForReady)(flashDevice_t *fdevice);
void (*eraseSector)(flashDevice_t *fdevice, uint32_t address);
void (*eraseCompletely)(flashDevice_t *fdevice);
void (*pageProgramBegin)(flashDevice_t *fdevice, uint32_t address);
void (*pageProgramContinue)(flashDevice_t *fdevice, const uint8_t *data, int length);
void (*pageProgramBegin)(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length));
uint32_t (*pageProgramContinue)(flashDevice_t *fdevice, uint8_t const **buffers, uint32_t *bufferSizes, uint32_t bufferCount);
void (*pageProgramFinish)(flashDevice_t *fdevice);
void (*pageProgram)(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, int length);
void (*pageProgram)(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length));
void (*flush)(flashDevice_t *fdevice);
int (*readBytes)(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length);
int (*readBytes)(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length);
const flashGeometry_t *(*getGeometry)(flashDevice_t *fdevice);
} flashVTable_t;

View File

@ -119,7 +119,6 @@ STATIC_ASSERT(M25P16_PAGESIZE < FLASH_MAX_PAGE_SIZE, M25P16_PAGESIZE_too_small);
const flashVTable_t m25p16_vTable;
static uint8_t m25p16_readStatus(flashDevice_t *fdevice)
{
STATIC_DMA_DATA_AUTO uint8_t readStatus[2] = { M25P16_INSTRUCTION_READ_STATUS_REG, 0 };
@ -130,7 +129,6 @@ static uint8_t m25p16_readStatus(flashDevice_t *fdevice)
return readyStatus[1];
}
static bool m25p16_isReady(flashDevice_t *fdevice)
{
// If we're waiting on DMA completion, then SPI is busy
@ -218,7 +216,6 @@ static void m25p16_setCommandAddress(uint8_t *buf, uint32_t address, bool useLon
*buf = address & 0xff;
}
// Called in ISR context
// A write enable has just been issued
busStatus_e m25p16_callbackWriteEnable(uint32_t arg)
@ -231,6 +228,20 @@ busStatus_e m25p16_callbackWriteEnable(uint32_t arg)
return BUS_READY;
}
// Called in ISR context
// Write operation has just completed
busStatus_e m25p16_callbackWriteComplete(uint32_t arg)
{
flashDevice_t *fdevice = (flashDevice_t *)arg;
// Call transfer completion callback
if (fdevice->callback) {
fdevice->callback(fdevice->callbackArg);
}
return BUS_READY;
}
// Called in ISR context
// Check if the status was busy and if so repeat the poll
busStatus_e m25p16_callbackReady(uint32_t arg)
@ -300,14 +311,14 @@ static void m25p16_eraseCompletely(flashDevice_t *fdevice)
spiWait(fdevice->io.handle.dev);
}
static void m25p16_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
static void m25p16_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length))
{
fdevice->callback = callback;
fdevice->currentWriteAddress = address;
}
static void m25p16_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *data, int length)
static uint32_t m25p16_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, uint32_t *bufferSizes, uint32_t bufferCount)
{
// The segment list cannot be in automatic storage as this routine is non-blocking
STATIC_DMA_DATA_AUTO uint8_t readStatus[2] = { M25P16_INSTRUCTION_READ_STATUS_REG, 0 };
@ -321,6 +332,7 @@ static void m25p16_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *da
{pageProgram, NULL, 0, false, NULL},
{NULL, NULL, 0, true, NULL},
{NULL, NULL, 0, true, NULL},
{NULL, NULL, 0, true, NULL},
};
// Ensure any prior DMA has completed before continuing
@ -330,9 +342,27 @@ static void m25p16_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *da
segments[2].len = fdevice->isLargeFlash ? 5 : 4;
m25p16_setCommandAddress(&pageProgram[1], fdevice->currentWriteAddress, fdevice->isLargeFlash);
// Patch the data segment
segments[3].txData = (uint8_t *)data;
segments[3].len = length;
// Patch the data segments
segments[3].txData = (uint8_t *)buffers[0];
segments[3].len = bufferSizes[0];
fdevice->callbackArg = bufferSizes[0];
if (bufferCount == 1) {
segments[3].negateCS = true;
segments[3].callback = m25p16_callbackWriteComplete;
// Mark segment following data as being of zero length
segments[4].len = 0;
} else if (bufferCount == 2) {
segments[3].negateCS = false;
segments[3].callback = NULL;
segments[4].txData = (uint8_t *)buffers[1];
segments[4].len = bufferSizes[1];
fdevice->callbackArg += bufferSizes[1];
segments[4].negateCS = true;
segments[4].callback = m25p16_callbackWriteComplete;
} else {
return 0;
}
spiSequence(fdevice->io.handle.dev, fdevice->couldBeBusy ? &segments[0] : &segments[1]);
@ -341,7 +371,7 @@ static void m25p16_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *da
spiWait(fdevice->io.handle.dev);
}
fdevice->currentWriteAddress += length;
return fdevice->callbackArg;
}
static void m25p16_pageProgramFinish(flashDevice_t *fdevice)
@ -364,11 +394,11 @@ static void m25p16_pageProgramFinish(flashDevice_t *fdevice)
* If you want to write multiple buffers (whose sum of sizes is still not more than the page size) then you can
* break this operation up into one beginProgram call, one or more continueProgram calls, and one finishProgram call.
*/
static void m25p16_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, int length)
static void m25p16_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length))
{
m25p16_pageProgramBegin(fdevice, address);
m25p16_pageProgramBegin(fdevice, address, callback);
m25p16_pageProgramContinue(fdevice, data, length);
m25p16_pageProgramContinue(fdevice, &data, &length, 1);
m25p16_pageProgramFinish(fdevice);
}
@ -379,7 +409,7 @@ static void m25p16_pageProgram(flashDevice_t *fdevice, uint32_t address, const u
*
* The number of bytes actually read is returned, which can be zero if an error or timeout occurred.
*/
static int m25p16_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
static int m25p16_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length)
{
STATIC_DMA_DATA_AUTO uint8_t readStatus[2] = { M25P16_INSTRUCTION_READ_STATUS_REG, 0 };
STATIC_DMA_DATA_AUTO uint8_t readyStatus[2];

View File

@ -190,19 +190,19 @@ void w25m_eraseCompletely(flashDevice_t *fdevice)
static uint32_t currentWriteAddress;
static int currentWriteDie;
void w25m_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
void w25m_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length))
{
currentWriteDie = address / dieSize;
w25m_dieSelect(fdevice->io.handle.dev, currentWriteDie);
currentWriteAddress = address % dieSize;
dieDevice[currentWriteDie].vTable->pageProgramBegin(&dieDevice[currentWriteDie], address);
dieDevice[currentWriteDie].vTable->pageProgramBegin(&dieDevice[currentWriteDie], address, callback);
}
void w25m_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *data, int length)
uint32_t w25m_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, uint32_t *bufferSizes, uint32_t bufferCount)
{
UNUSED(fdevice);
dieDevice[currentWriteDie].vTable->pageProgramContinue(&dieDevice[currentWriteDie], data, length);
return dieDevice[currentWriteDie].vTable->pageProgramContinue(&dieDevice[currentWriteDie], buffers, bufferSizes, bufferCount);
}
void w25m_pageProgramFinish(flashDevice_t *fdevice)
@ -212,16 +212,16 @@ void w25m_pageProgramFinish(flashDevice_t *fdevice)
dieDevice[currentWriteDie].vTable->pageProgramFinish(&dieDevice[currentWriteDie]);
}
void w25m_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, int length)
void w25m_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length))
{
w25m_pageProgramBegin(fdevice, address);
w25m_pageProgramBegin(fdevice, address, callback);
w25m_pageProgramContinue(fdevice, data, length);
w25m_pageProgramContinue(fdevice, &data, &length, 1);
w25m_pageProgramFinish(fdevice);
}
int w25m_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
int w25m_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length)
{
int rlen; // remaining length
int tlen; // transfer length for a round

View File

@ -155,7 +155,7 @@ static void w25n01g_performOneByteCommand(flashDeviceIO_t *io, uint8_t command)
};
// Ensure any prior DMA has completed before continuing
spiWait(dev);
spiWaitClaim(dev);
spiSequence(dev, &segments[0]);
@ -183,7 +183,7 @@ static void w25n01g_performCommandWithPageAddress(flashDeviceIO_t *io, uint8_t c
};
// Ensure any prior DMA has completed before continuing
spiWait(dev);
spiWaitClaim(dev);
spiSequence(dev, &segments[0]);
@ -420,7 +420,7 @@ static void w25n01g_programDataLoad(flashDevice_t *fdevice, uint16_t columnAddre
};
// Ensure any prior DMA has completed before continuing
spiWait(dev);
spiWaitClaim(dev);
spiSequence(dev, &segments[0]);
@ -454,7 +454,7 @@ static void w25n01g_randomProgramDataLoad(flashDevice_t *fdevice, uint16_t colum
};
// Ensure any prior DMA has completed before continuing
spiWait(dev);
spiWaitClaim(dev);
spiSequence(dev, &segments[0]);
@ -521,8 +521,10 @@ static uint32_t programLoadAddress;
bool bufferDirty = false;
bool isProgramming = false;
void w25n01g_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
void w25n01g_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length))
{
fdevice->callback = callback;
if (bufferDirty) {
if (address != programLoadAddress) {
w25n01g_waitForReady(fdevice);
@ -541,8 +543,13 @@ void w25n01g_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
}
}
void w25n01g_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *data, int length)
uint32_t w25n01g_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, uint32_t *bufferSizes, uint32_t bufferCount)
{
if (bufferCount < 1) {
fdevice->callback(0);
return 0;
}
w25n01g_waitForReady(fdevice);
w25n01g_writeEnable(fdevice);
@ -550,15 +557,21 @@ void w25n01g_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *data, in
isProgramming = false;
if (!bufferDirty) {
w25n01g_programDataLoad(fdevice, W25N01G_LINEAR_TO_COLUMN(programLoadAddress), data, length);
w25n01g_programDataLoad(fdevice, W25N01G_LINEAR_TO_COLUMN(programLoadAddress), buffers[0], bufferSizes[0]);
} else {
w25n01g_randomProgramDataLoad(fdevice, W25N01G_LINEAR_TO_COLUMN(programLoadAddress), data, length);
w25n01g_randomProgramDataLoad(fdevice, W25N01G_LINEAR_TO_COLUMN(programLoadAddress), buffers[0], bufferSizes[0]);
}
// XXX Test if write enable is reset after each data loading.
bufferDirty = true;
programLoadAddress += length;
programLoadAddress += bufferSizes[0];
if (fdevice->callback) {
fdevice->callback(bufferSizes[0]);
}
return bufferSizes[0];
}
static uint32_t currentPage = UINT32_MAX;
@ -594,10 +607,10 @@ void w25n01g_pageProgramFinish(flashDevice_t *fdevice)
* break this operation up into one beginProgram call, one or more continueProgram calls, and one finishProgram call.
*/
void w25n01g_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, int length)
void w25n01g_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length))
{
w25n01g_pageProgramBegin(fdevice, address);
w25n01g_pageProgramContinue(fdevice, data, length);
w25n01g_pageProgramBegin(fdevice, address, callback);
w25n01g_pageProgramContinue(fdevice, &data, &length, 1);
w25n01g_pageProgramFinish(fdevice);
}
@ -641,7 +654,7 @@ void w25n01g_addError(uint32_t address, uint8_t code)
// (3) Issue READ_DATA on column address.
// (4) Return transferLength.
int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length)
{
uint32_t targetPage = W25N01G_LINEAR_TO_PAGE(address);
@ -662,7 +675,7 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
currentPage = targetPage;
}
int column = W25N01G_LINEAR_TO_COLUMN(address);
uint32_t column = W25N01G_LINEAR_TO_COLUMN(address);
uint16_t transferLength;
if (length > W25N01G_PAGE_SIZE - column) {
@ -687,7 +700,7 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
};
// Ensure any prior DMA has completed before continuing
spiWait(dev);
spiWaitClaim(dev);
spiSequence(dev, &segments[0]);
@ -800,10 +813,42 @@ const flashVTable_t w25n01g_vTable = {
.getGeometry = w25n01g_getGeometry,
};
typedef volatile struct cb_context_s {
flashDevice_t *fdevice;
bblut_t *bblut;
int lutsize;
int lutindex;
} cb_context_t;
// Called in ISR context
// Read of BBLUT entry has just completed
busStatus_e w25n01g_readBBLUTCallback(uint32_t arg)
{
cb_context_t *cb_context = (cb_context_t *)arg;
flashDevice_t *fdevice = cb_context->fdevice;
uint8_t *rxData = fdevice->io.handle.dev->bus->curSegment->rxData;
cb_context->bblut->pba = (rxData[0] << 16)|rxData[1];
cb_context->bblut->lba = (rxData[2] << 16)|rxData[3];
if (++cb_context->lutindex < cb_context->lutsize) {
cb_context->bblut++;
return BUS_BUSY; // Repeat the operation
}
return BUS_READY; // All done
}
void w25n01g_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
{
cb_context_t cb_context;
uint8_t in[4];
cb_context.fdevice = fdevice;
fdevice->callbackArg = (uint32_t)&cb_context;
if (fdevice->io.mode == FLASHIO_SPI) {
extDevice_t *dev = fdevice->io.handle.dev;
@ -812,25 +857,23 @@ void w25n01g_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
cmd[0] = W25N01G_INSTRUCTION_READ_BBM_LUT;
cmd[1] = 0;
cb_context.bblut = &bblut[0];
cb_context.lutsize = lutsize;
cb_context.lutindex = 0;
busSegment_t segments[] = {
{cmd, NULL, sizeof (cmd), false, NULL},
{NULL, in, sizeof (in), true, NULL},
{NULL, in, sizeof (in), true, w25n01g_readBBLUTCallback},
{NULL, NULL, 0, true, NULL},
};
// Ensure any prior DMA has completed before continuing
spiWait(dev);
spiWaitClaim(dev);
spiSequence(dev, &segments[0]);
// Block pending completion of SPI access
spiWait(dev);
for (int i = 0 ; i < lutsize ; i++) {
spiReadWriteBuf(dev, NULL, in, 4);
bblut[i].pba = (in[0] << 16)|in[1];
bblut[i].lba = (in[2] << 16)|in[3];
}
}
#ifdef USE_QUADSPI
else if (fdevice->io.mode == FLASHIO_QUADSPI) {

View File

@ -303,7 +303,7 @@ bool w25q128fv_detect(flashDevice_t *fdevice, uint32_t chipID)
return true;
}
void w25q128fv_eraseSector(flashDevice_t *fdevice, uint32_t address)
static void w25q128fv_eraseSector(flashDevice_t *fdevice, uint32_t address)
{
w25q128fv_waitForReady(fdevice);
@ -315,7 +315,7 @@ void w25q128fv_eraseSector(flashDevice_t *fdevice, uint32_t address)
w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_BLOCK_ERASE_64KB_MS);
}
void w25q128fv_eraseCompletely(flashDevice_t *fdevice)
static void w25q128fv_eraseCompletely(flashDevice_t *fdevice)
{
w25q128fv_waitForReady(fdevice);
@ -344,42 +344,45 @@ static void w25q128fv_loadProgramData(flashDevice_t *fdevice, const uint8_t *dat
w25q128fvState.currentWriteAddress += length;
}
void w25q128fv_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
static void w25q128fv_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length))
{
UNUSED(fdevice);
fdevice->callback = callback;
w25q128fvState.currentWriteAddress = address;
}
void w25q128fv_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *data, int length)
static uint32_t w25q128fv_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, uint32_t *bufferSizes, uint32_t bufferCount)
{
w25q128fv_waitForReady(fdevice);
for (uint32_t i = 0; i < bufferCount; i++) {
w25q128fv_waitForReady(fdevice);
w25q128fv_writeEnable(fdevice);
w25q128fv_writeEnable(fdevice);
// verify write enable is set.
w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_WRITE_ENABLE_MS);
bool writable = false;
do {
writable = w25q128fv_isWritable(fdevice);
} while (!writable && w25q128fv_hasTimedOut(fdevice));
// verify write enable is set.
w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_WRITE_ENABLE_MS);
bool writable = false;
do {
writable = w25q128fv_isWritable(fdevice);
} while (!writable && w25q128fv_hasTimedOut(fdevice));
if (!writable) {
return; // TODO report failure somehow.
if (!writable) {
return 0; // TODO report failure somehow.
}
w25q128fv_loadProgramData(fdevice, buffers[i], bufferSizes[i]);
}
w25q128fv_loadProgramData(fdevice, data, length);
return fdevice->callbackArg;
}
void w25q128fv_pageProgramFinish(flashDevice_t *fdevice)
static void w25q128fv_pageProgramFinish(flashDevice_t *fdevice)
{
UNUSED(fdevice);
}
void w25q128fv_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, int length)
static void w25q128fv_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length))
{
w25q128fv_pageProgramBegin(fdevice, address);
w25q128fv_pageProgramContinue(fdevice, data, length);
w25q128fv_pageProgramBegin(fdevice, address, callback);
w25q128fv_pageProgramContinue(fdevice, &data, &length, 1);
w25q128fv_pageProgramFinish(fdevice);
}
@ -388,7 +391,7 @@ void w25q128fv_flush(flashDevice_t *fdevice)
UNUSED(fdevice);
}
int w25q128fv_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
static int w25q128fv_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length)
{
if (!w25q128fv_waitForReady(fdevice)) {
return 0;

View File

@ -55,8 +55,33 @@ static DMA_DATA_ZERO_INIT uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE];
* oldest byte that has yet to be written to flash.
*
* When the circular buffer is empty, head == tail
*
* The tail is advanced once a write is complete up to the location behind head. The tail is advanced
* by a callback from the FLASH write routine. This prevents data being overwritten whilst a write is in progress.
*/
static uint8_t bufferHead = 0, bufferTail = 0;
static uint8_t bufferHead = 0;
static volatile uint8_t bufferTail = 0;
/* Track if there is new data to write. Until the contents of the buffer have been completely
* written flashfsFlushAsync() will be repeatedly called. The tail pointer is only updated
* once an asynchronous write has completed. To do so any earlier could result in data being
* overwritten in the ring buffer. This routine checks that flashfsFlushAsync() should attempt
* to write new data and avoids it writing old data during the race condition that occurs if
* its called again before the previous write to FLASH has completed.
*/
static volatile bool dataWritten = true;
//#define CHECK_FLASH
#ifdef CHECK_FLASH
// Write an incrementing sequence of bytes instead of the requested data and verify
DMA_DATA uint8_t checkFlashBuffer[FLASHFS_WRITE_BUFFER_SIZE];
uint32_t checkFlashPtr = 0;
uint32_t checkFlashLen = 0;
uint8_t checkFlashWrite = 0x00;
uint8_t checkFlashExpected = 0x00;
uint32_t checkFlashErrors = 0;
#endif
// The position of the buffer's tail in the overall flash address space:
static uint32_t tailAddress = 0;
@ -173,6 +198,19 @@ uint32_t flashfsGetWriteBufferFreeSpace(void)
return flashfsGetWriteBufferSize() - flashfsTransmitBufferUsed();
}
/**
* Called after bytes have been written from the buffer to advance the position of the tail by the given amount.
*/
static void flashfsAdvanceTailInBuffer(uint32_t delta)
{
bufferTail += delta;
// Wrap tail around the end of the buffer
if (bufferTail >= FLASHFS_WRITE_BUFFER_SIZE) {
bufferTail -= FLASHFS_WRITE_BUFFER_SIZE;
}
}
/**
* Write the given buffers to flash sequentially at the current tail address, advancing the tail address after
* each write.
@ -192,89 +230,58 @@ uint32_t flashfsGetWriteBufferFreeSpace(void)
*
* Returns the number of bytes written
*/
void flashfsWriteCallback(uint32_t arg)
{
// Advance the cursor in the file system to match the bytes we wrote
flashfsSetTailAddress(tailAddress + arg);
// Free bytes in the ring buffer
flashfsAdvanceTailInBuffer(arg);
// Mark that data has been written from the buffer
dataWritten = true;
}
static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, int bufferCount, bool sync)
{
uint32_t bytesTotal = 0;
uint32_t bytesWritten;
int i;
// It's OK to overwrite the buffer addresses/lengths being passed in
for (i = 0; i < bufferCount; i++) {
bytesTotal += bufferSizes[i];
// If sync is true, block until the FLASH device is ready, otherwise return 0 if the device isn't ready
if (sync) {
while (!flashIsReady());
} else {
if (!flashIsReady()) {
return 0;
}
}
if (!sync && !flashIsReady()) {
// Are we at EOF already? Abort.
if (flashfsIsEOF()) {
return 0;
}
uint32_t bytesTotalRemaining = bytesTotal;
#ifdef CHECK_FLASH
checkFlashPtr = tailAddress;
#endif
uint16_t pageSize = flashGeometry->pageSize;
flashPageProgramBegin(tailAddress, flashfsWriteCallback);
while (bytesTotalRemaining > 0) {
uint32_t bytesTotalThisIteration;
uint32_t bytesRemainThisIteration;
/* Mark that data has yet to be written. There is no race condition as the DMA engine is known
* to be idle at this point
*/
dataWritten = false;
/*
* Each page needs to be saved in a separate program operation, so
* if we would cross a page boundary, only write up to the boundary in this iteration:
*/
if (tailAddress % pageSize + bytesTotalRemaining > pageSize) {
bytesTotalThisIteration = pageSize - tailAddress % pageSize;
} else {
bytesTotalThisIteration = bytesTotalRemaining;
}
bytesWritten = flashPageProgramContinue(buffers, bufferSizes, bufferCount);
// Are we at EOF already? Abort.
if (flashfsIsEOF()) {
// May as well throw away any buffered data
flashfsClearBuffer();
#ifdef CHECK_FLASH
checkFlashLen = bytesWritten;
#endif
break;
}
flashPageProgramFinish();
flashPageProgramBegin(tailAddress);
bytesRemainThisIteration = bytesTotalThisIteration;
for (i = 0; i < bufferCount; i++) {
if (bufferSizes[i] > 0) {
// Is buffer larger than our write limit? Write our limit out of it
if (bufferSizes[i] >= bytesRemainThisIteration) {
flashPageProgramContinue(buffers[i], bytesRemainThisIteration);
buffers[i] += bytesRemainThisIteration;
bufferSizes[i] -= bytesRemainThisIteration;
bytesRemainThisIteration = 0;
break;
} else {
// We'll still have more to write after finishing this buffer off
flashPageProgramContinue(buffers[i], bufferSizes[i]);
bytesRemainThisIteration -= bufferSizes[i];
buffers[i] += bufferSizes[i];
bufferSizes[i] = 0;
}
}
}
flashPageProgramFinish();
bytesTotalRemaining -= bytesTotalThisIteration;
// Advance the cursor in the file system to match the bytes we wrote
flashfsSetTailAddress(tailAddress + bytesTotalThisIteration);
/*
* We'll have to wait for that write to complete before we can issue the next one, so if
* the user requested asynchronous writes, break now.
*/
if (!sync)
break;
}
return bytesTotal - bytesTotalRemaining;
return bytesWritten;
}
/*
@ -283,20 +290,38 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
*
* This routine will fill the details of those buffers into the provided arrays, which must be at least 2 elements long.
*/
static void flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t bufferSizes[])
static int flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t bufferSizes[])
{
buffers[0] = flashWriteBuffer + bufferTail;
buffers[1] = flashWriteBuffer + 0;
if (bufferHead >= bufferTail) {
if (bufferHead > bufferTail) {
bufferSizes[0] = bufferHead - bufferTail;
bufferSizes[1] = 0;
} else {
return 1;
} else if (bufferHead < bufferTail) {
bufferSizes[0] = FLASHFS_WRITE_BUFFER_SIZE - bufferTail;
bufferSizes[1] = bufferHead;
if (bufferSizes[1] == 0) {
return 1;
} else {
return 2;
}
}
bufferSizes[0] = 0;
bufferSizes[1] = 0;
return 0;
}
static bool flashfsNewData()
{
return dataWritten;
}
/**
* Get the current offset of the file pointer within the volume.
*/
@ -312,23 +337,6 @@ uint32_t flashfsGetOffset(void)
return tailAddress + bufferSizes[0] + bufferSizes[1];
}
/**
* Called after bytes have been written from the buffer to advance the position of the tail by the given amount.
*/
static void flashfsAdvanceTailInBuffer(uint32_t delta)
{
bufferTail += delta;
// Wrap tail around the end of the buffer
if (bufferTail >= FLASHFS_WRITE_BUFFER_SIZE) {
bufferTail -= FLASHFS_WRITE_BUFFER_SIZE;
}
if (flashfsBufferIsEmpty()) {
flashfsClearBuffer(); // Bring buffer pointers back to the start to be tidier
}
}
/**
* If the flash is ready to accept writes, flush the buffer to it.
*
@ -337,17 +345,37 @@ static void flashfsAdvanceTailInBuffer(uint32_t delta)
*/
bool flashfsFlushAsync(void)
{
uint8_t const * buffers[2];
uint32_t bufferSizes[2];
int bufCount;
if (flashfsBufferIsEmpty()) {
return true; // Nothing to flush
}
uint8_t const * buffers[2];
uint32_t bufferSizes[2];
uint32_t bytesWritten;
if (!flashfsNewData()) {
// The previous write has yet to complete
return false;
}
flashfsGetDirtyDataBuffers(buffers, bufferSizes);
bytesWritten = flashfsWriteBuffers(buffers, bufferSizes, 2, false);
flashfsAdvanceTailInBuffer(bytesWritten);
#ifdef CHECK_FLASH
// Verify the data written last time
if (checkFlashLen) {
while (!flashIsReady());
flashReadBytes(checkFlashPtr, checkFlashBuffer, checkFlashLen);
for (uint32_t i = 0; i < checkFlashLen; i++) {
if (checkFlashBuffer[i] != checkFlashExpected++) {
checkFlashErrors++; // <-- insert breakpoint here to catch errors
}
}
}
#endif
bufCount = flashfsGetDirtyDataBuffers(buffers, bufferSizes);
if (bufCount) {
flashfsWriteBuffers(buffers, bufferSizes, bufCount, false);
}
return flashfsBufferIsEmpty();
}
@ -360,18 +388,20 @@ bool flashfsFlushAsync(void)
*/
void flashfsFlushSync(void)
{
uint8_t const * buffers[2];
uint32_t bufferSizes[2];
int bufCount;
if (flashfsBufferIsEmpty()) {
return; // Nothing to flush
}
uint8_t const * buffers[2];
uint32_t bufferSizes[2];
bufCount = flashfsGetDirtyDataBuffers(buffers, bufferSizes);
if (bufCount) {
flashfsWriteBuffers(buffers, bufferSizes, bufCount, true);
}
flashfsGetDirtyDataBuffers(buffers, bufferSizes);
flashfsWriteBuffers(buffers, bufferSizes, 2, true);
// We've written our entire buffer now:
flashfsClearBuffer();
while (!flashIsReady());
}
void flashfsSeekAbs(uint32_t offset)
@ -381,18 +411,15 @@ void flashfsSeekAbs(uint32_t offset)
flashfsSetTailAddress(offset);
}
void flashfsSeekRel(int32_t offset)
{
flashfsFlushSync();
flashfsSetTailAddress(tailAddress + offset);
}
/**
* Write the given byte asynchronously to the flash. If the buffer overflows, data is silently discarded.
*/
void flashfsWriteByte(uint8_t byte)
{
#ifdef CHECK_FLASH
byte = checkFlashWrite++;
#endif
flashWriteBuffer[bufferHead++] = byte;
if (bufferHead >= FLASHFS_WRITE_BUFFER_SIZE) {
@ -412,79 +439,26 @@ void flashfsWriteByte(uint8_t byte)
*/
void flashfsWrite(const uint8_t *data, unsigned int len, bool sync)
{
uint8_t const * buffers[3];
uint32_t bufferSizes[3];
uint8_t const * buffers[2];
uint32_t bufferSizes[2];
int bufCount;
uint32_t totalBufSize;
// Buffer up the data the user supplied instead of writing it right away
for (unsigned int i = 0; i < len; i++) {
flashfsWriteByte(data[i]);
}
// There could be two dirty buffers to write out already:
flashfsGetDirtyDataBuffers(buffers, bufferSizes);
// Plus the buffer the user supplied:
buffers[2] = data;
bufferSizes[2] = len;
bufCount = flashfsGetDirtyDataBuffers(buffers, bufferSizes);
totalBufSize = bufferSizes[0] + bufferSizes[1];
/*
* Would writing this data to our buffer cause our buffer to reach the flush threshold? If so try to write through
* to the flash now
*/
if (bufferSizes[0] + bufferSizes[1] + bufferSizes[2] >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) {
uint32_t bytesWritten;
// Attempt to write all three buffers through to the flash asynchronously
bytesWritten = flashfsWriteBuffers(buffers, bufferSizes, 3, false);
if (bufferSizes[0] == 0 && bufferSizes[1] == 0) {
// We wrote all the data that was previously buffered
flashfsClearBuffer();
if (bufferSizes[2] == 0) {
// And we wrote all the data the user supplied! Job done!
return;
}
} else {
// We only wrote a portion of the old data, so advance the tail to remove the bytes we did write from the buffer
flashfsAdvanceTailInBuffer(bytesWritten);
}
// Is the remainder of the data to be written too big to fit in the buffers?
if (bufferSizes[0] + bufferSizes[1] + bufferSizes[2] > FLASHFS_WRITE_BUFFER_USABLE) {
if (sync) {
// Write it through synchronously
flashfsWriteBuffers(buffers, bufferSizes, 3, true);
flashfsClearBuffer();
} else {
/*
* Silently drop the data the user asked to write (i.e. no-op) since we can't buffer it and they
* requested async.
*/
}
return;
}
// Fall through and add the remainder of the incoming data to our buffer
data = buffers[2];
len = bufferSizes[2];
}
// Buffer up the data the user supplied instead of writing it right away
// First write the portion before we wrap around the end of the circular buffer
unsigned int bufferBytesBeforeWrap = FLASHFS_WRITE_BUFFER_SIZE - bufferHead;
unsigned int firstPortion = len < bufferBytesBeforeWrap ? len : bufferBytesBeforeWrap;
memcpy(flashWriteBuffer + bufferHead, data, firstPortion);
bufferHead += firstPortion;
data += firstPortion;
len -= firstPortion;
// If we wrap the head around, write the remainder to the start of the buffer (if any)
if (bufferHead == FLASHFS_WRITE_BUFFER_SIZE) {
memcpy(flashWriteBuffer + 0, data, len);
bufferHead = len;
if (bufCount && (totalBufSize >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN)) {
flashfsWriteBuffers(buffers, bufferSizes, bufCount, sync);
}
}

View File

@ -38,7 +38,6 @@ struct flashGeometry_s;
const struct flashGeometry_s* flashfsGetGeometry(void);
void flashfsSeekAbs(uint32_t offset);
void flashfsSeekRel(int32_t offset);
void flashfsWriteByte(uint8_t byte);
void flashfsWrite(const uint8_t *data, unsigned int len, bool sync);

View File

@ -29,6 +29,7 @@
#include "platform.h"
#include "blackbox/blackbox.h"
#include "blackbox/blackbox_io.h"
#include "build/build_config.h"
#include "build/debug.h"
@ -3177,7 +3178,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
#ifdef USE_FLASHFS
case MSP_DATAFLASH_ERASE:
flashfsEraseCompletely();
blackboxEraseAll();
break;
#endif