Add PRBS checking of BB FLASH with USE_FLASH_TEST_PRBS (#13987)
[betaflight.git] / src / main / io / flashfs.c
blob3359a2b42b78f0efe8964d7bbd2056192182604b
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 /**
22 * This provides a stream interface to a flash chip if one is present.
24 * On statup, call flashfsInit() after initialising the flash chip in order to init the filesystem. This will
25 * result in the file pointer being pointed at the first free block found, or at the end of the device if the
26 * flash chip is full.
28 * Note that bits can only be set to 0 when writing, not back to 1 from 0. You must erase sectors in order
29 * to bring bits back to 1 again.
31 * In future, we can add support for multiple different flash chips by adding a flash device driver vtable
32 * and make calls through that, at the moment flashfs just calls m25p16_* routines explicitly.
35 #include <stdint.h>
36 #include <stdbool.h>
37 #include <string.h>
39 #include "platform.h"
41 #if defined(USE_FLASHFS)
43 #include "build/debug.h"
44 #include "common/maths.h"
45 #include "common/printf.h"
46 #include "drivers/flash/flash.h"
47 #include "drivers/light_led.h"
49 #include "io/flashfs.h"
51 typedef enum {
52 FLASHFS_IDLE,
53 FLASHFS_ERASING,
54 } flashfsState_e;
56 static const flashPartition_t *flashPartition = NULL;
57 static const flashGeometry_t *flashGeometry = NULL;
58 static uint32_t flashfsSize = 0;
59 static flashfsState_e flashfsState = FLASHFS_IDLE;
60 static flashSector_t eraseSectorCurrent = 0;
62 static DMA_DATA_ZERO_INIT uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE];
64 /* The position of our head and tail in the circular flash write buffer.
66 * The head is the index that a byte would be inserted into on writing, while the tail is the index of the
67 * oldest byte that has yet to be written to flash.
69 * When the circular buffer is empty, head == tail
71 * The tail is advanced once a write is complete up to the location behind head. The tail is advanced
72 * by a callback from the FLASH write routine. This prevents data being overwritten whilst a write is in progress.
74 static uint8_t bufferHead = 0;
75 static volatile uint8_t bufferTail = 0;
77 /* Track if there is new data to write. Until the contents of the buffer have been completely
78 * written flashfsFlushAsync() will be repeatedly called. The tail pointer is only updated
79 * once an asynchronous write has completed. To do so any earlier could result in data being
80 * overwritten in the ring buffer. This routine checks that flashfsFlushAsync() should attempt
81 * to write new data and avoids it writing old data during the race condition that occurs if
82 * its called again before the previous write to FLASH has completed.
84 static volatile bool dataWritten = true;
86 // The position of the buffer's tail in the overall flash address space:
87 static uint32_t tailAddress = 0;
90 #ifdef USE_FLASH_TEST_PRBS
91 // Write an incrementing sequence of bytes instead of the requested data and verify
92 static DMA_DATA uint8_t checkFlashBuffer[FLASHFS_WRITE_BUFFER_SIZE];
93 static uint32_t checkFlashPtr = 0;
94 static uint32_t checkFlashLen = 0;
95 static uint32_t checkFlashErrors = 0;
96 static bool checkFlashActive = false;
97 static uint32_t checkFlashSeedPRBS;
99 static uint8_t checkFlashNextByte(void)
101 uint32_t newLSB = ((checkFlashSeedPRBS >> 31) ^ (checkFlashSeedPRBS >> 28)) & 1;
103 checkFlashSeedPRBS = (checkFlashSeedPRBS << 1) | newLSB;
105 return checkFlashSeedPRBS & 0xff;
108 // Called from blackboxSetState() to start/stop writing of pseudo-random data to FLASH
109 void checkFlashStart(void)
111 checkFlashSeedPRBS = 0xdeadbeef;
112 checkFlashPtr = tailAddress;
113 checkFlashLen = 0;
114 checkFlashActive = true;
117 void checkFlashStop(void)
119 checkFlashSeedPRBS = 0xdeadbeef;
120 checkFlashErrors = 0;
122 debug[6] = checkFlashLen / flashGeometry->pageSize;
124 // Verify the data written since flashfsSeekAbs() last called
125 while (checkFlashLen) {
126 uint32_t checkLen = MIN(checkFlashLen, sizeof(checkFlashBuffer));
128 // Don't read over a page boundary
129 checkLen = MIN(checkLen, flashGeometry->pageSize - (checkFlashPtr & (flashGeometry->pageSize - 1)));
131 flashReadBytes(checkFlashPtr, checkFlashBuffer, checkLen);
133 for (uint32_t i = 0; i < checkLen; i++) {
134 uint8_t expected = checkFlashNextByte();
135 if (checkFlashBuffer[i] != expected) {
136 checkFlashErrors++; // <-- insert breakpoint here to catch errors
140 checkFlashPtr += checkLen;
141 checkFlashLen -= checkLen;
144 debug[7] = checkFlashErrors;
146 checkFlashActive = false;
148 #endif
150 static void flashfsClearBuffer(void)
152 bufferTail = bufferHead = 0;
155 static bool flashfsBufferIsEmpty(void)
157 return bufferTail == bufferHead;
160 static void flashfsSetTailAddress(uint32_t address)
162 tailAddress = address;
165 void flashfsEraseCompletely(void)
167 if (flashGeometry->sectors > 0 && flashPartitionCount() > 0) {
168 // if there's a single FLASHFS partition and it uses the entire flash then do a full erase
169 const bool doFullErase = (flashPartitionCount() == 1) && (FLASH_PARTITION_SECTOR_COUNT(flashPartition) == flashGeometry->sectors);
170 if (doFullErase) {
171 flashEraseCompletely();
172 } else {
173 // start asynchronous erase of all sectors
174 eraseSectorCurrent = flashPartition->startSector;
175 flashfsState = FLASHFS_ERASING;
179 flashfsClearBuffer();
181 flashfsSetTailAddress(0);
185 * Start and end must lie on sector boundaries, or they will be rounded out to sector boundaries such that
186 * all the bytes in the range [start...end) are erased.
188 void flashfsEraseRange(uint32_t start, uint32_t end)
190 if (flashGeometry->sectorSize <= 0)
191 return;
193 // Round the start down to a sector boundary
194 int startSector = start / flashGeometry->sectorSize;
196 // And the end upward
197 int endSector = end / flashGeometry->sectorSize;
198 int endRemainder = end % flashGeometry->sectorSize;
200 if (endRemainder > 0) {
201 endSector++;
204 for (int sectorIndex = startSector; sectorIndex < endSector; sectorIndex++) {
205 uint32_t sectorAddress = sectorIndex * flashGeometry->sectorSize;
206 flashEraseSector(sectorAddress);
211 * Return true if the flash is not currently occupied with an operation.
213 bool flashfsIsReady(void)
215 // Check for flash chip existence first, then check if idle and ready.
217 return (flashfsIsSupported() && (flashfsState == FLASHFS_IDLE) && flashIsReady());
220 bool flashfsIsSupported(void)
222 return flashfsSize > 0;
225 uint32_t flashfsGetSize(void)
227 return flashfsSize;
230 static uint32_t flashfsTransmitBufferUsed(void)
232 if (bufferHead >= bufferTail)
233 return bufferHead - bufferTail;
235 return FLASHFS_WRITE_BUFFER_SIZE - bufferTail + bufferHead;
239 * Get the size of the largest single write that flashfs could ever accept without blocking or data loss.
241 uint32_t flashfsGetWriteBufferSize(void)
243 return FLASHFS_WRITE_BUFFER_USABLE;
247 * Get the number of bytes that can currently be written to flashfs without any blocking or data loss.
249 uint32_t flashfsGetWriteBufferFreeSpace(void)
251 return flashfsGetWriteBufferSize() - flashfsTransmitBufferUsed();
255 * Called after bytes have been written from the buffer to advance the position of the tail by the given amount.
257 static void flashfsAdvanceTailInBuffer(uint32_t delta)
259 bufferTail += delta;
261 // Wrap tail around the end of the buffer
262 if (bufferTail >= FLASHFS_WRITE_BUFFER_SIZE) {
263 bufferTail -= FLASHFS_WRITE_BUFFER_SIZE;
268 * Write the given buffers to flash sequentially at the current tail address, advancing the tail address after
269 * each write.
271 * In synchronous mode, waits for the flash to become ready before writing so that every byte requested can be written.
273 * In asynchronous mode, if the flash is busy, then the write is aborted and the routine returns immediately.
274 * In this case the returned number of bytes written will be less than the total amount requested.
276 * Modifies the supplied buffer pointers and sizes to reflect how many bytes remain in each of them.
278 * bufferCount: the number of buffers provided
279 * buffers: an array of pointers to the beginning of buffers
280 * bufferSizes: an array of the sizes of those buffers
281 * sync: true if we should wait for the device to be idle before writes, otherwise if the device is busy the
282 * write will be aborted and this routine will return immediately.
284 * Returns the number of bytes written
286 void flashfsWriteCallback(uint32_t arg)
288 // Advance the cursor in the file system to match the bytes we wrote
289 flashfsSetTailAddress(tailAddress + arg);
291 // Free bytes in the ring buffer
292 flashfsAdvanceTailInBuffer(arg);
294 // Mark that data has been written from the buffer
295 dataWritten = true;
298 static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, int bufferCount, bool sync)
300 uint32_t bytesWritten;
302 // It's OK to overwrite the buffer addresses/lengths being passed in
304 // If sync is true, block until the FLASH device is ready, otherwise return 0 if the device isn't ready
305 if (sync) {
306 while (!flashIsReady());
307 } else {
308 if (!flashIsReady()) {
309 return 0;
313 // Are we at EOF already? Abort.
314 if (flashfsIsEOF()) {
315 return 0;
318 flashPageProgramBegin(tailAddress, flashfsWriteCallback);
320 /* Mark that data has yet to be written. There is no race condition as the DMA engine is known
321 * to be idle at this point
323 dataWritten = false;
325 bytesWritten = flashPageProgramContinue(buffers, bufferSizes, bufferCount);
327 flashPageProgramFinish();
329 return bytesWritten;
333 * Since the buffered data might wrap around the end of the circular buffer, we can have two segments of data to write,
334 * an initial portion and a possible wrapped portion.
336 * This routine will fill the details of those buffers into the provided arrays, which must be at least 2 elements long.
338 static int flashfsGetDirtyDataBuffers(uint8_t const *buffers[], uint32_t bufferSizes[])
340 buffers[0] = flashWriteBuffer + bufferTail;
341 buffers[1] = flashWriteBuffer + 0;
343 if (bufferHead > bufferTail) {
344 bufferSizes[0] = bufferHead - bufferTail;
345 bufferSizes[1] = 0;
346 return 1;
347 } else if (bufferHead < bufferTail) {
348 bufferSizes[0] = FLASHFS_WRITE_BUFFER_SIZE - bufferTail;
349 bufferSizes[1] = bufferHead;
350 if (bufferSizes[1] == 0) {
351 return 1;
352 } else {
353 return 2;
357 bufferSizes[0] = 0;
358 bufferSizes[1] = 0;
360 return 0;
364 static bool flashfsNewData(void)
366 return dataWritten;
371 * Get the current offset of the file pointer within the volume.
373 uint32_t flashfsGetOffset(void)
375 uint8_t const * buffers[2];
376 uint32_t bufferSizes[2];
378 // Dirty data in the buffers contributes to the offset
380 flashfsGetDirtyDataBuffers(buffers, bufferSizes);
382 return tailAddress + bufferSizes[0] + bufferSizes[1];
386 * If the flash is ready to accept writes, flush the buffer to it.
388 * Returns true if all data in the buffer has been flushed to the device, or false if
389 * there is still data to be written (call flush again later).
391 bool flashfsFlushAsync(bool force)
393 uint8_t const * buffers[2];
394 uint32_t bufferSizes[2];
395 int bufCount;
397 if (flashfsBufferIsEmpty()) {
398 return true; // Nothing to flush
401 if (!flashfsNewData()) {
402 // The previous write has yet to complete
403 return false;
406 bufCount = flashfsGetDirtyDataBuffers(buffers, bufferSizes);
407 uint32_t bufferedBytes = bufferSizes[0] + bufferSizes[1];
409 if (bufCount && (force || (bufferedBytes >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN))) {
410 flashfsWriteBuffers(buffers, bufferSizes, bufCount, false);
413 return flashfsBufferIsEmpty();
417 * Wait for the flash to become ready and begin flushing any buffered data to flash.
419 * The flash will still be busy some time after this sync completes, but space will
420 * be freed up to accept more writes in the write buffer.
422 void flashfsFlushSync(void)
424 uint8_t const * buffers[2];
425 uint32_t bufferSizes[2];
426 int bufCount;
428 if (flashfsBufferIsEmpty()) {
429 return; // Nothing to flush
432 bufCount = flashfsGetDirtyDataBuffers(buffers, bufferSizes);
433 if (bufCount) {
434 flashfsWriteBuffers(buffers, bufferSizes, bufCount, true);
437 while (!flashIsReady());
441 * Asynchronously erase the flash: Check if ready and then erase sector.
443 void flashfsEraseAsync(void)
445 if (flashfsState == FLASHFS_ERASING) {
446 if ((flashfsIsSupported() && flashIsReady())) {
447 if (eraseSectorCurrent <= flashPartition->endSector) {
448 // Erase sector
449 uint32_t sectorAddress = eraseSectorCurrent * flashGeometry->sectorSize;
450 flashEraseSector(sectorAddress);
451 eraseSectorCurrent++;
452 LED1_TOGGLE;
453 } else {
454 // Done erasing
455 flashfsState = FLASHFS_IDLE;
456 LED1_OFF;
462 void flashfsSeekAbs(uint32_t offset)
464 flashfsFlushSync();
466 flashfsSetTailAddress(offset);
470 * Write the given byte asynchronously to the flash. If the buffer overflows, data is silently discarded.
472 void flashfsWriteByte(uint8_t byte)
474 #ifdef USE_FLASH_TEST_PRBS
475 if (checkFlashActive) {
476 byte = checkFlashNextByte();
477 checkFlashLen++;
479 #endif
481 flashWriteBuffer[bufferHead++] = byte;
483 if (bufferHead >= FLASHFS_WRITE_BUFFER_SIZE) {
484 bufferHead = 0;
487 if (flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) {
488 flashfsFlushAsync(false);
493 * Write the given buffer to the flash either synchronously or asynchronously depending on the 'sync' parameter.
495 * If writing asynchronously, data will be silently discarded if the buffer overflows.
496 * If writing synchronously, the routine will block waiting for the flash to become ready so will never drop data.
498 void flashfsWrite(const uint8_t *data, unsigned int len, bool sync)
500 uint8_t const * buffers[2];
501 uint32_t bufferSizes[2];
502 int bufCount;
503 uint32_t totalBufSize;
505 // Buffer up the data the user supplied instead of writing it right away
506 for (unsigned int i = 0; i < len; i++) {
507 flashfsWriteByte(data[i]);
510 // There could be two dirty buffers to write out already:
511 bufCount = flashfsGetDirtyDataBuffers(buffers, bufferSizes);
512 totalBufSize = bufferSizes[0] + bufferSizes[1];
515 * Would writing this data to our buffer cause our buffer to reach the flush threshold? If so try to write through
516 * to the flash now
518 if (bufCount && (totalBufSize >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN)) {
519 flashfsWriteBuffers(buffers, bufferSizes, bufCount, sync);
524 * Read `len` bytes from the given address into the supplied buffer.
526 * Returns the number of bytes actually read which may be less than that requested.
528 int flashfsReadAbs(uint32_t address, uint8_t *buffer, unsigned int len)
530 int bytesRead;
532 // Did caller try to read past the end of the volume?
533 if (address + len > flashfsSize) {
534 // Truncate their request
535 len = flashfsSize - address;
538 // Don't read across a page boundary
539 len = MIN(len, flashGeometry->pageSize - (address & (flashGeometry->pageSize - 1)));
541 // Since the read could overlap data in our dirty buffers, force a sync to clear those first
542 flashfsFlushSync();
544 bytesRead = flashReadBytes(address, buffer, len);
546 return bytesRead;
550 * Find the offset of the start of the free space on the device (or the size of the device if it is full).
552 int flashfsIdentifyStartOfFreeSpace(void)
554 /* Find the start of the free space on the device by examining the beginning of blocks with a binary search,
555 * looking for ones that appear to be erased. We can achieve this with good accuracy because an erased block
556 * is all bits set to 1, which pretty much never appears in reasonable size substrings of blackbox logs.
558 * To do better we might write a volume header instead, which would mark how much free space remains. But keeping
559 * a header up to date while logging would incur more writes to the flash, which would consume precious write
560 * bandwidth and block more often.
563 enum {
564 /* We can choose whatever power of 2 size we like, which determines how much wastage of free space we'll have
565 * at the end of the last written data. But smaller blocksizes will require more searching.
567 FREE_BLOCK_SIZE = 2048, // XXX This can't be smaller than page size for underlying flash device.
569 /* We don't expect valid data to ever contain this many consecutive uint32_t's of all 1 bits: */
570 FREE_BLOCK_TEST_SIZE_INTS = 4, // i.e. 16 bytes
571 FREE_BLOCK_TEST_SIZE_BYTES = FREE_BLOCK_TEST_SIZE_INTS * sizeof(uint32_t)
574 STATIC_ASSERT(FREE_BLOCK_SIZE >= FLASH_MAX_PAGE_SIZE, FREE_BLOCK_SIZE_too_small);
576 STATIC_DMA_DATA_AUTO union {
577 uint8_t bytes[FREE_BLOCK_TEST_SIZE_BYTES];
578 uint32_t ints[FREE_BLOCK_TEST_SIZE_INTS];
579 } testBuffer;
581 int left = 0; // Smallest block index in the search region
582 int right = flashfsSize / FREE_BLOCK_SIZE; // One past the largest block index in the search region
583 int mid;
584 int result = right;
585 int i;
586 bool blockErased;
588 while (left < right) {
589 mid = (left + right) / 2;
591 if (flashReadBytes(mid * FREE_BLOCK_SIZE, testBuffer.bytes, FREE_BLOCK_TEST_SIZE_BYTES) < FREE_BLOCK_TEST_SIZE_BYTES) {
592 // Unexpected timeout from flash, so bail early (reporting the device fuller than it really is)
593 break;
596 // Checking the buffer 4 bytes at a time like this is probably faster than byte-by-byte, but I didn't benchmark it :)
597 blockErased = true;
598 for (i = 0; i < FREE_BLOCK_TEST_SIZE_INTS; i++) {
599 if (testBuffer.ints[i] != 0xFFFFFFFF) {
600 blockErased = false;
601 break;
605 if (blockErased) {
606 /* This erased block might be the leftmost erased block in the volume, but we'll need to continue the
607 * search leftwards to find out:
609 result = mid;
611 right = mid;
612 } else {
613 left = mid + 1;
617 return result * FREE_BLOCK_SIZE;
621 * Returns true if the file pointer is at the end of the device.
623 bool flashfsIsEOF(void)
625 return tailAddress >= flashfsSize;
628 void flashfsClose(void)
630 switch(flashGeometry->flashType) {
631 case FLASH_TYPE_NOR:
632 break;
634 case FLASH_TYPE_NAND:
635 flashFlush();
637 // Advance tailAddress to next page boundary.
638 uint32_t pageSize = flashGeometry->pageSize;
639 flashfsSetTailAddress((tailAddress + pageSize - 1) & ~(pageSize - 1));
641 break;
646 * Call after initializing the flash chip in order to set up the filesystem.
648 void flashfsInit(void)
650 flashfsSize = 0;
652 flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS);
653 flashGeometry = flashGetGeometry();
655 if (!flashPartition) {
656 return;
659 flashfsSize = FLASH_PARTITION_SECTOR_COUNT(flashPartition) * flashGeometry->sectorSize;
661 // Start the file pointer off at the beginning of free space so caller can start writing immediately
662 flashfsSeekAbs(flashfsIdentifyStartOfFreeSpace());
665 #ifdef USE_FLASH_TOOLS
666 bool flashfsVerifyEntireFlash(void)
668 flashfsEraseCompletely();
670 uint32_t address = 0;
671 flashfsSeekAbs(address);
673 const int bufferSize = 32;
674 char buffer[bufferSize + 1];
676 const uint32_t testLimit = flashfsGetSize();
678 for (address = 0; address < testLimit; address += bufferSize) {
679 tfp_sprintf(buffer, "%08x >> **0123456789ABCDEF**", address);
680 flashfsWrite((uint8_t*)buffer, strlen(buffer), true);
681 if ((address % 0x10000) == 0) {
682 LED0_TOGGLE;
684 // Don't overwrite the buffer if the FLASH is busy writing
685 flashfsFlushSync();
687 flashfsClose();
689 char expectedBuffer[bufferSize + 1];
691 flashfsSeekAbs(0);
693 int verificationFailures = 0;
694 for (address = 0; address < testLimit; address += bufferSize) {
695 tfp_sprintf(expectedBuffer, "%08x >> **0123456789ABCDEF**", address);
697 memset(buffer, 0, sizeof(buffer));
698 int bytesRead = flashfsReadAbs(address, (uint8_t *)buffer, bufferSize);
700 int result = strncmp(buffer, expectedBuffer, bufferSize);
701 if (result != 0 || bytesRead != bufferSize) {
702 verificationFailures++;
704 if ((address % 0x10000) == 0) {
705 LED0_TOGGLE;
708 return verificationFailures == 0;
710 #endif // USE_FLASH_TOOLS
711 #endif // USE_FLASHFS