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

Add flash partitioning system (#8297)

Add flash partitioning system
This commit is contained in:
Michael Keller 2019-05-20 01:21:09 +12:00 committed by GitHub
commit a20274c27d
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
9 changed files with 264 additions and 55 deletions

View file

@ -2209,16 +2209,36 @@ static void cliSdInfo(char *cmdline)
#endif
#ifdef USE_FLASHFS
#ifdef USE_FLASH_CHIP
static void cliFlashInfo(char *cmdline)
{
const flashGeometry_t *layout = flashfsGetGeometry();
const flashGeometry_t *layout = flashGetGeometry();
UNUSED(cmdline);
cliPrintLinef("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u",
layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
cliPrintLinef("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u",
layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize);
for (uint8_t index = 0; index < FLASH_MAX_PARTITIONS; index++) {
const flashPartition_t *partition;
if (index == 0) {
cliPrintLine("Paritions:");
}
partition = flashPartitionFindByIndex(index);
if (!partition) {
break;
}
cliPrintLinef(" %d: %s %u %u", index, flashPartitionGetTypeName(partition->type), partition->startSector, partition->endSector);
}
#ifdef USE_FLASHFS
const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS);
cliPrintLinef("FlashFS size=%u, usedSize=%u",
FLASH_PARTITION_SECTOR_COUNT(flashPartition) * layout->sectorSize,
flashfsGetOffset()
);
#endif
}

View file

@ -126,9 +126,11 @@ static void cmsx_Blackbox_GetDeviceStatus(void)
if (storageDeviceIsWorking) {
tfp_sprintf(cmsx_BlackboxStatus, "READY");
const flashGeometry_t *geometry = flashfsGetGeometry();
const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS);
const flashGeometry_t *flashGeometry = flashGetGeometry();
storageUsed = flashfsGetOffset() / 1024;
storageFree = (geometry->totalSize / 1024) - storageUsed;
storageFree = ((FLASH_PARTITION_SECTOR_COUNT(flashPartition) * flashGeometry->sectorSize) / 1024) - storageUsed;
} else {
tfp_sprintf(cmsx_BlackboxStatus, "FAULT");
}

View file

@ -20,6 +20,7 @@
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "platform.h"
@ -41,6 +42,8 @@ static busDevice_t busInstance;
static busDevice_t *busdev;
static flashDevice_t flashDevice;
static flashPartitionTable_t flashPartitionTable;
static int flashPartitions = 0;
#define FLASH_INSTRUCTION_RDID 0x9F
@ -177,7 +180,7 @@ static bool flashSpiInit(const flashConfig_t *flashConfig)
}
#endif // USE_SPI
bool flashInit(const flashConfig_t *flashConfig)
bool flashDeviceInit(const flashConfig_t *flashConfig)
{
#ifdef USE_SPI
bool useSpi = (SPI_CFG_TO_DEV(flashConfig->spiDevice) != SPIINVALID);
@ -259,4 +262,137 @@ const flashGeometry_t *flashGetGeometry(void)
return &noFlashGeometry;
}
/*
* Flash partitioning
*
* Partition table is not currently stored on the flash, in-memory only.
*
* Partitions are required so that Badblock management (inc spare blocks), FlashFS (Blackbox Logging), Configuration and Firmware can be kept separate and tracked.
*
* XXX FIXME
* XXX Note that Flash FS must start at sector 0.
* XXX There is existing blackbox/flash FS code the relies on this!!!
* XXX This restriction can and will be fixed by creating a set of flash operation functions that take partition as an additional parameter.
*/
static void flashConfigurePartitions(void)
{
const flashGeometry_t *flashGeometry = flashGetGeometry();
if (flashGeometry->totalSize == 0) {
return;
}
flashSector_t startSector = 0;
flashSector_t endSector = flashGeometry->sectors - 1; // 0 based index
const flashPartition_t *badBlockPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT);
if (badBlockPartition) {
endSector = badBlockPartition->startSector - 1;
}
#if defined(FIRMWARE_SIZE)
const uint32_t firmwareSize = (FIRMWARE_SIZE * 1024);
flashSector_t firmwareSectors = (firmwareSize / flashGeometry->sectorSize);
if (firmwareSize % flashGeometry->sectorSize > 0) {
firmwareSectors++; // needs a portion of a sector.
}
startSector = (endSector + 1) - firmwareSectors; // + 1 for inclusive
flashPartitionSet(FLASH_PARTITION_TYPE_FIRMWARE, startSector, endSector);
endSector = startSector - 1;
startSector = 0;
#endif
#if defined(EEPROM_IN_EXTERNAL_FLASH)
const uint32_t configSize = EEPROM_SIZE;
flashSector_t configSectors = (configSize / flashGeometry->sectorSize);
if (configSize % flashGeometry->sectorSize > 0) {
configSectors++; // needs a portion of a sector.
}
startSector = (endSector + 1) - configSectors; // + 1 for inclusive
flashPartitionSet(FLASH_PARTITION_TYPE_CONFIG, startSector, endSector);
endSector = startSector - 1;
startSector = 0;
#endif
#ifdef USE_FLASHFS
flashPartitionSet(FLASH_PARTITION_TYPE_FLASHFS, startSector, endSector);
#endif
}
flashPartition_t *flashPartitionFindByType(uint8_t type)
{
for (int index = 0; index < FLASH_MAX_PARTITIONS; index++) {
flashPartition_t *candidate = &flashPartitionTable.partitions[index];
if (candidate->type == type) {
return candidate;
}
}
return NULL;
}
const flashPartition_t *flashPartitionFindByIndex(uint8_t index)
{
if (index >= flashPartitions) {
return NULL;
}
return &flashPartitionTable.partitions[index];
}
void flashPartitionSet(uint8_t type, uint32_t startSector, uint32_t endSector)
{
flashPartition_t *entry = flashPartitionFindByType(type);
if (!entry) {
if (flashPartitions == FLASH_MAX_PARTITIONS - 1) {
return;
}
entry = &flashPartitionTable.partitions[flashPartitions++];
}
entry->type = type;
entry->startSector = startSector;
entry->endSector = endSector;
}
// Must be in sync with FLASH_PARTITION_TYPE
static const char *flashPartitionNames[] = {
"UNKNOWN ",
"PARTITION",
"FLASHFS ",
"BBMGMT ",
"FIRMWARE ",
"CONFIG ",
};
const char *flashPartitionGetTypeName(flashPartitionType_e type)
{
if (type < ARRAYLEN(flashPartitionNames)) {
return flashPartitionNames[type];
}
return NULL;
}
bool flashInit(const flashConfig_t *flashConfig)
{
memset(&flashPartitionTable, 0x00, sizeof(flashPartitionTable));
bool haveFlash = flashDeviceInit(flashConfig);
flashConfigurePartitions();
return haveFlash;
}
#endif // USE_FLASH_CHIP

View file

@ -36,8 +36,10 @@ typedef enum {
FLASH_TYPE_NAND
} flashType_e;
typedef uint16_t flashSector_t;
typedef struct flashGeometry_s {
uint16_t sectors; // Count of the number of erasable blocks on the device
flashSector_t sectors; // Count of the number of erasable blocks on the device
uint16_t pageSize; // In bytes
uint32_t sectorSize; // This is just pagesPerSector * pageSize
uint32_t totalSize; // This is just sectorSize * sectors
@ -59,3 +61,36 @@ void flashPageProgram(uint32_t address, const uint8_t *data, int length);
int flashReadBytes(uint32_t address, uint8_t *buffer, int length);
void flashFlush(void);
const flashGeometry_t *flashGetGeometry(void);
//
// flash partitioning api
//
typedef struct flashPartition_s {
uint8_t type;
flashSector_t startSector;
flashSector_t endSector;
} flashPartition_t;
#define FLASH_PARTITION_SECTOR_COUNT(partition) (partition->endSector + 1 - partition->startSector) // + 1 for inclusive, start and end sector can be the same sector.
// Must be in sync with flashPartitionTypeNames[]
// Should not be deleted or reordered once the code is writing a table to a flash.
typedef enum {
FLASH_PARTITION_TYPE_UNKNOWN = 0,
FLASH_PARTITION_TYPE_PARTITION_TABLE,
FLASH_PARTITION_TYPE_FLASHFS,
FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT,
FLASH_PARTITION_TYPE_FIRMWARE,
FLASH_PARTITION_TYPE_CONFIG,
FLASH_MAX_PARTITIONS
} flashPartitionType_e;
typedef struct flashPartitionTable_s {
flashPartition_t partitions[FLASH_MAX_PARTITIONS];
} flashPartitionTable_t;
void flashPartitionSet(uint8_t index, uint32_t startSector, uint32_t endSector);
flashPartition_t *flashPartitionFindByType(flashPartitionType_e type);
const flashPartition_t *flashPartitionFindByIndex(uint8_t index);
const char *flashPartitionGetTypeName(flashPartitionType_e type);

View file

@ -58,6 +58,15 @@ serialPort_t *debugSerialPort = NULL;
#define W25N01G_PAGES_PER_BLOCK 64
#define W25N01G_BLOCKS_PER_DIE 1024
// BB replacement area
#define W25N01G_BB_MARKER_BLOCKS 1
#define W25N01G_BB_REPLACEMENT_BLOCKS 20
#define W25N01G_BB_MANAGEMENT_BLOCKS (W25N01G_BB_REPLACEMENT_BLOCKS + W25N01G_BB_MARKER_BLOCKS)
// blocks are zero-based index
#define W25N01G_BB_REPLACEMENT_START_BLOCK (W25N01G_BLOCKS_PER_DIE - W25N01G_BB_REPLACEMENT_BLOCKS)
#define W25N01G_BB_MANAGEMENT_START_BLOCK (W25N01G_BLOCKS_PER_DIE - W25N01G_BB_MANAGEMENT_BLOCKS)
#define W25N01G_BB_MARKER_BLOCK (W25N01G_BB_REPLACEMENT_START_BLOCK - W25N01G_BB_MARKER_BLOCKS)
// Instructions
#define W25N01G_INSTRUCTION_RDID 0x9F
@ -113,12 +122,6 @@ serialPort_t *debugSerialPort = NULL;
#define W25N01G_BLOCK_TO_PAGE(block) ((block) * W25N01G_PAGES_PER_BLOCK)
#define W25N01G_BLOCK_TO_LINEAR(block) (W25N01G_BLOCK_TO_PAGE(block) * W25N01G_PAGE_SIZE)
// BB replacement area
#define W25N01G_BB_MARKER_BLOCKS 1
#define W25N01G_BB_REPLACEMENT_BLOCKS 21
#define W25N01G_BB_REPLACEMENT_START_BLOCK (W25N01G_BLOCKS_PER_DIE - W25N01G_BB_REPLACEMENT_BLOCKS)
#define W25N01G_BB_MARKER_BLOCK (W25N01G_BB_REPLACEMENT_START_BLOCK - W25N01G_BB_MARKER_BLOCKS)
// The timeout values (2ms minimum to avoid 1 tick advance in consecutive calls to millis).
#define W25N01G_TIMEOUT_PAGE_READ_MS 2 // tREmax = 60us (ECC enabled)
#define W25N01G_TIMEOUT_PAGE_PROGRAM_MS 2 // tPPmax = 700us
@ -354,10 +357,13 @@ bool w25n01g_detect(flashDevice_t *fdevice, uint32_t chipID)
}
fdevice->geometry.flashType = FLASH_TYPE_NAND;
fdevice->geometry.sectors -= W25N01G_BB_REPLACEMENT_BLOCKS;
fdevice->geometry.sectorSize = fdevice->geometry.pagesPerSector * fdevice->geometry.pageSize;
fdevice->geometry.totalSize = fdevice->geometry.sectorSize * fdevice->geometry.sectors;
flashPartitionSet(FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT,
W25N01G_BB_MANAGEMENT_START_BLOCK,
W25N01G_BB_MANAGEMENT_START_BLOCK + W25N01G_BB_MANAGEMENT_BLOCKS - 1);
fdevice->couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be
w25n01g_deviceReset(fdevice);

View file

@ -716,11 +716,9 @@ void init(void)
#endif
#ifdef USE_FLASH_CHIP
bool haveFlash = flashInit(flashConfig());
flashInit(flashConfig());
#ifdef USE_FLASHFS
if (haveFlash) {
flashfsInit();
}
flashfsInit();
#endif
#endif

View file

@ -43,6 +43,10 @@
#include "io/flashfs.h"
static const flashPartition_t *flashPartition = NULL;
static const flashGeometry_t *flashGeometry = NULL;
static uint32_t flashfsSize = 0;
static uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE];
/* The position of our head and tail in the circular flash write buffer.
@ -74,7 +78,10 @@ static void flashfsSetTailAddress(uint32_t address)
void flashfsEraseCompletely(void)
{
flashEraseCompletely();
for (flashSector_t sectorIndex = flashPartition->startSector; sectorIndex <= flashPartition->endSector; sectorIndex++) {
uint32_t sectorAddress = sectorIndex * flashGeometry->sectorSize;
flashEraseSector(sectorAddress);
}
flashfsClearBuffer();
@ -87,24 +94,23 @@ void flashfsEraseCompletely(void)
*/
void flashfsEraseRange(uint32_t start, uint32_t end)
{
const flashGeometry_t *geometry = flashGetGeometry();
if (geometry->sectorSize <= 0)
if (flashGeometry->sectorSize <= 0)
return;
// Round the start down to a sector boundary
int startSector = start / geometry->sectorSize;
int startSector = start / flashGeometry->sectorSize;
// And the end upward
int endSector = end / geometry->sectorSize;
int endRemainder = end % geometry->sectorSize;
int endSector = end / flashGeometry->sectorSize;
int endRemainder = end % flashGeometry->sectorSize;
if (endRemainder > 0) {
endSector++;
}
for (int i = startSector; i < endSector; i++) {
flashEraseSector(i * geometry->sectorSize);
for (int sectorIndex = startSector; sectorIndex < endSector; sectorIndex++) {
uint32_t sectorAddress = sectorIndex * flashGeometry->sectorSize;
flashEraseSector(sectorAddress);
}
}
@ -120,12 +126,12 @@ bool flashfsIsReady(void)
bool flashfsIsSupported(void)
{
return flashfsGetSize() > 0;
return flashfsSize > 0;
}
uint32_t flashfsGetSize(void)
{
return flashGetGeometry()->totalSize;
return flashfsSize;
}
static uint32_t flashfsTransmitBufferUsed(void)
@ -152,11 +158,6 @@ uint32_t flashfsGetWriteBufferFreeSpace(void)
return flashfsGetWriteBufferSize() - flashfsTransmitBufferUsed();
}
const flashGeometry_t* flashfsGetGeometry(void)
{
return flashGetGeometry();
}
/**
* Write the given buffers to flash sequentially at the current tail address, advancing the tail address after
* each write.
@ -192,7 +193,7 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
uint32_t bytesTotalRemaining = bytesTotal;
uint16_t pageSize = flashfsGetGeometry()->pageSize;
uint16_t pageSize = flashGeometry->pageSize;
while (bytesTotalRemaining > 0) {
uint32_t bytesTotalThisIteration;
@ -482,9 +483,9 @@ int flashfsReadAbs(uint32_t address, uint8_t *buffer, unsigned int len)
int bytesRead;
// Did caller try to read past the end of the volume?
if (address + len > flashfsGetSize()) {
if (address + len > flashfsSize) {
// Truncate their request
len = flashfsGetSize() - address;
len = flashfsSize - address;
}
// Since the read could overlap data in our dirty buffers, force a sync to clear those first
@ -528,7 +529,7 @@ int flashfsIdentifyStartOfFreeSpace(void)
} testBuffer;
int left = 0; // Smallest block index in the search region
int right = flashfsGetSize() / FREE_BLOCK_SIZE; // One past the largest block index in the search region
int right = flashfsSize / FREE_BLOCK_SIZE; // One past the largest block index in the search region
int mid;
int result = right;
int i;
@ -571,12 +572,12 @@ int flashfsIdentifyStartOfFreeSpace(void)
*/
bool flashfsIsEOF(void)
{
return tailAddress >= flashfsGetSize();
return tailAddress >= flashfsSize;
}
void flashfsClose(void)
{
switch(flashfsGetGeometry()->flashType) {
switch(flashGeometry->flashType) {
case FLASH_TYPE_NOR:
break;
@ -584,7 +585,7 @@ void flashfsClose(void)
flashFlush();
// Advance tailAddress to next page boundary.
uint32_t pageSize = flashfsGetGeometry()->pageSize;
uint32_t pageSize = flashGeometry->pageSize;
flashfsSetTailAddress((tailAddress + pageSize - 1) & ~(pageSize - 1));
break;
@ -596,28 +597,34 @@ void flashfsClose(void)
*/
void flashfsInit(void)
{
// If we have a flash chip present at all
if (flashfsGetSize() > 0) {
// Start the file pointer off at the beginning of free space so caller can start writing immediately
flashfsSeekAbs(flashfsIdentifyStartOfFreeSpace());
flashfsSize = 0;
flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS);
flashGeometry = flashGetGeometry();
if (!flashPartition) {
return;
}
flashfsSize = FLASH_PARTITION_SECTOR_COUNT(flashPartition) * flashGeometry->sectorSize;
// Start the file pointer off at the beginning of free space so caller can start writing immediately
flashfsSeekAbs(flashfsIdentifyStartOfFreeSpace());
}
#ifdef USE_FLASH_TOOLS
bool flashfsVerifyEntireFlash(void)
{
flashEraseCompletely();
flashfsEraseCompletely();
flashfsInit();
const flashGeometry_t *flashGeometry = flashfsGetGeometry();
uint32_t address = 0;
flashfsSeekAbs(address);
const int bufferSize = 32;
char buffer[bufferSize + 1];
const uint32_t testLimit = flashGeometry->totalSize;
const uint32_t testLimit = flashfsGetSize();
for (address = 0; address < testLimit; address += bufferSize) {
tfp_sprintf(buffer, "%08x >> **0123456789ABCDEF**", address);

View file

@ -337,10 +337,12 @@ static void serializeDataflashSummaryReply(sbuf_t *dst)
if (flashfsIsSupported()) {
uint8_t flags = MSP_FLASHFS_FLAG_SUPPORTED;
flags |= (flashfsIsReady() ? MSP_FLASHFS_FLAG_READY : 0);
const flashGeometry_t *geometry = flashfsGetGeometry();
const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS);
sbufWriteU8(dst, flags);
sbufWriteU32(dst, geometry->sectors);
sbufWriteU32(dst, geometry->totalSize);
sbufWriteU32(dst, FLASH_PARTITION_SECTOR_COUNT(flashPartition));
sbufWriteU32(dst, flashfsGetSize());
sbufWriteU32(dst, flashfsGetOffset()); // Effectively the current number of bytes stored on the volume
} else
#endif

View file

@ -432,8 +432,11 @@ static void osdGetBlackboxStatusString(char * buff)
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
if (storageDeviceIsWorking) {
const flashGeometry_t *geometry = flashfsGetGeometry();
storageTotal = geometry->totalSize / 1024;
const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS);
const flashGeometry_t *flashGeometry = flashGetGeometry();
storageTotal = ((FLASH_PARTITION_SECTOR_COUNT(flashPartition) * flashGeometry->sectorSize) / 1024);
storageUsed = flashfsGetOffset() / 1024;
}
break;