mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +03:00
Prepare flash code for multiple device type support (#5683)
* Prepare flash drivers for multiple device type support * Add static assertions on device page and flashfs alloc sizes.
This commit is contained in:
parent
4a5e79a534
commit
864dba98c1
13 changed files with 387 additions and 187 deletions
|
@ -372,6 +372,7 @@ endif
|
||||||
|
|
||||||
ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
|
ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
|
||||||
SRC += \
|
SRC += \
|
||||||
|
drivers/flash.c \
|
||||||
drivers/flash_m25p16.c \
|
drivers/flash_m25p16.c \
|
||||||
io/flashfs.c \
|
io/flashfs.c \
|
||||||
pg/flash.c \
|
pg/flash.c \
|
||||||
|
|
|
@ -298,12 +298,13 @@ bool isBlackboxErased(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Close the Blackbox logging device immediately without attempting to flush any remaining data.
|
* Close the Blackbox logging device.
|
||||||
*/
|
*/
|
||||||
void blackboxDeviceClose(void)
|
void blackboxDeviceClose(void)
|
||||||
{
|
{
|
||||||
switch (blackboxConfig()->device) {
|
switch (blackboxConfig()->device) {
|
||||||
case BLACKBOX_DEVICE_SERIAL:
|
case BLACKBOX_DEVICE_SERIAL:
|
||||||
|
// Can immediately close without attempting to flush any remaining data.
|
||||||
// Since the serial port could be shared with other processes, we have to give it back here
|
// Since the serial port could be shared with other processes, we have to give it back here
|
||||||
closeSerialPort(blackboxPort);
|
closeSerialPort(blackboxPort);
|
||||||
blackboxPort = NULL;
|
blackboxPort = NULL;
|
||||||
|
@ -316,6 +317,12 @@ void blackboxDeviceClose(void)
|
||||||
mspSerialAllocatePorts();
|
mspSerialAllocatePorts();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
#ifdef USE_FLASHFS
|
||||||
|
case BLACKBOX_DEVICE_FLASH:
|
||||||
|
// Some flash device, e.g., NAND devices, require explicit close to flush internally buffered data.
|
||||||
|
flashfsClose();
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
default:
|
default:
|
||||||
;
|
;
|
||||||
}
|
}
|
||||||
|
|
153
src/main/drivers/flash.c
Normal file
153
src/main/drivers/flash.c
Normal file
|
@ -0,0 +1,153 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Betaflight/Cleanflight.
|
||||||
|
*
|
||||||
|
* Betaflight/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.
|
||||||
|
*
|
||||||
|
* Betaflight/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 Betaflight/Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
#ifdef USE_FLASH
|
||||||
|
|
||||||
|
#include "flash.h"
|
||||||
|
#include "flash_impl.h"
|
||||||
|
#include "flash_m25p16.h"
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/io.h"
|
||||||
|
#include "drivers/time.h"
|
||||||
|
|
||||||
|
static busDevice_t busInstance;
|
||||||
|
static busDevice_t *busdev;
|
||||||
|
|
||||||
|
static flashDevice_t flashDevice;
|
||||||
|
|
||||||
|
// Read chip identification and send it to device detect
|
||||||
|
|
||||||
|
bool flashInit(const flashConfig_t *flashConfig)
|
||||||
|
{
|
||||||
|
busdev = &busInstance;
|
||||||
|
busdev->bustype = BUSTYPE_SPI;
|
||||||
|
spiBusSetInstance(busdev, spiInstanceByDevice(SPI_CFG_TO_DEV(flashConfig->spiDevice)));
|
||||||
|
if (flashConfig->csTag) {
|
||||||
|
busdev->busdev_u.spi.csnPin = IOGetByTag(flashConfig->csTag);
|
||||||
|
} else {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
IOInit(busdev->busdev_u.spi.csnPin, OWNER_FLASH_CS, 0);
|
||||||
|
IOConfigGPIO(busdev->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
|
||||||
|
IOHi(busdev->busdev_u.spi.csnPin);
|
||||||
|
|
||||||
|
#ifndef M25P16_SPI_SHARED
|
||||||
|
//Maximum speed for standard READ command is 20mHz, other commands tolerate 25mHz
|
||||||
|
//spiSetDivisor(busdev->busdev_u.spi.instance, SPI_CLOCK_FAST);
|
||||||
|
spiSetDivisor(busdev->busdev_u.spi.instance, SPI_CLOCK_STANDARD*2);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
flashDevice.busdev = busdev;
|
||||||
|
|
||||||
|
const uint8_t out[] = { SPIFLASH_INSTRUCTION_RDID, 0, 0, 0 };
|
||||||
|
|
||||||
|
delay(50); // short delay required after initialisation of SPI device instance.
|
||||||
|
|
||||||
|
/* Just in case transfer fails and writes nothing, so we don't try to verify the ID against random garbage
|
||||||
|
* from the stack:
|
||||||
|
*/
|
||||||
|
uint8_t in[4];
|
||||||
|
in[1] = 0;
|
||||||
|
|
||||||
|
// Clearing the CS bit terminates the command early so we don't have to read the chip UID:
|
||||||
|
spiBusTransfer(busdev, out, in, sizeof(out));
|
||||||
|
|
||||||
|
// Manufacturer, memory type, and capacity
|
||||||
|
uint32_t chipID = (in[1] << 16) | (in[2] << 8) | (in[3]);
|
||||||
|
|
||||||
|
#ifdef USE_FLASH_M25P16
|
||||||
|
if (m25p16_detect(&flashDevice, chipID)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
spiPreInitCs(flashConfig->csTag);
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool flashIsReady(void)
|
||||||
|
{
|
||||||
|
return flashDevice.vTable->isReady(&flashDevice);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool flashWaitForReady(uint32_t timeoutMillis)
|
||||||
|
{
|
||||||
|
return flashDevice.vTable->waitForReady(&flashDevice, timeoutMillis);
|
||||||
|
}
|
||||||
|
|
||||||
|
void flashEraseSector(uint32_t address)
|
||||||
|
{
|
||||||
|
flashDevice.vTable->eraseSector(&flashDevice, address);
|
||||||
|
}
|
||||||
|
|
||||||
|
void flashEraseCompletely(void)
|
||||||
|
{
|
||||||
|
flashDevice.vTable->eraseCompletely(&flashDevice);
|
||||||
|
}
|
||||||
|
|
||||||
|
void flashPageProgramBegin(uint32_t address)
|
||||||
|
{
|
||||||
|
flashDevice.vTable->pageProgramBegin(&flashDevice, address);
|
||||||
|
}
|
||||||
|
|
||||||
|
void flashPageProgramContinue(const uint8_t *data, int length)
|
||||||
|
{
|
||||||
|
flashDevice.vTable->pageProgramContinue(&flashDevice, data, length);
|
||||||
|
}
|
||||||
|
|
||||||
|
void flashPageProgramFinish(void)
|
||||||
|
{
|
||||||
|
flashDevice.vTable->pageProgramFinish(&flashDevice);
|
||||||
|
}
|
||||||
|
|
||||||
|
void flashPageProgram(uint32_t address, const uint8_t *data, int length)
|
||||||
|
{
|
||||||
|
flashDevice.vTable->pageProgram(&flashDevice, address, data, length);
|
||||||
|
}
|
||||||
|
|
||||||
|
int flashReadBytes(uint32_t address, uint8_t *buffer, int length)
|
||||||
|
{
|
||||||
|
return flashDevice.vTable->readBytes(&flashDevice, address, buffer, length);
|
||||||
|
}
|
||||||
|
|
||||||
|
void flashFlush(void)
|
||||||
|
{
|
||||||
|
flashDevice.vTable->flush(&flashDevice);
|
||||||
|
}
|
||||||
|
|
||||||
|
static const flashGeometry_t noFlashGeometry = {
|
||||||
|
.totalSize = 0,
|
||||||
|
};
|
||||||
|
|
||||||
|
const flashGeometry_t *flashGetGeometry(void)
|
||||||
|
{
|
||||||
|
if (flashDevice.vTable && flashDevice.vTable->getGeometry) {
|
||||||
|
return flashDevice.vTable->getGeometry(&flashDevice);
|
||||||
|
}
|
||||||
|
|
||||||
|
return &noFlashGeometry;
|
||||||
|
}
|
||||||
|
#endif // USE_FLASH
|
|
@ -19,10 +19,39 @@
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "pg/flash.h"
|
||||||
|
#include "drivers/io.h"
|
||||||
|
|
||||||
|
// Maximum page size of all supported SPI flash devices.
|
||||||
|
// Used to detect flashfs allocation size being too small.
|
||||||
|
#define FLASH_MAX_PAGE_SIZE 2048
|
||||||
|
|
||||||
|
#define SPIFLASH_INSTRUCTION_RDID 0x9F
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
FLASH_TYPE_NOR = 0,
|
||||||
|
FLASH_TYPE_NAND
|
||||||
|
} flashType_e;
|
||||||
|
|
||||||
typedef struct flashGeometry_s {
|
typedef struct flashGeometry_s {
|
||||||
uint16_t sectors; // Count of the number of erasable blocks on the device
|
uint16_t sectors; // Count of the number of erasable blocks on the device
|
||||||
const uint16_t pageSize; // In bytes
|
uint16_t pageSize; // In bytes
|
||||||
uint32_t sectorSize; // This is just pagesPerSector * pageSize
|
uint32_t sectorSize; // This is just pagesPerSector * pageSize
|
||||||
uint32_t totalSize; // This is just sectorSize * sectors
|
uint32_t totalSize; // This is just sectorSize * sectors
|
||||||
uint16_t pagesPerSector;
|
uint16_t pagesPerSector;
|
||||||
|
flashType_e flashType;
|
||||||
} flashGeometry_t;
|
} flashGeometry_t;
|
||||||
|
|
||||||
|
bool flashInit(const flashConfig_t *flashConfig);
|
||||||
|
|
||||||
|
bool flashIsReady(void);
|
||||||
|
bool flashWaitForReady(uint32_t timeoutMillis);
|
||||||
|
void flashEraseSector(uint32_t address);
|
||||||
|
void flashEraseCompletely(void);
|
||||||
|
void flashPageProgramBegin(uint32_t address);
|
||||||
|
void flashPageProgramContinue(const uint8_t *data, int length);
|
||||||
|
void flashPageProgramFinish(void);
|
||||||
|
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);
|
||||||
|
|
50
src/main/drivers/flash_impl.h
Normal file
50
src/main/drivers/flash_impl.h
Normal file
|
@ -0,0 +1,50 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Betaflight/Cleanflight.
|
||||||
|
*
|
||||||
|
* Betaflight/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.
|
||||||
|
*
|
||||||
|
* Betaflight/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 <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
* Author: jflyper
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "drivers/bus.h"
|
||||||
|
|
||||||
|
struct flashVTable_s;
|
||||||
|
|
||||||
|
typedef struct flashDevice_s {
|
||||||
|
busDevice_t *busdev;
|
||||||
|
const struct flashVTable_s *vTable;
|
||||||
|
flashGeometry_t geometry;
|
||||||
|
uint32_t currentWriteAddress;
|
||||||
|
bool isLargeFlash;
|
||||||
|
// 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.
|
||||||
|
bool couldBeBusy;
|
||||||
|
} flashDevice_t;
|
||||||
|
|
||||||
|
typedef struct flashVTable_s {
|
||||||
|
bool (*isReady)(flashDevice_t *fdevice);
|
||||||
|
bool (*waitForReady)(flashDevice_t *fdevice, uint32_t timeoutMillis);
|
||||||
|
void (*eraseSector)(flashDevice_t *fdevice, uint32_t address);
|
||||||
|
void (*eraseCompletely)(flashDevice_t *fdevice);
|
||||||
|
void (*pageProgramBegin)(flashDevice_t *fdevice, uint32_t address);
|
||||||
|
void (*pageProgramContinue)(flashDevice_t *fdevice, const uint8_t *data, int length);
|
||||||
|
void (*pageProgramFinish)(flashDevice_t *fdevice);
|
||||||
|
void (*pageProgram)(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, int length);
|
||||||
|
void (*flush)(flashDevice_t *fdevice);
|
||||||
|
int (*readBytes)(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length);
|
||||||
|
const flashGeometry_t *(*getGeometry)(flashDevice_t *fdevice);
|
||||||
|
} flashVTable_t;
|
|
@ -20,10 +20,13 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
#ifdef USE_FLASH_M25P16
|
#ifdef USE_FLASH_M25P16
|
||||||
|
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
#include "drivers/flash.h"
|
#include "drivers/flash.h"
|
||||||
|
#include "drivers/flash_impl.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
|
@ -31,7 +34,7 @@
|
||||||
|
|
||||||
#include "flash_m25p16.h"
|
#include "flash_m25p16.h"
|
||||||
|
|
||||||
#define M25P16_INSTRUCTION_RDID 0x9F
|
#define M25P16_INSTRUCTION_RDID SPIFLASH_INSTRUCTION_RDID
|
||||||
#define M25P16_INSTRUCTION_READ_BYTES 0x03
|
#define M25P16_INSTRUCTION_READ_BYTES 0x03
|
||||||
#define M25P16_INSTRUCTION_READ_STATUS_REG 0x05
|
#define M25P16_INSTRUCTION_READ_STATUS_REG 0x05
|
||||||
#define M25P16_INSTRUCTION_WRITE_STATUS_REG 0x01
|
#define M25P16_INSTRUCTION_WRITE_STATUS_REG 0x01
|
||||||
|
@ -47,6 +50,7 @@
|
||||||
#define W25Q256_INSTRUCTION_ENTER_4BYTE_ADDRESS_MODE 0xB7
|
#define W25Q256_INSTRUCTION_ENTER_4BYTE_ADDRESS_MODE 0xB7
|
||||||
|
|
||||||
// Format is manufacturer, memory type, then capacity
|
// Format is manufacturer, memory type, then capacity
|
||||||
|
// See also flash_m25p16.h for additional JEDEC IDs.
|
||||||
#define JEDEC_ID_MACRONIX_MX25L3206E 0xC22016
|
#define JEDEC_ID_MACRONIX_MX25L3206E 0xC22016
|
||||||
#define JEDEC_ID_MACRONIX_MX25L6406E 0xC22017
|
#define JEDEC_ID_MACRONIX_MX25L6406E 0xC22017
|
||||||
#define JEDEC_ID_MACRONIX_MX25L25635E 0xC22019
|
#define JEDEC_ID_MACRONIX_MX25L25635E 0xC22019
|
||||||
|
@ -56,13 +60,8 @@
|
||||||
#define JEDEC_ID_WINBOND_W25Q16 0xEF4015
|
#define JEDEC_ID_WINBOND_W25Q16 0xEF4015
|
||||||
#define JEDEC_ID_WINBOND_W25Q64 0xEF4017
|
#define JEDEC_ID_WINBOND_W25Q64 0xEF4017
|
||||||
#define JEDEC_ID_WINBOND_W25Q128 0xEF4018
|
#define JEDEC_ID_WINBOND_W25Q128 0xEF4018
|
||||||
#define JEDEC_ID_WINBOND_W25Q256 0xEF4019
|
|
||||||
#define JEDEC_ID_CYPRESS_S25FL128L 0x016018
|
#define JEDEC_ID_CYPRESS_S25FL128L 0x016018
|
||||||
|
|
||||||
static busDevice_t busInstance;
|
|
||||||
static busDevice_t *bus;
|
|
||||||
static bool isLargeFlash = false;
|
|
||||||
|
|
||||||
// The timeout we expect between being able to issue page program instructions
|
// The timeout we expect between being able to issue page program instructions
|
||||||
#define DEFAULT_TIMEOUT_MILLIS 6
|
#define DEFAULT_TIMEOUT_MILLIS 6
|
||||||
|
|
||||||
|
@ -70,15 +69,11 @@ static bool isLargeFlash = false;
|
||||||
#define SECTOR_ERASE_TIMEOUT_MILLIS 5000
|
#define SECTOR_ERASE_TIMEOUT_MILLIS 5000
|
||||||
#define BULK_ERASE_TIMEOUT_MILLIS 21000
|
#define BULK_ERASE_TIMEOUT_MILLIS 21000
|
||||||
|
|
||||||
static flashGeometry_t geometry = {.pageSize = M25P16_PAGESIZE};
|
#define M25P16_PAGESIZE 256
|
||||||
|
|
||||||
/*
|
STATIC_ASSERT(M25P16_PAGESIZE < FLASH_MAX_PAGE_SIZE, M25P16_PAGESIZE_too_small);
|
||||||
* 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;
|
|
||||||
|
|
||||||
|
const flashVTable_t m25p16_vTable;
|
||||||
|
|
||||||
static void m25p16_disable(busDevice_t *bus)
|
static void m25p16_disable(busDevice_t *bus)
|
||||||
{
|
{
|
||||||
|
@ -115,12 +110,12 @@ static void m25p16_performOneByteCommand(busDevice_t *bus, uint8_t command)
|
||||||
* The flash requires this write enable command to be sent before commands that would cause
|
* The flash requires this write enable command to be sent before commands that would cause
|
||||||
* a write like program and erase.
|
* a write like program and erase.
|
||||||
*/
|
*/
|
||||||
static void m25p16_writeEnable(busDevice_t *bus)
|
static void m25p16_writeEnable(flashDevice_t *fdevice)
|
||||||
{
|
{
|
||||||
m25p16_performOneByteCommand(bus, M25P16_INSTRUCTION_WRITE_ENABLE);
|
m25p16_performOneByteCommand(fdevice->busdev, M25P16_INSTRUCTION_WRITE_ENABLE);
|
||||||
|
|
||||||
// Assume that we're about to do some writing, so the device is just about to become busy
|
// Assume that we're about to do some writing, so the device is just about to become busy
|
||||||
couldBeBusy = true;
|
fdevice->couldBeBusy = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static uint8_t m25p16_readStatus(busDevice_t *bus)
|
static uint8_t m25p16_readStatus(busDevice_t *bus)
|
||||||
|
@ -133,18 +128,18 @@ static uint8_t m25p16_readStatus(busDevice_t *bus)
|
||||||
return in[1];
|
return in[1];
|
||||||
}
|
}
|
||||||
|
|
||||||
bool m25p16_isReady(void)
|
static bool m25p16_isReady(flashDevice_t *fdevice)
|
||||||
{
|
{
|
||||||
// If couldBeBusy is false, don't bother to poll the flash chip for its status
|
// If couldBeBusy is false, don't bother to poll the flash chip for its status
|
||||||
couldBeBusy = couldBeBusy && ((m25p16_readStatus(bus) & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0);
|
fdevice->couldBeBusy = fdevice->couldBeBusy && ((m25p16_readStatus(fdevice->busdev) & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0);
|
||||||
|
|
||||||
return !couldBeBusy;
|
return !fdevice->couldBeBusy;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool m25p16_waitForReady(uint32_t timeoutMillis)
|
static bool m25p16_waitForReady(flashDevice_t *fdevice, uint32_t timeoutMillis)
|
||||||
{
|
{
|
||||||
uint32_t time = millis();
|
uint32_t time = millis();
|
||||||
while (!m25p16_isReady()) {
|
while (!m25p16_isReady(fdevice)) {
|
||||||
if (millis() - time > timeoutMillis) {
|
if (millis() - time > timeoutMillis) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -158,115 +153,61 @@ bool m25p16_waitForReady(uint32_t timeoutMillis)
|
||||||
*
|
*
|
||||||
* Returns true if we get valid ident, false if something bad happened like there is no M25P16.
|
* Returns true if we get valid ident, false if something bad happened like there is no M25P16.
|
||||||
*/
|
*/
|
||||||
static bool m25p16_readIdentification(void)
|
|
||||||
|
bool m25p16_detect(flashDevice_t *fdevice, uint32_t chipID)
|
||||||
{
|
{
|
||||||
const uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 };
|
|
||||||
|
|
||||||
delay(50); // short delay required after initialisation of SPI device instance.
|
|
||||||
|
|
||||||
/* Just in case transfer fails and writes nothing, so we don't try to verify the ID against random garbage
|
|
||||||
* from the stack:
|
|
||||||
*/
|
|
||||||
uint8_t in[4];
|
|
||||||
in[1] = 0;
|
|
||||||
|
|
||||||
// Clearing the CS bit terminates the command early so we don't have to read the chip UID:
|
|
||||||
m25p16_transfer(bus, out, in, sizeof(out));
|
|
||||||
|
|
||||||
// Manufacturer, memory type, and capacity
|
|
||||||
const uint32_t chipID = (in[1] << 16) | (in[2] << 8) | (in[3]);
|
|
||||||
|
|
||||||
// All supported chips use the same pagesize of 256 bytes
|
|
||||||
|
|
||||||
switch (chipID) {
|
switch (chipID) {
|
||||||
case JEDEC_ID_WINBOND_W25Q16:
|
case JEDEC_ID_WINBOND_W25Q16:
|
||||||
case JEDEC_ID_MICRON_M25P16:
|
case JEDEC_ID_MICRON_M25P16:
|
||||||
geometry.sectors = 32;
|
fdevice->geometry.sectors = 32;
|
||||||
geometry.pagesPerSector = 256;
|
fdevice->geometry.pagesPerSector = 256;
|
||||||
break;
|
break;
|
||||||
case JEDEC_ID_MACRONIX_MX25L3206E:
|
case JEDEC_ID_MACRONIX_MX25L3206E:
|
||||||
geometry.sectors = 64;
|
fdevice->geometry.sectors = 64;
|
||||||
geometry.pagesPerSector = 256;
|
fdevice->geometry.pagesPerSector = 256;
|
||||||
break;
|
break;
|
||||||
case JEDEC_ID_MICRON_N25Q064:
|
case JEDEC_ID_MICRON_N25Q064:
|
||||||
case JEDEC_ID_WINBOND_W25Q64:
|
case JEDEC_ID_WINBOND_W25Q64:
|
||||||
case JEDEC_ID_MACRONIX_MX25L6406E:
|
case JEDEC_ID_MACRONIX_MX25L6406E:
|
||||||
geometry.sectors = 128;
|
fdevice->geometry.sectors = 128;
|
||||||
geometry.pagesPerSector = 256;
|
fdevice->geometry.pagesPerSector = 256;
|
||||||
break;
|
break;
|
||||||
case JEDEC_ID_MICRON_N25Q128:
|
case JEDEC_ID_MICRON_N25Q128:
|
||||||
case JEDEC_ID_WINBOND_W25Q128:
|
case JEDEC_ID_WINBOND_W25Q128:
|
||||||
case JEDEC_ID_CYPRESS_S25FL128L:
|
case JEDEC_ID_CYPRESS_S25FL128L:
|
||||||
geometry.sectors = 256;
|
fdevice->geometry.sectors = 256;
|
||||||
geometry.pagesPerSector = 256;
|
fdevice->geometry.pagesPerSector = 256;
|
||||||
break;
|
break;
|
||||||
case JEDEC_ID_WINBOND_W25Q256:
|
case JEDEC_ID_WINBOND_W25Q256:
|
||||||
case JEDEC_ID_MACRONIX_MX25L25635E:
|
case JEDEC_ID_MACRONIX_MX25L25635E:
|
||||||
geometry.sectors = 512;
|
fdevice->geometry.sectors = 512;
|
||||||
geometry.pagesPerSector = 256;
|
fdevice->geometry.pagesPerSector = 256;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
// Unsupported chip or not an SPI NOR flash
|
// Unsupported chip or not an SPI NOR flash
|
||||||
geometry.sectors = 0;
|
fdevice->geometry.sectors = 0;
|
||||||
geometry.pagesPerSector = 0;
|
fdevice->geometry.pagesPerSector = 0;
|
||||||
|
fdevice->geometry.sectorSize = 0;
|
||||||
geometry.sectorSize = 0;
|
fdevice->geometry.totalSize = 0;
|
||||||
geometry.totalSize = 0;
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
geometry.sectorSize = geometry.pagesPerSector * geometry.pageSize;
|
fdevice->geometry.flashType = FLASH_TYPE_NOR;
|
||||||
geometry.totalSize = geometry.sectorSize * geometry.sectors;
|
fdevice->geometry.pageSize = M25P16_PAGESIZE;
|
||||||
|
fdevice->geometry.sectorSize = fdevice->geometry.pagesPerSector * fdevice->geometry.pageSize;
|
||||||
|
fdevice->geometry.totalSize = fdevice->geometry.sectorSize * fdevice->geometry.sectors;
|
||||||
|
|
||||||
if (geometry.totalSize > 16 * 1024 * 1024) {
|
if (fdevice->geometry.totalSize > 16 * 1024 * 1024) {
|
||||||
isLargeFlash = true;
|
fdevice->isLargeFlash = true;
|
||||||
m25p16_performOneByteCommand(bus, W25Q256_INSTRUCTION_ENTER_4BYTE_ADDRESS_MODE);
|
m25p16_performOneByteCommand(fdevice->busdev, W25Q256_INSTRUCTION_ENTER_4BYTE_ADDRESS_MODE);
|
||||||
}
|
}
|
||||||
|
|
||||||
couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be
|
fdevice->couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be
|
||||||
|
fdevice->vTable = &m25p16_vTable;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
static void m25p16_setCommandAddress(uint8_t *buf, uint32_t address, bool useLongAddress)
|
||||||
* 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(const flashConfig_t *flashConfig)
|
|
||||||
{
|
|
||||||
/*
|
|
||||||
if we have already detected a flash device we can simply exit
|
|
||||||
*/
|
|
||||||
if (geometry.sectors) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bus = &busInstance;
|
|
||||||
bus->bustype = BUSTYPE_SPI;
|
|
||||||
spiBusSetInstance(bus, spiInstanceByDevice(SPI_CFG_TO_DEV(flashConfig->spiDevice)));
|
|
||||||
if (flashConfig->csTag) {
|
|
||||||
bus->busdev_u.spi.csnPin = IOGetByTag(flashConfig->csTag);
|
|
||||||
} else {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
IOInit(bus->busdev_u.spi.csnPin, OWNER_FLASH_CS, 0);
|
|
||||||
IOConfigGPIO(bus->busdev_u.spi.csnPin, SPI_IO_CS_CFG);
|
|
||||||
|
|
||||||
m25p16_disable(bus);
|
|
||||||
|
|
||||||
#ifndef M25P16_SPI_SHARED
|
|
||||||
//Maximum speed for standard READ command is 20mHz, other commands tolerate 25mHz
|
|
||||||
spiSetDivisor(bus->busdev_u.spi.instance, SPI_CLOCK_FAST);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
return m25p16_readIdentification();
|
|
||||||
}
|
|
||||||
|
|
||||||
void m25p16_setCommandAddress(uint8_t *buf, uint32_t address, bool useLongAddress)
|
|
||||||
{
|
{
|
||||||
if (useLongAddress) {
|
if (useLongAddress) {
|
||||||
*buf++ = (address >> 24) & 0xff;
|
*buf++ = (address >> 24) & 0xff;
|
||||||
|
@ -279,58 +220,59 @@ void m25p16_setCommandAddress(uint8_t *buf, uint32_t address, bool useLongAddres
|
||||||
/**
|
/**
|
||||||
* Erase a sector full of bytes to all 1's at the given byte offset in the flash chip.
|
* 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)
|
static void m25p16_eraseSector(flashDevice_t *fdevice, uint32_t address)
|
||||||
{
|
{
|
||||||
uint8_t out[5] = { M25P16_INSTRUCTION_SECTOR_ERASE };
|
uint8_t out[5] = { M25P16_INSTRUCTION_SECTOR_ERASE };
|
||||||
|
|
||||||
m25p16_setCommandAddress(&out[1], address, isLargeFlash);
|
m25p16_setCommandAddress(&out[1], address, fdevice->isLargeFlash);
|
||||||
|
|
||||||
m25p16_waitForReady(SECTOR_ERASE_TIMEOUT_MILLIS);
|
m25p16_waitForReady(fdevice, SECTOR_ERASE_TIMEOUT_MILLIS);
|
||||||
|
|
||||||
m25p16_writeEnable(bus);
|
m25p16_writeEnable(fdevice);
|
||||||
|
|
||||||
m25p16_transfer(bus, out, NULL, sizeof(out));
|
m25p16_transfer(fdevice->busdev, out, NULL, sizeof(out));
|
||||||
}
|
}
|
||||||
|
|
||||||
void m25p16_eraseCompletely(void)
|
static void m25p16_eraseCompletely(flashDevice_t *fdevice)
|
||||||
{
|
{
|
||||||
m25p16_waitForReady(BULK_ERASE_TIMEOUT_MILLIS);
|
m25p16_waitForReady(fdevice, BULK_ERASE_TIMEOUT_MILLIS);
|
||||||
|
|
||||||
m25p16_writeEnable(bus);
|
m25p16_writeEnable(fdevice);
|
||||||
|
|
||||||
m25p16_performOneByteCommand(bus, M25P16_INSTRUCTION_BULK_ERASE);
|
m25p16_performOneByteCommand(fdevice->busdev, M25P16_INSTRUCTION_BULK_ERASE);
|
||||||
}
|
}
|
||||||
|
|
||||||
static uint32_t currentWriteAddress;
|
static void m25p16_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
|
||||||
|
|
||||||
void m25p16_pageProgramBegin(uint32_t address)
|
|
||||||
{
|
{
|
||||||
currentWriteAddress = address;
|
UNUSED(fdevice);
|
||||||
|
|
||||||
|
fdevice->currentWriteAddress = address;
|
||||||
}
|
}
|
||||||
|
|
||||||
void m25p16_pageProgramContinue(const uint8_t *data, int length)
|
static void m25p16_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *data, int length)
|
||||||
{
|
{
|
||||||
uint8_t command[5] = { M25P16_INSTRUCTION_PAGE_PROGRAM };
|
uint8_t command[5] = { M25P16_INSTRUCTION_PAGE_PROGRAM };
|
||||||
|
|
||||||
m25p16_setCommandAddress(&command[1], currentWriteAddress, isLargeFlash);
|
m25p16_setCommandAddress(&command[1], fdevice->currentWriteAddress, fdevice->isLargeFlash);
|
||||||
|
|
||||||
m25p16_waitForReady(DEFAULT_TIMEOUT_MILLIS);
|
m25p16_waitForReady(fdevice, DEFAULT_TIMEOUT_MILLIS);
|
||||||
|
|
||||||
m25p16_writeEnable(bus);
|
m25p16_writeEnable(fdevice);
|
||||||
|
|
||||||
m25p16_enable(bus);
|
m25p16_enable(fdevice->busdev);
|
||||||
|
|
||||||
spiTransfer(bus->busdev_u.spi.instance, command, NULL, isLargeFlash ? 5 : 4);
|
spiTransfer(fdevice->busdev->busdev_u.spi.instance, command, NULL, fdevice->isLargeFlash ? 5 : 4);
|
||||||
|
|
||||||
spiTransfer(bus->busdev_u.spi.instance, data, NULL, length);
|
spiTransfer(fdevice->busdev->busdev_u.spi.instance, data, NULL, length);
|
||||||
|
|
||||||
m25p16_disable(bus);
|
m25p16_disable(fdevice->busdev);
|
||||||
|
|
||||||
currentWriteAddress += length;
|
fdevice->currentWriteAddress += length;
|
||||||
}
|
}
|
||||||
|
|
||||||
void m25p16_pageProgramFinish(void)
|
static void m25p16_pageProgramFinish(flashDevice_t *fdevice)
|
||||||
{
|
{
|
||||||
|
UNUSED(fdevice);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -348,13 +290,13 @@ void m25p16_pageProgramFinish(void)
|
||||||
* If you want to write multiple buffers (whose sum of sizes is still not more than the page size) then you can
|
* 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.
|
* 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)
|
static void m25p16_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, int length)
|
||||||
{
|
{
|
||||||
m25p16_pageProgramBegin(address);
|
m25p16_pageProgramBegin(fdevice, address);
|
||||||
|
|
||||||
m25p16_pageProgramContinue(data, length);
|
m25p16_pageProgramContinue(fdevice, data, length);
|
||||||
|
|
||||||
m25p16_pageProgramFinish();
|
m25p16_pageProgramFinish(fdevice);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -365,22 +307,22 @@ void m25p16_pageProgram(uint32_t address, const uint8_t *data, int length)
|
||||||
*
|
*
|
||||||
* The number of bytes actually read is returned, which can be zero if an error or timeout occurred.
|
* The number of bytes actually read is returned, which can be zero if an error or timeout occurred.
|
||||||
*/
|
*/
|
||||||
int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length)
|
static int m25p16_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
|
||||||
{
|
{
|
||||||
uint8_t command[5] = { M25P16_INSTRUCTION_READ_BYTES };
|
uint8_t command[5] = { M25P16_INSTRUCTION_READ_BYTES };
|
||||||
|
|
||||||
m25p16_setCommandAddress(&command[1], address, isLargeFlash);
|
m25p16_setCommandAddress(&command[1], address, fdevice->isLargeFlash);
|
||||||
|
|
||||||
if (!m25p16_waitForReady(DEFAULT_TIMEOUT_MILLIS)) {
|
if (!m25p16_waitForReady(fdevice, DEFAULT_TIMEOUT_MILLIS)) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
m25p16_enable(bus);
|
m25p16_enable(fdevice->busdev);
|
||||||
|
|
||||||
spiTransfer(bus->busdev_u.spi.instance, command, NULL, isLargeFlash ? 5 : 4);
|
spiTransfer(fdevice->busdev->busdev_u.spi.instance, command, NULL, fdevice->isLargeFlash ? 5 : 4);
|
||||||
spiTransfer(bus->busdev_u.spi.instance, NULL, buffer, length);
|
spiTransfer(fdevice->busdev->busdev_u.spi.instance, NULL, buffer, length);
|
||||||
|
|
||||||
m25p16_disable(bus);
|
m25p16_disable(fdevice->busdev);
|
||||||
|
|
||||||
return length;
|
return length;
|
||||||
}
|
}
|
||||||
|
@ -390,9 +332,21 @@ int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length)
|
||||||
*
|
*
|
||||||
* Can be called before calling m25p16_init() (the result would have totalSize = 0).
|
* Can be called before calling m25p16_init() (the result would have totalSize = 0).
|
||||||
*/
|
*/
|
||||||
const flashGeometry_t* m25p16_getGeometry(void)
|
static const flashGeometry_t* m25p16_getGeometry(flashDevice_t *fdevice)
|
||||||
{
|
{
|
||||||
return &geometry;
|
return &fdevice->geometry;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
const flashVTable_t m25p16_vTable = {
|
||||||
|
.isReady = m25p16_isReady,
|
||||||
|
.waitForReady = m25p16_waitForReady,
|
||||||
|
.eraseSector = m25p16_eraseSector,
|
||||||
|
.eraseCompletely = m25p16_eraseCompletely,
|
||||||
|
.pageProgramBegin = m25p16_pageProgramBegin,
|
||||||
|
.pageProgramContinue = m25p16_pageProgramContinue,
|
||||||
|
.pageProgramFinish = m25p16_pageProgramFinish,
|
||||||
|
.pageProgram = m25p16_pageProgram,
|
||||||
|
.readBytes = m25p16_readBytes,
|
||||||
|
.getGeometry = m25p16_getGeometry,
|
||||||
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -17,27 +17,8 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <stdint.h>
|
#include "flash_impl.h"
|
||||||
#include "flash.h"
|
|
||||||
|
|
||||||
#define M25P16_PAGESIZE 256
|
#define JEDEC_ID_WINBOND_W25Q256 0xEF4019
|
||||||
|
|
||||||
struct flashConfig_s;
|
bool m25p16_detect(flashDevice_t *fdevice, uint32_t chipID);
|
||||||
bool m25p16_init(const struct flashConfig_s *flashConfig);
|
|
||||||
|
|
||||||
void m25p16_eraseSector(uint32_t address);
|
|
||||||
void m25p16_eraseCompletely(void);
|
|
||||||
|
|
||||||
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(void);
|
|
||||||
|
|
||||||
int m25p16_readBytes(uint32_t address, uint8_t *buffer, int length);
|
|
||||||
|
|
||||||
bool m25p16_isReady(void);
|
|
||||||
bool m25p16_waitForReady(uint32_t timeoutMillis);
|
|
||||||
|
|
||||||
struct flashGeometry_s;
|
|
||||||
const struct flashGeometry_s* m25p16_getGeometry(void);
|
|
||||||
|
|
|
@ -49,7 +49,7 @@
|
||||||
#include "drivers/compass/compass.h"
|
#include "drivers/compass/compass.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/exti.h"
|
#include "drivers/exti.h"
|
||||||
#include "drivers/flash_m25p16.h"
|
#include "drivers/flash.h"
|
||||||
#include "drivers/inverter.h"
|
#include "drivers/inverter.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
|
@ -685,8 +685,8 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
#if defined(USE_FLASH_M25P16)
|
#if defined(USE_FLASH)
|
||||||
m25p16_init(flashConfig());
|
flashInit(flashConfig());
|
||||||
#endif
|
#endif
|
||||||
flashfsInit();
|
flashfsInit();
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -34,7 +34,6 @@
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
#include "drivers/flash.h"
|
#include "drivers/flash.h"
|
||||||
#include "drivers/flash_m25p16.h"
|
|
||||||
|
|
||||||
#include "io/flashfs.h"
|
#include "io/flashfs.h"
|
||||||
|
|
||||||
|
@ -69,7 +68,7 @@ static void flashfsSetTailAddress(uint32_t address)
|
||||||
|
|
||||||
void flashfsEraseCompletely(void)
|
void flashfsEraseCompletely(void)
|
||||||
{
|
{
|
||||||
m25p16_eraseCompletely();
|
flashEraseCompletely();
|
||||||
|
|
||||||
flashfsClearBuffer();
|
flashfsClearBuffer();
|
||||||
|
|
||||||
|
@ -82,7 +81,7 @@ void flashfsEraseCompletely(void)
|
||||||
*/
|
*/
|
||||||
void flashfsEraseRange(uint32_t start, uint32_t end)
|
void flashfsEraseRange(uint32_t start, uint32_t end)
|
||||||
{
|
{
|
||||||
const flashGeometry_t *geometry = m25p16_getGeometry();
|
const flashGeometry_t *geometry = flashGetGeometry();
|
||||||
|
|
||||||
if (geometry->sectorSize <= 0)
|
if (geometry->sectorSize <= 0)
|
||||||
return;
|
return;
|
||||||
|
@ -99,7 +98,7 @@ void flashfsEraseRange(uint32_t start, uint32_t end)
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int i = startSector; i < endSector; i++) {
|
for (int i = startSector; i < endSector; i++) {
|
||||||
m25p16_eraseSector(i * geometry->sectorSize);
|
flashEraseSector(i * geometry->sectorSize);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -108,7 +107,7 @@ void flashfsEraseRange(uint32_t start, uint32_t end)
|
||||||
*/
|
*/
|
||||||
bool flashfsIsReady(void)
|
bool flashfsIsReady(void)
|
||||||
{
|
{
|
||||||
return m25p16_isReady();
|
return flashIsReady();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool flashfsIsSupported(void)
|
bool flashfsIsSupported(void)
|
||||||
|
@ -118,7 +117,7 @@ bool flashfsIsSupported(void)
|
||||||
|
|
||||||
uint32_t flashfsGetSize(void)
|
uint32_t flashfsGetSize(void)
|
||||||
{
|
{
|
||||||
return m25p16_getGeometry()->totalSize;
|
return flashGetGeometry()->totalSize;
|
||||||
}
|
}
|
||||||
|
|
||||||
static uint32_t flashfsTransmitBufferUsed(void)
|
static uint32_t flashfsTransmitBufferUsed(void)
|
||||||
|
@ -147,7 +146,7 @@ uint32_t flashfsGetWriteBufferFreeSpace(void)
|
||||||
|
|
||||||
const flashGeometry_t* flashfsGetGeometry(void)
|
const flashGeometry_t* flashfsGetGeometry(void)
|
||||||
{
|
{
|
||||||
return m25p16_getGeometry();
|
return flashGetGeometry();
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -179,12 +178,14 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
|
||||||
bytesTotal += bufferSizes[i];
|
bytesTotal += bufferSizes[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!sync && !m25p16_isReady()) {
|
if (!sync && !flashIsReady()) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t bytesTotalRemaining = bytesTotal;
|
uint32_t bytesTotalRemaining = bytesTotal;
|
||||||
|
|
||||||
|
uint16_t pageSize = flashfsGetGeometry()->pageSize;
|
||||||
|
|
||||||
while (bytesTotalRemaining > 0) {
|
while (bytesTotalRemaining > 0) {
|
||||||
uint32_t bytesTotalThisIteration;
|
uint32_t bytesTotalThisIteration;
|
||||||
uint32_t bytesRemainThisIteration;
|
uint32_t bytesRemainThisIteration;
|
||||||
|
@ -193,8 +194,8 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
|
||||||
* Each page needs to be saved in a separate program operation, so
|
* 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 we would cross a page boundary, only write up to the boundary in this iteration:
|
||||||
*/
|
*/
|
||||||
if (tailAddress % M25P16_PAGESIZE + bytesTotalRemaining > M25P16_PAGESIZE) {
|
if (tailAddress % pageSize + bytesTotalRemaining > pageSize) {
|
||||||
bytesTotalThisIteration = M25P16_PAGESIZE - tailAddress % M25P16_PAGESIZE;
|
bytesTotalThisIteration = pageSize - tailAddress % pageSize;
|
||||||
} else {
|
} else {
|
||||||
bytesTotalThisIteration = bytesTotalRemaining;
|
bytesTotalThisIteration = bytesTotalRemaining;
|
||||||
}
|
}
|
||||||
|
@ -207,7 +208,7 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
m25p16_pageProgramBegin(tailAddress);
|
flashPageProgramBegin(tailAddress);
|
||||||
|
|
||||||
bytesRemainThisIteration = bytesTotalThisIteration;
|
bytesRemainThisIteration = bytesTotalThisIteration;
|
||||||
|
|
||||||
|
@ -215,7 +216,7 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
|
||||||
if (bufferSizes[i] > 0) {
|
if (bufferSizes[i] > 0) {
|
||||||
// Is buffer larger than our write limit? Write our limit out of it
|
// Is buffer larger than our write limit? Write our limit out of it
|
||||||
if (bufferSizes[i] >= bytesRemainThisIteration) {
|
if (bufferSizes[i] >= bytesRemainThisIteration) {
|
||||||
m25p16_pageProgramContinue(buffers[i], bytesRemainThisIteration);
|
flashPageProgramContinue(buffers[i], bytesRemainThisIteration);
|
||||||
|
|
||||||
buffers[i] += bytesRemainThisIteration;
|
buffers[i] += bytesRemainThisIteration;
|
||||||
bufferSizes[i] -= bytesRemainThisIteration;
|
bufferSizes[i] -= bytesRemainThisIteration;
|
||||||
|
@ -224,7 +225,7 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
|
||||||
break;
|
break;
|
||||||
} else {
|
} else {
|
||||||
// We'll still have more to write after finishing this buffer off
|
// We'll still have more to write after finishing this buffer off
|
||||||
m25p16_pageProgramContinue(buffers[i], bufferSizes[i]);
|
flashPageProgramContinue(buffers[i], bufferSizes[i]);
|
||||||
|
|
||||||
bytesRemainThisIteration -= bufferSizes[i];
|
bytesRemainThisIteration -= bufferSizes[i];
|
||||||
|
|
||||||
|
@ -234,7 +235,7 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
m25p16_pageProgramFinish();
|
flashPageProgramFinish();
|
||||||
|
|
||||||
bytesTotalRemaining -= bytesTotalThisIteration;
|
bytesTotalRemaining -= bytesTotalThisIteration;
|
||||||
|
|
||||||
|
@ -481,7 +482,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
|
// Since the read could overlap data in our dirty buffers, force a sync to clear those first
|
||||||
flashfsFlushSync();
|
flashfsFlushSync();
|
||||||
|
|
||||||
bytesRead = m25p16_readBytes(address, buffer, len);
|
bytesRead = flashReadBytes(address, buffer, len);
|
||||||
|
|
||||||
return bytesRead;
|
return bytesRead;
|
||||||
}
|
}
|
||||||
|
@ -504,13 +505,15 @@ int flashfsIdentifyStartOfFreeSpace(void)
|
||||||
/* We can choose whatever power of 2 size we like, which determines how much wastage of free space we'll have
|
/* We can choose whatever power of 2 size we like, which determines how much wastage of free space we'll have
|
||||||
* at the end of the last written data. But smaller blocksizes will require more searching.
|
* at the end of the last written data. But smaller blocksizes will require more searching.
|
||||||
*/
|
*/
|
||||||
FREE_BLOCK_SIZE = 2048,
|
FREE_BLOCK_SIZE = 2048, // XXX This can't be smaller than page size for underlying flash device.
|
||||||
|
|
||||||
/* We don't expect valid data to ever contain this many consecutive uint32_t's of all 1 bits: */
|
/* We don't expect valid data to ever contain this many consecutive uint32_t's of all 1 bits: */
|
||||||
FREE_BLOCK_TEST_SIZE_INTS = 4, // i.e. 16 bytes
|
FREE_BLOCK_TEST_SIZE_INTS = 4, // i.e. 16 bytes
|
||||||
FREE_BLOCK_TEST_SIZE_BYTES = FREE_BLOCK_TEST_SIZE_INTS * sizeof(uint32_t)
|
FREE_BLOCK_TEST_SIZE_BYTES = FREE_BLOCK_TEST_SIZE_INTS * sizeof(uint32_t)
|
||||||
};
|
};
|
||||||
|
|
||||||
|
STATIC_ASSERT(FREE_BLOCK_SIZE >= FLASH_MAX_PAGE_SIZE, FREE_BLOCK_SIZE_too_small);
|
||||||
|
|
||||||
union {
|
union {
|
||||||
uint8_t bytes[FREE_BLOCK_TEST_SIZE_BYTES];
|
uint8_t bytes[FREE_BLOCK_TEST_SIZE_BYTES];
|
||||||
uint32_t ints[FREE_BLOCK_TEST_SIZE_INTS];
|
uint32_t ints[FREE_BLOCK_TEST_SIZE_INTS];
|
||||||
|
@ -526,7 +529,7 @@ int flashfsIdentifyStartOfFreeSpace(void)
|
||||||
while (left < right) {
|
while (left < right) {
|
||||||
mid = (left + right) / 2;
|
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)
|
// Unexpected timeout from flash, so bail early (reporting the device fuller than it really is)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -563,6 +566,23 @@ bool flashfsIsEOF(void)
|
||||||
return tailAddress >= flashfsGetSize();
|
return tailAddress >= flashfsGetSize();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void flashfsClose(void)
|
||||||
|
{
|
||||||
|
switch(flashfsGetGeometry()->flashType) {
|
||||||
|
case FLASH_TYPE_NOR:
|
||||||
|
break;
|
||||||
|
|
||||||
|
case FLASH_TYPE_NAND:
|
||||||
|
flashFlush();
|
||||||
|
|
||||||
|
// Advance tailAddress to next page boundary.
|
||||||
|
uint32_t pageSize = flashfsGetGeometry()->pageSize;
|
||||||
|
flashfsSetTailAddress((tailAddress + pageSize - 1) & ~(pageSize - 1));
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Call after initializing the flash chip in order to set up the filesystem.
|
* Call after initializing the flash chip in order to set up the filesystem.
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -45,6 +45,7 @@ int flashfsReadAbs(uint32_t offset, uint8_t *data, unsigned int len);
|
||||||
bool flashfsFlushAsync(void);
|
bool flashfsFlushAsync(void);
|
||||||
void flashfsFlushSync(void);
|
void flashfsFlushSync(void);
|
||||||
|
|
||||||
|
void flashfsClose(void);
|
||||||
void flashfsInit(void);
|
void flashfsInit(void);
|
||||||
bool flashfsIsSupported(void);
|
bool flashfsIsSupported(void);
|
||||||
|
|
||||||
|
|
|
@ -34,7 +34,7 @@
|
||||||
|
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
#include "drivers/flash_m25p16.h"
|
#include "drivers/flash.h"
|
||||||
|
|
||||||
#include "io/flashfs.h"
|
#include "io/flashfs.h"
|
||||||
|
|
||||||
|
@ -69,8 +69,8 @@ static int8_t STORAGE_Init(uint8_t lun)
|
||||||
LED0_ON;
|
LED0_ON;
|
||||||
|
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
#if defined(USE_FLASH_M25P16)
|
#ifdef USE_FLASH
|
||||||
m25p16_init(flashConfig());
|
flashInit(flashConfig());
|
||||||
#endif
|
#endif
|
||||||
flashfsInit();
|
flashfsInit();
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
#include "drivers/flash_m25p16.h"
|
#include "drivers/flash.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
|
@ -85,7 +85,7 @@ void updateHardwareRevision(void)
|
||||||
if flash exists on PB3 then Rev1
|
if flash exists on PB3 then Rev1
|
||||||
*/
|
*/
|
||||||
flashConfig_t flashConfig = { .csTag = IO_TAG(PB3) };
|
flashConfig_t flashConfig = { .csTag = IO_TAG(PB3) };
|
||||||
if (m25p16_init(&flashConfig)) {
|
if (flashInit(&flashConfig)) {
|
||||||
hardwareRevision = BJF4_REV1;
|
hardwareRevision = BJF4_REV1;
|
||||||
} else {
|
} else {
|
||||||
IOInit(IOGetByTag(IO_TAG(PB3)), OWNER_FREE, 0);
|
IOInit(IOGetByTag(IO_TAG(PB3)), OWNER_FREE, 0);
|
||||||
|
|
|
@ -119,3 +119,7 @@
|
||||||
#if defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20689)
|
#if defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20689)
|
||||||
#define USE_32K_CAPABLE_GYRO
|
#define USE_32K_CAPABLE_GYRO
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(USE_FLASH_M25P16)
|
||||||
|
#define USE_FLASH
|
||||||
|
#endif
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue