1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-25 09:16:01 +03:00

Add flash partitioning support (#5474)

This commit is contained in:
Michel Pastor 2020-04-27 13:23:13 +02:00 committed by GitHub
parent 42a59f38c2
commit 0551f8743a
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
10 changed files with 432 additions and 53 deletions

View file

@ -236,6 +236,7 @@ TARGET_SRC := $(filter-out $(MCU_EXCLUDES), $(TARGET_SRC))
ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
TARGET_SRC += \
drivers/flash.c \
drivers/flash_m25p16.c \
io/flashfs.c \
$(MSC_SRC)

View file

@ -36,6 +36,7 @@
#include "config/feature.h"
#include "drivers/flash.h"
#include "drivers/time.h"
#include "fc/config.h"
@ -53,7 +54,7 @@ static long cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr)
displayResync(pDisplay); // Was max7456RefreshAll(); Why at this timing?
flashfsEraseCompletely();
while (!flashfsIsReady()) {
while (!flashIsReady()) {
delay(100);
}

288
src/main/drivers/flash.c Normal file
View file

@ -0,0 +1,288 @@
/*
* This file is part of iNav.
*
* iNav is free software. You can redistribute
* this software and/or modify this software 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.
*
* iNav 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 this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "platform.h"
#include "build/debug.h"
#ifdef USE_FLASHFS
#include "flash.h"
#include "flash_m25p16.h"
#include "drivers/bus_spi.h"
#include "drivers/io.h"
#include "drivers/time.h"
static flashPartitionTable_t flashPartitionTable;
static int flashPartitions = 0;
#ifdef USE_SPI
static bool flashSpiInit(void)
{
#ifdef USE_FLASH_M25P16
return m25p16_init(0);
#endif
return false;
}
#endif // USE_SPI
bool flashDeviceInit(void)
{
#ifdef USE_SPI
return flashSpiInit();
#endif
return false;
}
bool flashIsReady(void)
{
#ifdef USE_FLASH_M25P16
return m25p16_isReady();
#endif
return false;
}
bool flashWaitForReady(void)
{
#ifdef USE_FLASH_M25P16
return m25p16_waitForReady(10);
#endif
return false;
}
void flashEraseSector(uint32_t address)
{
#ifdef USE_FLASH_M25P16
return m25p16_eraseSector(address);
#endif
}
void flashEraseCompletely(void)
{
#ifdef USE_FLASH_M25P16
return m25p16_eraseCompletely();
#endif
}
#if 0
void flashPageProgramBegin(uint32_t address)
{
#ifdef USE_FLASH_M25P16
return m25p16_pageProgramBegin(address);
#endif
}
void flashPageProgramContinue(const uint8_t *data, int length)
{
#ifdef USE_FLASH_M25P16
return m25p16_pageProgramContinue(data, length);
#endif
}
void flashPageProgramFinish(void)
{
#ifdef USE_FLASH_M25P16
return m25p16_pageProgramFinish();
#endif
}
#endif
uint32_t flashPageProgram(uint32_t address, const uint8_t *data, int length)
{
#ifdef USE_FLASH_M25P16
return m25p16_pageProgram(address, data, length);
#endif
}
int flashReadBytes(uint32_t address, uint8_t *buffer, int length)
{
#ifdef USE_FLASH_M25P16
return m25p16_readBytes(address, buffer, length);
#endif
return 0;
}
void flashFlush(void)
{
}
const flashGeometry_t *flashGetGeometry(void)
{
#ifdef USE_FLASH_M25P16
return m25p16_getGeometry();
#endif
return NULL;
}
/*
* 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 __attribute__((unused)) void createPartition(flashPartitionType_e type, uint32_t size, flashSector_t *endSector)
{
const flashGeometry_t *flashGeometry = flashGetGeometry();
flashSector_t partitionSectors = (size / flashGeometry->sectorSize);
if (size % flashGeometry->sectorSize > 0) {
partitionSectors++; // needs a portion of a sector.
}
flashSector_t startSector = (*endSector + 1) - partitionSectors; // + 1 for inclusive
flashPartitionSet(type, startSector, *endSector);
*endSector = startSector - 1;
}
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)
createPartition(FLASH_PARTITION_TYPE_FIRMWARE, FIRMWARE_SIZE*1024, &endSector);
#endif
#if defined(MSP_FIRMWARE_UPDATE)
createPartition(FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META, flashGeometry->sectorSize, &endSector);
createPartition(FLASH_PARTITION_TYPE_UPDATE_FIRMWARE, FLASH_SIZE*1024, &endSector);
createPartition(FLASH_PARTITION_TYPE_FULL_BACKUP, FLASH_SIZE*1024, &endSector);
#endif
#if defined(CONFIG_IN_EXTERNAL_FLASH)
createPartition(FLASH_PARTITION_TYPE_CONFIG, EEPROM_SIZE, &endSector);
#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 ",
"FW UPDT ",
};
const char *flashPartitionGetTypeName(flashPartitionType_e type)
{
if (type < ARRAYLEN(flashPartitionNames)) {
return flashPartitionNames[type];
}
return NULL;
}
bool flashInit(void)
{
memset(&flashPartitionTable, 0x00, sizeof(flashPartitionTable));
bool haveFlash = flashDeviceInit();
flashConfigurePartitions();
return haveFlash;
}
int flashPartitionCount(void)
{
return flashPartitions;
}
uint32_t flashPartitionSize(flashPartition_t *partition)
{
const flashGeometry_t * const geometry = flashGetGeometry();
return (partition->endSector - partition->startSector + 1) * geometry->sectorSize;
}
void flashPartitionErase(flashPartition_t *partition)
{
for (uint16_t sector = partition->startSector; sector <= partition->endSector; ++sector) {
flashEraseSector(sector);
}
}
#endif // USE_FLASH_CHIP

View file

@ -1,31 +1,94 @@
/*
* This file is part of Cleanflight.
* This file is part of iNav.
*
* 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.
* iNav is free software. You can redistribute
* this software and/or modify this software 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.
* iNav 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 <http://www.gnu.org/licenses/>.
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <stdint.h>
//#include "drivers/io.h"
//#ifdef USE_FLASHFS
typedef uint16_t flashSector_t;
typedef struct flashGeometry_s {
uint16_t sectors; // Count of the number of erasable blocks on the device
uint16_t pagesPerSector;
const uint16_t pageSize; // In bytes
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
uint16_t pagesPerSector;
} flashGeometry_t;
bool flashInit(void);
bool flashIsReady(void);
bool flashWaitForReady(void);
void flashEraseSector(uint32_t address);
void flashEraseCompletely(void);
#if 0
void flashPageProgramBegin(uint32_t address);
void flashPageProgramContinue(const uint8_t *data, int length);
void flashPageProgramFinish(void);
#endif
uint32_t 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_PARTITION_TYPE_FULL_BACKUP,
FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META,
FLASH_PARTITION_TYPE_UPDATE_FIRMWARE,
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);
int flashPartitionCount(void);
uint32_t flashPartitionSize(flashPartition_t *partition);
void flashPartitionErase(flashPartition_t *partition);
//#endif [> USE_FLASHFS <]

View file

@ -56,6 +56,7 @@ extern uint8_t __config_end;
#include "drivers/buf_writer.h"
#include "drivers/bus_i2c.h"
#include "drivers/compass/compass.h"
#include "drivers/flash.h"
#include "drivers/io.h"
#include "drivers/io_impl.h"
#include "drivers/osd_symbols.h"
@ -2115,12 +2116,32 @@ static void cliSdInfo(char *cmdline)
static void cliFlashInfo(char *cmdline)
{
const flashGeometry_t *layout = flashfsGetGeometry();
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());
const flashGeometry_t *layout = flashGetGeometry();
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
}
static void cliFlashErase(char *cmdline)
@ -2130,7 +2151,7 @@ static void cliFlashErase(char *cmdline)
cliPrintLine("Erasing...");
flashfsEraseCompletely();
while (!flashfsIsReady()) {
while (!flashIsReady()) {
delay(100);
}

View file

@ -54,6 +54,7 @@
#include "drivers/flash_m25p16.h"
#include "drivers/io.h"
#include "drivers/io_pca9685.h"
#include "drivers/flash.h"
#include "drivers/light_led.h"
#include "drivers/nvic.h"
#include "drivers/osd.h"
@ -183,6 +184,10 @@ void flashLedsAndBeep(void)
void init(void)
{
#if defined(USE_FLASHFS) && defined(USE_FLASH_M25P16)
bool flashDeviceInitialized = false;
#endif
#ifdef USE_HAL_DRIVER
HAL_Init();
#endif
@ -362,7 +367,10 @@ void init(void)
if (blackboxConfig()->device == BLACKBOX_DEVICE_FLASH) {
#ifdef USE_FLASH_M25P16
// Must initialise the device to read _anything_
m25p16_init(0);
/*m25p16_init(0);*/
if (!flashDeviceInitialized) {
flashDeviceInitialized = flashInit();
}
#endif
emfat_init_files();
}
@ -579,7 +587,9 @@ void init(void)
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
#ifdef USE_FLASH_M25P16
m25p16_init(0);
if (!flashDeviceInitialized) {
flashDeviceInitialized = flashInit();
}
#endif
flashfsInit();
break;

View file

@ -44,6 +44,7 @@
#include "drivers/bus_i2c.h"
#include "drivers/compass/compass.h"
#include "drivers/display.h"
#include "drivers/flash.h"
#include "drivers/osd.h"
#include "drivers/osd_symbols.h"
#include "drivers/pwm_mapping.h"
@ -293,8 +294,8 @@ static void serializeSDCardSummaryReply(sbuf_t *dst)
static void serializeDataflashSummaryReply(sbuf_t *dst)
{
#ifdef USE_FLASHFS
const flashGeometry_t *geometry = flashfsGetGeometry();
sbufWriteU8(dst, flashfsIsReady() ? 1 : 0);
const flashGeometry_t *geometry = flashGetGeometry();
sbufWriteU8(dst, flashIsReady() ? 1 : 0);
sbufWriteU32(dst, geometry->sectors);
sbufWriteU32(dst, geometry->totalSize);
sbufWriteU32(dst, flashfsGetOffset()); // Effectively the current number of bytes stored on the volume

View file

@ -24,18 +24,17 @@
*
* 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.
*
* In future, we can add support for multiple different flash chips by adding a flash device driver vtable
* and make calls through that, at the moment flashfs just calls m25p16_* routines explicitly.
*/
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#include "drivers/flash_m25p16.h"
#include "drivers/flash.h"
#include "flashfs.h"
static flashPartition_t *flashPartition;
static uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE];
/* The position of our head and tail in the circular flash write buffer.
@ -67,10 +66,8 @@ static void flashfsSetTailAddress(uint32_t address)
void flashfsEraseCompletely(void)
{
m25p16_eraseCompletely();
flashPartitionErase(flashPartition);
flashfsClearBuffer();
flashfsSetTailAddress(0);
}
@ -80,7 +77,7 @@ void flashfsEraseCompletely(void)
*/
void flashfsEraseRange(uint32_t start, uint32_t end)
{
const flashGeometry_t *geometry = m25p16_getGeometry();
const flashGeometry_t *geometry = flashGetGeometry();
if (geometry->sectorSize <= 0)
return;
@ -97,7 +94,7 @@ void flashfsEraseRange(uint32_t start, uint32_t end)
}
for (int i = startSector; i < endSector; i++) {
m25p16_eraseSector(i * geometry->sectorSize);
flashEraseSector(i * geometry->sectorSize);
}
}
@ -106,12 +103,12 @@ void flashfsEraseRange(uint32_t start, uint32_t end)
*/
bool flashfsIsReady(void)
{
return m25p16_isReady();
return !!flashPartition;
}
uint32_t flashfsGetSize(void)
{
return m25p16_getGeometry()->totalSize;
return flashPartitionSize(flashPartition);
}
static uint32_t flashfsTransmitBufferUsed(void)
@ -138,11 +135,6 @@ uint32_t flashfsGetWriteBufferFreeSpace(void)
return flashfsGetWriteBufferSize() - flashfsTransmitBufferUsed();
}
const flashGeometry_t* flashfsGetGeometry(void)
{
return m25p16_getGeometry();
}
/**
* Write the given buffers to flash sequentially at the current tail address, advancing the tail address after
* each write.
@ -164,6 +156,8 @@ const flashGeometry_t* flashfsGetGeometry(void)
*/
static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSizes, int bufferCount, bool sync)
{
const flashGeometry_t *geometry = flashGetGeometry();
uint32_t bytesTotal = 0;
int i;
@ -172,7 +166,7 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
bytesTotal += bufferSizes[i];
}
if (!sync && !m25p16_isReady()) {
if (!sync && !flashIsReady()) {
return 0;
}
@ -187,8 +181,8 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
* 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 % M25P16_PAGESIZE + bytesTotalRemaining > M25P16_PAGESIZE) {
bytesTotalThisIteration = M25P16_PAGESIZE - tailAddress % M25P16_PAGESIZE;
if (tailAddress % geometry->pageSize + bytesTotalRemaining > geometry->pageSize) {
bytesTotalThisIteration = geometry->pageSize - tailAddress % geometry->pageSize;
} else {
bytesTotalThisIteration = bytesTotalRemaining;
}
@ -207,7 +201,7 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
if (bufferSizes[i] > 0) {
// Is buffer larger than our write limit? Write our limit out of it
if (bufferSizes[i] >= bytesRemainThisIteration) {
currentFlashAddress = m25p16_pageProgram(currentFlashAddress, buffers[i], bytesRemainThisIteration);
currentFlashAddress = flashPageProgram(currentFlashAddress, buffers[i], bytesRemainThisIteration);
buffers[i] += bytesRemainThisIteration;
bufferSizes[i] -= bytesRemainThisIteration;
@ -216,7 +210,7 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
break;
} else {
// We'll still have more to write after finishing this buffer off
currentFlashAddress = m25p16_pageProgram(currentFlashAddress, buffers[i], bufferSizes[i]);
currentFlashAddress = flashPageProgram(currentFlashAddress, buffers[i], bufferSizes[i]);
bytesRemainThisIteration -= bufferSizes[i];
@ -471,7 +465,7 @@ int flashfsReadAbs(uint32_t address, uint8_t *buffer, unsigned int len)
// Since the read could overlap data in our dirty buffers, force a sync to clear those first
flashfsFlushSync();
bytesRead = m25p16_readBytes(address, buffer, len);
bytesRead = flashReadBytes(address, buffer, len);
return bytesRead;
}
@ -516,7 +510,7 @@ int flashfsIdentifyStartOfFreeSpace(void)
while (left < right) {
mid = (left + right) / 2;
if (m25p16_readBytes(mid * FREE_BLOCK_SIZE, testBuffer.bytes, FREE_BLOCK_TEST_SIZE_BYTES) < FREE_BLOCK_TEST_SIZE_BYTES) {
if (flashReadBytes(mid * FREE_BLOCK_SIZE, testBuffer.bytes, FREE_BLOCK_TEST_SIZE_BYTES) < FREE_BLOCK_TEST_SIZE_BYTES) {
// Unexpected timeout from flash, so bail early (reporting the device fuller than it really is)
break;
}
@ -558,8 +552,9 @@ bool flashfsIsEOF(void)
*/
void flashfsInit(void)
{
// If we have a flash chip present at all
if (flashfsGetSize() > 0) {
flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS);
if (flashPartition) {
// Start the file pointer off at the beginning of free space so caller can start writing immediately
flashfsSeekAbs(flashfsIdentifyStartOfFreeSpace());
}

View file

@ -35,7 +35,6 @@ uint32_t flashfsGetOffset(void);
uint32_t flashfsGetWriteBufferFreeSpace(void);
uint32_t flashfsGetWriteBufferSize(void);
int flashfsIdentifyStartOfFreeSpace(void);
const flashGeometry_t* flashfsGetGeometry(void);
void flashfsSeekAbs(uint32_t offset);
void flashfsSeekRel(int32_t offset);

View file

@ -93,7 +93,7 @@ void updateHardwareRevision(void)
}
/* if flash exists on PB3 (busDevice m25p16_bjf3_rev1) then Rev1 */
if (m25p16_init(1)) {
if (flashInit()) {
hardwareRevision = BJF4_REV1;
} else {
IOInit(IOGetByTag(IO_TAG(PB3)), OWNER_FREE, RESOURCE_NONE, 0);