1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 00:35:39 +03:00

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

@ -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);
}
}