From 3eb28f16eaa5d4f4a085bcb87f334ba85d3ace84 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Wed, 28 Jan 2015 17:45:36 +1300 Subject: [PATCH] Basic read/write/erase flash functionality works from the CLI Very little code coverage tested yet, only writes of small sizes --- Makefile | 2 + src/main/drivers/bus_spi.c | 2 +- src/main/drivers/bus_spi.h | 2 +- src/main/drivers/flash.h | 31 +++ src/main/drivers/flash_m25p16.c | 278 +++++++++++++++++++ src/main/drivers/flash_m25p16.h | 39 +++ src/main/io/flashfs.c | 339 +++++++++++++++++++++++ src/main/io/flashfs.h | 45 +++ src/main/io/serial_cli.c | 84 ++++++ src/main/main.c | 8 + src/main/target/NAZE/hardware_revision.c | 4 +- src/main/target/NAZE/target.h | 9 + 12 files changed, 839 insertions(+), 4 deletions(-) create mode 100644 src/main/drivers/flash.h create mode 100644 src/main/drivers/flash_m25p16.c create mode 100644 src/main/drivers/flash_m25p16.h create mode 100644 src/main/io/flashfs.c create mode 100644 src/main/io/flashfs.h diff --git a/Makefile b/Makefile index f818e8107..7670f66fc 100644 --- a/Makefile +++ b/Makefile @@ -292,6 +292,8 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \ drivers/system_stm32f10x.c \ drivers/timer.c \ drivers/timer_stm32f10x.c \ + drivers/flash_m25p16.c \ + io/flashfs.c \ hardware_revision.c \ $(HIGHEND_SRC) \ $(COMMON_SRC) diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 28fece232..248e17d39 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -198,7 +198,7 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data) #endif } -bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, uint8_t *in, int len) +bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len) { uint16_t spiTimeout = 1000; diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index fd94abe09..62b20aeb0 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -24,7 +24,7 @@ bool spiInit(SPI_TypeDef *instance); void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor); uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in); -bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, uint8_t *in, int len); +bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len); uint16_t spiGetErrorCounter(SPI_TypeDef *instance); void spiResetErrorCounter(SPI_TypeDef *instance); diff --git a/src/main/drivers/flash.h b/src/main/drivers/flash.h new file mode 100644 index 000000000..6ccba0d7b --- /dev/null +++ b/src/main/drivers/flash.h @@ -0,0 +1,31 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#include + +typedef struct flashGeometry_t { + uint8_t sectors; + + uint16_t pagesPerSector; + uint16_t pageSize; + + uint32_t sectorSize; + + uint32_t totalSize; +} flashGeometry_t; diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c new file mode 100644 index 000000000..864eacd77 --- /dev/null +++ b/src/main/drivers/flash_m25p16.c @@ -0,0 +1,278 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +#include "drivers/flash_m25p16.h" +#include "drivers/bus_spi.h" +#include "drivers/system.h" + +#define M25P16_INSTRUCTION_RDID 0x9F +#define M25P16_INSTRUCTION_READ_BYTES 0x03 +#define M25P16_INSTRUCTION_READ_STATUS_REG 0x05 +#define M25P16_INSTRUCTION_WRITE_STATUS_REG 0x01 +#define M25P16_INSTRUCTION_WRITE_ENABLE 0x06 +#define M25P16_INSTRUCTION_WRITE_DISABLE 0x04 +#define M25P16_INSTRUCTION_PAGE_PROGRAM 0x02 +#define M25P16_INSTRUCTION_SECTOR_ERASE 0xD8 +#define M25P16_INSTRUCTION_BULK_ERASE 0xC7 + +#define M25P16_STATUS_FLAG_WRITE_IN_PROGRESS 0x01 +#define M25P16_STATUS_FLAG_WRITE_ENABLED 0x02 + +#define DISABLE_M25P16 GPIO_SetBits(M25P16_CS_GPIO, M25P16_CS_PIN) +#define ENABLE_M25P16 GPIO_ResetBits(M25P16_CS_GPIO, M25P16_CS_PIN) + +// The timeout we expect between being able to issue page program instructions +#define DEFAULT_TIMEOUT_MILLIS 6 + +// These take sooooo long: +#define SECTOR_ERASE_TIMEOUT_MILLIS 5000 +#define BULK_ERASE_TIMEOUT_MILLIS 21000 + +static flashGeometry_t geometry; + +/* + * Whether we've performed an action that could have made the device busy for writes. + * + * This allows us to avoid polling for writable status when it is definitely ready already. + */ +static bool couldBeBusy = false; + +/** + * Send the given command byte to the device. + */ +static void m25p16_performOneByteCommand(uint8_t command) +{ + ENABLE_M25P16; + + spiTransferByte(M25P16_SPI_INSTANCE, command); + + DISABLE_M25P16; +} + +/** + * The flash requires this write enable command to be sent before commands that would cause + * a write like program and erase. + */ +static void m25p16_writeEnable() +{ + m25p16_performOneByteCommand(M25P16_INSTRUCTION_WRITE_ENABLE); + + // Assume that we're about to do some writing, so the device is just about to become busy + couldBeBusy = true; +} + +static uint8_t m25p16_readStatus() +{ + uint8_t command[2] = {M25P16_INSTRUCTION_READ_STATUS_REG, 0}; + uint8_t in[2]; + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, in, command, sizeof(command)); + + DISABLE_M25P16; + + return in[1]; +} + +bool m25p16_isReady() +{ + couldBeBusy = couldBeBusy && ((m25p16_readStatus() & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0); + + return !couldBeBusy; +} + +bool m25p16_waitForReady(uint32_t timeoutMillis) +{ + uint32_t time = millis(); + while (!m25p16_isReady()) { + if (millis() - time > timeoutMillis) { + return false; + } + } + + return true; +} + +/** + * Read chip identification and geometry information (into global `geometry`). + * + * Returns true if we get valid ident, false if something bad happened like there is no M25P16. + */ +static bool m25p16_readIdentification() +{ + uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0}; + uint8_t in[4]; + + delay(50); // short delay required after initialisation of SPI device instance. + + in[1] = 0; // Just in case transfer fails and writes nothing + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, in, out, sizeof(out)); + + // Clearing the CS bit terminates the command early so we don't have to read the chip UID: + DISABLE_M25P16; + + // Check manufacturer, memory type, and capacity + if (in[1] == 0x20 && in[2] == 0x20 && in[3] == 0x15) { + // In the future we can support other chip geometries here: + geometry.sectors = 32; + geometry.pagesPerSector = 256; + geometry.pageSize = 256; + + geometry.sectorSize = geometry.pagesPerSector * geometry.pageSize; + geometry.totalSize = geometry.sectorSize * geometry.sectors; + + couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be + + return true; + } + + geometry.sectors = 0; + geometry.pagesPerSector = 0; + geometry.pageSize = 0; + + geometry.sectorSize = 0; + geometry.totalSize = 0; + + return false; +} + +/** + * Initialize the driver, must be called before any other routines. + * + * Attempts to detect a connected m25p16. If found, true is returned and device capacity can be fetched with + * m25p16_getGeometry(). + */ +bool m25p16_init() +{ + //Maximum speed for standard READ command is 20mHz, other commands tolerate 25mHz + spiSetDivisor(M25P16_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); + + return m25p16_readIdentification(); +} + +/** + * Erase a sector full of bytes to all 1's at the given byte offset in the flash chip. + */ +void m25p16_eraseSector(uint32_t address) +{ + uint8_t out[] = { M25P16_INSTRUCTION_SECTOR_ERASE, (address >> 16) & 0xFF, (address >> 8) & 0xFF, address & 0xFF}; + + m25p16_waitForReady(SECTOR_ERASE_TIMEOUT_MILLIS); + + m25p16_writeEnable(); + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, NULL, out, sizeof(out)); + + DISABLE_M25P16; +} + +void m25p16_eraseCompletely() +{ + m25p16_waitForReady(BULK_ERASE_TIMEOUT_MILLIS); + + m25p16_writeEnable(); + + m25p16_performOneByteCommand(M25P16_INSTRUCTION_BULK_ERASE); +} + +void m25p16_pageProgramBegin(uint32_t address) +{ + uint8_t command[] = { M25P16_INSTRUCTION_PAGE_PROGRAM, (address >> 16) & 0xFF, (address >> 8) & 0xFF, address & 0xFF}; + + m25p16_waitForReady(DEFAULT_TIMEOUT_MILLIS); + + m25p16_writeEnable(); + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, NULL, command, sizeof(command)); +} + +void m25p16_pageProgramContinue(const uint8_t *data, int length) +{ + spiTransfer(M25P16_SPI_INSTANCE, NULL, data, length); +} + +void m25p16_pageProgramFinish() +{ + DISABLE_M25P16; +} + +/** + * Write bytes to a flash page. Address must not cross a page boundary. + * + * Bits can only be set to zero, not from zero back to one again. In order to set bits to 1, use the erase command. + * + * Length must be smaller than the page size. + * + * This will wait for the flash to become ready before writing begins. + * + * Datasheet indicates typical programming time is 0.8ms for 256 bytes, 0.2ms for 64 bytes, 0.05ms for 16 bytes. + * (Although the maximum possible write time is noted as 5ms). + * + * 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. + */ +void m25p16_pageProgram(uint32_t address, const uint8_t *data, int length) +{ + m25p16_pageProgramBegin(address); + + m25p16_pageProgramContinue(data, length); + + m25p16_pageProgramFinish(); +} + +/** + * Read `length` bytes into the provided `buffer` from the flash starting from the given `address` (which need not lie + * on a page boundary). + * + * The number of bytes actually read is returned, which can be zero if an error occurred. + */ +int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length) +{ + uint8_t command[] = { M25P16_INSTRUCTION_READ_BYTES, (address >> 16) & 0xFF, (address >> 8) & 0xFF, address & 0xFF}; + + if (!m25p16_waitForReady(DEFAULT_TIMEOUT_MILLIS)) { + return 0; + } + + ENABLE_M25P16; + + spiTransfer(M25P16_SPI_INSTANCE, NULL, command, sizeof(command)); + spiTransfer(M25P16_SPI_INSTANCE, buffer, NULL, length); + + DISABLE_M25P16; + + return length; +} + +const flashGeometry_t* m25p16_getGeometry() +{ + return &geometry; +} diff --git a/src/main/drivers/flash_m25p16.h b/src/main/drivers/flash_m25p16.h new file mode 100644 index 000000000..79d782715 --- /dev/null +++ b/src/main/drivers/flash_m25p16.h @@ -0,0 +1,39 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#include +#include "flash.h" + +bool m25p16_init(); + +void m25p16_eraseSector(uint32_t address); +void m25p16_eraseCompletely(); + +void m25p16_pageProgram(uint32_t address, const uint8_t *data, int length); + +void m25p16_pageProgramBegin(uint32_t address); +void m25p16_pageProgramContinue(const uint8_t *data, int length); +void m25p16_pageProgramFinish(); + +int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length); + +bool m25p16_isReady(); +bool m25p16_waitForReady(uint32_t timeoutMillis); + +const flashGeometry_t* m25p16_getGeometry(); diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c new file mode 100644 index 000000000..3a6795ff1 --- /dev/null +++ b/src/main/io/flashfs.c @@ -0,0 +1,339 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +/** + * This provides a stream interface to a flash chip if one is present. + * + * Note that bits can only be set to 0 when writing, not back to 1 from 0. You must erase sectors in order + * to bring bits back to 1 again. + */ + +#include +#include + +#include "drivers/flash_m25p16.h" +#include "flashfs.h" + +static uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE]; + +/* The position of our head and tail in the circular flash write buffer. + * + * The head is the index that a byte would be inserted into on writing, while the tail is the index of the + * oldest byte that has yet to be written to flash. + * + * When the circular buffer is empty, head == tail + */ +static uint8_t bufferHead = 0, bufferTail = 0; + +// The position of our tail in the overall flash address space: +static uint32_t tailAddress = 0; +// The index of the tail within the flash page it is inside +static uint16_t tailIndexInPage = 0; + +static bool shouldFlush = false; + +static void flashfsClearBuffer() +{ + bufferTail = bufferHead = 0; + shouldFlush = false; +} + +static void flashfsSetTailAddress(uint32_t address) +{ + tailAddress = address; + tailIndexInPage = tailAddress % m25p16_getGeometry()->pageSize; +} + +void flashfsEraseCompletely() +{ + m25p16_eraseCompletely(); + + flashfsClearBuffer(); + + flashfsSetTailAddress(0); +} + +/** + * Start and end must lie on sector boundaries, or they will be rounded out to sector boundaries such that + * all the bytes in the range [start...end) are erased. + */ +void flashfsEraseRange(uint32_t start, uint32_t end) +{ + const flashGeometry_t *geometry = m25p16_getGeometry(); + + if (geometry->sectorSize <= 0) + return; + + // Round the start down to a sector boundary + int startSector = start / geometry->sectorSize; + + // And the end upward + int endSector = end / geometry->sectorSize; + int endRemainder = end % geometry->sectorSize; + + if (endRemainder > 0) { + endSector++; + } + + for (int i = startSector; i < endSector; i++) { + m25p16_eraseSector(i * geometry->sectorSize); + } +} + +uint32_t flashfsGetSize() +{ + return m25p16_getGeometry()->totalSize; +} + +const flashGeometry_t* flashfsGetGeometry() +{ + return m25p16_getGeometry(); +} + +static uint32_t flashfsTransmitBufferUsed() +{ + if (bufferHead >= bufferTail) + return bufferHead - bufferTail; + + return FLASHFS_WRITE_BUFFER_SIZE - bufferTail + bufferHead; +} + +static uint32_t flashfsTransmitBufferRemaining() +{ + /* + * We subtract one from the actual transmit buffer remaining space to allow us to distinguish + * between completely full and completely empty states, that would otherwise both have head = tail + */ + return FLASHFS_WRITE_BUFFER_USABLE - flashfsTransmitBufferUsed(); +} + +/** + * Waits for the flash device to be ready to accept writes, then write the given buffers to flash. + * + * Advances the address of the beginning of the supplied buffers and reduces the size of the buffers according to how + * many bytes get written. + * + * bufferCount: the number of buffers provided + * buffers: an array of pointers to the beginning of buffers + * bufferSizes: an array of the sizes of those buffers + */ +static void flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, int bufferCount) +{ + const flashGeometry_t *geometry = m25p16_getGeometry(); + + uint32_t bytesTotalToWrite = 0; + uint32_t bytesTotalRemaining; + + int i; + + for (i = 0; i < bufferCount; i++) { + bytesTotalToWrite += bufferSizes[i]; + } + + bytesTotalRemaining = bytesTotalToWrite; + + while (bytesTotalRemaining > 0) { + uint32_t bytesTotalThisIteration; + uint32_t bytesRemainThisIteration; + + // If we would cross a page boundary, only write up to the boundary in this iteration: + if (tailIndexInPage + bytesTotalRemaining > geometry->pageSize) { + bytesTotalThisIteration = geometry->pageSize - tailIndexInPage; + } else { + bytesTotalThisIteration = bytesTotalRemaining; + } + + m25p16_pageProgramBegin(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) { + m25p16_pageProgramContinue(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 + m25p16_pageProgramContinue(buffers[i], bufferSizes[i]); + + bytesRemainThisIteration -= bufferSizes[i]; + + buffers[i] += bufferSizes[i]; + bufferSizes[i] = 0; + } + } + } + + m25p16_pageProgramFinish(); + + bytesTotalRemaining -= bytesTotalThisIteration; + + // Advance the cursor in the file system to match the bytes we wrote + flashfsSetTailAddress(tailAddress + bytesTotalToWrite); + } +} + +/* + * Since the buffered data might wrap around the end of the circular buffer, we can have two segments of data to write, + * an initial portion and a possible wrapped portion. + * + * 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[]) +{ + buffers[0] = flashWriteBuffer + bufferTail; + buffers[1] = flashWriteBuffer + 0; + + if (bufferHead >= bufferTail) { + bufferSizes[0] = bufferHead - bufferTail; + bufferSizes[1] = 0; + } else { + bufferSizes[0] = FLASHFS_WRITE_BUFFER_SIZE - bufferTail; + bufferSizes[1] = bufferHead; + } +} + +/** + * If the flash is ready to accept writes, flush the buffer to it, otherwise schedule + * a flush for later and return immediately. + */ +void flashfsFlushAsync() +{ + if (bufferHead == bufferTail) { + return; // Nothing to flush + } + + if (m25p16_isReady()) { + uint8_t const * buffers[2]; + uint32_t bufferSizes[2]; + + flashfsGetDirtyDataBuffers(buffers, bufferSizes); + flashfsWriteBuffers(buffers, bufferSizes, 2); + + flashfsClearBuffer(); + } else { + shouldFlush = true; + } +} + +/** + * Wait for the flash to become ready and begin flushing any buffered data to flash. + * + * The flash will still be busy some time after this sync completes, but space will + * be freed up to accept more writes in the write buffer. + */ +void flashfsFlushSync() +{ + if (bufferHead == bufferTail) + return; // Nothing to write + + m25p16_waitForReady(10); //TODO caller should customize timeout + + flashfsFlushAsync(); +} + +void flashfsSeekAbs(uint32_t offset) +{ + flashfsFlushSync(); + + flashfsSetTailAddress(offset); +} + +void flashfsSeekRel(int32_t offset) +{ + flashfsFlushSync(); + + flashfsSetTailAddress(tailAddress + offset); +} + +void flashfsWriteByte(uint8_t byte) +{ + flashWriteBuffer[bufferHead++] = byte; + + if (bufferHead >= FLASHFS_WRITE_BUFFER_SIZE) { + bufferHead = 0; + } + + if (flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN) { + flashfsFlushAsync(); + } +} + +void flashfsWrite(const uint8_t *data, unsigned int len) +{ + // Would writing this cause our buffer to reach the flush threshold? If so just write it now + if (len + flashfsTransmitBufferUsed() >= FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN || shouldFlush) { + uint8_t const * buffers[3]; + uint32_t bufferSizes[3]; + + // 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; + + // Write all three buffers through to the flash + flashfsWriteBuffers(buffers, bufferSizes, 3); + + // And now our buffer is empty + flashfsClearBuffer(); + } + + // 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 bufferBytesBeforeLoop = FLASHFS_WRITE_BUFFER_SIZE - bufferHead; + + unsigned int firstPortion = len < bufferBytesBeforeLoop ? len : bufferBytesBeforeLoop; + unsigned int remainder = firstPortion < len ? len - firstPortion : 0; + + for (unsigned int i = 0; i < firstPortion; i++) { + flashWriteBuffer[bufferHead++] = *data; + data++; + } + + if (bufferHead == FLASHFS_WRITE_BUFFER_SIZE) { + bufferHead = 0; + } + + // Then the remainder (if any) + for (unsigned int i = 0; i < remainder; i++) { + flashWriteBuffer[bufferHead++] = *data; + data++; + } +} + +/** + * Read `len` bytes from the current cursor location into the supplied buffer. + * + * Returns the number of bytes actually read which may be less than that requested. + */ +int flashfsRead(uint8_t *data, unsigned int len) +{ + int result = m25p16_readBytes(tailAddress, data, len); + + flashfsSetTailAddress(tailAddress + result); + + return result; +} diff --git a/src/main/io/flashfs.h b/src/main/io/flashfs.h new file mode 100644 index 000000000..a9f8403da --- /dev/null +++ b/src/main/io/flashfs.h @@ -0,0 +1,45 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#include + +#include "drivers/flash.h" + +#define FLASHFS_WRITE_BUFFER_SIZE 128 +#define FLASHFS_WRITE_BUFFER_USABLE (FLASHFS_WRITE_BUFFER_SIZE - 1) + +// Automatically trigger a flush when this much data is in the buffer +#define FLASHFS_WRITE_BUFFER_AUTO_FLUSH_LEN 64 + +void flashfsEraseCompletely(); +void flashfsEraseRange(uint32_t start, uint32_t end); + +uint32_t flashfsGetSize(); +const flashGeometry_t* flashfsGetGeometry(); + +void flashfsSeekAbs(uint32_t offset); +void flashfsSeekRel(int32_t offset); + +void flashfsWriteByte(uint8_t byte); +void flashfsWrite(const uint8_t *data, unsigned int len); + +int flashfsRead(uint8_t *data, unsigned int len); + +void flashfsFlushAsync(); +void flashfsFlushSync(); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index adf96d7f5..66aaf3464 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -44,6 +44,7 @@ #include "drivers/gpio.h" #include "drivers/timer.h" #include "drivers/pwm_rx.h" +#include "drivers/flash_m25p16.h" #include "flight/flight.h" #include "flight/mixer.h" #include "flight/navigation.h" @@ -55,6 +56,7 @@ #include "io/rc_controls.h" #include "io/serial.h" #include "io/ledstrip.h" +#include "io/flashfs.h" #include "rx/spektrum.h" #include "sensors/battery.h" #include "sensors/boardalignment.h" @@ -111,6 +113,13 @@ static void cliColor(char *cmdline); static void cliMixer(char *cmdline); #endif +#ifdef FLASHFS +static void cliFlashIdent(char *cmdline); +static void cliFlashEraseSector(char *cmdline); +static void cliFlashWrite(char *cmdline); +static void cliFlashRead(char *cmdline); +#endif + // signal that we're in cli mode uint8_t cliMode = 0; @@ -166,6 +175,12 @@ const clicmd_t cmdTable[] = { { "dump", "print configurable settings in a pastable form", cliDump }, { "exit", "", cliExit }, { "feature", "list or -val or val", cliFeature }, +#ifdef FLASHFS + { "flash_erase_sector", "erase flash sector at the given address", cliFlashEraseSector }, + { "flash_ident", "get flash chip details", cliFlashIdent }, + { "flash_read", "read text from the given address", cliFlashRead }, + { "flash_write", "write text to the given address", cliFlashWrite }, +#endif { "get", "get variable value", cliGet }, #ifdef GPS { "gpspassthrough", "passthrough gps to serial", cliGpsPassthrough }, @@ -729,6 +744,75 @@ static void cliColor(char *cmdline) } #endif +#ifdef FLASHFS + +static void cliFlashIdent(char *cmdline) +{ + const flashGeometry_t *layout = flashfsGetGeometry(); + + UNUSED(cmdline); + + printf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u\r\n", + layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize); +} + +static void cliFlashEraseSector(char *cmdline) +{ + uint32_t address = atoi(cmdline); + + flashfsEraseRange(address, address + 1); + printf("Erased sector at %u.\r\n", address); +} + +static void cliFlashWrite(char *cmdline) +{ + uint32_t address = atoi(cmdline); + char *text = strchr(cmdline, ' '); + + if (!text) { + printf("Missing text to write.\r\n"); + } else { + flashfsSeekAbs(address); + flashfsWrite((uint8_t*)text, strlen(text)); + flashfsFlushSync(); + + printf("Wrote %u bytes at %u.\r\n", strlen(text), address); + } +} + +static void cliFlashRead(char *cmdline) +{ + uint32_t address = atoi(cmdline); + uint32_t length; + uint32_t i; + + uint8_t buffer[32]; + + char *nextArg = strchr(cmdline, ' '); + + if (!nextArg) { + printf("Missing length argument.\r\n"); + } else { + length = atoi(nextArg); + if (length > 32) { + length = 32; + printf("Length truncated to 32 bytes.\r\n"); + } + + flashfsSeekAbs(address); + flashfsRead(buffer, length); + + printf("Read %u bytes at %u:\r\n", length, address); + + for (i = 0; i < length; i++) { + printf("%c", (char) buffer[i]); + } + printf("\r\n"); + } +} + +#endif + static void dumpValues(uint16_t mask) { uint32_t i; diff --git a/src/main/main.c b/src/main/main.c index 08c1e6469..a4fcfccb2 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -44,6 +44,7 @@ #include "drivers/bus_i2c.h" #include "drivers/bus_spi.h" #include "drivers/inverter.h" +#include "drivers/flash_m25p16.h" #include "flight/flight.h" #include "flight/mixer.h" @@ -348,6 +349,13 @@ void init(void) initTelemetry(); #endif +#ifdef FLASHFS + #ifdef NAZE + // naze32 rev5 and above have 16mbit of flash available + m25p16_init(); + #endif +#endif + #ifdef BLACKBOX initBlackbox(); #endif diff --git a/src/main/target/NAZE/hardware_revision.c b/src/main/target/NAZE/hardware_revision.c index 3726c79e4..bed18b72f 100644 --- a/src/main/target/NAZE/hardware_revision.c +++ b/src/main/target/NAZE/hardware_revision.c @@ -58,7 +58,7 @@ void detectHardwareRevision(void) #define SPI_DEVICE_MPU (2) #define M25P16_INSTRUCTION_RDID 0x9F -#define FLASH_M25P16 (0x202015) +#define FLASH_M25P16_ID (0x202015) uint8_t detectSpiDevice(void) { @@ -74,7 +74,7 @@ uint8_t detectSpiDevice(void) DISABLE_SPI_CS; flash_id = in[1] << 16 | in[2] << 8 | in[3]; - if (flash_id == FLASH_M25P16) + if (flash_id == FLASH_M25P16_ID) return SPI_DEVICE_FLASH; // try autodetect MPU diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index ffd179baa..217d14366 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -56,10 +56,19 @@ #define NAZE_SPI_CS_GPIO GPIOB #define NAZE_SPI_CS_PIN GPIO_Pin_12 +// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision: +#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO +#define M25P16_CS_PIN NAZE_SPI_CS_PIN +#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE + #define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO #define MPU6500_CS_PIN NAZE_SPI_CS_PIN #define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE +#define FLASHFS + +#define USE_FLASH_M25P16 + #define GYRO #define USE_GYRO_MPU3050 #define USE_GYRO_MPU6050