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)
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/>.
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
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.
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"
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;
89 #ifdef USE_FLASH_TEST_PRBS
90 // Write an incrementing sequence of bytes instead of the requested data and verify
91 static DMA_DATA
uint8_t checkFlashBuffer
[FLASHFS_WRITE_BUFFER_SIZE
];
92 static uint32_t checkFlashPtr
= 0;
93 static uint32_t checkFlashLen
= 0;
94 static uint32_t checkFlashErrors
= 0;
95 static bool checkFlashActive
= false;
96 static uint32_t checkFlashSeedPRBS
;
98 static uint8_t checkFlashNextByte(void)
100 uint32_t newLSB
= ((checkFlashSeedPRBS
>> 31) ^ (checkFlashSeedPRBS
>> 28)) & 1;
102 checkFlashSeedPRBS
= (checkFlashSeedPRBS
<< 1) | newLSB
;
104 return checkFlashSeedPRBS
& 0xff;
107 // Called from blackboxSetState() to start/stop writing of pseudo-random data to FLASH
108 void checkFlashStart(void)
110 checkFlashSeedPRBS
= 0xdeadbeef;
111 checkFlashPtr
= tailAddress
;
113 checkFlashActive
= true;
116 void checkFlashStop(void)
118 checkFlashSeedPRBS
= 0xdeadbeef;
119 checkFlashErrors
= 0;
121 debug
[6] = checkFlashLen
/ flashGeometry
->pageSize
;
123 // Verify the data written since flashfsSeekAbs() last called
124 while (checkFlashLen
) {
125 uint32_t checkLen
= MIN(checkFlashLen
, sizeof(checkFlashBuffer
));
127 // Don't read over a page boundary
128 checkLen
= MIN(checkLen
, flashGeometry
->pageSize
- (checkFlashPtr
& (flashGeometry
->pageSize
- 1)));
130 flashReadBytes(checkFlashPtr
, checkFlashBuffer
, checkLen
);
132 for (uint32_t i
= 0; i
< checkLen
; i
++) {
133 uint8_t expected
= checkFlashNextByte();
134 if (checkFlashBuffer
[i
] != expected
) {
135 checkFlashErrors
++; // <-- insert breakpoint here to catch errors
139 checkFlashPtr
+= checkLen
;
140 checkFlashLen
-= checkLen
;
143 debug
[7] = checkFlashErrors
;
145 checkFlashActive
= false;
149 static void flashfsClearBuffer(void)
151 bufferTail
= bufferHead
= 0;
154 static bool flashfsBufferIsEmpty(void)
156 return bufferTail
== bufferHead
;
159 static void flashfsSetTailAddress(uint32_t address
)
161 tailAddress
= address
;
164 void flashfsEraseCompletely(void)
166 if (flashGeometry
->sectors
> 0 && flashPartitionCount() > 0) {
167 // if there's a single FLASHFS partition and it uses the entire flash then do a full erase
168 const bool doFullErase
= (flashPartitionCount() == 1) && (FLASH_PARTITION_SECTOR_COUNT(flashPartition
) == flashGeometry
->sectors
);
170 flashEraseCompletely();
172 // start asynchronous erase of all sectors
173 eraseSectorCurrent
= flashPartition
->startSector
;
174 flashfsState
= FLASHFS_ERASING
;
178 flashfsClearBuffer();
180 flashfsSetTailAddress(0);
184 * Start and end must lie on sector boundaries, or they will be rounded out to sector boundaries such that
185 * all the bytes in the range [start...end) are erased.
187 void flashfsEraseRange(uint32_t start
, uint32_t end
)
189 if (flashGeometry
->sectorSize
<= 0)
192 // Round the start down to a sector boundary
193 int startSector
= start
/ flashGeometry
->sectorSize
;
195 // And the end upward
196 int endSector
= end
/ flashGeometry
->sectorSize
;
197 int endRemainder
= end
% flashGeometry
->sectorSize
;
199 if (endRemainder
> 0) {
203 for (int sectorIndex
= startSector
; sectorIndex
< endSector
; sectorIndex
++) {
204 uint32_t sectorAddress
= sectorIndex
* flashGeometry
->sectorSize
;
205 flashEraseSector(sectorAddress
);
210 * Return true if the flash is not currently occupied with an operation.
212 bool flashfsIsReady(void)
214 // Check for flash chip existence first, then check if idle and ready.
216 return (flashfsIsSupported() && (flashfsState
== FLASHFS_IDLE
) && flashIsReady());
219 bool flashfsIsSupported(void)
221 return flashfsSize
> 0;
224 uint32_t flashfsGetSize(void)
229 static uint32_t flashfsTransmitBufferUsed(void)
231 if (bufferHead
>= bufferTail
)
232 return bufferHead
- bufferTail
;
234 return FLASHFS_WRITE_BUFFER_SIZE
- bufferTail
+ bufferHead
;
238 * Get the size of the largest single write that flashfs could ever accept without blocking or data loss.
240 uint32_t flashfsGetWriteBufferSize(void)
242 return FLASHFS_WRITE_BUFFER_USABLE
;
246 * Get the number of bytes that can currently be written to flashfs without any blocking or data loss.
248 uint32_t flashfsGetWriteBufferFreeSpace(void)
250 return flashfsGetWriteBufferSize() - flashfsTransmitBufferUsed();
254 * Called after bytes have been written from the buffer to advance the position of the tail by the given amount.
256 static void flashfsAdvanceTailInBuffer(uint32_t delta
)
260 // Wrap tail around the end of the buffer
261 if (bufferTail
>= FLASHFS_WRITE_BUFFER_SIZE
) {
262 bufferTail
-= FLASHFS_WRITE_BUFFER_SIZE
;
267 * Write the given buffers to flash sequentially at the current tail address, advancing the tail address after
270 * In synchronous mode, waits for the flash to become ready before writing so that every byte requested can be written.
272 * In asynchronous mode, if the flash is busy, then the write is aborted and the routine returns immediately.
273 * In this case the returned number of bytes written will be less than the total amount requested.
275 * Modifies the supplied buffer pointers and sizes to reflect how many bytes remain in each of them.
277 * bufferCount: the number of buffers provided
278 * buffers: an array of pointers to the beginning of buffers
279 * bufferSizes: an array of the sizes of those buffers
280 * sync: true if we should wait for the device to be idle before writes, otherwise if the device is busy the
281 * write will be aborted and this routine will return immediately.
283 * Returns the number of bytes written
285 static void flashfsWriteCallback(uint32_t arg
)
287 // Advance the cursor in the file system to match the bytes we wrote
288 flashfsSetTailAddress(tailAddress
+ arg
);
290 // Free bytes in the ring buffer
291 flashfsAdvanceTailInBuffer(arg
);
293 // Mark that data has been written from the buffer
297 static uint32_t flashfsWriteBuffers(uint8_t const **buffers
, uint32_t *bufferSizes
, int bufferCount
, bool sync
)
299 uint32_t bytesWritten
;
301 // It's OK to overwrite the buffer addresses/lengths being passed in
303 // If sync is true, block until the FLASH device is ready, otherwise return 0 if the device isn't ready
305 while (!flashIsReady());
307 if (!flashIsReady()) {
312 // Are we at EOF already? Abort.
313 if (flashfsIsEOF()) {
317 flashPageProgramBegin(tailAddress
, flashfsWriteCallback
);
319 /* Mark that data has yet to be written. There is no race condition as the DMA engine is known
320 * to be idle at this point
324 bytesWritten
= flashPageProgramContinue(buffers
, bufferSizes
, bufferCount
);
326 flashPageProgramFinish();
332 * Since the buffered data might wrap around the end of the circular buffer, we can have two segments of data to write,
333 * an initial portion and a possible wrapped portion.
335 * This routine will fill the details of those buffers into the provided arrays, which must be at least 2 elements long.
337 static int flashfsGetDirtyDataBuffers(uint8_t const *buffers
[], uint32_t bufferSizes
[])
339 buffers
[0] = flashWriteBuffer
+ bufferTail
;
340 buffers
[1] = flashWriteBuffer
+ 0;
342 if (bufferHead
> bufferTail
) {
343 bufferSizes
[0] = bufferHead
- bufferTail
;
346 } else if (bufferHead
< bufferTail
) {
347 bufferSizes
[0] = FLASHFS_WRITE_BUFFER_SIZE
- bufferTail
;
348 bufferSizes
[1] = bufferHead
;
349 if (bufferSizes
[1] == 0) {
362 static bool flashfsNewData(void)
368 * Get the current offset of the file pointer within the volume.
370 uint32_t flashfsGetOffset(void)
372 uint8_t const * buffers
[2];
373 uint32_t bufferSizes
[2];
375 // Dirty data in the buffers contributes to the offset
377 flashfsGetDirtyDataBuffers(buffers
, bufferSizes
);
379 return tailAddress
+ bufferSizes
[0] + bufferSizes
[1];
383 * If the flash is ready to accept writes, flush the buffer to it.
385 * Returns true if all data in the buffer has been flushed to the device, or false if
386 * there is still data to be written (call flush again later).
388 bool flashfsFlushAsync(bool force
)
390 uint8_t const * buffers
[2];
391 uint32_t bufferSizes
[2];
394 if (flashfsBufferIsEmpty()) {
395 return true; // Nothing to flush
398 if (!flashfsNewData()) {
399 // The previous write has yet to complete
403 bufCount
= flashfsGetDirtyDataBuffers(buffers
, bufferSizes
);
404 uint32_t bufferedBytes
= bufferSizes
[0] + bufferSizes
[1];
406 if (bufCount
&& (force
|| (bufferedBytes
>= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN
))) {
407 flashfsWriteBuffers(buffers
, bufferSizes
, bufCount
, false);
410 return flashfsBufferIsEmpty();
414 * Wait for the flash to become ready and begin flushing any buffered data to flash.
416 * The flash will still be busy some time after this sync completes, but space will
417 * be freed up to accept more writes in the write buffer.
419 void flashfsFlushSync(void)
421 uint8_t const * buffers
[2];
422 uint32_t bufferSizes
[2];
425 if (flashfsBufferIsEmpty()) {
426 return; // Nothing to flush
429 bufCount
= flashfsGetDirtyDataBuffers(buffers
, bufferSizes
);
431 flashfsWriteBuffers(buffers
, bufferSizes
, bufCount
, true);
434 while (!flashIsReady());
438 * Asynchronously erase the flash: Check if ready and then erase sector.
440 void flashfsEraseAsync(void)
442 if (flashfsState
== FLASHFS_ERASING
) {
443 if ((flashfsIsSupported() && flashIsReady())) {
444 if (eraseSectorCurrent
<= flashPartition
->endSector
) {
446 uint32_t sectorAddress
= eraseSectorCurrent
* flashGeometry
->sectorSize
;
447 flashEraseSector(sectorAddress
);
448 eraseSectorCurrent
++;
452 flashfsState
= FLASHFS_IDLE
;
459 void flashfsSeekAbs(uint32_t offset
)
463 flashfsSetTailAddress(offset
);
467 * Write the given byte asynchronously to the flash. If the buffer overflows, data is silently discarded.
469 void flashfsWriteByte(uint8_t byte
)
471 #ifdef USE_FLASH_TEST_PRBS
472 if (checkFlashActive
) {
473 byte
= checkFlashNextByte();
478 flashWriteBuffer
[bufferHead
++] = byte
;
480 if (bufferHead
>= FLASHFS_WRITE_BUFFER_SIZE
) {
484 if (flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN
) {
485 flashfsFlushAsync(false);
490 * Write the given buffer to the flash either synchronously or asynchronously depending on the 'sync' parameter.
492 * If writing asynchronously, data will be silently discarded if the buffer overflows.
493 * If writing synchronously, the routine will block waiting for the flash to become ready so will never drop data.
495 void flashfsWrite(const uint8_t *data
, unsigned int len
, bool sync
)
497 uint8_t const * buffers
[2];
498 uint32_t bufferSizes
[2];
500 uint32_t totalBufSize
;
502 // Buffer up the data the user supplied instead of writing it right away
503 for (unsigned int i
= 0; i
< len
; i
++) {
504 flashfsWriteByte(data
[i
]);
507 // There could be two dirty buffers to write out already:
508 bufCount
= flashfsGetDirtyDataBuffers(buffers
, bufferSizes
);
509 totalBufSize
= bufferSizes
[0] + bufferSizes
[1];
512 * Would writing this data to our buffer cause our buffer to reach the flush threshold? If so try to write through
515 if (bufCount
&& (totalBufSize
>= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN
)) {
516 flashfsWriteBuffers(buffers
, bufferSizes
, bufCount
, sync
);
521 * Read `len` bytes from the given address into the supplied buffer.
523 * Returns the number of bytes actually read which may be less than that requested.
525 int flashfsReadAbs(uint32_t address
, uint8_t *buffer
, unsigned int len
)
529 // Did caller try to read past the end of the volume?
530 if (address
+ len
> flashfsSize
) {
531 // Truncate their request
532 len
= flashfsSize
- address
;
535 // Since the read could overlap data in our dirty buffers, force a sync to clear those first
538 bytesRead
= flashReadBytes(address
, buffer
, len
);
544 * Find the offset of the start of the free space on the device (or the size of the device if it is full).
546 int flashfsIdentifyStartOfFreeSpace(void)
548 /* Find the start of the free space on the device by examining the beginning of blocks with a binary search,
549 * looking for ones that appear to be erased. We can achieve this with good accuracy because an erased block
550 * is all bits set to 1, which pretty much never appears in reasonable size substrings of blackbox logs.
552 * To do better we might write a volume header instead, which would mark how much free space remains. But keeping
553 * a header up to date while logging would incur more writes to the flash, which would consume precious write
554 * bandwidth and block more often.
558 /* We can choose whatever power of 2 size we like, which determines how much wastage of free space we'll have
559 * at the end of the last written data. But smaller blocksizes will require more searching.
561 FREE_BLOCK_SIZE
= 2048, // XXX This can't be smaller than page size for underlying flash device.
563 /* We don't expect valid data to ever contain this many consecutive uint32_t's of all 1 bits: */
564 FREE_BLOCK_TEST_SIZE_INTS
= 4, // i.e. 16 bytes
565 FREE_BLOCK_TEST_SIZE_BYTES
= FREE_BLOCK_TEST_SIZE_INTS
* sizeof(uint32_t)
568 STATIC_ASSERT(FREE_BLOCK_SIZE
>= FLASH_MAX_PAGE_SIZE
, FREE_BLOCK_SIZE_too_small
);
570 STATIC_DMA_DATA_AUTO
union {
571 uint8_t bytes
[FREE_BLOCK_TEST_SIZE_BYTES
];
572 uint32_t ints
[FREE_BLOCK_TEST_SIZE_INTS
];
575 int left
= 0; // Smallest block index in the search region
576 int right
= flashfsSize
/ FREE_BLOCK_SIZE
; // One past the largest block index in the search region
582 while (left
< right
) {
583 mid
= (left
+ right
) / 2;
585 if (flashReadBytes(mid
* FREE_BLOCK_SIZE
, testBuffer
.bytes
, FREE_BLOCK_TEST_SIZE_BYTES
) < FREE_BLOCK_TEST_SIZE_BYTES
) {
586 // Unexpected timeout from flash, so bail early (reporting the device fuller than it really is)
590 // Checking the buffer 4 bytes at a time like this is probably faster than byte-by-byte, but I didn't benchmark it :)
592 for (i
= 0; i
< FREE_BLOCK_TEST_SIZE_INTS
; i
++) {
593 if (testBuffer
.ints
[i
] != 0xFFFFFFFF) {
600 /* This erased block might be the leftmost erased block in the volume, but we'll need to continue the
601 * search leftwards to find out:
611 return result
* FREE_BLOCK_SIZE
;
615 * Returns true if the file pointer is at the end of the device.
617 bool flashfsIsEOF(void)
619 return tailAddress
>= flashfsSize
;
622 void flashfsClose(void)
624 switch(flashGeometry
->flashType
) {
628 case FLASH_TYPE_NAND
:
631 // Advance tailAddress to next page boundary.
632 uint32_t pageSize
= flashGeometry
->pageSize
;
633 flashfsSetTailAddress((tailAddress
+ pageSize
- 1) & ~(pageSize
- 1));
640 * Call after initializing the flash chip in order to set up the filesystem.
642 void flashfsInit(void)
646 flashPartition
= flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS
);
647 flashGeometry
= flashGetGeometry();
649 if (!flashPartition
) {
653 flashfsSize
= FLASH_PARTITION_SECTOR_COUNT(flashPartition
) * flashGeometry
->sectorSize
;
655 // Start the file pointer off at the beginning of free space so caller can start writing immediately
656 flashfsSeekAbs(flashfsIdentifyStartOfFreeSpace());
659 #ifdef USE_FLASH_TOOLS
660 bool flashfsVerifyEntireFlash(void)
662 flashfsEraseCompletely();
664 uint32_t address
= 0;
665 flashfsSeekAbs(address
);
667 const int bufferSize
= 32;
668 char buffer
[bufferSize
+ 1];
670 const uint32_t testLimit
= flashfsGetSize();
672 for (address
= 0; address
< testLimit
; address
+= bufferSize
) {
673 tfp_sprintf(buffer
, "%08x >> **0123456789ABCDEF**", address
);
674 flashfsWrite((uint8_t*)buffer
, strlen(buffer
), true);
675 if ((address
% 0x10000) == 0) {
678 // Don't overwrite the buffer if the FLASH is busy writing
683 char expectedBuffer
[bufferSize
+ 1];
687 int verificationFailures
= 0;
688 for (address
= 0; address
< testLimit
; address
+= bufferSize
) {
689 tfp_sprintf(expectedBuffer
, "%08x >> **0123456789ABCDEF**", address
);
691 memset(buffer
, 0, sizeof(buffer
));
692 int bytesRead
= flashfsReadAbs(address
, (uint8_t *)buffer
, bufferSize
);
694 int result
= strncmp(buffer
, expectedBuffer
, bufferSize
);
695 if (result
!= 0 || bytesRead
!= bufferSize
) {
696 verificationFailures
++;
698 if ((address
% 0x10000) == 0) {
702 return verificationFailures
== 0;
704 #endif // USE_FLASH_TOOLS
705 #endif // USE_FLASHFS