1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 11:59:58 +03:00

Update flash drivers to support QuadSPI

- Update flash w25n01g driver to support QuadSPI.

- flash_m25p16 update for QuadSPI support

- w25m driver update for QuadSPI support

- Use 100Mhz (ULTRAFAST) clock for QuadSPI w25n01

- Conditionalize QUADSPI code in w25n01g driver

- Use handle instead of handle_u
This commit is contained in:
Dominic Clifton 2019-05-07 14:55:59 +09:00 committed by jflyper
parent c0ee056d68
commit dcd138ae20
7 changed files with 385 additions and 148 deletions

View file

@ -33,6 +33,7 @@
#include "flash_w25n01g.h" #include "flash_w25n01g.h"
#include "flash_w25m.h" #include "flash_w25m.h"
#include "drivers/bus_spi.h" #include "drivers/bus_spi.h"
#include "drivers/bus_quadspi.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/time.h" #include "drivers/time.h"
@ -41,15 +42,49 @@ static busDevice_t *busdev;
static flashDevice_t flashDevice; static flashDevice_t flashDevice;
#define FLASH_INSTRUCTION_RDID 0x9F
#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);
uint8_t readIdResponse[4];
bool status = quadSpiReceive1LINE(quadSpiInstance, FLASH_INSTRUCTION_RDID, 8, readIdResponse, sizeof(readIdResponse));
if (!status) {
return false;
}
flashDevice.io.mode = FLASHIO_QUADSPI;
flashDevice.io.handle.quadSpi = quadSpiInstance;
// Manufacturer, memory type, and capacity
uint32_t chipID = (readIdResponse[0] << 16) | (readIdResponse[1] << 8) | (readIdResponse[2]);
#ifdef USE_FLASH_W25N01G
quadSpiSetDivisor(quadSpiInstance, QUADSPI_CLOCK_ULTRAFAST);
if (w25n01g_detect(&flashDevice, chipID)) {
return true;
}
#endif
return false;
}
#endif // USE_QUADSPI
#ifdef USE_SPI
void flashPreInit(const flashConfig_t *flashConfig) void flashPreInit(const flashConfig_t *flashConfig)
{ {
spiPreinitRegister(flashConfig->csTag, IOCFG_IPU, 1); spiPreinitRegister(flashConfig->csTag, IOCFG_IPU, 1);
} }
// Read chip identification and send it to device detect static bool flashSpiInit(const flashConfig_t *flashConfig)
bool flashInit(const flashConfig_t *flashConfig)
{ {
// Read chip identification and send it to device detect
busdev = &busInstance; busdev = &busInstance;
if (flashConfig->csTag) { if (flashConfig->csTag) {
@ -85,11 +120,10 @@ bool flashInit(const flashConfig_t *flashConfig)
#endif #endif
#endif #endif
flashDevice.busdev = busdev; flashDevice.io.mode = FLASHIO_SPI;
flashDevice.io.handle.busdev = busdev;
#define SPIFLASH_INSTRUCTION_RDID 0x9F const uint8_t out[] = { FLASH_INSTRUCTION_RDID, 0, 0, 0, 0 };
const uint8_t out[] = { SPIFLASH_INSTRUCTION_RDID, 0, 0, 0, 0 };
delay(50); // short delay required after initialisation of SPI device instance. delay(50); // short delay required after initialisation of SPI device instance.
@ -97,18 +131,18 @@ bool flashInit(const flashConfig_t *flashConfig)
* Some newer chips require one dummy byte to be read; we can read * Some newer chips require one dummy byte to be read; we can read
* 4 bytes for these chips while retaining backward compatibility. * 4 bytes for these chips while retaining backward compatibility.
*/ */
uint8_t in[5]; uint8_t readIdResponse[5];
in[1] = in[2] = 0; readIdResponse[1] = readIdResponse[2] = 0;
// Clearing the CS bit terminates the command early so we don't have to read the chip UID: // Clearing the CS bit terminates the command early so we don't have to read the chip UID:
#ifdef USE_SPI_TRANSACTION #ifdef USE_SPI_TRANSACTION
spiBusTransactionTransfer(busdev, out, in, sizeof(out)); spiBusTransactionTransfer(busdev, out, readIdResponse, sizeof(out));
#else #else
spiBusTransfer(busdev, out, in, sizeof(out)); spiBusTransfer(busdev, out, readIdResponse, sizeof(out));
#endif #endif
// Manufacturer, memory type, and capacity // Manufacturer, memory type, and capacity
uint32_t chipID = (in[1] << 16) | (in[2] << 8) | (in[3]); uint32_t chipID = (readIdResponse[1] << 16) | (readIdResponse[2] << 8) | (readIdResponse[3]);
#ifdef USE_FLASH_M25P16 #ifdef USE_FLASH_M25P16
if (m25p16_detect(&flashDevice, chipID)) { if (m25p16_detect(&flashDevice, chipID)) {
@ -123,7 +157,7 @@ bool flashInit(const flashConfig_t *flashConfig)
#endif #endif
// Newer chips // Newer chips
chipID = (in[2] << 16) | (in[3] << 8) | (in[4]); chipID = (readIdResponse[2] << 16) | (readIdResponse[3] << 8) | (readIdResponse[4]);
#ifdef USE_FLASH_W25N01G #ifdef USE_FLASH_W25N01G
if (w25n01g_detect(&flashDevice, chipID)) { if (w25n01g_detect(&flashDevice, chipID)) {
@ -141,6 +175,27 @@ bool flashInit(const flashConfig_t *flashConfig)
return false; return false;
} }
#endif // USE_SPI
bool flashInit(const flashConfig_t *flashConfig)
{
#ifdef USE_SPI
bool useSpi = (SPI_CFG_TO_DEV(flashConfig->spiDevice) != SPIINVALID);
if (useSpi) {
return flashSpiInit(flashConfig);
}
#endif
#ifdef USE_QUADSPI
bool useQuadSpi = (QUADSPI_CFG_TO_DEV(flashConfig->quadSpiDevice) != QUADSPIINVALID);
if (useQuadSpi) {
return flashQuadSpiInit(flashConfig);
}
#endif
return false;
}
bool flashIsReady(void) bool flashIsReady(void)
{ {

View file

@ -28,8 +28,23 @@
struct flashVTable_s; struct flashVTable_s;
typedef enum {
FLASHIO_NONE = 0,
FLASHIO_SPI,
FLASHIO_QUADSPI
} flashDeviceIoMode_e;
typedef struct flashDeviceIO_s {
union {
busDevice_t *busdev; // Device interface dependent handle (spi/i2c)
#ifdef USE_QUADSPI
QUADSPI_TypeDef *quadSpi;
#endif
} handle;
flashDeviceIoMode_e mode;
} flashDeviceIO_t;
typedef struct flashDevice_s { typedef struct flashDevice_s {
busDevice_t *busdev;
const struct flashVTable_s *vTable; const struct flashVTable_s *vTable;
flashGeometry_t geometry; flashGeometry_t geometry;
uint32_t currentWriteAddress; uint32_t currentWriteAddress;
@ -38,6 +53,7 @@ typedef struct flashDevice_s {
// for writes. This allows us to avoid polling for writable status // for writes. This allows us to avoid polling for writable status
// when it is definitely ready already. // when it is definitely ready already.
bool couldBeBusy; bool couldBeBusy;
flashDeviceIO_t io;
} flashDevice_t; } flashDevice_t;
typedef struct flashVTable_s { typedef struct flashVTable_s {

View file

@ -126,7 +126,7 @@ static void m25p16_performOneByteCommand(busDevice_t *bus, uint8_t command)
*/ */
static void m25p16_writeEnable(flashDevice_t *fdevice) static void m25p16_writeEnable(flashDevice_t *fdevice)
{ {
m25p16_performOneByteCommand(fdevice->busdev, M25P16_INSTRUCTION_WRITE_ENABLE); m25p16_performOneByteCommand(fdevice->io.handle.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
fdevice->couldBeBusy = true; fdevice->couldBeBusy = true;
@ -145,7 +145,7 @@ static uint8_t m25p16_readStatus(busDevice_t *bus)
static bool m25p16_isReady(flashDevice_t *fdevice) 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
fdevice->couldBeBusy = fdevice->couldBeBusy && ((m25p16_readStatus(fdevice->busdev) & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0); fdevice->couldBeBusy = fdevice->couldBeBusy && ((m25p16_readStatus(fdevice->io.handle.busdev) & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0);
return !fdevice->couldBeBusy; return !fdevice->couldBeBusy;
} }
@ -219,7 +219,7 @@ bool m25p16_detect(flashDevice_t *fdevice, uint32_t chipID)
if (fdevice->geometry.totalSize > 16 * 1024 * 1024) { if (fdevice->geometry.totalSize > 16 * 1024 * 1024) {
fdevice->isLargeFlash = true; fdevice->isLargeFlash = true;
m25p16_performOneByteCommand(fdevice->busdev, W25Q256_INSTRUCTION_ENTER_4BYTE_ADDRESS_MODE); m25p16_performOneByteCommand(fdevice->io.handle.busdev, W25Q256_INSTRUCTION_ENTER_4BYTE_ADDRESS_MODE);
} }
fdevice->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
@ -250,7 +250,7 @@ static void m25p16_eraseSector(flashDevice_t *fdevice, uint32_t address)
m25p16_writeEnable(fdevice); m25p16_writeEnable(fdevice);
m25p16_transfer(fdevice->busdev, out, NULL, sizeof(out)); m25p16_transfer(fdevice->io.handle.busdev, out, NULL, sizeof(out));
} }
static void m25p16_eraseCompletely(flashDevice_t *fdevice) static void m25p16_eraseCompletely(flashDevice_t *fdevice)
@ -259,7 +259,7 @@ static void m25p16_eraseCompletely(flashDevice_t *fdevice)
m25p16_writeEnable(fdevice); m25p16_writeEnable(fdevice);
m25p16_performOneByteCommand(fdevice->busdev, M25P16_INSTRUCTION_BULK_ERASE); m25p16_performOneByteCommand(fdevice->io.handle.busdev, M25P16_INSTRUCTION_BULK_ERASE);
} }
static void m25p16_pageProgramBegin(flashDevice_t *fdevice, uint32_t address) static void m25p16_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
@ -280,18 +280,18 @@ static void m25p16_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *da
m25p16_writeEnable(fdevice); m25p16_writeEnable(fdevice);
#ifdef USE_SPI_TRANSACTION #ifdef USE_SPI_TRANSACTION
spiBusTransactionBegin(fdevice->busdev); spiBusTransactionBegin(fdevice->io.handle.busdev);
#else #else
m25p16_enable(fdevice->busdev); m25p16_enable(fdevice->io.handle.busdev);
#endif #endif
spiTransfer(fdevice->busdev->busdev_u.spi.instance, command, NULL, fdevice->isLargeFlash ? 5 : 4); spiTransfer(fdevice->io.handle.busdev->busdev_u.spi.instance, command, NULL, fdevice->isLargeFlash ? 5 : 4);
spiTransfer(fdevice->busdev->busdev_u.spi.instance, data, NULL, length); spiTransfer(fdevice->io.handle.busdev->busdev_u.spi.instance, data, NULL, length);
#ifdef USE_SPI_TRANSACTION #ifdef USE_SPI_TRANSACTION
spiBusTransactionEnd(fdevice->busdev); spiBusTransactionEnd(fdevice->io.handle.busdev);
#else #else
m25p16_disable(fdevice->busdev); m25p16_disable(fdevice->io.handle.busdev);
#endif #endif
fdevice->currentWriteAddress += length; fdevice->currentWriteAddress += length;
@ -345,18 +345,18 @@ static int m25p16_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *b
} }
#ifdef USE_SPI_TRANSACTION #ifdef USE_SPI_TRANSACTION
spiBusTransactionBegin(fdevice->busdev); spiBusTransactionBegin(fdevice->io.handle.busdev);
#else #else
m25p16_enable(fdevice->busdev); m25p16_enable(fdevice->io.handle.busdev);
#endif #endif
spiTransfer(fdevice->busdev->busdev_u.spi.instance, command, NULL, fdevice->isLargeFlash ? 5 : 4); spiTransfer(fdevice->io.handle.busdev->busdev_u.spi.instance, command, NULL, fdevice->isLargeFlash ? 5 : 4);
spiTransfer(fdevice->busdev->busdev_u.spi.instance, NULL, buffer, length); spiTransfer(fdevice->io.handle.busdev->busdev_u.spi.instance, NULL, buffer, length);
#ifdef USE_SPI_TRANSACTION #ifdef USE_SPI_TRANSACTION
spiBusTransactionEnd(fdevice->busdev); spiBusTransactionEnd(fdevice->io.handle.busdev);
#else #else
m25p16_disable(fdevice->busdev); m25p16_disable(fdevice->io.handle.busdev);
#endif #endif
return length; return length;

View file

@ -84,7 +84,7 @@ static bool w25m_isReady(flashDevice_t *fdevice)
for (int die = 0 ; die < dieCount ; die++) { for (int die = 0 ; die < dieCount ; die++) {
if (dieDevice[die].couldBeBusy) { if (dieDevice[die].couldBeBusy) {
w25m_dieSelect(fdevice->busdev, die); w25m_dieSelect(fdevice->io.handle.busdev, die);
if (!dieDevice[die].vTable->isReady(&dieDevice[die])) { if (!dieDevice[die].vTable->isReady(&dieDevice[die])) {
return false; return false;
} }
@ -115,8 +115,9 @@ bool w25m_detect(flashDevice_t *fdevice, uint32_t chipID)
dieCount = 2; dieCount = 2;
for (int die = 0 ; die < dieCount ; die++) { for (int die = 0 ; die < dieCount ; die++) {
w25m_dieSelect(fdevice->busdev, die); w25m_dieSelect(fdevice->io.handle.busdev, die);
dieDevice[die].busdev = fdevice->busdev; dieDevice[die].io.handle.busdev = fdevice->io.handle.busdev;
dieDevice[die].io.mode = fdevice->io.mode;
m25p16_detect(&dieDevice[die], JEDEC_ID_WINBOND_W25Q256); m25p16_detect(&dieDevice[die], JEDEC_ID_WINBOND_W25Q256);
} }
@ -147,7 +148,7 @@ void w25m_eraseSector(flashDevice_t *fdevice, uint32_t address)
{ {
int dieNumber = address / dieSize; int dieNumber = address / dieSize;
w25m_dieSelect(fdevice->busdev, dieNumber); w25m_dieSelect(fdevice->io.handle.busdev, dieNumber);
dieDevice[dieNumber].vTable->eraseSector(&dieDevice[dieNumber], address % dieSize); dieDevice[dieNumber].vTable->eraseSector(&dieDevice[dieNumber], address % dieSize);
} }
@ -155,7 +156,7 @@ void w25m_eraseSector(flashDevice_t *fdevice, uint32_t address)
void w25m_eraseCompletely(flashDevice_t *fdevice) void w25m_eraseCompletely(flashDevice_t *fdevice)
{ {
for (int dieNumber = 0 ; dieNumber < dieCount ; dieNumber++) { for (int dieNumber = 0 ; dieNumber < dieCount ; dieNumber++) {
w25m_dieSelect(fdevice->busdev, dieNumber); w25m_dieSelect(fdevice->io.handle.busdev, dieNumber);
dieDevice[dieNumber].vTable->eraseCompletely(&dieDevice[dieNumber]); dieDevice[dieNumber].vTable->eraseCompletely(&dieDevice[dieNumber]);
} }
} }
@ -168,7 +169,7 @@ void w25m_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
UNUSED(fdevice); UNUSED(fdevice);
currentWriteDie = address / dieSize; currentWriteDie = address / dieSize;
w25m_dieSelect(fdevice->busdev, currentWriteDie); w25m_dieSelect(fdevice->io.handle.busdev, currentWriteDie);
currentWriteAddress = address % dieSize; currentWriteAddress = address % dieSize;
dieDevice[currentWriteDie].vTable->pageProgramBegin(&dieDevice[currentWriteDie], currentWriteAddress); dieDevice[currentWriteDie].vTable->pageProgramBegin(&dieDevice[currentWriteDie], currentWriteAddress);
} }
@ -210,7 +211,7 @@ int w25m_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, in
uint32_t dieAddress = address % dieSize; uint32_t dieAddress = address % dieSize;
tlen = MIN(dieAddress + rlen, dieSize) - dieAddress; tlen = MIN(dieAddress + rlen, dieSize) - dieAddress;
w25m_dieSelect(fdevice->busdev, dieNumber); w25m_dieSelect(fdevice->io.handle.busdev, dieNumber);
rbytes = dieDevice[dieNumber].vTable->readBytes(&dieDevice[dieNumber], dieAddress, buffer, tlen); rbytes = dieDevice[dieNumber].vTable->readBytes(&dieDevice[dieNumber], dieAddress, buffer, tlen);

View file

@ -33,6 +33,7 @@
#include "flash_impl.h" #include "flash_impl.h"
#include "flash_w25n01g.h" #include "flash_w25n01g.h"
#include "drivers/bus_spi.h" #include "drivers/bus_spi.h"
#include "drivers/bus_quadspi.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/time.h" #include "drivers/time.h"
@ -62,7 +63,9 @@ serialPort_t *debugSerialPort = NULL;
#define W25N01G_INSTRUCTION_RDID 0x9F #define W25N01G_INSTRUCTION_RDID 0x9F
#define W25N01G_INSTRUCTION_DEVICE_RESET 0xFF #define W25N01G_INSTRUCTION_DEVICE_RESET 0xFF
#define W25N01G_INSTRUCTION_READ_STATUS_REG 0x05 #define W25N01G_INSTRUCTION_READ_STATUS_REG 0x05
#define W25N01G_INSTRUCTION_READ_STATUS_ALTERNATE_REG 0x0F
#define W25N01G_INSTRUCTION_WRITE_STATUS_REG 0x01 #define W25N01G_INSTRUCTION_WRITE_STATUS_REG 0x01
#define W25N01G_INSTRUCTION_WRITE_STATUS_ALTERNATE_REG 0x1F
#define W25N01G_INSTRUCTION_WRITE_ENABLE 0x06 #define W25N01G_INSTRUCTION_WRITE_ENABLE 0x06
#define W25N01G_INSTRUCTION_DIE_SELECT 0xC2 #define W25N01G_INSTRUCTION_DIE_SELECT 0xC2
#define W25N01G_INSTRUCTION_BLOCK_ERASE 0xD8 #define W25N01G_INSTRUCTION_BLOCK_ERASE 0xD8
@ -74,6 +77,7 @@ serialPort_t *debugSerialPort = NULL;
#define W25N01G_INSTRUCTION_PAGE_DATA_READ 0x13 #define W25N01G_INSTRUCTION_PAGE_DATA_READ 0x13
#define W25N01G_INSTRUCTION_READ_DATA 0x03 #define W25N01G_INSTRUCTION_READ_DATA 0x03
#define W25N01G_INSTRUCTION_FAST_READ 0x1B #define W25N01G_INSTRUCTION_FAST_READ 0x1B
#define W25N01G_INSTRUCTION_FAST_READ_QUAD_OUTPUT 0x6B
// Configu/status register addresses // Configu/status register addresses
#define W25N01G_PROT_REG 0xA0 #define W25N01G_PROT_REG 0xA0
@ -94,6 +98,9 @@ serialPort_t *debugSerialPort = NULL;
#define W25N01G_STATUS_FLAG_WRITE_ENABLED (1 << 1) #define W25N01G_STATUS_FLAG_WRITE_ENABLED (1 << 1)
#define W25N01G_STATUS_FLAG_BUSY (1 << 0) #define W25N01G_STATUS_FLAG_BUSY (1 << 0)
#define W25N01G_BBLUT_TABLE_ENTRY_COUNT 20
#define W25N01G_BBLUT_TABLE_ENTRY_SIZE 4 // in bytes
// Bits in LBA for BB LUT // Bits in LBA for BB LUT
#define W25N01G_BBLUT_STATUS_ENABLED (1 << 15) #define W25N01G_BBLUT_STATUS_ENABLED (1 << 15)
#define W25N01G_BBLUT_STATUS_INVALID (1 << 14) #define W25N01G_BBLUT_STATUS_INVALID (1 << 14)
@ -116,6 +123,12 @@ serialPort_t *debugSerialPort = NULL;
#define W25N01G_TIMEOUT_PAGE_READ_MS 2 // tREmax = 60us (ECC enabled) #define W25N01G_TIMEOUT_PAGE_READ_MS 2 // tREmax = 60us (ECC enabled)
#define W25N01G_TIMEOUT_PAGE_PROGRAM_MS 2 // tPPmax = 700us #define W25N01G_TIMEOUT_PAGE_PROGRAM_MS 2 // tPPmax = 700us
#define W25N01G_TIMEOUT_BLOCK_ERASE_MS 15 // tBEmax = 10ms #define W25N01G_TIMEOUT_BLOCK_ERASE_MS 15 // tBEmax = 10ms
#define W25N01G_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms
// Sizes (in bits)
#define W28N01G_STATUS_REGISTER_SIZE 8
#define W28N01G_STATUS_PAGE_ADDRESS_SIZE 16
#define W28N01G_STATUS_COLUMN_ADDRESS_SIZE 16
typedef struct bblut_s { typedef struct bblut_s {
uint16_t pba; uint16_t pba;
@ -127,50 +140,125 @@ typedef struct bblut_s {
#define DISABLE(busdev) IOHi((busdev)->busdev_u.spi.csnPin); __NOP() #define DISABLE(busdev) IOHi((busdev)->busdev_u.spi.csnPin); __NOP()
#define ENABLE(busdev) __NOP(); IOLo((busdev)->busdev_u.spi.csnPin) #define ENABLE(busdev) __NOP(); IOLo((busdev)->busdev_u.spi.csnPin)
// XXX remove - add a forward declaration to keep git diff small while this is work-in-progress.
bool w25n01g_waitForReady(flashDevice_t *fdevice, uint32_t timeoutMillis);
/** /**
* Send the given command byte to the device. * Send the given command byte to the device.
*/ */
static void w25n01g_performOneByteCommand(busDevice_t *busdev, uint8_t command) static void w25n01g_performOneByteCommand(flashDeviceIO_t *io, uint8_t command)
{ {
if (io->mode == FLASHIO_SPI) {
busDevice_t *busdev = io->handle.busdev;
ENABLE(busdev); ENABLE(busdev);
spiTransferByte(busdev->busdev_u.spi.instance, command); spiTransferByte(busdev->busdev_u.spi.instance, command);
DISABLE(busdev); DISABLE(busdev);
}
#ifdef USE_QUADSPI
else if (io->mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
quadSpiTransmit1LINE(quadSpi, command, 0, NULL, 0);
}
#endif
} }
static uint8_t w25n01g_readRegister(busDevice_t *busdev, uint8_t reg) static void w25n01g_performCommandWithPageAddress(flashDeviceIO_t *io, uint8_t command, uint32_t pageAddress)
{ {
if (io->mode == FLASHIO_SPI) {
busDevice_t *busdev = io->handle.busdev;
const uint8_t cmd[] = { command, 0, (pageAddress >> 8) & 0xff, (pageAddress >> 0) & 0xff};
ENABLE(busdev);
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
DISABLE(busdev);
}
#ifdef USE_QUADSPI
else if (io->mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
quadSpiInstructionWithAddress1LINE(quadSpi, command, 0, pageAddress & 0xffff, W28N01G_STATUS_PAGE_ADDRESS_SIZE + 8);
}
#endif
}
static uint8_t w25n01g_readRegister(flashDeviceIO_t *io, uint8_t reg)
{
if (io->mode == FLASHIO_SPI) {
busDevice_t *busdev = io->handle.busdev;
ENABLE(busdev);
const uint8_t cmd[3] = { W25N01G_INSTRUCTION_READ_STATUS_REG, reg, 0 }; const uint8_t cmd[3] = { W25N01G_INSTRUCTION_READ_STATUS_REG, reg, 0 };
uint8_t in[3]; uint8_t in[3];
ENABLE(busdev);
spiTransfer(busdev->busdev_u.spi.instance, cmd, in, sizeof(cmd)); spiTransfer(busdev->busdev_u.spi.instance, cmd, in, sizeof(cmd));
DISABLE(busdev); DISABLE(busdev);
return in[2]; return in[2];
}
#ifdef USE_QUADSPI
else if (io->mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
uint8_t in[1];
quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_STATUS_REG, 0, reg, W28N01G_STATUS_REGISTER_SIZE, in, sizeof(in));
return in[0];
}
#endif
return 0;
} }
static void w25n01g_writeRegister(busDevice_t *busdev, uint8_t reg, uint8_t data) static void w25n01g_writeRegister(flashDeviceIO_t *io, uint8_t reg, uint8_t data)
{ {
if (io->mode == FLASHIO_SPI) {
busDevice_t *busdev = io->handle.busdev;
const uint8_t cmd[3] = { W25N01G_INSTRUCTION_WRITE_STATUS_REG, reg, data }; const uint8_t cmd[3] = { W25N01G_INSTRUCTION_WRITE_STATUS_REG, reg, data };
ENABLE(busdev); ENABLE(busdev);
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd)); spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
DISABLE(busdev); DISABLE(busdev);
}
#ifdef USE_QUADSPI
else if (io->mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_WRITE_STATUS_REG, 0, reg, W28N01G_STATUS_REGISTER_SIZE, &data, 1);
}
#endif
} }
static void w25n01g_deviceReset(busDevice_t *busdev)
static void w25n01g_deviceReset(flashDevice_t *fdevice)
{ {
w25n01g_performOneByteCommand(busdev, W25N01G_INSTRUCTION_DEVICE_RESET); flashDeviceIO_t *io = &fdevice->io;
w25n01g_performOneByteCommand(io, W25N01G_INSTRUCTION_DEVICE_RESET);
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_RESET_MS);
// Protection for upper 1/32 (BP[3:0] = 0101, TB=0), WP-E on; to protect bad block replacement area // Protection for upper 1/32 (BP[3:0] = 0101, TB=0), WP-E on; to protect bad block replacement area
// DON'T DO THIS. This will prevent writes through the bblut as well. // DON'T DO THIS. This will prevent writes through the bblut as well.
// w25n01g_writeRegister(busdev, W25N01G_PROT_REG, (5 << 3)|(0 << 2)|(1 << 1)); // w25n01g_writeRegister(busdev, W25N01G_PROT_REG, (5 << 3)|(0 << 2)|(1 << 1));
// No protection, WP-E on uint8_t value = (0 << 3)|(0 << 2); // No protection
w25n01g_writeRegister(busdev, W25N01G_PROT_REG, (0 << 3)|(0 << 2)|(1 << 1));
if (io->mode == FLASHIO_SPI) {
value |= (1 << 1); // WP-E on
}
#ifdef USE_QUADSPI
else if (io->mode == FLASHIO_QUADSPI) {
value |= (0 << 1); // WP-E off, WP-E prevents use of IO2
}
#endif
w25n01g_writeRegister(io, W25N01G_PROT_REG, value);
// Buffered read mode (BUF = 1), ECC enabled (ECC = 1) // Buffered read mode (BUF = 1), ECC enabled (ECC = 1)
w25n01g_writeRegister(busdev, W25N01G_CONF_REG, W25N01G_CONFIG_ECC_ENABLE|W25N01G_CONFIG_BUFFER_READ_MODE); w25n01g_writeRegister(io, W25N01G_CONF_REG, W25N01G_CONFIG_ECC_ENABLE|W25N01G_CONFIG_BUFFER_READ_MODE);
} }
bool w25n01g_isReady(flashDevice_t *fdevice) bool w25n01g_isReady(flashDevice_t *fdevice)
@ -179,11 +267,11 @@ bool w25n01g_isReady(flashDevice_t *fdevice)
#if 0 #if 0
// 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
fdevice->couldBeBusy = fdevice->couldBeBusy && ((w25n01g_readRegister(fdevice->busdev, W25N01G_STAT_REG) & W25N01G_STATUS_FLAG_BUSY) != 0); fdevice->couldBeBusy = fdevice->couldBeBusy && ((w25n01g_readRegister(fdevice->handle.busdev, W25N01G_STAT_REG) & W25N01G_STATUS_FLAG_BUSY) != 0);
return !couldBeBusy; return !couldBeBusy;
#else #else
uint8_t status = w25n01g_readRegister(fdevice->busdev, W25N01G_STAT_REG); uint8_t status = w25n01g_readRegister(&fdevice->io, W25N01G_STAT_REG);
if (status & W25N01G_STATUS_PROGRAM_FAIL) { if (status & W25N01G_STATUS_PROGRAM_FAIL) {
DPRINTF(("*** PROGRAM_FAIL\r\n")); DPRINTF(("*** PROGRAM_FAIL\r\n"));
@ -221,7 +309,7 @@ bool w25n01g_waitForReady(flashDevice_t *fdevice, uint32_t timeoutMillis)
*/ */
static void w25n01g_writeEnable(flashDevice_t *fdevice) static void w25n01g_writeEnable(flashDevice_t *fdevice)
{ {
w25n01g_performOneByteCommand(fdevice->busdev, W25N01G_INSTRUCTION_WRITE_ENABLE); w25n01g_performOneByteCommand(&fdevice->io, W25N01G_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
fdevice->couldBeBusy = true; fdevice->couldBeBusy = true;
@ -272,7 +360,7 @@ bool w25n01g_detect(flashDevice_t *fdevice, uint32_t chipID)
fdevice->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
w25n01g_deviceReset(fdevice->busdev); w25n01g_deviceReset(fdevice);
// Upper 4MB (32 blocks * 128KB/block) will be used for bad block replacement area. // Upper 4MB (32 blocks * 128KB/block) will be used for bad block replacement area.
@ -290,21 +378,21 @@ bool w25n01g_detect(flashDevice_t *fdevice, uint32_t chipID)
#if 0 #if 0
// Protection to upper 1/32 (BP[3:0] = 0101, TB=0), WP-E on // Protection to upper 1/32 (BP[3:0] = 0101, TB=0), WP-E on
//w25n01g_writeRegister(fdevice->busdev, W25N01G_PROT_REG, (5 << 3)|(0 << 2)|(1 << 1)); //w25n01g_writeRegister(fdevice->handle.busdev, W25N01G_PROT_REG, (5 << 3)|(0 << 2)|(1 << 1));
// No protection, WP-E on // No protection, WP-E on
w25n01g_writeRegister(fdevice->busdev, W25N01G_PROT_REG, (0 << 3)|(0 << 2)|(1 << 1)); w25n01g_writeRegister(fdevice->handle, W25N01G_PROT_REG, (0 << 3)|(0 << 2)|(1 << 1));
// Continuous mode (BUF = 0), ECC enabled (ECC = 1) // Continuous mode (BUF = 0), ECC enabled (ECC = 1)
w25n01g_writeRegister(fdevice->busdev, W25N01G_CONF_REG, W25N01G_CONFIG_ECC_ENABLE); w25n01g_writeRegister(fdevice->handle, W25N01G_CONF_REG, W25N01G_CONFIG_ECC_ENABLE);
#endif #endif
#if 0 #if 0
// XXX Should be gone in production // XXX Should be gone in production
uint8_t sr1, sr2, sr3; uint8_t sr1, sr2, sr3;
sr1 = w25n01g_readRegister(fdevice->busdev, W25N01G_PROT_REG); sr1 = w25n01g_readRegister(fdevice->handle.busdev, W25N01G_PROT_REG);
sr2 = w25n01g_readRegister(fdevice->busdev, W25N01G_CONF_REG); sr2 = w25n01g_readRegister(fdevice->handle.busdev, W25N01G_CONF_REG);
sr3 = w25n01g_readRegister(fdevice->busdev, W25N01G_STAT_REG); sr3 = w25n01g_readRegister(fdevice->handle.busdev, W25N01G_STAT_REG);
debug[1] = sr1; debug[1] = sr1;
debug[2] = sr2; debug[2] = sr2;
@ -325,15 +413,12 @@ bool w25n01g_detect(flashDevice_t *fdevice, uint32_t chipID)
*/ */
void w25n01g_eraseSector(flashDevice_t *fdevice, uint32_t address) void w25n01g_eraseSector(flashDevice_t *fdevice, uint32_t address)
{ {
const uint8_t cmd[] = { W25N01G_INSTRUCTION_BLOCK_ERASE, 0, W25N01G_LINEAR_TO_PAGE(address) >> 8, W25N01G_LINEAR_TO_PAGE(address) & 0xff };
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_BLOCK_ERASE_MS); w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_BLOCK_ERASE_MS);
w25n01g_writeEnable(fdevice); w25n01g_writeEnable(fdevice);
ENABLE(fdevice->busdev); w25n01g_performCommandWithPageAddress(&fdevice->io, W25N01G_INSTRUCTION_BLOCK_ERASE, W25N01G_LINEAR_TO_PAGE(address));
spiTransfer(fdevice->busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
DISABLE(fdevice->busdev);
} }
// //
@ -343,55 +428,74 @@ void w25n01g_eraseSector(flashDevice_t *fdevice, uint32_t address)
void w25n01g_eraseCompletely(flashDevice_t *fdevice) void w25n01g_eraseCompletely(flashDevice_t *fdevice)
{ {
for (uint32_t block = 0; block < fdevice->geometry.sectors; block++) { for (uint32_t block = 0; block < fdevice->geometry.sectors; block++) {
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_BLOCK_ERASE_MS);
// Issue erase block command
w25n01g_writeEnable(fdevice);
w25n01g_eraseSector(fdevice, W25N01G_BLOCK_TO_LINEAR(block)); w25n01g_eraseSector(fdevice, W25N01G_BLOCK_TO_LINEAR(block));
} }
} }
static void w25n01g_programDataLoad(flashDevice_t *fdevice, uint16_t columnAddress, const uint8_t *data, int length) static void w25n01g_programDataLoad(flashDevice_t *fdevice, uint16_t columnAddress, const uint8_t *data, int length)
{ {
const uint8_t cmd[] = { W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress& 0xff };
//DPRINTF((" load WaitForReady\r\n")); //DPRINTF((" load WaitForReady\r\n"));
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS); w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS);
//DPRINTF((" load Issuing command\r\n")); //DPRINTF((" load Issuing command\r\n"));
ENABLE(fdevice->busdev);
spiTransfer(fdevice->busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd)); if (fdevice->io.mode == FLASHIO_SPI) {
spiTransfer(fdevice->busdev->busdev_u.spi.instance, data, NULL, length); busDevice_t *busdev = fdevice->io.handle.busdev;
DISABLE(fdevice->busdev); const uint8_t cmd[] = { W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff };
ENABLE(busdev);
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
spiTransfer(busdev->busdev_u.spi.instance, data, NULL, length);
DISABLE(busdev);
}
#ifdef USE_QUADSPI
else if (fdevice->io.mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, 0, columnAddress, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, data, length);
}
#endif
//DPRINTF((" load Done\r\n")); //DPRINTF((" load Done\r\n"));
} }
static void w25n01g_randomProgramDataLoad(flashDevice_t *fdevice, uint16_t columnAddress, const uint8_t *data, int length) static void w25n01g_randomProgramDataLoad(flashDevice_t *fdevice, uint16_t columnAddress, const uint8_t *data, int length)
{ {
const uint8_t cmd[] = { W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress& 0xff }; const uint8_t cmd[] = { W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff };
//DPRINTF((" random WaitForReady\r\n")); //DPRINTF((" random WaitForReady\r\n"));
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS); w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS);
//DPRINTF((" random Issuing command\r\n")); //DPRINTF((" random Issuing command\r\n"));
ENABLE(fdevice->busdev); if (fdevice->io.mode == FLASHIO_SPI) {
spiTransfer(fdevice->busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd)); busDevice_t *busdev = fdevice->io.handle.busdev;
spiTransfer(fdevice->busdev->busdev_u.spi.instance, data, NULL, length);
DISABLE(fdevice->busdev); ENABLE(busdev);
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
spiTransfer(busdev->busdev_u.spi.instance, data, NULL, length);
DISABLE(busdev);
}
#ifdef USE_QUADSPI
else if (fdevice->io.mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, 0, columnAddress, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, data, length);
}
#endif
//DPRINTF((" random Done\r\n")); //DPRINTF((" random Done\r\n"));
} }
static void w25n01g_programExecute(flashDevice_t *fdevice, uint32_t pageAddress) static void w25n01g_programExecute(flashDevice_t *fdevice, uint32_t pageAddress)
{ {
const uint8_t cmd[] = { W25N01G_INSTRUCTION_PROGRAM_EXECUTE, 0, pageAddress >> 8, pageAddress & 0xff };
//DPRINTF((" execute WaitForReady\r\n")); //DPRINTF((" execute WaitForReady\r\n"));
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS); w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS);
//DPRINTF((" execute Issueing command\r\n")); //DPRINTF((" execute Issuing command\r\n"));
ENABLE(fdevice->busdev);
spiTransfer(fdevice->busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd)); w25n01g_performCommandWithPageAddress(&fdevice->io, W25N01G_INSTRUCTION_PROGRAM_EXECUTE, pageAddress);
DISABLE(fdevice->busdev);
//DPRINTF((" execute Done\r\n")); //DPRINTF((" execute Done\r\n"));
} }
@ -507,9 +611,10 @@ void w25n01g_pageProgramFinish(flashDevice_t *fdevice)
PAGEPROG_DPRINTF(("pageProgramFinish: (loaded 0x%x bytes)\r\n", programLoadAddress - programStartAddress)); PAGEPROG_DPRINTF(("pageProgramFinish: (loaded 0x%x bytes)\r\n", programLoadAddress - programStartAddress));
if (bufferDirty && W25N01G_LINEAR_TO_COLUMN(programLoadAddress) == 0) { if (bufferDirty && W25N01G_LINEAR_TO_COLUMN(programLoadAddress) == 0) {
currentPage = W25N01G_LINEAR_TO_PAGE(programStartAddress); // reset page to the page being written
PAGEPROG_DPRINTF((" PROGRAM_EXECUTE PA 0x%x\r\n", W25N01G_LINEAR_TO_PAGE(programStartAddress)));
currentPage = W25N01G_LINEAR_TO_PAGE(programStartAddress); // reset page to the page being written
PAGEPROG_DPRINTF((" PROGRAM_EXECUTE PA 0x%x\r\n", W25N01G_LINEAR_TO_PAGE(programStartAddress)));
w25n01g_programExecute(fdevice, W25N01G_LINEAR_TO_PAGE(programStartAddress)); w25n01g_programExecute(fdevice, W25N01G_LINEAR_TO_PAGE(programStartAddress));
bufferDirty = false; bufferDirty = false;
@ -596,8 +701,6 @@ void w25n01g_addError(uint32_t address, uint8_t code)
int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length) int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
{ {
uint8_t cmd[4];
READBYTES_DPRINTF(("readBytes: address 0x%x length %d\r\n", address, length)); READBYTES_DPRINTF(("readBytes: address 0x%x length %d\r\n", address, length));
uint32_t targetPage = W25N01G_LINEAR_TO_PAGE(address); uint32_t targetPage = W25N01G_LINEAR_TO_PAGE(address);
@ -605,10 +708,6 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
if (currentPage != targetPage) { if (currentPage != targetPage) {
READBYTES_DPRINTF(("readBytes: PAGE_DATA_READ page 0x%x\r\n", targetPage)); READBYTES_DPRINTF(("readBytes: PAGE_DATA_READ page 0x%x\r\n", targetPage));
cmd[0] = W25N01G_INSTRUCTION_PAGE_DATA_READ;
cmd[1] = 0;
cmd[2] = targetPage >> 8;
cmd[3] = targetPage;
if (!w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS)) { if (!w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS)) {
return 0; return 0;
@ -616,9 +715,7 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
currentPage = UINT32_MAX; currentPage = UINT32_MAX;
ENABLE(fdevice->busdev); w25n01g_performCommandWithPageAddress(&fdevice->io, W25N01G_INSTRUCTION_PAGE_DATA_READ, targetPage);
spiTransfer(fdevice->busdev->busdev_u.spi.instance, cmd, NULL, 4);
DISABLE(fdevice->busdev);
if (!w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS)) { if (!w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS)) {
return 0; return 0;
@ -636,17 +733,31 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
transferLength = length; transferLength = length;
} }
cmd[0] = W25N01G_INSTRUCTION_READ_DATA;
cmd[1] = column >> 8;
cmd[2] = column;
cmd[3] = 0;
READBYTES_DPRINTF(("readBytes: READ_DATA column 0x%x transferLength 0x%x\r\n", column, transferLength)); READBYTES_DPRINTF(("readBytes: READ_DATA column 0x%x transferLength 0x%x\r\n", column, transferLength));
ENABLE(fdevice->busdev); if (fdevice->io.mode == FLASHIO_SPI) {
spiTransfer(fdevice->busdev->busdev_u.spi.instance, cmd, NULL, 4); busDevice_t *busdev = fdevice->io.handle.busdev;
spiTransfer(fdevice->busdev->busdev_u.spi.instance, NULL, buffer, length);
DISABLE(fdevice->busdev); uint8_t cmd[4];
cmd[0] = W25N01G_INSTRUCTION_READ_DATA;
cmd[1] = (column >> 8) & 0xff;
cmd[2] = (column >> 0) & 0xff;
cmd[3] = 0;
ENABLE(busdev);
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
spiTransfer(busdev->busdev_u.spi.instance, NULL, buffer, length);
DISABLE(busdev);
}
#ifdef USE_QUADSPI
else if (fdevice->io.mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
//quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_DATA, 8, column, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length);
quadSpiReceiveWithAddress4LINES(quadSpi, W25N01G_INSTRUCTION_FAST_READ_QUAD_OUTPUT, 8, column, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length);
}
#endif
// XXX Don't need this? // XXX Don't need this?
if (!w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS)) { if (!w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS)) {
@ -655,7 +766,7 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
// Check ECC // Check ECC
uint8_t statReg = w25n01g_readRegister(fdevice->busdev, W25N01G_STAT_REG); uint8_t statReg = w25n01g_readRegister(&fdevice->io, W25N01G_STAT_REG);
uint8_t eccCode = W25N01G_STATUS_FLAG_ECC(statReg); uint8_t eccCode = W25N01G_STATUS_FLAG_ECC(statReg);
switch (eccCode) { switch (eccCode) {
@ -665,7 +776,7 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
case 2: // Uncorrectable ECC in a single page case 2: // Uncorrectable ECC in a single page
case 3: // Uncorrectable ECC in multiple pages case 3: // Uncorrectable ECC in multiple pages
w25n01g_addError(address, eccCode); w25n01g_addError(address, eccCode);
w25n01g_deviceReset(fdevice->busdev); w25n01g_deviceReset(fdevice);
break; break;
} }
@ -676,30 +787,37 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
int w25n01g_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length) int w25n01g_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
{ {
uint8_t cmd[4];
cmd[0] = W25N01G_INSTRUCTION_PAGE_DATA_READ; w25n01g_performCommandWithPageAddress(&fdevice->io, W25N01G_INSTRUCTION_PAGE_DATA_READ, W25N01G_LINEAR_TO_PAGE(address));
cmd[1] = 0;
cmd[2] = W25N01G_LINEAR_TO_PAGE(address) >> 8;
cmd[3] = W25N01G_LINEAR_TO_PAGE(address);
ENABLE(fdevice->busdev);
spiTransfer(fdevice->busdev->busdev_u.spi.instance, cmd, NULL, 4);
DISABLE(fdevice->busdev);
if (!w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS)) { if (!w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS)) {
return 0; return 0;
} }
cmd[0] = W25N01G_INSTRUCTION_READ_DATA; uint32_t column = 2048;
cmd[1] = 0;
cmd[2] = (2048 >> 8) & 0xff;
cmd[3] = 2048 & 0xff;
ENABLE(fdevice->busdev); if (fdevice->io.mode == FLASHIO_SPI) {
spiTransfer(fdevice->busdev->busdev_u.spi.instance, cmd, NULL, 4); busDevice_t *busdev = fdevice->io.handle.busdev;
spiTransfer(fdevice->busdev->busdev_u.spi.instance, NULL, buffer, length);
DISABLE(fdevice->busdev); uint8_t cmd[4];
cmd[0] = W25N01G_INSTRUCTION_READ_DATA;
cmd[1] = (column >> 8) & 0xff;
cmd[2] = (column >> 0) & 0xff;
cmd[3] = 0;
ENABLE(busdev);
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
spiTransfer(busdev->busdev_u.spi.instance, NULL, buffer, length);
DISABLE(busdev);
}
#ifdef USE_QUADSPI
else if (fdevice->io.mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_DATA, 8, column, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length);
}
#endif
return length; return length;
} }
@ -730,32 +848,68 @@ const flashVTable_t w25n01g_vTable = {
void w25n01g_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize) void w25n01g_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
{ {
uint8_t cmd[4];
uint8_t in[4]; uint8_t in[4];
if (fdevice->io.mode == FLASHIO_SPI) {
busDevice_t *busdev = fdevice->io.handle.busdev;
uint8_t cmd[4];
cmd[0] = W25N01G_INSTRUCTION_READ_BBM_LUT; cmd[0] = W25N01G_INSTRUCTION_READ_BBM_LUT;
cmd[1] = 0; cmd[1] = 0;
ENABLE(fdevice->busdev); ENABLE(busdev);
spiTransfer(fdevice->busdev->busdev_u.spi.instance, cmd, NULL, 2); spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, 2);
for (int i = 0 ; i < lutsize ; i++) { for (int i = 0 ; i < lutsize ; i++) {
spiTransfer(fdevice->busdev->busdev_u.spi.instance, NULL, in, 4); spiTransfer(busdev->busdev_u.spi.instance, NULL, in, 4);
bblut[i].pba = (in[0] << 16)|in[1]; bblut[i].pba = (in[0] << 16)|in[1];
bblut[i].lba = (in[2] << 16)|in[3]; bblut[i].lba = (in[2] << 16)|in[3];
} }
DISABLE(fdevice->busdev); DISABLE(busdev);
}
#ifdef USE_QUADSPI
else if (fdevice->io.mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
// Note: Using HAL QuadSPI there doesn't appear to be a way to send 2 bytes, then blocks of 4 bytes, while keeping the CS line LOW
// thus, we have to read the entire BBLUT in one go and process the result.
uint8_t bblutBuffer[W25N01G_BBLUT_TABLE_ENTRY_COUNT * W25N01G_BBLUT_TABLE_ENTRY_SIZE];
quadSpiReceive1LINE(quadSpi, W25N01G_INSTRUCTION_READ_BBM_LUT, 8, bblutBuffer, sizeof(bblutBuffer));
for (int i = 0, offset = 0 ; i < lutsize ; i++, offset += 4) {
if (i < W25N01G_BBLUT_TABLE_ENTRY_COUNT) {
bblut[i].pba = (in[offset + 0] << 16)|in[offset + 1];
bblut[i].lba = (in[offset + 2] << 16)|in[offset + 3];
}
}
}
#endif
} }
void w25n01g_writeBBLUT(flashDevice_t *fdevice, uint16_t lba, uint16_t pba) void w25n01g_writeBBLUT(flashDevice_t *fdevice, uint16_t lba, uint16_t pba)
{ {
if (fdevice->io.mode == FLASHIO_SPI) {
busDevice_t *busdev = fdevice->io.handle.busdev;
uint8_t cmd[5] = { W25N01G_INSTRUCTION_BB_MANAGEMENT, lba >> 8, lba, pba >> 8, pba }; uint8_t cmd[5] = { W25N01G_INSTRUCTION_BB_MANAGEMENT, lba >> 8, lba, pba >> 8, pba };
ENABLE(fdevice->busdev); ENABLE(busdev);
spiTransfer(fdevice->busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd)); spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
DISABLE(fdevice->busdev); DISABLE(busdev);
}
#ifdef USE_QUADSPI
else if (fdevice->io.mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
uint8_t data[4] = { lba >> 8, lba, pba >> 8, pba };
quadSpiInstructionWithData1LINE(quadSpi, W25N01G_INSTRUCTION_BB_MANAGEMENT, 0, data, sizeof(data));
}
#endif
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS); w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS);
} }

View file

@ -26,6 +26,7 @@
#ifdef USE_FLASH_CHIP #ifdef USE_FLASH_CHIP
#include "drivers/bus_spi.h" #include "drivers/bus_spi.h"
#include "drivers/bus_quadspi.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "pg/pg.h" #include "pg/pg.h"
@ -33,11 +34,20 @@
#include "flash.h" #include "flash.h"
#ifndef FLASH_CS_PIN
#define FLASH_CS_PIN NONE
#endif
PG_REGISTER_WITH_RESET_FN(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0); PG_REGISTER_WITH_RESET_FN(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0);
void pgResetFn_flashConfig(flashConfig_t *flashConfig) void pgResetFn_flashConfig(flashConfig_t *flashConfig)
{ {
flashConfig->csTag = IO_TAG(FLASH_CS_PIN); flashConfig->csTag = IO_TAG(FLASH_CS_PIN);
#if defined(USE_SPI) && defined(FLASH_SPI_INSTANCE)
flashConfig->spiDevice = SPI_DEV_TO_CFG(spiDeviceByInstance(FLASH_SPI_INSTANCE)); flashConfig->spiDevice = SPI_DEV_TO_CFG(spiDeviceByInstance(FLASH_SPI_INSTANCE));
#endif
#if defined(USE_QUADSPI) && defined(FLASH_QUADSPI_INSTANCE)
flashConfig->quadSpiDevice = QUADSPI_DEV_TO_CFG(quadSpiDeviceByInstance(FLASH_QUADSPI_INSTANCE));
#endif
} }
#endif #endif

View file

@ -29,6 +29,7 @@
typedef struct flashConfig_s { typedef struct flashConfig_s {
ioTag_t csTag; ioTag_t csTag;
uint8_t spiDevice; uint8_t spiDevice;
uint8_t quadSpiDevice;
} flashConfig_t; } flashConfig_t;
PG_DECLARE(flashConfig_t, flashConfig); PG_DECLARE(flashConfig_t, flashConfig);