Add W25Q128FV driver (QSPI only)

* Enable QSPI flash chip drivers on NUCLEOH743 for some CI visibility.
* Rework QSPI flash detection.
* Supports chips that are in QSPI mode by default (factory).
* Supports chips that are in QSPI mode due to configuration (e.g. Quad
Enable in Non-Volatile on W25Q128FV)
* Supports chips that need 8 dummy bytes (e.g. W25Q128JV) and ones that
don't (e.g. W25N01G)
This commit is contained in:
Dominic Clifton 2020-06-11 19:46:07 +02:00 committed by Dominic Clifton
parent 2a5e457603
commit c8e741bd18
7 changed files with 586 additions and 24 deletions

View File

@ -406,6 +406,7 @@ SRC += \
drivers/flash.c \
drivers/flash_m25p16.c \
drivers/flash_w25n01g.c \
drivers/flash_w25q128fv.c \
drivers/flash_w25m.c \
io/flashfs.c \
$(MSC_SRC)

View File

@ -109,12 +109,14 @@ void quadSpiSetDivisor(QUADSPI_TypeDef *instance, uint16_t divisor);
bool quadSpiTransmit1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, const uint8_t *out, int length);
bool quadSpiReceive1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length);
bool quadSpiReceive4LINES(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length);
bool quadSpiInstructionWithData1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, const uint8_t *out, int length);
bool quadSpiReceiveWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, uint8_t *in, int length);
bool quadSpiReceiveWithAddress4LINES(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, uint8_t *in, int length);
bool quadSpiTransmitWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length);
bool quadSpiTransmitWithAddress4LINES(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length);
bool quadSpiInstructionWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize);

View File

@ -286,6 +286,44 @@ bool quadSpiReceive1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t
return true;
}
bool quadSpiReceive4LINES(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length)
{
QUADSPIDevice device = quadSpiDeviceByInstance(instance);
HAL_StatusTypeDef status;
QSPI_CommandTypeDef cmd;
cmd.InstructionMode = QSPI_INSTRUCTION_4_LINES;
cmd.AddressMode = QSPI_ADDRESS_NONE;
cmd.AlternateByteMode = QSPI_ALTERNATE_BYTES_NONE;
cmd.DataMode = QSPI_DATA_4_LINES;
cmd.DummyCycles = dummyCycles;
cmd.DdrMode = QSPI_DDR_MODE_DISABLE;
cmd.DdrHoldHalfCycle = QSPI_DDR_HHC_ANALOG_DELAY;
cmd.SIOOMode = QSPI_SIOO_INST_EVERY_CMD;
cmd.Instruction = instruction;
cmd.NbData = length;
quadSpiSelectDevice(instance);
status = HAL_QSPI_Command(&quadSpiDevice[device].hquadSpi, &cmd, QUADSPI_DEFAULT_TIMEOUT);
bool timeout = (status != HAL_OK);
if (!timeout) {
status = HAL_QSPI_Receive(&quadSpiDevice[device].hquadSpi, in, QUADSPI_DEFAULT_TIMEOUT);
timeout = (status != HAL_OK);
}
quadSpiDeselectDevice(instance);
if (timeout) {
quadSpiTimeoutUserCallback(instance);
return false;
}
return true;
}
bool quadSpiReceiveWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, uint8_t *in, int length)
{
QUADSPIDevice device = quadSpiDeviceByInstance(instance);
@ -404,6 +442,46 @@ bool quadSpiTransmitWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instruct
return true;
}
bool quadSpiTransmitWithAddress4LINES(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length)
{
QUADSPIDevice device = quadSpiDeviceByInstance(instance);
HAL_StatusTypeDef status;
QSPI_CommandTypeDef cmd;
cmd.InstructionMode = QSPI_INSTRUCTION_1_LINE;
cmd.AddressMode = QSPI_ADDRESS_1_LINE;
cmd.AlternateByteMode = QSPI_ALTERNATE_BYTES_NONE;
cmd.DataMode = QSPI_DATA_4_LINES;
cmd.DummyCycles = dummyCycles;
cmd.DdrMode = QSPI_DDR_MODE_DISABLE;
cmd.DdrHoldHalfCycle = QSPI_DDR_HHC_ANALOG_DELAY;
cmd.SIOOMode = QSPI_SIOO_INST_EVERY_CMD;
cmd.Instruction = instruction;
cmd.Address = address;
cmd.AddressSize = quadSpi_addressSizeFromValue(addressSize);
cmd.NbData = length;
quadSpiSelectDevice(instance);
status = HAL_QSPI_Command(&quadSpiDevice[device].hquadSpi, &cmd, QUADSPI_DEFAULT_TIMEOUT);
bool timeout = (status != HAL_OK);
if (!timeout) {
status = HAL_QSPI_Transmit(&quadSpiDevice[device].hquadSpi, (uint8_t *)out, QUADSPI_DEFAULT_TIMEOUT);
timeout = (status != HAL_OK);
}
quadSpiDeselectDevice(instance);
if (timeout) {
quadSpiTimeoutUserCallback(instance);
return false;
}
return true;
}
bool quadSpiInstructionWithAddress1LINE(QUADSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize)
{
QUADSPIDevice device = quadSpiDeviceByInstance(instance);

View File

@ -32,6 +32,7 @@
#include "flash_impl.h"
#include "flash_m25p16.h"
#include "flash_w25n01g.h"
#include "flash_w25q128fv.h"
#include "flash_w25m.h"
#include "drivers/bus_spi.h"
#include "drivers/bus_quadspi.h"
@ -55,39 +56,72 @@ static int flashPartitions = 0;
#ifdef USE_QUADSPI
static bool flashQuadSpiInit(const flashConfig_t *flashConfig)
{
QUADSPI_TypeDef *quadSpiInstance = quadSpiInstanceByDevice(QUADSPI_CFG_TO_DEV(flashConfig->quadSpiDevice));
quadSpiSetDivisor(quadSpiInstance, QUADSPI_CLOCK_INITIALISATION);
bool detected = false;
uint8_t readIdResponse[4];
bool status = quadSpiReceive1LINE(quadSpiInstance, FLASH_INSTRUCTION_RDID, 8, readIdResponse, sizeof(readIdResponse));
if (!status) {
return false;
}
enum { TRY_1LINE = 0, TRY_4LINE, BAIL};
int phase = TRY_1LINE;
flashDevice.io.mode = FLASHIO_QUADSPI;
flashDevice.io.handle.quadSpi = quadSpiInstance;
QUADSPI_TypeDef *hqspi = quadSpiInstanceByDevice(QUADSPI_CFG_TO_DEV(flashConfig->quadSpiDevice));
// Manufacturer, memory type, and capacity
uint32_t chipID = (readIdResponse[0] << 16) | (readIdResponse[1] << 8) | (readIdResponse[2]);
do {
quadSpiSetDivisor(hqspi, QUADSPI_CLOCK_INITIALISATION);
#if defined(USE_FLASH_W25N01G) || defined(USE_FLASH_W25M02G)
quadSpiSetDivisor(quadSpiInstance, QUADSPI_CLOCK_ULTRAFAST);
// 3 bytes for what we need, but some IC's need 8 dummy cycles after the instruction, so read 4 and make two attempts to
// assemble the chip id from the response.
uint8_t readIdResponse[4];
#if defined(USE_FLASH_W25N01G)
if (w25n01g_detect(&flashDevice, chipID)) {
return true;
}
bool status = false;
switch (phase) {
case TRY_1LINE:
status = quadSpiReceive1LINE(hqspi, FLASH_INSTRUCTION_RDID, 0, readIdResponse, 4);
break;
case TRY_4LINE:
status = quadSpiReceive4LINES(hqspi, FLASH_INSTRUCTION_RDID, 2, readIdResponse, 3);
break;
default:
break;
}
if (!status) {
phase++;
continue;
}
flashDevice.io.handle.quadSpi = hqspi;
flashDevice.io.mode = FLASHIO_QUADSPI;
quadSpiSetDivisor(hqspi, QUADSPI_CLOCK_ULTRAFAST);
for (uint8_t offset = 0; offset <= 1 && !detected; offset++) {
uint32_t chipID = (readIdResponse[offset + 0] << 16) | (readIdResponse[offset + 1] << 8) | (readIdResponse[offset + 2]);
if (offset == 0) {
#ifdef USE_FLASH_W25Q128FV
if (!detected && w25q128fv_detect(&flashDevice, chipID)) {
detected = true;
}
#endif
}
if (offset == 1) {
#ifdef USE_FLASH_W25N01G
if (!detected && w25n01g_detect(&flashDevice, chipID)) {
detected = true;
}
#endif
#if defined(USE_FLASH_W25M02G)
if (w25m_detect(&flashDevice, chipID)) {
return true;
}
if (!detected && w25m_detect(&flashDevice, chipID)) {
detected = true;
}
#endif
}
}
phase++;
} while (phase != BAIL && !detected);
#endif
return false;
return detected;
}
#endif // USE_QUADSPI

View File

@ -0,0 +1,438 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are 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 and Betaflight are distributed in the hope that they
* 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/>.
*
* Author: Dominic Clifton - Initial implementation and testing.
*/
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#if defined(USE_FLASH_W25Q128FV) && defined(USE_QUADSPI)
#define USE_FLASH_WRITES_USING_4LINES
#define USE_FLASH_READS_USING_4LINES
#include "build/debug.h"
#include "common/utils.h"
#include "drivers/flash.h"
#include "drivers/flash_impl.h"
#include "drivers/flash_w25q128fv.h"
#include "drivers/bus_quadspi.h"
// JEDEC ID
#define JEDEC_ID_WINBOND_W25Q128FV_SPI 0xEF4018
#define JEDEC_ID_WINBOND_W25Q128FV_QUADSPI 0xEF6018
#define JEDEC_ID_WINBOND_W25Q128JV_QUADSPI 0xEF7018
// Device size parameters
#define W25Q128FV_PAGE_SIZE 2048
#define W25Q128FV_PAGES_PER_BLOCK 64
#define W25Q128FV_BLOCKS_PER_DIE 1024
#define W25Q128FV_BLOCK_SIZE (W25Q128FV_PAGES_PER_BLOCK * W25Q128FV_PAGE_SIZE)
// Sizes
#define W25Q128FV_STATUS_REGISTER_BITS 8
#define W25Q128FV_ADDRESS_BITS 24
// Instructions
#define W25Q128FV_INSTRUCTION_RDID 0x9F
#define W25Q128FV_INSTRUCTION_ENABLE_RESET 0x66
#define W25Q128FV_INSTRUCTION_RESET_DEVICE 0x99
#define W25Q128FV_INSTRUCTION_READ_STATUS1_REG 0x05
#define W25Q128FV_INSTRUCTION_READ_STATUS2_REG 0x35
#define W25Q128FV_INSTRUCTION_READ_STATUS3_REG 0x15
#define W25Q128FV_INSTRUCTION_WRITE_STATUS1_REG 0x01
#define W25Q128FV_INSTRUCTION_WRITE_STATUS2_REG 0x31
#define W25Q128FV_INSTRUCTION_WRITE_STATUS3_REG 0x11
#define W25Q128FV_INSTRUCTION_WRITE_ENABLE 0x06
#define W25Q128FV_INSTRUCTION_VOLATILE_WRITE_ENABLE 0x50
#define W25Q128FV_INSTRUCTION_BLOCK_ERASE_64KB 0xD8
#define W25Q128FV_INSTRUCTION_CHIP_ERASE 0xC7
#define W25Q128FV_INSTRUCTION_ENTER_QPI_MODE 0x38
#define W25Q128FV_INSTRUCTION_FAST_READ 0x0B
#define W25Q128FV_INSTRUCTION_FAST_READ_QUAD_OUTPUT 0x6B
#define W25Q128FV_INSTRUCTION_PAGE_PROGRAM 0x02
#define W25Q128FV_INSTRUCTION_QUAD_PAGE_PROGRAM 0x32
#define W25Q128FV_SR1_BIT_WRITE_IN_PROGRESS (1 << 0)
#define W25Q128FV_SR1_BIT_WRITE_ENABLED (1 << 1)
#define W25Q128FV_SR2_BIT_QUAD_ENABLE (1 << 1)
//#define W25Q128FV_INSTRUCTION_WRITE_DISABLE 0x04
//#define W25Q128FV_INSTRUCTION_PAGE_PROGRAM 0x02
// Timings (2ms minimum to avoid 1 tick advance in consecutive calls to HAL_GetTick).
#define W25Q128FV_TIMEOUT_PAGE_READ_MS 4
#define W25Q128FV_TIMEOUT_RESET_MS 2 // tRST = 30us
#define W25Q128FV_TIMEOUT_BLOCK_ERASE_64KB_MS 2000 // tBE2max = 2000ms, tBE2typ = 150ms
#define W25Q128FV_TIMEOUT_CHIP_ERASE_MS (200 * 1000) // tCEmax 200s, tCEtyp = 40s
#define W25Q128FV_TIMEOUT_PAGE_PROGRAM_MS 2 // tPPmax = 700us, tPPtyp = 250us
#define W25Q128FV_TIMEOUT_WRITE_ENABLE_MS 2
typedef enum {
INITIAL_MODE_SPI = 0,
INITIAL_MODE_QUADSPI,
} w25q128fv_initialMode_e;
typedef struct w25q128fvState_s {
w25q128fv_initialMode_e initialMode;
uint32_t currentWriteAddress;
} w25q128fvState_t;
w25q128fvState_t w25q128fvState = { 0 };
static bool w25q128fv_waitForReady(flashDevice_t *fdevice);
static void w25q128fv_waitForTimeout(flashDevice_t *fdevice);
static void w25q128fv_setTimeout(flashDevice_t *fdevice, uint32_t timeoutMillis)
{
uint32_t now = HAL_GetTick();
fdevice->timeoutAt = now + timeoutMillis;
}
static void w25q128fv_performOneByteCommand(flashDeviceIO_t *io, uint8_t command)
{
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
quadSpiTransmit1LINE(quadSpi, command, 0, NULL, 0);
}
static void w25q128fv_performCommandWithAddress(flashDeviceIO_t *io, uint8_t command, uint32_t address)
{
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
quadSpiInstructionWithAddress1LINE(quadSpi, command, 0, address & 0xffffff, W25Q128FV_ADDRESS_BITS);
}
static void w25q128fv_writeEnable(flashDevice_t *fdevice)
{
w25q128fv_performOneByteCommand(&fdevice->io, W25Q128FV_INSTRUCTION_WRITE_ENABLE);
}
static uint8_t w25q128fv_readRegister(flashDeviceIO_t *io, uint8_t command)
{
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
uint8_t in[1];
quadSpiReceive1LINE(quadSpi, command, 0, in, W25Q128FV_STATUS_REGISTER_BITS / 8);
return in[0];
}
static void w25q128fv_writeRegister(flashDeviceIO_t *io, uint8_t command, uint8_t data)
{
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
quadSpiTransmit1LINE(quadSpi, command, 0, &data, W25Q128FV_STATUS_REGISTER_BITS / 8);
}
static void w25q128fv_deviceReset(flashDevice_t *fdevice)
{
flashDeviceIO_t *io = &fdevice->io;
w25q128fv_waitForReady(fdevice);
w25q128fv_performOneByteCommand(io, W25Q128FV_INSTRUCTION_ENABLE_RESET);
w25q128fv_performOneByteCommand(io, W25Q128FV_INSTRUCTION_RESET_DEVICE);
w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_RESET_MS);
w25q128fv_waitForTimeout(fdevice);
w25q128fv_waitForReady(fdevice);
#ifdef DISABLE_NONVOLATILE_QE_MODE // Use this if you encounter a chip with it's QE bit enabled when it shouldn't be.
w25q128fv_performOneByteCommand(io, W25Q128FV_INSTRUCTION_WRITE_ENABLE);
w25q128fv_writeRegister(io, W25Q128FV_INSTRUCTION_WRITE_STATUS2_REG, 0x00);
#endif
#if defined(USE_FLASH_WRITES_USING_4LINES) || defined(USE_FLASH_READS_USING_4LINES)
uint8_t registerValue = w25q128fv_readRegister(io, W25Q128FV_INSTRUCTION_READ_STATUS2_REG);
//
// WARNING: DO NOT ENABLE QE bit if IO2/IO3 are connected to GND or VCC.
//
// See datasheet https://www.winbond.com/resource-files/w25q128fv%20rev.m%2005132016%20kms.pdf
// W25Q128FV - Revision M - 7.1.10 Quad Enable
//
// There is no such warning for the W25Q128JV in the same documentation section
// See datasheet https://www.winbond.com/resource-files/w25q128jv%20revg%2004082019%20plus.pdf
// W25Q128JV - Revision G - 7.1.4 Quad Enable
//
if ((registerValue & W25Q128FV_SR2_BIT_QUAD_ENABLE) == 0) {
// Enable QUADSPI mode.
registerValue = w25q128fv_readRegister(io, W25Q128FV_INSTRUCTION_READ_STATUS2_REG);
uint8_t newValue = registerValue;
newValue |= W25Q128FV_SR2_BIT_QUAD_ENABLE;
//w25q128fv_performOneByteCommand(io, W25Q128FV_INSTRUCTION_WRITE_ENABLE);
w25q128fv_performOneByteCommand(io, W25Q128FV_INSTRUCTION_VOLATILE_WRITE_ENABLE);
w25q128fv_writeRegister(io, W25Q128FV_INSTRUCTION_WRITE_STATUS2_REG, newValue);
}
#endif
}
bool w25q128fv_isReady(flashDevice_t *fdevice)
{
uint8_t status = w25q128fv_readRegister(&fdevice->io, W25Q128FV_INSTRUCTION_READ_STATUS1_REG);
bool busy = (status & W25Q128FV_SR1_BIT_WRITE_IN_PROGRESS);
return !busy;
}
static bool w25q128fv_isWritable(flashDevice_t *fdevice)
{
uint8_t status = w25q128fv_readRegister(&fdevice->io, W25Q128FV_INSTRUCTION_READ_STATUS1_REG);
bool writable = (status & W25Q128FV_SR1_BIT_WRITE_ENABLED);
return writable;
}
bool w25q128fv_hasTimedOut(flashDevice_t *fdevice)
{
uint32_t now = HAL_GetTick();
if (cmp32(now, fdevice->timeoutAt) >= 0) {
return true;
}
return false;
}
void w25q128fv_waitForTimeout(flashDevice_t *fdevice)
{
while (!w25q128fv_hasTimedOut(fdevice)) { }
fdevice->timeoutAt = 0;
}
bool w25q128fv_waitForReady(flashDevice_t *fdevice)
{
bool ready = true;
while (!w25q128fv_isReady(fdevice)) {
if (w25q128fv_hasTimedOut(fdevice)) {
ready = false;
break;
}
}
fdevice->timeoutAt = 0;
return ready;
}
const flashVTable_t w25q128fv_vTable;
static void w25q128fv_deviceInit(flashDevice_t *flashdev);
bool w25q128fv_detect(flashDevice_t *fdevice, uint32_t chipID)
{
switch (chipID) {
case JEDEC_ID_WINBOND_W25Q128FV_SPI:
case JEDEC_ID_WINBOND_W25Q128FV_QUADSPI:
case JEDEC_ID_WINBOND_W25Q128JV_QUADSPI:
fdevice->geometry.sectors = 256;
fdevice->geometry.pagesPerSector = 256;
fdevice->geometry.pageSize = 256;
break;
default:
// Unsupported chip
fdevice->geometry.sectors = 0;
fdevice->geometry.pagesPerSector = 0;
fdevice->geometry.sectorSize = 0;
fdevice->geometry.totalSize = 0;
return false;
}
// use the chip id to determine the initial interface mode on cold-boot.
switch (chipID) {
case JEDEC_ID_WINBOND_W25Q128FV_SPI:
w25q128fvState.initialMode = INITIAL_MODE_SPI;
break;
case JEDEC_ID_WINBOND_W25Q128JV_QUADSPI:
case JEDEC_ID_WINBOND_W25Q128FV_QUADSPI:
w25q128fvState.initialMode = INITIAL_MODE_QUADSPI;
break;
default:
break;
}
fdevice->geometry.flashType = FLASH_TYPE_NOR;
fdevice->geometry.sectorSize = fdevice->geometry.pagesPerSector * fdevice->geometry.pageSize;
fdevice->geometry.totalSize = fdevice->geometry.sectorSize * fdevice->geometry.sectors;
w25q128fv_deviceReset(fdevice);
w25q128fv_deviceInit(fdevice);
fdevice->vTable = &w25q128fv_vTable;
return true;
}
void w25q128fv_eraseSector(flashDevice_t *fdevice, uint32_t address)
{
w25q128fv_waitForReady(fdevice);
w25q128fv_writeEnable(fdevice);
w25q128fv_performCommandWithAddress(&fdevice->io, W25Q128FV_INSTRUCTION_BLOCK_ERASE_64KB, address);
w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_BLOCK_ERASE_64KB_MS);
}
void w25q128fv_eraseCompletely(flashDevice_t *fdevice)
{
w25q128fv_waitForReady(fdevice);
w25q128fv_writeEnable(fdevice);
w25q128fv_performOneByteCommand(&fdevice->io, W25Q128FV_INSTRUCTION_CHIP_ERASE);
w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_CHIP_ERASE_MS);
}
static void w25q128fv_loadProgramData(flashDevice_t *fdevice, const uint8_t *data, int length)
{
w25q128fv_waitForReady(fdevice);
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
#ifdef USE_FLASH_WRITES_USING_4LINES
quadSpiTransmitWithAddress4LINES(quadSpi, W25Q128FV_INSTRUCTION_QUAD_PAGE_PROGRAM, 0, w25q128fvState.currentWriteAddress, W25Q128FV_ADDRESS_BITS, data, length);
#else
quadSpiTransmitWithAddress1LINE(quadSpi, W25Q128FV_INSTRUCTION_PAGE_PROGRAM, 0, w25q128fvState.currentWriteAddress, W25Q128FV_ADDRESS_BITS, data, length);
#endif
w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_PAGE_PROGRAM_MS);
w25q128fvState.currentWriteAddress += length;
}
void w25q128fv_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
{
UNUSED(fdevice);
w25q128fvState.currentWriteAddress = address;
}
void w25q128fv_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *data, int length)
{
w25q128fv_waitForReady(fdevice);
w25q128fv_writeEnable(fdevice);
// verify write enable is set.
w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_WRITE_ENABLE_MS);
bool writable = false;
do {
writable = w25q128fv_isWritable(fdevice);
} while (!writable && w25q128fv_hasTimedOut(fdevice));
if (!writable) {
return; // TODO report failure somehow.
}
w25q128fv_loadProgramData(fdevice, data, length);
}
void w25q128fv_pageProgramFinish(flashDevice_t *fdevice)
{
UNUSED(fdevice);
}
void w25q128fv_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, int length)
{
w25q128fv_pageProgramBegin(fdevice, address);
w25q128fv_pageProgramContinue(fdevice, data, length);
w25q128fv_pageProgramFinish(fdevice);
}
void w25q128fv_flush(flashDevice_t *fdevice)
{
UNUSED(fdevice);
}
int w25q128fv_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
{
if (!w25q128fv_waitForReady(fdevice)) {
return 0;
}
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
#ifdef USE_FLASH_READS_USING_4LINES
bool status = quadSpiReceiveWithAddress4LINES(quadSpi, W25Q128FV_INSTRUCTION_FAST_READ_QUAD_OUTPUT, 8, address, W25Q128FV_ADDRESS_BITS, buffer, length);
#else
bool status = quadSpiReceiveWithAddress1LINE(quadSpi, W25Q128FV_INSTRUCTION_FAST_READ, 8, address, W25Q128FV_ADDRESS_BITS, buffer, length);
#endif
w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_PAGE_READ_MS);
if (!status) {
return 0;
}
return length;
}
const flashGeometry_t* w25q128fv_getGeometry(flashDevice_t *fdevice)
{
return &fdevice->geometry;
}
const flashVTable_t w25q128fv_vTable = {
.isReady = w25q128fv_isReady,
.waitForReady = w25q128fv_waitForReady,
.eraseSector = w25q128fv_eraseSector,
.eraseCompletely = w25q128fv_eraseCompletely,
.pageProgramBegin = w25q128fv_pageProgramBegin,
.pageProgramContinue = w25q128fv_pageProgramContinue,
.pageProgramFinish = w25q128fv_pageProgramFinish,
.pageProgram = w25q128fv_pageProgram,
.flush = w25q128fv_flush,
.readBytes = w25q128fv_readBytes,
.getGeometry = w25q128fv_getGeometry,
};
static void w25q128fv_deviceInit(flashDevice_t *flashdev)
{
UNUSED(flashdev);
}
#endif

View File

@ -0,0 +1,7 @@
#pragma once
#ifdef USE_FLASH_W25Q128FV
bool w25q128fv_detect(flashDevice_t *fdevice, uint32_t chipID);
#endif

View File

@ -121,7 +121,7 @@
#define SPI6_MISO_PIN NONE
#define SPI6_MOSI_PIN NONE
// #define USE_QUADSPI
#define USE_QUADSPI
#define USE_QUADSPI_DEVICE_1
#define QUADSPI1_SCK_PIN NONE // PB2
@ -224,6 +224,8 @@
#define USE_FLASH_CHIP
#define USE_FLASH_M25P16
#define USE_FLASH_W25M
#define USE_FLASH_W25Q128FV
#define USE_FLASH_W25N01G
#define FLASH_SPI_INSTANCE NULL
#define FLASH_CS_PIN NONE
#define USE_FLASHFS