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

Add support for W25N02K 2Gbit/256Mbyte FLASH (#13677)

* Add support for W25N02K 2Gbit/256Mbyte FLASH

* Remove duplicate defintion check

* Rename W25N01G_BB_*_BLOCK macros

* Remove debug

* Create unified driver for W25N01G and W25N02K devices

* Put device parameters in a table

* Add W25N01GV to stacked die driver
This commit is contained in:
Steve Evans 2024-06-08 23:30:33 +01:00 committed by GitHub
parent 6080bffccc
commit ab022b0467
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
7 changed files with 268 additions and 256 deletions

View file

@ -247,7 +247,7 @@ RX_SRC = \
FLASH_SRC += \ FLASH_SRC += \
drivers/flash.c \ drivers/flash.c \
drivers/flash_m25p16.c \ drivers/flash_m25p16.c \
drivers/flash_w25n01g.c \ drivers/flash_w25n.c \
drivers/flash_w25q128fv.c \ drivers/flash_w25q128fv.c \
drivers/flash_w25m.c \ drivers/flash_w25m.c \
io/flashfs.c io/flashfs.c

View file

@ -31,7 +31,7 @@
#include "flash.h" #include "flash.h"
#include "flash_impl.h" #include "flash_impl.h"
#include "flash_m25p16.h" #include "flash_m25p16.h"
#include "flash_w25n01g.h" #include "flash_w25n.h"
#include "flash_w25q128fv.h" #include "flash_w25q128fv.h"
#include "flash_w25m.h" #include "flash_w25m.h"
#include "drivers/bus_spi.h" #include "drivers/bus_spi.h"
@ -162,8 +162,8 @@ MMFLASH_CODE_NOINLINE static bool flashOctoSpiInit(const flashConfig_t *flashCon
#ifdef USE_OCTOSPI_EXPERIMENTAL #ifdef USE_OCTOSPI_EXPERIMENTAL
if (!memoryMappedModeEnabledOnBoot) { if (!memoryMappedModeEnabledOnBoot) {
// These flash chips DO NOT support memory mapped mode; suitable flash read commands must be available. // These flash chips DO NOT support memory mapped mode; suitable flash read commands must be available.
#if defined(USE_FLASH_W25N01G) #if defined(USE_FLASH_W25N01G) || defined(USE_FLASH_W25N02K)
if (!detected && w25n01g_identify(&flashDevice, jedecID)) { if (!detected && w25n_identify(&flashDevice, jedecID)) {
detected = true; detected = true;
} }
#endif #endif
@ -247,7 +247,7 @@ static bool flashQuadSpiInit(const flashConfig_t *flashConfig)
if (offset == 1) { if (offset == 1) {
#if defined(USE_FLASH_W25N01G) #if defined(USE_FLASH_W25N01G)
if (!detected && w25n01g_identify(&flashDevice, jedecID)) { if (!detected && w25n_identify(&flashDevice, jedecID)) {
detected = true; detected = true;
} }
#endif #endif
@ -333,8 +333,8 @@ static bool flashSpiInit(const flashConfig_t *flashConfig)
jedecID = (readIdResponse[1] << 16) | (readIdResponse[2] << 8) | (readIdResponse[3]); jedecID = (readIdResponse[1] << 16) | (readIdResponse[2] << 8) | (readIdResponse[3]);
} }
#ifdef USE_FLASH_W25N01G #ifdef USE_FLASH_W25N
if (!detected && w25n01g_identify(&flashDevice, jedecID)) { if (!detected && w25n_identify(&flashDevice, jedecID)) {
detected = true; detected = true;
} }
#endif #endif

View file

@ -43,7 +43,7 @@
#include "flash_m25p16.h" #include "flash_m25p16.h"
#include "flash_w25m.h" #include "flash_w25m.h"
#include "flash_w25n01g.h" #include "flash_w25n.h"
#include "pg/flash.h" #include "pg/flash.h"
@ -52,6 +52,7 @@
#define JEDEC_ID_WINBOND_W25M512 0xEF7119 // W25Q256 x 2 #define JEDEC_ID_WINBOND_W25M512 0xEF7119 // W25Q256 x 2
#define JEDEC_ID_WINBOND_W25M02G 0xEFAB21 // W25N01G x 2 #define JEDEC_ID_WINBOND_W25M02G 0xEFAB21 // W25N01G x 2
#define JEDEC_ID_WINBOND_W25Q256 0xEF4019 #define JEDEC_ID_WINBOND_W25Q256 0xEF4019
#define JEDEC_ID_WINBOND_W25N01GV 0xEFAA21
static const flashVTable_t w25m_vTable; static const flashVTable_t w25m_vTable;
@ -143,7 +144,7 @@ bool w25m_identify(flashDevice_t *fdevice, uint32_t jedecID)
w25m_dieSelect(fdevice->io.handle.dev, die); w25m_dieSelect(fdevice->io.handle.dev, die);
dieDevice[die].io.handle.dev = fdevice->io.handle.dev; dieDevice[die].io.handle.dev = fdevice->io.handle.dev;
dieDevice[die].io.mode = fdevice->io.mode; dieDevice[die].io.mode = fdevice->io.mode;
w25n01g_identify(&dieDevice[die], JEDEC_ID_WINBOND_W25N01GV); w25n_identify(&dieDevice[die], JEDEC_ID_WINBOND_W25N01GV);
} }
fdevice->geometry.flashType = FLASH_TYPE_NAND; fdevice->geometry.flashType = FLASH_TYPE_NAND;

View file

@ -25,117 +25,128 @@
#include "platform.h" #include "platform.h"
#ifdef USE_FLASH_W25N01G #ifdef USE_FLASH_W25N
#include "flash.h" #include "flash.h"
#include "flash_impl.h" #include "flash_impl.h"
#include "flash_w25n01g.h" #include "flash_w25n.h"
#include "drivers/bus_spi.h" #include "drivers/bus_spi.h"
#include "drivers/bus_quadspi.h" #include "drivers/bus_quadspi.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/time.h" #include "drivers/time.h"
// Device size parameters
#define W25N01G_PAGE_SIZE 2048
#define W25N01G_PAGES_PER_BLOCK 64
#define W25N01G_BLOCKS_PER_DIE 1024
// BB replacement area // BB replacement area
#define W25N01G_BB_MARKER_BLOCKS 1 #define W25N_BB_MARKER_BLOCKS 1
#define W25N01G_BB_REPLACEMENT_BLOCKS 20 #define W25N_BB_REPLACEMENT_BLOCKS 20
#define W25N01G_BB_MANAGEMENT_BLOCKS (W25N01G_BB_REPLACEMENT_BLOCKS + W25N01G_BB_MARKER_BLOCKS) #define W25N_BB_MANAGEMENT_BLOCKS (W25N_BB_REPLACEMENT_BLOCKS + W25N_BB_MARKER_BLOCKS)
// blocks are zero-based index // blocks are zero-based index
#define W25N01G_BB_REPLACEMENT_START_BLOCK (W25N01G_BLOCKS_PER_DIE - W25N01G_BB_REPLACEMENT_BLOCKS) #define W25N_BB_REPLACEMENT_START_BLOCK (fdevice->geometry.sectors - W25N_BB_REPLACEMENT_BLOCKS)
#define W25N01G_BB_MANAGEMENT_START_BLOCK (W25N01G_BLOCKS_PER_DIE - W25N01G_BB_MANAGEMENT_BLOCKS) #define W25N_BB_MANAGEMENT_START_BLOCK (fdevice->geometry.sectors - W25N_BB_MANAGEMENT_BLOCKS)
#define W25N01G_BB_MARKER_BLOCK (W25N01G_BB_REPLACEMENT_START_BLOCK - W25N01G_BB_MARKER_BLOCKS)
// Instructions // Instructions
#define W25N01G_INSTRUCTION_RDID 0x9F #define W25N_INSTRUCTION_RDID 0x9F
#define W25N01G_INSTRUCTION_DEVICE_RESET 0xFF #define W25N_INSTRUCTION_DEVICE_RESET 0xFF
#define W25N01G_INSTRUCTION_READ_STATUS_REG 0x05 #define W25N_INSTRUCTION_READ_STATUS_REG 0x05
#define W25N01G_INSTRUCTION_READ_STATUS_ALTERNATE_REG 0x0F #define W25N_INSTRUCTION_READ_STATUS_ALTERNATE_REG 0x0F
#define W25N01G_INSTRUCTION_WRITE_STATUS_REG 0x01 #define W25N_INSTRUCTION_WRITE_STATUS_REG 0x01
#define W25N01G_INSTRUCTION_WRITE_STATUS_ALTERNATE_REG 0x1F #define W25N_INSTRUCTION_WRITE_STATUS_ALTERNATE_REG 0x1F
#define W25N01G_INSTRUCTION_WRITE_ENABLE 0x06 #define W25N_INSTRUCTION_WRITE_ENABLE 0x06
#define W25N01G_INSTRUCTION_DIE_SELECT 0xC2 #define W25N_INSTRUCTION_DIE_SELECT 0xC2
#define W25N01G_INSTRUCTION_BLOCK_ERASE 0xD8 #define W25N_INSTRUCTION_BLOCK_ERASE 0xD8
#define W25N01G_INSTRUCTION_READ_BBM_LUT 0xA5 #define W25N_INSTRUCTION_READ_BBM_LUT 0xA5
#define W25N01G_INSTRUCTION_BB_MANAGEMENT 0xA1 #define W25N_INSTRUCTION_BB_MANAGEMENT 0xA1
#define W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD 0x02 #define W25N_INSTRUCTION_PROGRAM_DATA_LOAD 0x02
#define W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD 0x84 #define W25N_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD 0x84
#define W25N01G_INSTRUCTION_PROGRAM_EXECUTE 0x10 #define W25N_INSTRUCTION_PROGRAM_EXECUTE 0x10
#define W25N01G_INSTRUCTION_PAGE_DATA_READ 0x13 #define W25N_INSTRUCTION_PAGE_DATA_READ 0x13
#define W25N01G_INSTRUCTION_READ_DATA 0x03 #define W25N_INSTRUCTION_READ_DATA 0x03
#define W25N01G_INSTRUCTION_FAST_READ 0x1B #define W25N_INSTRUCTION_FAST_READ 0x1B
#define W25N01G_INSTRUCTION_FAST_READ_QUAD_OUTPUT 0x6B #define W25N_INSTRUCTION_FAST_READ_QUAD_OUTPUT 0x6B
// Config/status register addresses // Config/status register addresses
#define W25N01G_PROT_REG 0xA0 #define W25N_PROT_REG 0xA0
#define W25N01G_CONF_REG 0xB0 #define W25N_CONF_REG 0xB0
#define W25N01G_STAT_REG 0xC0 #define W25N_STAT_REG 0xC0
// Bits in config/status register 1 (W25N01G_PROT_REG) // Bits in config/status register 1 (W25N_PROT_REG)
#define W25N01G_PROT_CLEAR (0) #define W25N_PROT_CLEAR (0)
#define W25N01G_PROT_SRP1_ENABLE (1 << 0) #define W25N_PROT_SRP1_ENABLE (1 << 0)
#define W25N01G_PROT_WP_E_ENABLE (1 << 1) #define W25N_PROT_WP_E_ENABLE (1 << 1)
#define W25N01G_PROT_TB_ENABLE (1 << 2) #define W25N_PROT_TB_ENABLE (1 << 2)
#define W25N01G_PROT_PB0_ENABLE (1 << 3) #define W25N_PROT_PB0_ENABLE (1 << 3)
#define W25N01G_PROT_PB1_ENABLE (1 << 4) #define W25N_PROT_PB1_ENABLE (1 << 4)
#define W25N01G_PROT_PB2_ENABLE (1 << 5) #define W25N_PROT_PB2_ENABLE (1 << 5)
#define W25N01G_PROT_PB3_ENABLE (1 << 6) #define W25N_PROT_PB3_ENABLE (1 << 6)
#define W25N01G_PROT_SRP2_ENABLE (1 << 7) #define W25N_PROT_SRP2_ENABLE (1 << 7)
// Bits in config/status register 2 (W25N01G_CONF_REG) // Bits in config/status register 2 (W25N_CONF_REG)
#define W25N01G_CONFIG_ECC_ENABLE (1 << 4) #define W25N_CONFIG_ECC_ENABLE (1 << 4)
#define W25N01G_CONFIG_BUFFER_READ_MODE (1 << 3) #define W25N_CONFIG_BUFFER_READ_MODE (1 << 3)
// Bits in config/status register 3 (W25N01G_STATREG) // Bits in config/status register 3 (W25N_STATREG)
#define W25N01G_STATUS_BBM_LUT_FULL (1 << 6) #define W25N_STATUS_BBM_LUT_FULL (1 << 6)
#define W25N01G_STATUS_FLAG_ECC_POS 4 #define W25N_STATUS_FLAG_ECC_POS 4
#define W25N01G_STATUS_FLAG_ECC_MASK ((1 << 5)|(1 << 4)) #define W25N_STATUS_FLAG_ECC_MASK ((1 << 5)|(1 << 4))
#define W25N01G_STATUS_FLAG_ECC(status) (((status) & W25N01G_STATUS_FLAG_ECC_MASK) >> 4) #define W25N_STATUS_FLAG_ECC(status) (((status) & W25N_STATUS_FLAG_ECC_MASK) >> 4)
#define W25N01G_STATUS_PROGRAM_FAIL (1 << 3) #define W25N_STATUS_PROGRAM_FAIL (1 << 3)
#define W25N01G_STATUS_ERASE_FAIL (1 << 2) #define W25N_STATUS_ERASE_FAIL (1 << 2)
#define W25N01G_STATUS_FLAG_WRITE_ENABLED (1 << 1) #define W25N_STATUS_FLAG_WRITE_ENABLED (1 << 1)
#define W25N01G_STATUS_FLAG_BUSY (1 << 0) #define W25N_STATUS_FLAG_BUSY (1 << 0)
#define W25N01G_BBLUT_TABLE_ENTRY_COUNT 20 #define W25N_BBLUT_TABLE_ENTRY_COUNT 20
#define W25N01G_BBLUT_TABLE_ENTRY_SIZE 4 // in bytes #define W25N_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 W25N_BBLUT_STATUS_ENABLED (1 << 15)
#define W25N01G_BBLUT_STATUS_INVALID (1 << 14) #define W25N_BBLUT_STATUS_INVALID (1 << 14)
#define W25N01G_BBLUT_STATUS_MASK (W25N01G_BBLUT_STATUS_ENABLED | W25N01G_BBLUT_STATUS_INVALID) #define W25N_BBLUT_STATUS_MASK (W25N_BBLUT_STATUS_ENABLED | W25N_BBLUT_STATUS_INVALID)
// Some useful defs and macros // Some useful defs and macros
#define W25N01G_LINEAR_TO_COLUMN(laddr) ((laddr) % W25N01G_PAGE_SIZE) #define W25N_PAGE_SIZE fdevice->geometry.pageSize
#define W25N01G_LINEAR_TO_PAGE(laddr) ((laddr) / W25N01G_PAGE_SIZE) #define W25N_LINEAR_TO_COLUMN(laddr) ((laddr) % W25N_PAGE_SIZE)
#define W25N01G_LINEAR_TO_BLOCK(laddr) (W25N01G_LINEAR_TO_PAGE(laddr) / W25N01G_PAGES_PER_BLOCK) #define W25N_LINEAR_TO_PAGE(laddr) ((laddr) / W25N_PAGE_SIZE)
#define W25N01G_BLOCK_TO_PAGE(block) ((block) * W25N01G_PAGES_PER_BLOCK) #define W25N_LINEAR_TO_BLOCK(laddr) (W25N_LINEAR_TO_PAGE(laddr) / fdevice->geometry.pagesPerSector)
#define W25N01G_BLOCK_TO_LINEAR(block) (W25N01G_BLOCK_TO_PAGE(block) * W25N01G_PAGE_SIZE) #define W25N_BLOCK_TO_PAGE(block) ((block) * fdevice->geometry.pagesPerSector)
#define W25N_BLOCK_TO_LINEAR(block) (W25N_BLOCK_TO_PAGE(block) * W25N_PAGE_SIZE)
// IMPORTANT: Timeout values are currently required to be set to the highest value required by any of the supported flash chips by this driver // IMPORTANT: Timeout values are currently required to be set to the highest value required by any of the supported flash chips by this driver
// The timeout values (2ms minimum to avoid 1 tick advance in consecutive calls to millis). // The timeout values (2ms minimum to avoid 1 tick advance in consecutive calls to millis).
#define W25N01G_TIMEOUT_PAGE_READ_MS 2 // tREmax = 60us (ECC enabled) #define W25N_TIMEOUT_PAGE_READ_MS 2 // tREmax = 60us (ECC enabled)
#define W25N01G_TIMEOUT_PAGE_PROGRAM_MS 2 // tPPmax = 700us #define W25N_TIMEOUT_PAGE_PROGRAM_MS 2 // tPPmax = 700us
#define W25N01G_TIMEOUT_BLOCK_ERASE_MS 15 // tBEmax = 10ms #define W25N_TIMEOUT_BLOCK_ERASE_MS 15 // tBEmax = 10ms
#define W25N01G_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms #define W25N_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms
// Sizes (in bits) // Sizes (in bits)
#define W25N01G_STATUS_REGISTER_SIZE 8 #define W25N_STATUS_REGISTER_SIZE 8
#define W25N01G_STATUS_PAGE_ADDRESS_SIZE 16 #define W25N_STATUS_PAGE_ADDRESS_SIZE 16
#define W25N01G_STATUS_COLUMN_ADDRESS_SIZE 16 #define W25N_STATUS_COLUMN_ADDRESS_SIZE 16
typedef struct bblut_s { typedef struct bblut_s {
uint16_t pba; uint16_t pba;
uint16_t lba; uint16_t lba;
} bblut_t; } bblut_t;
static bool w25n01g_waitForReady(flashDevice_t *fdevice); // Table of recognised FLASH devices
struct {
uint32_t jedecID;
flashSector_t sectors;
uint16_t pagesPerSector;
uint16_t pageSize;
} w25nFlashConfig[] = {
// Winbond W25N01GV
// Datasheet: https://www.winbond.com/resource-files/W25N01GV%20Rev%20R%20070323.pdf
{ 0xEFAA21, 2048, 64, 1024 },
// Winbond W25N02KV
// Datasheet: https://www.winbond.com/resource-files/W25N02KVxxIRU_Datasheet_RevM.pdf
{ 0xEFAA22, 2048, 64, 2048 },
{ 0, 0, 0, 0 },
};
static void w25n01g_setTimeout(flashDevice_t *fdevice, uint32_t timeoutMillis) static bool w25n_waitForReady(flashDevice_t *fdevice);
static void w25n_setTimeout(flashDevice_t *fdevice, uint32_t timeoutMillis)
{ {
uint32_t now = millis(); uint32_t now = millis();
fdevice->timeoutAt = now + timeoutMillis; fdevice->timeoutAt = now + timeoutMillis;
@ -144,7 +155,7 @@ static void w25n01g_setTimeout(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(flashDeviceIO_t *io, uint8_t command) static void w25n_performOneByteCommand(flashDeviceIO_t *io, uint8_t command)
{ {
if (io->mode == FLASHIO_SPI) { if (io->mode == FLASHIO_SPI) {
extDevice_t *dev = io->handle.dev; extDevice_t *dev = io->handle.dev;
@ -167,7 +178,7 @@ static void w25n01g_performOneByteCommand(flashDeviceIO_t *io, uint8_t command)
#endif #endif
} }
static void w25n01g_performCommandWithPageAddress(flashDeviceIO_t *io, uint8_t command, uint32_t pageAddress) static void w25n_performCommandWithPageAddress(flashDeviceIO_t *io, uint8_t command, uint32_t pageAddress)
{ {
if (io->mode == FLASHIO_SPI) { if (io->mode == FLASHIO_SPI) {
extDevice_t *dev = io->handle.dev; extDevice_t *dev = io->handle.dev;
@ -188,17 +199,17 @@ static void w25n01g_performCommandWithPageAddress(flashDeviceIO_t *io, uint8_t c
else if (io->mode == FLASHIO_QUADSPI) { else if (io->mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi; QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
quadSpiInstructionWithAddress1LINE(quadSpi, command, 0, pageAddress & 0xffff, W25N01G_STATUS_PAGE_ADDRESS_SIZE + 8); quadSpiInstructionWithAddress1LINE(quadSpi, command, 0, pageAddress & 0xffff, W25N_STATUS_PAGE_ADDRESS_SIZE + 8);
} }
#endif #endif
} }
static uint8_t w25n01g_readRegister(flashDeviceIO_t *io, uint8_t reg) static uint8_t w25n_readRegister(flashDeviceIO_t *io, uint8_t reg)
{ {
if (io->mode == FLASHIO_SPI) { if (io->mode == FLASHIO_SPI) {
extDevice_t *dev = io->handle.dev; extDevice_t *dev = io->handle.dev;
uint8_t cmd[3] = { W25N01G_INSTRUCTION_READ_STATUS_REG, reg, 0 }; uint8_t cmd[3] = { W25N_INSTRUCTION_READ_STATUS_REG, reg, 0 };
uint8_t in[3]; uint8_t in[3];
busSegment_t segments[] = { busSegment_t segments[] = {
@ -221,8 +232,8 @@ static uint8_t w25n01g_readRegister(flashDeviceIO_t *io, uint8_t reg)
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi; QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
uint8_t in[W25N01G_STATUS_REGISTER_SIZE / 8]; uint8_t in[W25N_STATUS_REGISTER_SIZE / 8];
quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_STATUS_REG, 0, reg, W25N01G_STATUS_REGISTER_SIZE, in, sizeof(in)); quadSpiReceiveWithAddress1LINE(quadSpi, W25N_INSTRUCTION_READ_STATUS_REG, 0, reg, W25N_STATUS_REGISTER_SIZE, in, sizeof(in));
return in[0]; return in[0];
} }
@ -230,11 +241,11 @@ static uint8_t w25n01g_readRegister(flashDeviceIO_t *io, uint8_t reg)
return 0; return 0;
} }
static void w25n01g_writeRegister(flashDeviceIO_t *io, uint8_t reg, uint8_t data) static void w25n_writeRegister(flashDeviceIO_t *io, uint8_t reg, uint8_t data)
{ {
if (io->mode == FLASHIO_SPI) { if (io->mode == FLASHIO_SPI) {
extDevice_t *dev = io->handle.dev; extDevice_t *dev = io->handle.dev;
uint8_t cmd[3] = { W25N01G_INSTRUCTION_WRITE_STATUS_REG, reg, data }; uint8_t cmd[3] = { W25N_INSTRUCTION_WRITE_STATUS_REG, reg, data };
busSegment_t segments[] = { busSegment_t segments[] = {
{.u.buffers = {cmd, NULL}, sizeof(cmd), true, NULL}, {.u.buffers = {cmd, NULL}, sizeof(cmd), true, NULL},
@ -253,33 +264,33 @@ static void w25n01g_writeRegister(flashDeviceIO_t *io, uint8_t reg, uint8_t data
else if (io->mode == FLASHIO_QUADSPI) { else if (io->mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi; QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_WRITE_STATUS_REG, 0, reg, W25N01G_STATUS_REGISTER_SIZE, &data, 1); quadSpiTransmitWithAddress1LINE(quadSpi, W25N_INSTRUCTION_WRITE_STATUS_REG, 0, reg, W25N_STATUS_REGISTER_SIZE, &data, 1);
} }
#endif #endif
} }
static void w25n01g_deviceReset(flashDevice_t *fdevice) static void w25n_deviceReset(flashDevice_t *fdevice)
{ {
flashDeviceIO_t *io = &fdevice->io; flashDeviceIO_t *io = &fdevice->io;
w25n01g_performOneByteCommand(io, W25N01G_INSTRUCTION_DEVICE_RESET); w25n_performOneByteCommand(io, W25N_INSTRUCTION_DEVICE_RESET);
w25n01g_setTimeout(fdevice, W25N01G_TIMEOUT_RESET_MS); w25n_setTimeout(fdevice, W25N_TIMEOUT_RESET_MS);
w25n01g_waitForReady(fdevice); w25n_waitForReady(fdevice);
// 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(dev, W25N01G_PROT_REG, W25N01G_PROT_PB0_ENABLE|W25N01G_PROT_PB2_ENABLE|W25N01G_PROT_WP_E_ENABLE); // w25n_writeRegister(dev, W25N_PROT_REG, W25N_PROT_PB0_ENABLE|W25N_PROT_PB2_ENABLE|W25N_PROT_WP_E_ENABLE);
// No protection, WP-E off, WP-E prevents use of IO2 // No protection, WP-E off, WP-E prevents use of IO2
w25n01g_writeRegister(io, W25N01G_PROT_REG, W25N01G_PROT_CLEAR); w25n_writeRegister(io, W25N_PROT_REG, W25N_PROT_CLEAR);
// Buffered read mode (BUF = 1), ECC enabled (ECC = 1) // Buffered read mode (BUF = 1), ECC enabled (ECC = 1)
w25n01g_writeRegister(io, W25N01G_CONF_REG, W25N01G_CONFIG_ECC_ENABLE|W25N01G_CONFIG_BUFFER_READ_MODE); w25n_writeRegister(io, W25N_CONF_REG, W25N_CONFIG_ECC_ENABLE|W25N_CONFIG_BUFFER_READ_MODE);
} }
bool w25n01g_isReady(flashDevice_t *fdevice) bool w25n_isReady(flashDevice_t *fdevice)
{ {
// If we're waiting on DMA completion, then SPI is busy // If we're waiting on DMA completion, then SPI is busy
if (fdevice->io.mode == FLASHIO_SPI) { if (fdevice->io.mode == FLASHIO_SPI) {
@ -291,14 +302,14 @@ bool w25n01g_isReady(flashDevice_t *fdevice)
// Irrespective of the current state of fdevice->couldBeBusy read the status or device blocks // Irrespective of the current state of fdevice->couldBeBusy read the status or device blocks
// Poll the FLASH device to see if it's busy // Poll the FLASH device to see if it's busy
fdevice->couldBeBusy = ((w25n01g_readRegister(&fdevice->io, W25N01G_STAT_REG) & W25N01G_STATUS_FLAG_BUSY) != 0); fdevice->couldBeBusy = ((w25n_readRegister(&fdevice->io, W25N_STAT_REG) & W25N_STATUS_FLAG_BUSY) != 0);
return !fdevice->couldBeBusy; return !fdevice->couldBeBusy;
} }
static bool w25n01g_waitForReady(flashDevice_t *fdevice) static bool w25n_waitForReady(flashDevice_t *fdevice)
{ {
while (!w25n01g_isReady(fdevice)) { while (!w25n_isReady(fdevice)) {
uint32_t now = millis(); uint32_t now = millis();
if (cmp32(now, fdevice->timeoutAt) >= 0) { if (cmp32(now, fdevice->timeoutAt) >= 0) {
return false; return false;
@ -313,30 +324,34 @@ static bool w25n01g_waitForReady(flashDevice_t *fdevice)
* 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 w25n01g_writeEnable(flashDevice_t *fdevice) static void w25n_writeEnable(flashDevice_t *fdevice)
{ {
w25n01g_performOneByteCommand(&fdevice->io, W25N01G_INSTRUCTION_WRITE_ENABLE); w25n_performOneByteCommand(&fdevice->io, W25N_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;
} }
const flashVTable_t w25n01g_vTable; const flashVTable_t w25n_vTable;
bool w25n01g_identify(flashDevice_t *fdevice, uint32_t jedecID) bool w25n_identify(flashDevice_t *fdevice, uint32_t jedecID)
{ {
switch (jedecID) { flashGeometry_t *geometry = &fdevice->geometry;
case JEDEC_ID_WINBOND_W25N01GV: uint8_t index;
fdevice->geometry.sectors = 1024; // Blocks
fdevice->geometry.pagesPerSector = 64; // Pages/Blocks
fdevice->geometry.pageSize = 2048;
break;
default: for (index = 0; w25nFlashConfig[index].jedecID; index++) {
if (w25nFlashConfig[index].jedecID == jedecID) {
geometry->sectors = w25nFlashConfig[index].sectors;
geometry->pagesPerSector = w25nFlashConfig[index].pagesPerSector;
geometry->pageSize = w25nFlashConfig[index].pageSize;
break;
}
}
if (w25nFlashConfig[index].jedecID == 0) {
// Unsupported chip // Unsupported chip
fdevice->geometry.sectors = 0; fdevice->geometry.sectors = 0;
fdevice->geometry.pagesPerSector = 0; fdevice->geometry.pagesPerSector = 0;
fdevice->geometry.sectorSize = 0; fdevice->geometry.sectorSize = 0;
fdevice->geometry.totalSize = 0; fdevice->geometry.totalSize = 0;
return false; return false;
@ -347,25 +362,25 @@ bool w25n01g_identify(flashDevice_t *fdevice, uint32_t jedecID)
fdevice->geometry.totalSize = fdevice->geometry.sectorSize * fdevice->geometry.sectors; fdevice->geometry.totalSize = fdevice->geometry.sectorSize * fdevice->geometry.sectors;
flashPartitionSet(FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT, flashPartitionSet(FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT,
W25N01G_BB_MANAGEMENT_START_BLOCK, W25N_BB_MANAGEMENT_START_BLOCK,
W25N01G_BB_MANAGEMENT_START_BLOCK + W25N01G_BB_MANAGEMENT_BLOCKS - 1); W25N_BB_MANAGEMENT_START_BLOCK + W25N_BB_MANAGEMENT_BLOCKS - 1);
fdevice->couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be fdevice->couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be
fdevice->vTable = &w25n01g_vTable; fdevice->vTable = &w25n_vTable;
return true; return true;
} }
static void w25n01g_deviceInit(flashDevice_t *flashdev); static void w25n_deviceInit(flashDevice_t *flashdev);
void w25n01g_configure(flashDevice_t *fdevice, uint32_t configurationFlags) void w25n_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
{ {
if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) { if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) {
return; return;
} }
w25n01g_deviceReset(fdevice); w25n_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.
@ -385,44 +400,44 @@ void w25n01g_configure(flashDevice_t *fdevice, uint32_t configurationFlags)
spiSetClkDivisor(fdevice->io.handle.dev, spiCalculateDivider(100000000)); spiSetClkDivisor(fdevice->io.handle.dev, spiCalculateDivider(100000000));
} }
w25n01g_deviceInit(fdevice); w25n_deviceInit(fdevice);
} }
/** /**
* 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 w25n01g_eraseSector(flashDevice_t *fdevice, uint32_t address) void w25n_eraseSector(flashDevice_t *fdevice, uint32_t address)
{ {
w25n01g_waitForReady(fdevice); w25n_waitForReady(fdevice);
w25n01g_writeEnable(fdevice); w25n_writeEnable(fdevice);
w25n01g_performCommandWithPageAddress(&fdevice->io, W25N01G_INSTRUCTION_BLOCK_ERASE, W25N01G_LINEAR_TO_PAGE(address)); w25n_performCommandWithPageAddress(&fdevice->io, W25N_INSTRUCTION_BLOCK_ERASE, W25N_LINEAR_TO_PAGE(address));
w25n01g_setTimeout(fdevice, W25N01G_TIMEOUT_BLOCK_ERASE_MS); w25n_setTimeout(fdevice, W25N_TIMEOUT_BLOCK_ERASE_MS);
} }
// //
// W25N01G does not support full chip erase. // W25N01G does not support full chip erase.
// Call eraseSector repeatedly. // Call eraseSector repeatedly.
void w25n01g_eraseCompletely(flashDevice_t *fdevice) void w25n_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_eraseSector(fdevice, W25N01G_BLOCK_TO_LINEAR(block)); w25n_eraseSector(fdevice, W25N_BLOCK_TO_LINEAR(block));
} }
} }
#ifdef USE_QUADSPI #ifdef USE_QUADSPI
static void w25n01g_programDataLoad(flashDevice_t *fdevice, uint16_t columnAddress, const uint8_t *data, int length) static void w25n_programDataLoad(flashDevice_t *fdevice, uint16_t columnAddress, const uint8_t *data, int length)
{ {
w25n01g_waitForReady(fdevice); w25n_waitForReady(fdevice);
if (fdevice->io.mode == FLASHIO_SPI) { if (fdevice->io.mode == FLASHIO_SPI) {
extDevice_t *dev = fdevice->io.handle.dev; extDevice_t *dev = fdevice->io.handle.dev;
uint8_t cmd[] = { W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff }; uint8_t cmd[] = { W25N_INSTRUCTION_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff };
busSegment_t segments[] = { busSegment_t segments[] = {
{.u.buffers = {cmd, NULL}, sizeof(cmd), false, NULL}, {.u.buffers = {cmd, NULL}, sizeof(cmd), false, NULL},
@ -439,18 +454,18 @@ static void w25n01g_programDataLoad(flashDevice_t *fdevice, uint16_t columnAddre
else if (fdevice->io.mode == FLASHIO_QUADSPI) { else if (fdevice->io.mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi; QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, 0, columnAddress, W25N01G_STATUS_COLUMN_ADDRESS_SIZE, data, length); quadSpiTransmitWithAddress1LINE(quadSpi, W25N_INSTRUCTION_PROGRAM_DATA_LOAD, 0, columnAddress, W25N_STATUS_COLUMN_ADDRESS_SIZE, data, length);
} }
#endif #endif
w25n01g_setTimeout(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS); w25n_setTimeout(fdevice, W25N_TIMEOUT_PAGE_PROGRAM_MS);
} }
static void w25n01g_randomProgramDataLoad(flashDevice_t *fdevice, uint16_t columnAddress, const uint8_t *data, int length) static void w25n_randomProgramDataLoad(flashDevice_t *fdevice, uint16_t columnAddress, const uint8_t *data, int length)
{ {
uint8_t cmd[] = { W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff }; uint8_t cmd[] = { W25N_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff };
w25n01g_waitForReady(fdevice); w25n_waitForReady(fdevice);
if (fdevice->io.mode == FLASHIO_SPI) { if (fdevice->io.mode == FLASHIO_SPI) {
extDevice_t *dev = fdevice->io.handle.dev; extDevice_t *dev = fdevice->io.handle.dev;
@ -470,22 +485,22 @@ static void w25n01g_randomProgramDataLoad(flashDevice_t *fdevice, uint16_t colum
else if (fdevice->io.mode == FLASHIO_QUADSPI) { else if (fdevice->io.mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi; QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, 0, columnAddress, W25N01G_STATUS_COLUMN_ADDRESS_SIZE, data, length); quadSpiTransmitWithAddress1LINE(quadSpi, W25N_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, 0, columnAddress, W25N_STATUS_COLUMN_ADDRESS_SIZE, data, length);
} }
#endif #endif
w25n01g_setTimeout(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS); w25n_setTimeout(fdevice, W25N_TIMEOUT_PAGE_PROGRAM_MS);
} }
#endif #endif
static void w25n01g_programExecute(flashDevice_t *fdevice, uint32_t pageAddress) static void w25n_programExecute(flashDevice_t *fdevice, uint32_t pageAddress)
{ {
w25n01g_waitForReady(fdevice); w25n_waitForReady(fdevice);
w25n01g_performCommandWithPageAddress(&fdevice->io, W25N01G_INSTRUCTION_PROGRAM_EXECUTE, pageAddress); w25n_performCommandWithPageAddress(&fdevice->io, W25N_INSTRUCTION_PROGRAM_EXECUTE, pageAddress);
w25n01g_setTimeout(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS); w25n_setTimeout(fdevice, W25N_TIMEOUT_PAGE_PROGRAM_MS);
} }
// //
@ -525,19 +540,19 @@ bool bufferDirty = false;
#ifdef USE_QUADSPI #ifdef USE_QUADSPI
bool isProgramming = false; bool isProgramming = false;
void w25n01g_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length)) void w25n_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length))
{ {
fdevice->callback = callback; fdevice->callback = callback;
if (bufferDirty) { if (bufferDirty) {
if (address != programLoadAddress) { if (address != programLoadAddress) {
w25n01g_waitForReady(fdevice); w25n_waitForReady(fdevice);
isProgramming = false; isProgramming = false;
w25n01g_writeEnable(fdevice); w25n_writeEnable(fdevice);
w25n01g_programExecute(fdevice, W25N01G_LINEAR_TO_PAGE(programStartAddress)); w25n_programExecute(fdevice, W25N_LINEAR_TO_PAGE(programStartAddress));
bufferDirty = false; bufferDirty = false;
isProgramming = true; isProgramming = true;
@ -547,23 +562,23 @@ void w25n01g_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*c
} }
} }
uint32_t w25n01g_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount) uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount)
{ {
if (bufferCount < 1) { if (bufferCount < 1) {
fdevice->callback(0); fdevice->callback(0);
return 0; return 0;
} }
w25n01g_waitForReady(fdevice); w25n_waitForReady(fdevice);
w25n01g_writeEnable(fdevice); w25n_writeEnable(fdevice);
isProgramming = false; isProgramming = false;
if (!bufferDirty) { if (!bufferDirty) {
w25n01g_programDataLoad(fdevice, W25N01G_LINEAR_TO_COLUMN(programLoadAddress), buffers[0], bufferSizes[0]); w25n_programDataLoad(fdevice, W25N_LINEAR_TO_COLUMN(programLoadAddress), buffers[0], bufferSizes[0]);
} else { } else {
w25n01g_randomProgramDataLoad(fdevice, W25N01G_LINEAR_TO_COLUMN(programLoadAddress), buffers[0], bufferSizes[0]); w25n_randomProgramDataLoad(fdevice, W25N_LINEAR_TO_COLUMN(programLoadAddress), buffers[0], bufferSizes[0]);
} }
// XXX Test if write enable is reset after each data loading. // XXX Test if write enable is reset after each data loading.
@ -580,13 +595,13 @@ uint32_t w25n01g_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buf
static uint32_t currentPage = UINT32_MAX; static uint32_t currentPage = UINT32_MAX;
void w25n01g_pageProgramFinish(flashDevice_t *fdevice) void w25n_pageProgramFinish(flashDevice_t *fdevice)
{ {
if (bufferDirty && W25N01G_LINEAR_TO_COLUMN(programLoadAddress) == 0) { if (bufferDirty && W25N_LINEAR_TO_COLUMN(programLoadAddress) == 0) {
currentPage = W25N01G_LINEAR_TO_PAGE(programStartAddress); // reset page to the page being written currentPage = W25N_LINEAR_TO_PAGE(programStartAddress); // reset page to the page being written
w25n01g_programExecute(fdevice, W25N01G_LINEAR_TO_PAGE(programStartAddress)); w25n_programExecute(fdevice, W25N_LINEAR_TO_PAGE(programStartAddress));
bufferDirty = false; bufferDirty = false;
isProgramming = true; isProgramming = true;
@ -595,7 +610,7 @@ void w25n01g_pageProgramFinish(flashDevice_t *fdevice)
} }
} }
#else #else
void w25n01g_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length)) void w25n_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length))
{ {
fdevice->callback = callback; fdevice->callback = callback;
fdevice->currentWriteAddress = address; fdevice->currentWriteAddress = address;
@ -606,14 +621,14 @@ static uint32_t currentPage = UINT32_MAX;
// Called in ISR context // Called in ISR context
// Check if the status was busy and if so repeat the poll // Check if the status was busy and if so repeat the poll
busStatus_e w25n01g_callbackReady(uint32_t arg) busStatus_e w25n_callbackReady(uint32_t arg)
{ {
flashDevice_t *fdevice = (flashDevice_t *)arg; flashDevice_t *fdevice = (flashDevice_t *)arg;
extDevice_t *dev = fdevice->io.handle.dev; extDevice_t *dev = fdevice->io.handle.dev;
uint8_t readyPoll = dev->bus->curSegment->u.buffers.rxData[2]; uint8_t readyPoll = dev->bus->curSegment->u.buffers.rxData[2];
if (readyPoll & W25N01G_STATUS_FLAG_BUSY) { if (readyPoll & W25N_STATUS_FLAG_BUSY) {
return BUS_BUSY; return BUS_BUSY;
} }
@ -625,7 +640,7 @@ busStatus_e w25n01g_callbackReady(uint32_t arg)
// Called in ISR context // Called in ISR context
// A write enable has just been issued // A write enable has just been issued
busStatus_e w25n01g_callbackWriteEnable(uint32_t arg) busStatus_e w25n_callbackWriteEnable(uint32_t arg)
{ {
flashDevice_t *fdevice = (flashDevice_t *)arg; flashDevice_t *fdevice = (flashDevice_t *)arg;
@ -637,7 +652,7 @@ busStatus_e w25n01g_callbackWriteEnable(uint32_t arg)
// Called in ISR context // Called in ISR context
// Write operation has just completed // Write operation has just completed
busStatus_e w25n01g_callbackWriteComplete(uint32_t arg) busStatus_e w25n_callbackWriteComplete(uint32_t arg)
{ {
flashDevice_t *fdevice = (flashDevice_t *)arg; flashDevice_t *fdevice = (flashDevice_t *)arg;
@ -650,7 +665,7 @@ busStatus_e w25n01g_callbackWriteComplete(uint32_t arg)
return BUS_READY; return BUS_READY;
} }
uint32_t w25n01g_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount) uint32_t w25n_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, const uint32_t *bufferSizes, uint32_t bufferCount)
{ {
if (bufferCount < 1) { if (bufferCount < 1) {
fdevice->callback(0); fdevice->callback(0);
@ -658,23 +673,23 @@ uint32_t w25n01g_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buf
} }
// The segment list cannot be in automatic storage as this routine is non-blocking // The segment list cannot be in automatic storage as this routine is non-blocking
STATIC_DMA_DATA_AUTO uint8_t readStatus[] = { W25N01G_INSTRUCTION_READ_STATUS_REG, W25N01G_STAT_REG, 0 }; STATIC_DMA_DATA_AUTO uint8_t readStatus[] = { W25N_INSTRUCTION_READ_STATUS_REG, W25N_STAT_REG, 0 };
STATIC_DMA_DATA_AUTO uint8_t readyStatus[3]; STATIC_DMA_DATA_AUTO uint8_t readyStatus[3];
STATIC_DMA_DATA_AUTO uint8_t writeEnable[] = { W25N01G_INSTRUCTION_WRITE_ENABLE }; STATIC_DMA_DATA_AUTO uint8_t writeEnable[] = { W25N_INSTRUCTION_WRITE_ENABLE };
STATIC_DMA_DATA_AUTO uint8_t progExecCmd[] = { W25N01G_INSTRUCTION_PROGRAM_EXECUTE, 0, 0, 0}; STATIC_DMA_DATA_AUTO uint8_t progExecCmd[] = { W25N_INSTRUCTION_PROGRAM_EXECUTE, 0, 0, 0};
STATIC_DMA_DATA_AUTO uint8_t progExecDataLoad[] = { W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, 0, 0}; STATIC_DMA_DATA_AUTO uint8_t progExecDataLoad[] = { W25N_INSTRUCTION_PROGRAM_DATA_LOAD, 0, 0};
STATIC_DMA_DATA_AUTO uint8_t progRandomProgDataLoad[] = { W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, 0, 0}; STATIC_DMA_DATA_AUTO uint8_t progRandomProgDataLoad[] = { W25N_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, 0, 0};
static busSegment_t segmentsDataLoad[] = { static busSegment_t segmentsDataLoad[] = {
{.u.buffers = {readStatus, readyStatus}, sizeof(readStatus), true, w25n01g_callbackReady}, {.u.buffers = {readStatus, readyStatus}, sizeof(readStatus), true, w25n_callbackReady},
{.u.buffers = {writeEnable, NULL}, sizeof(writeEnable), true, w25n01g_callbackWriteEnable}, {.u.buffers = {writeEnable, NULL}, sizeof(writeEnable), true, w25n_callbackWriteEnable},
{.u.buffers = {progExecDataLoad, NULL}, sizeof(progExecDataLoad), false, NULL}, {.u.buffers = {progExecDataLoad, NULL}, sizeof(progExecDataLoad), false, NULL},
{.u.link = {NULL, NULL}, 0, true, NULL}, {.u.link = {NULL, NULL}, 0, true, NULL},
}; };
static busSegment_t segmentsRandomDataLoad[] = { static busSegment_t segmentsRandomDataLoad[] = {
{.u.buffers = {readStatus, readyStatus}, sizeof(readStatus), true, w25n01g_callbackReady}, {.u.buffers = {readStatus, readyStatus}, sizeof(readStatus), true, w25n_callbackReady},
{.u.buffers = {writeEnable, NULL}, sizeof(writeEnable), true, w25n01g_callbackWriteEnable}, {.u.buffers = {writeEnable, NULL}, sizeof(writeEnable), true, w25n_callbackWriteEnable},
{.u.buffers = {progRandomProgDataLoad, NULL}, sizeof(progRandomProgDataLoad), false, NULL}, {.u.buffers = {progRandomProgDataLoad, NULL}, sizeof(progRandomProgDataLoad), false, NULL},
{.u.link = {NULL, NULL}, 0, true, NULL}, {.u.link = {NULL, NULL}, 0, true, NULL},
}; };
@ -685,9 +700,9 @@ uint32_t w25n01g_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buf
}; };
static busSegment_t segmentsFlash[] = { static busSegment_t segmentsFlash[] = {
{.u.buffers = {readStatus, readyStatus}, sizeof(readStatus), true, w25n01g_callbackReady}, {.u.buffers = {readStatus, readyStatus}, sizeof(readStatus), true, w25n_callbackReady},
{.u.buffers = {writeEnable, NULL}, sizeof(writeEnable), true, w25n01g_callbackWriteEnable}, {.u.buffers = {writeEnable, NULL}, sizeof(writeEnable), true, w25n_callbackWriteEnable},
{.u.buffers = {progExecCmd, NULL}, sizeof(progExecCmd), true, w25n01g_callbackWriteComplete}, {.u.buffers = {progExecCmd, NULL}, sizeof(progExecCmd), true, w25n_callbackWriteComplete},
{.u.link = {NULL, NULL}, 0, true, NULL}, {.u.link = {NULL, NULL}, 0, true, NULL},
}; };
@ -699,14 +714,14 @@ uint32_t w25n01g_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buf
uint32_t columnAddress; uint32_t columnAddress;
if (bufferDirty) { if (bufferDirty) {
columnAddress = W25N01G_LINEAR_TO_COLUMN(programLoadAddress); columnAddress = W25N_LINEAR_TO_COLUMN(programLoadAddress);
// Set the address and buffer details for the random data load // Set the address and buffer details for the random data load
progRandomProgDataLoad[1] = (columnAddress >> 8) & 0xff; progRandomProgDataLoad[1] = (columnAddress >> 8) & 0xff;
progRandomProgDataLoad[2] = columnAddress & 0xff; progRandomProgDataLoad[2] = columnAddress & 0xff;
programSegment = segmentsRandomDataLoad; programSegment = segmentsRandomDataLoad;
} else { } else {
programStartAddress = programLoadAddress = fdevice->currentWriteAddress; programStartAddress = programLoadAddress = fdevice->currentWriteAddress;
columnAddress = W25N01G_LINEAR_TO_COLUMN(programLoadAddress); columnAddress = W25N_LINEAR_TO_COLUMN(programLoadAddress);
// Set the address and buffer details for the data load // Set the address and buffer details for the data load
progExecDataLoad[1] = (columnAddress >> 8) & 0xff; progExecDataLoad[1] = (columnAddress >> 8) & 0xff;
progExecDataLoad[2] = columnAddress & 0xff; progExecDataLoad[2] = columnAddress & 0xff;
@ -723,9 +738,9 @@ uint32_t w25n01g_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buf
bufferDirty = true; bufferDirty = true;
programLoadAddress += bufferSizes[0]; programLoadAddress += bufferSizes[0];
if (W25N01G_LINEAR_TO_COLUMN(programLoadAddress) == 0) { if (W25N_LINEAR_TO_COLUMN(programLoadAddress) == 0) {
// Flash the loaded data // Flash the loaded data
currentPage = W25N01G_LINEAR_TO_PAGE(programStartAddress); currentPage = W25N_LINEAR_TO_PAGE(programStartAddress);
progExecCmd[2] = (currentPage >> 8) & 0xff; progExecCmd[2] = (currentPage >> 8) & 0xff;
progExecCmd[3] = currentPage & 0xff; progExecCmd[3] = currentPage & 0xff;
@ -737,7 +752,7 @@ uint32_t w25n01g_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buf
programStartAddress = programLoadAddress; programStartAddress = programLoadAddress;
} else { } else {
// Callback on completion of data load // Callback on completion of data load
segmentsBuffer[0].callback = w25n01g_callbackWriteComplete; segmentsBuffer[0].callback = w25n_callbackWriteComplete;
} }
if (!fdevice->couldBeBusy) { if (!fdevice->couldBeBusy) {
@ -758,7 +773,7 @@ uint32_t w25n01g_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buf
return fdevice->callbackArg; return fdevice->callbackArg;
} }
void w25n01g_pageProgramFinish(flashDevice_t *fdevice) void w25n_pageProgramFinish(flashDevice_t *fdevice)
{ {
UNUSED(fdevice); UNUSED(fdevice);
} }
@ -780,25 +795,25 @@ void w25n01g_pageProgramFinish(flashDevice_t *fdevice)
* 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 w25n01g_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length)) void w25n_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length))
{ {
w25n01g_pageProgramBegin(fdevice, address, callback); w25n_pageProgramBegin(fdevice, address, callback);
w25n01g_pageProgramContinue(fdevice, &data, &length, 1); w25n_pageProgramContinue(fdevice, &data, &length, 1);
w25n01g_pageProgramFinish(fdevice); w25n_pageProgramFinish(fdevice);
} }
void w25n01g_flush(flashDevice_t *fdevice) void w25n_flush(flashDevice_t *fdevice)
{ {
if (bufferDirty) { if (bufferDirty) {
currentPage = W25N01G_LINEAR_TO_PAGE(programStartAddress); // reset page to the page being written currentPage = W25N_LINEAR_TO_PAGE(programStartAddress); // reset page to the page being written
w25n01g_programExecute(fdevice, W25N01G_LINEAR_TO_PAGE(programStartAddress)); w25n_programExecute(fdevice, W25N_LINEAR_TO_PAGE(programStartAddress));
bufferDirty = false; bufferDirty = false;
} }
} }
void w25n01g_addError(uint32_t address, uint8_t code) void w25n_addError(uint32_t address, uint8_t code)
{ {
UNUSED(address); UNUSED(address);
UNUSED(code); UNUSED(code);
@ -808,7 +823,7 @@ void w25n01g_addError(uint32_t address, uint8_t code)
* Read `length` bytes into the provided `buffer` from the flash starting from the given `address` (which need not lie * Read `length` bytes into the provided `buffer` from the flash starting from the given `address` (which need not lie
* on a page boundary). * on a page boundary).
* *
* Waits up to W25N01G_TIMEOUT_PAGE_READ_MS milliseconds for the flash to become ready before reading. * Waits up to W25N_TIMEOUT_PAGE_READ_MS milliseconds for the flash to become ready before reading.
* *
* 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.
*/ */
@ -824,32 +839,32 @@ void w25n01g_addError(uint32_t address, uint8_t code)
// (3) Issue READ_DATA on column address. // (3) Issue READ_DATA on column address.
// (4) Return transferLength. // (4) Return transferLength.
int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length) int w25n_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length)
{ {
uint32_t targetPage = W25N01G_LINEAR_TO_PAGE(address); uint32_t targetPage = W25N_LINEAR_TO_PAGE(address);
if (currentPage != targetPage) { if (currentPage != targetPage) {
if (!w25n01g_waitForReady(fdevice)) { if (!w25n_waitForReady(fdevice)) {
return 0; return 0;
} }
currentPage = UINT32_MAX; currentPage = UINT32_MAX;
w25n01g_performCommandWithPageAddress(&fdevice->io, W25N01G_INSTRUCTION_PAGE_DATA_READ, targetPage); w25n_performCommandWithPageAddress(&fdevice->io, W25N_INSTRUCTION_PAGE_DATA_READ, targetPage);
w25n01g_setTimeout(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS); w25n_setTimeout(fdevice, W25N_TIMEOUT_PAGE_READ_MS);
if (!w25n01g_waitForReady(fdevice)) { if (!w25n_waitForReady(fdevice)) {
return 0; return 0;
} }
currentPage = targetPage; currentPage = targetPage;
} }
uint32_t column = W25N01G_LINEAR_TO_COLUMN(address); uint32_t column = W25N_LINEAR_TO_COLUMN(address);
uint16_t transferLength; uint16_t transferLength;
if (length > W25N01G_PAGE_SIZE - column) { if (length > W25N_PAGE_SIZE - column) {
transferLength = W25N01G_PAGE_SIZE - column; transferLength = W25N_PAGE_SIZE - column;
} else { } else {
transferLength = length; transferLength = length;
} }
@ -858,7 +873,7 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
extDevice_t *dev = fdevice->io.handle.dev; extDevice_t *dev = fdevice->io.handle.dev;
uint8_t cmd[4]; uint8_t cmd[4];
cmd[0] = W25N01G_INSTRUCTION_READ_DATA; cmd[0] = W25N_INSTRUCTION_READ_DATA;
cmd[1] = (column >> 8) & 0xff; cmd[1] = (column >> 8) & 0xff;
cmd[2] = (column >> 0) & 0xff; cmd[2] = (column >> 0) & 0xff;
cmd[3] = 0; cmd[3] = 0;
@ -878,21 +893,21 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
else if (fdevice->io.mode == FLASHIO_QUADSPI) { else if (fdevice->io.mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi; QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
//quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_DATA, 8, column, W25N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length); //quadSpiReceiveWithAddress1LINE(quadSpi, W25N_INSTRUCTION_READ_DATA, 8, column, W25N_STATUS_COLUMN_ADDRESS_SIZE, buffer, length);
quadSpiReceiveWithAddress4LINES(quadSpi, W25N01G_INSTRUCTION_FAST_READ_QUAD_OUTPUT, 8, column, W25N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length); quadSpiReceiveWithAddress4LINES(quadSpi, W25N_INSTRUCTION_FAST_READ_QUAD_OUTPUT, 8, column, W25N_STATUS_COLUMN_ADDRESS_SIZE, buffer, length);
} }
#endif #endif
// XXX Don't need this? // XXX Don't need this?
w25n01g_setTimeout(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS); w25n_setTimeout(fdevice, W25N_TIMEOUT_PAGE_READ_MS);
if (!w25n01g_waitForReady(fdevice)) { if (!w25n_waitForReady(fdevice)) {
return 0; return 0;
} }
// Check ECC // Check ECC
uint8_t statReg = w25n01g_readRegister(&fdevice->io, W25N01G_STAT_REG); uint8_t statReg = w25n_readRegister(&fdevice->io, W25N_STAT_REG);
uint8_t eccCode = W25N01G_STATUS_FLAG_ECC(statReg); uint8_t eccCode = W25N_STATUS_FLAG_ECC(statReg);
switch (eccCode) { switch (eccCode) {
case 0: // Successful read, no ECC correction case 0: // Successful read, no ECC correction
@ -900,22 +915,22 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer,
case 1: // Successful read with ECC correction case 1: // Successful read with ECC correction
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); w25n_addError(address, eccCode);
w25n01g_deviceReset(fdevice); w25n_deviceReset(fdevice);
break; break;
} }
return transferLength; return transferLength;
} }
int w25n01g_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length) int w25n_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
{ {
if (!w25n01g_waitForReady(fdevice)) { if (!w25n_waitForReady(fdevice)) {
return 0; return 0;
} }
w25n01g_performCommandWithPageAddress(&fdevice->io, W25N01G_INSTRUCTION_PAGE_DATA_READ, W25N01G_LINEAR_TO_PAGE(address)); w25n_performCommandWithPageAddress(&fdevice->io, W25N_INSTRUCTION_PAGE_DATA_READ, W25N_LINEAR_TO_PAGE(address));
uint32_t column = 2048; uint32_t column = 2048;
@ -923,7 +938,7 @@ int w25n01g_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t
extDevice_t *dev = fdevice->io.handle.dev; extDevice_t *dev = fdevice->io.handle.dev;
uint8_t cmd[4]; uint8_t cmd[4];
cmd[0] = W25N01G_INSTRUCTION_READ_DATA; cmd[0] = W25N_INSTRUCTION_READ_DATA;
cmd[1] = (column >> 8) & 0xff; cmd[1] = (column >> 8) & 0xff;
cmd[2] = (column >> 0) & 0xff; cmd[2] = (column >> 0) & 0xff;
cmd[3] = 0; cmd[3] = 0;
@ -947,11 +962,11 @@ int w25n01g_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t
else if (fdevice->io.mode == FLASHIO_QUADSPI) { else if (fdevice->io.mode == FLASHIO_QUADSPI) {
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi; QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_DATA, 8, column, W25N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length); quadSpiReceiveWithAddress1LINE(quadSpi, W25N_INSTRUCTION_READ_DATA, 8, column, W25N_STATUS_COLUMN_ADDRESS_SIZE, buffer, length);
} }
#endif #endif
w25n01g_setTimeout(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS); w25n_setTimeout(fdevice, W25N_TIMEOUT_PAGE_READ_MS);
return length; return length;
} }
@ -959,26 +974,26 @@ int w25n01g_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t
/** /**
* Fetch information about the detected flash chip layout. * Fetch information about the detected flash chip layout.
* *
* Can be called before calling w25n01g_init() (the result would have totalSize = 0). * Can be called before calling w25n_init() (the result would have totalSize = 0).
*/ */
const flashGeometry_t* w25n01g_getGeometry(flashDevice_t *fdevice) const flashGeometry_t* w25n_getGeometry(flashDevice_t *fdevice)
{ {
return &fdevice->geometry; return &fdevice->geometry;
} }
const flashVTable_t w25n01g_vTable = { const flashVTable_t w25n_vTable = {
.configure = w25n01g_configure, .configure = w25n_configure,
.isReady = w25n01g_isReady, .isReady = w25n_isReady,
.waitForReady = w25n01g_waitForReady, .waitForReady = w25n_waitForReady,
.eraseSector = w25n01g_eraseSector, .eraseSector = w25n_eraseSector,
.eraseCompletely = w25n01g_eraseCompletely, .eraseCompletely = w25n_eraseCompletely,
.pageProgramBegin = w25n01g_pageProgramBegin, .pageProgramBegin = w25n_pageProgramBegin,
.pageProgramContinue = w25n01g_pageProgramContinue, .pageProgramContinue = w25n_pageProgramContinue,
.pageProgramFinish = w25n01g_pageProgramFinish, .pageProgramFinish = w25n_pageProgramFinish,
.pageProgram = w25n01g_pageProgram, .pageProgram = w25n_pageProgram,
.flush = w25n01g_flush, .flush = w25n_flush,
.readBytes = w25n01g_readBytes, .readBytes = w25n_readBytes,
.getGeometry = w25n01g_getGeometry, .getGeometry = w25n_getGeometry,
}; };
typedef volatile struct cb_context_s { typedef volatile struct cb_context_s {
@ -990,7 +1005,7 @@ typedef volatile struct cb_context_s {
// Called in ISR context // Called in ISR context
// Read of BBLUT entry has just completed // Read of BBLUT entry has just completed
busStatus_e w25n01g_readBBLUTCallback(uint32_t arg) busStatus_e w25n_readBBLUTCallback(uint32_t arg)
{ {
cb_context_t *cb_context = (cb_context_t *)arg; cb_context_t *cb_context = (cb_context_t *)arg;
flashDevice_t *fdevice = cb_context->fdevice; flashDevice_t *fdevice = cb_context->fdevice;
@ -1009,7 +1024,7 @@ busStatus_e w25n01g_readBBLUTCallback(uint32_t arg)
} }
void w25n01g_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize) void w25n_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
{ {
cb_context_t cb_context; cb_context_t cb_context;
uint8_t in[4]; uint8_t in[4];
@ -1022,7 +1037,7 @@ void w25n01g_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
uint8_t cmd[4]; uint8_t cmd[4];
cmd[0] = W25N01G_INSTRUCTION_READ_BBM_LUT; cmd[0] = W25N_INSTRUCTION_READ_BBM_LUT;
cmd[1] = 0; cmd[1] = 0;
cb_context.bblut = &bblut[0]; cb_context.bblut = &bblut[0];
@ -1031,7 +1046,7 @@ void w25n01g_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
busSegment_t segments[] = { busSegment_t segments[] = {
{.u.buffers = {cmd, NULL}, sizeof(cmd), false, NULL}, {.u.buffers = {cmd, NULL}, sizeof(cmd), false, NULL},
{.u.buffers = {NULL, in}, sizeof(in), true, w25n01g_readBBLUTCallback}, {.u.buffers = {NULL, in}, sizeof(in), true, w25n_readBBLUTCallback},
{.u.link = {NULL, NULL}, 0, true, NULL}, {.u.link = {NULL, NULL}, 0, true, NULL},
}; };
@ -1047,11 +1062,11 @@ void w25n01g_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
// 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 // 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. // 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]; uint8_t bblutBuffer[W25N_BBLUT_TABLE_ENTRY_COUNT * W25N_BBLUT_TABLE_ENTRY_SIZE];
quadSpiReceive1LINE(quadSpi, W25N01G_INSTRUCTION_READ_BBM_LUT, 8, bblutBuffer, sizeof(bblutBuffer)); quadSpiReceive1LINE(quadSpi, W25N_INSTRUCTION_READ_BBM_LUT, 8, bblutBuffer, sizeof(bblutBuffer));
for (int i = 0, offset = 0 ; i < lutsize ; i++, offset += 4) { for (int i = 0, offset = 0 ; i < lutsize ; i++, offset += 4) {
if (i < W25N01G_BBLUT_TABLE_ENTRY_COUNT) { if (i < W25N_BBLUT_TABLE_ENTRY_COUNT) {
bblut[i].pba = (in[offset + 0] << 16)|in[offset + 1]; bblut[i].pba = (in[offset + 0] << 16)|in[offset + 1];
bblut[i].lba = (in[offset + 2] << 16)|in[offset + 3]; bblut[i].lba = (in[offset + 2] << 16)|in[offset + 3];
} }
@ -1060,14 +1075,14 @@ void w25n01g_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
#endif #endif
} }
void w25n01g_writeBBLUT(flashDevice_t *fdevice, uint16_t lba, uint16_t pba) void w25n_writeBBLUT(flashDevice_t *fdevice, uint16_t lba, uint16_t pba)
{ {
w25n01g_waitForReady(fdevice); w25n_waitForReady(fdevice);
if (fdevice->io.mode == FLASHIO_SPI) { if (fdevice->io.mode == FLASHIO_SPI) {
extDevice_t *dev = fdevice->io.handle.dev; extDevice_t *dev = fdevice->io.handle.dev;
uint8_t cmd[5] = { W25N01G_INSTRUCTION_BB_MANAGEMENT, lba >> 8, lba, pba >> 8, pba }; uint8_t cmd[5] = { W25N_INSTRUCTION_BB_MANAGEMENT, lba >> 8, lba, pba >> 8, pba };
busSegment_t segments[] = { busSegment_t segments[] = {
{.u.buffers = {cmd, NULL}, sizeof(cmd), true, NULL}, {.u.buffers = {cmd, NULL}, sizeof(cmd), true, NULL},
@ -1087,14 +1102,14 @@ void w25n01g_writeBBLUT(flashDevice_t *fdevice, uint16_t lba, uint16_t pba)
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi; QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
uint8_t data[4] = { lba >> 8, lba, pba >> 8, pba }; uint8_t data[4] = { lba >> 8, lba, pba >> 8, pba };
quadSpiInstructionWithData1LINE(quadSpi, W25N01G_INSTRUCTION_BB_MANAGEMENT, 0, data, sizeof(data)); quadSpiInstructionWithData1LINE(quadSpi, W25N_INSTRUCTION_BB_MANAGEMENT, 0, data, sizeof(data));
} }
#endif #endif
w25n01g_setTimeout(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS); w25n_setTimeout(fdevice, W25N_TIMEOUT_PAGE_PROGRAM_MS);
} }
static void w25n01g_deviceInit(flashDevice_t *flashdev) static void w25n_deviceInit(flashDevice_t *flashdev)
{ {
UNUSED(flashdev); UNUSED(flashdev);
} }

View file

@ -22,7 +22,4 @@
#pragma once #pragma once
// JEDEC ID bool w25n_identify(flashDevice_t *fdevice, uint32_t jedecID);
#define JEDEC_ID_WINBOND_W25N01GV 0xEFAA21
bool w25n01g_identify(flashDevice_t *fdevice, uint32_t jedecID);

View file

@ -324,36 +324,34 @@
#endif #endif
#if (defined(USE_FLASH_W25M512) || defined(USE_FLASH_W25Q128FV) || defined(USE_FLASH_PY25Q128HA)) && !defined(USE_FLASH_M25P16) #if (defined(USE_FLASH_W25M512) || defined(USE_FLASH_W25Q128FV) || defined(USE_FLASH_PY25Q128HA)) && !defined(USE_FLASH_M25P16)
#if !defined(USE_FLASH_M25P16)
#define USE_FLASH_M25P16 #define USE_FLASH_M25P16
#endif #endif
#endif
#if defined(USE_FLASH_W25M02G) && !defined(USE_FLASH_W25N01G) #if defined(USE_FLASH_W25M02G) && !defined(USE_FLASH_W25N01G)
#if !defined(USE_FLASH_W25N01G)
#define USE_FLASH_W25N01G #define USE_FLASH_W25N01G
#endif #endif
#if defined(USE_FLASH_W25N02K) || defined(USE_FLASH_W25N01G)
#define USE_FLASH_W25N
#endif #endif
#if (defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25N01G)) && !defined(USE_FLASH_W25M) #if (defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25N)) && !defined(USE_FLASH_W25M)
#if !defined(USE_FLASH_W25M)
#define USE_FLASH_W25M #define USE_FLASH_W25M
#endif #endif
#endif
#if defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25M) || defined(USE_FLASH_W25N01G) || defined(USE_FLASH_W25Q128FV) #if defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25M) || defined(USE_FLASH_W25N) || defined(USE_FLASH_W25Q128FV)
#if !defined(USE_FLASH_CHIP) #if !defined(USE_FLASH_CHIP)
#define USE_FLASH_CHIP #define USE_FLASH_CHIP
#endif #endif
#endif #endif
#if defined(USE_SPI) && (defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25M512) || defined(USE_FLASH_W25N01G) || defined(USE_FLASH_W25M02G)) #if defined(USE_SPI) && (defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25M512) || defined(USE_FLASH_W25N) || defined(USE_FLASH_W25M02G))
#if !defined(USE_FLASH_SPI) #if !defined(USE_FLASH_SPI)
#define USE_FLASH_SPI #define USE_FLASH_SPI
#endif #endif
#endif #endif
#if defined(USE_QUADSPI) && (defined(USE_FLASH_W25Q128FV) || defined(USE_FLASH_W25N01G)) #if defined(USE_QUADSPI) && (defined(USE_FLASH_W25Q128FV) || defined(USE_FLASH_W25N))
#if !defined(USE_FLASH_QUADSPI) #if !defined(USE_FLASH_QUADSPI)
#define USE_FLASH_QUADSPI #define USE_FLASH_QUADSPI
#endif #endif

View file

@ -138,6 +138,7 @@
#define USE_FLASH_TOOLS #define USE_FLASH_TOOLS
#define USE_FLASH_M25P16 #define USE_FLASH_M25P16
#define USE_FLASH_W25N01G // 1Gb NAND flash support #define USE_FLASH_W25N01G // 1Gb NAND flash support
#define USE_FLASH_W25N02K // 2Gb NAND flash support
#define USE_FLASH_W25M // Stacked die support #define USE_FLASH_W25M // Stacked die support
#define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support #define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support
#define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support #define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support