decoupling chip specific functions from EXTERNAL_FLASH_QSPI_SINGLE
This commit is contained in:
parent
baad9c11df
commit
6c4decd4e2
@ -53,7 +53,7 @@ include $(TOP)/supervisor/supervisor.mk
|
|||||||
# Include make rules and variables common across CircuitPython builds.
|
# Include make rules and variables common across CircuitPython builds.
|
||||||
include $(TOP)/py/circuitpy_defns.mk
|
include $(TOP)/py/circuitpy_defns.mk
|
||||||
|
|
||||||
CROSS_COMPILE = arm-none-eabi-
|
CROSS_COMPILE = ~/opt/gcc-arm-none-eabi-9-2019-q4-major/bin/arm-none-eabi-
|
||||||
|
|
||||||
HAL_DIR=hal/$(MCU_SERIES)
|
HAL_DIR=hal/$(MCU_SERIES)
|
||||||
|
|
||||||
|
@ -1,4 +1,3 @@
|
|||||||
LD_FILE = boards/samd51x19-bootloader-external-flash.ld
|
|
||||||
USB_VID = 0x04D8
|
USB_VID = 0x04D8
|
||||||
USB_PID = 0xEC44
|
USB_PID = 0xEC44
|
||||||
USB_PRODUCT = "PyCubed"
|
USB_PRODUCT = "PyCubed"
|
||||||
@ -12,6 +11,8 @@ EXTERNAL_FLASH_DEVICE_COUNT = 1
|
|||||||
EXTERNAL_FLASH_DEVICES = W25Q80DV
|
EXTERNAL_FLASH_DEVICES = W25Q80DV
|
||||||
LONGINT_IMPL = MPZ
|
LONGINT_IMPL = MPZ
|
||||||
|
|
||||||
|
CIRCUITPY_DRIVE_LABEL = "PYCUBED"
|
||||||
|
|
||||||
# Not needed.
|
# Not needed.
|
||||||
CIRCUITPY_AUDIOBUSIO = 0
|
CIRCUITPY_AUDIOBUSIO = 0
|
||||||
CIRCUITPY_DISPLAYIO = 0
|
CIRCUITPY_DISPLAYIO = 0
|
||||||
|
@ -1,4 +1,3 @@
|
|||||||
|
|
||||||
#define MICROPY_HW_BOARD_NAME "PyCubedv04-MRAM"
|
#define MICROPY_HW_BOARD_NAME "PyCubedv04-MRAM"
|
||||||
#define MICROPY_HW_MCU_NAME "samd51j19"
|
#define MICROPY_HW_MCU_NAME "samd51j19"
|
||||||
#define CIRCUITPY_MCU_FAMILY samd51
|
#define CIRCUITPY_MCU_FAMILY samd51
|
||||||
@ -11,8 +10,12 @@
|
|||||||
#define MICROPY_PORT_C (0)
|
#define MICROPY_PORT_C (0)
|
||||||
#define MICROPY_PORT_D (0)
|
#define MICROPY_PORT_D (0)
|
||||||
|
|
||||||
|
#define SPI_FLASH_WP_PIN &pin_PA10
|
||||||
|
#define SPI_FLASH_HOLD_PIN &pin_PA11
|
||||||
|
|
||||||
// External flash MR2xH40 MRAM
|
// External flash MR2xH40 MRAM
|
||||||
#define EXTERNAL_FLASH_QSPI_SINGLE
|
#define EXTERNAL_FLASH_QSPI_SINGLE
|
||||||
|
#define EXTERNAL_FLASH_NO_JEDEC
|
||||||
|
|
||||||
#define AUTORESET_DELAY_MS 500
|
#define AUTORESET_DELAY_MS 500
|
||||||
|
|
||||||
@ -34,4 +37,3 @@
|
|||||||
|
|
||||||
#define IGNORE_PIN_PA24 1
|
#define IGNORE_PIN_PA24 1
|
||||||
#define IGNORE_PIN_PA25 1
|
#define IGNORE_PIN_PA25 1
|
||||||
|
|
||||||
|
@ -1,4 +1,3 @@
|
|||||||
LD_FILE = boards/samd51x19-bootloader-external-flash.ld
|
|
||||||
USB_VID = 0x04D8
|
USB_VID = 0x04D8
|
||||||
USB_PID = 0xEC44
|
USB_PID = 0xEC44
|
||||||
USB_PRODUCT = "PyCubed"
|
USB_PRODUCT = "PyCubed"
|
||||||
@ -12,10 +11,14 @@ EXTERNAL_FLASH_DEVICE_COUNT = 1
|
|||||||
EXTERNAL_FLASH_DEVICES = MR2xH40
|
EXTERNAL_FLASH_DEVICES = MR2xH40
|
||||||
LONGINT_IMPL = MPZ
|
LONGINT_IMPL = MPZ
|
||||||
|
|
||||||
|
CIRCUITPY_DRIVE_LABEL = "PYCUBED"
|
||||||
|
|
||||||
# Not needed.
|
# Not needed.
|
||||||
CIRCUITPY_AUDIOBUSIO = 0
|
CIRCUITPY_AUDIOBUSIO = 0
|
||||||
CIRCUITPY_DISPLAYIO = 0
|
CIRCUITPY_DISPLAYIO = 0
|
||||||
|
CIRCUITPY_FRAMEBUFFERIO = 0
|
||||||
CIRCUITPY_GAMEPAD = 0
|
CIRCUITPY_GAMEPAD = 0
|
||||||
|
CIRCUITPY_RGBMATRIX = 0
|
||||||
CIRCUITPY_PS2IO = 0
|
CIRCUITPY_PS2IO = 0
|
||||||
|
|
||||||
FROZEN_MPY_DIRS += $(TOP)/frozen/Adafruit_CircuitPython_BusDevice
|
FROZEN_MPY_DIRS += $(TOP)/frozen/Adafruit_CircuitPython_BusDevice
|
||||||
|
@ -169,7 +169,7 @@ bool spi_flash_read_data(uint32_t address, uint8_t* data, uint32_t length) {
|
|||||||
#ifdef EXTERNAL_FLASH_QSPI_SINGLE
|
#ifdef EXTERNAL_FLASH_QSPI_SINGLE
|
||||||
QSPI->INSTRCTRL.bit.INSTR = CMD_READ_DATA;
|
QSPI->INSTRCTRL.bit.INSTR = CMD_READ_DATA;
|
||||||
uint32_t mode = QSPI_INSTRFRAME_WIDTH_SINGLE_BIT_SPI;
|
uint32_t mode = QSPI_INSTRFRAME_WIDTH_SINGLE_BIT_SPI;
|
||||||
#elif defined EXTERNAL_FLASH_QSPI_DUAL
|
#elif defined(EXTERNAL_FLASH_QSPI_DUAL)
|
||||||
QSPI->INSTRCTRL.bit.INSTR = CMD_DUAL_READ;
|
QSPI->INSTRCTRL.bit.INSTR = CMD_DUAL_READ;
|
||||||
uint32_t mode = QSPI_INSTRFRAME_WIDTH_DUAL_OUTPUT;
|
uint32_t mode = QSPI_INSTRFRAME_WIDTH_DUAL_OUTPUT;
|
||||||
#else
|
#else
|
||||||
|
@ -64,6 +64,15 @@ typedef struct {
|
|||||||
// True when the status register is a single byte. This implies the Quad Enable bit is in the
|
// True when the status register is a single byte. This implies the Quad Enable bit is in the
|
||||||
// first byte and the Read Status Register 2 command (0x35) is unsupported.
|
// first byte and the Read Status Register 2 command (0x35) is unsupported.
|
||||||
bool single_status_byte: 1;
|
bool single_status_byte: 1;
|
||||||
|
|
||||||
|
// Does not support using a ready bit within the status register
|
||||||
|
bool no_ready_bit: 1;
|
||||||
|
|
||||||
|
// Does not support the erase command (0x20)
|
||||||
|
bool no_erase_cmd: 1;
|
||||||
|
|
||||||
|
// Device does not have a reset command
|
||||||
|
bool no_reset_cmd: 1;
|
||||||
} external_flash_device;
|
} external_flash_device;
|
||||||
|
|
||||||
// Settings for the Adesto Tech AT25DF081A 1MiB SPI flash. It's on the SAMD21
|
// Settings for the Adesto Tech AT25DF081A 1MiB SPI flash. It's on the SAMD21
|
||||||
@ -426,14 +435,15 @@ typedef struct {
|
|||||||
.single_status_byte = false, \
|
.single_status_byte = false, \
|
||||||
}
|
}
|
||||||
|
|
||||||
// Everspin MRAM
|
// Settings for the Everspin MR20H40 / MR25H40 magnetic non-volatile RAM
|
||||||
|
// Datasheet: https://www.everspin.com/supportdocs/MR25H40CDFR
|
||||||
#define MR2xH40 {\
|
#define MR2xH40 {\
|
||||||
.total_size = (1 << 22), /* 4 MiB */ \
|
.total_size = (1 << 22), /* 4 MiB */ \
|
||||||
.start_up_time_us = 10000, \
|
.start_up_time_us = 10000, \
|
||||||
.manufacturer_id = 0xef, /*no JDEC*/ \
|
.manufacturer_id = 0xef, /*no JDEC*/ \
|
||||||
.memory_type = 0x40, /*no JDEC*/ \
|
.memory_type = 0x40, /*no JDEC*/ \
|
||||||
.capacity = 0x14, /*no JDEC*/ \
|
.capacity = 0x14, /*no JDEC*/ \
|
||||||
.max_clock_speed_mhz = 40, \
|
.max_clock_speed_mhz = 10, \
|
||||||
.quad_enable_bit_mask = 0x00, \
|
.quad_enable_bit_mask = 0x00, \
|
||||||
.has_sector_protection = false, \
|
.has_sector_protection = false, \
|
||||||
.supports_fast_read = false, \
|
.supports_fast_read = false, \
|
||||||
@ -441,6 +451,9 @@ typedef struct {
|
|||||||
.supports_qspi_writes = false, \
|
.supports_qspi_writes = false, \
|
||||||
.write_status_register_split = false, \
|
.write_status_register_split = false, \
|
||||||
.single_status_byte = true, \
|
.single_status_byte = true, \
|
||||||
|
.no_ready_bit = true, \
|
||||||
|
.no_erase_cmd = true, \
|
||||||
|
.no_reset_cmd = true, \
|
||||||
}
|
}
|
||||||
|
|
||||||
// Settings for the Macronix MX25L1606 2MiB SPI flash.
|
// Settings for the Macronix MX25L1606 2MiB SPI flash.
|
||||||
@ -498,25 +511,6 @@ typedef struct {
|
|||||||
.single_status_byte = true, \
|
.single_status_byte = true, \
|
||||||
}
|
}
|
||||||
|
|
||||||
// Settings for the Macronix MX25R1635F 8MiB SPI flash.
|
|
||||||
// Datasheet: https://www.macronix.com/Lists/Datasheet/Attachments/7595/MX25R1635F,%20Wide%20Range,%2016Mb,%20v1.6.pdf
|
|
||||||
// In low power mode, quad operations can only run at 8 MHz.
|
|
||||||
#define MX25R1635F {\
|
|
||||||
.total_size = (1 << 21), /* 2 MiB */ \
|
|
||||||
.start_up_time_us = 800, \
|
|
||||||
.manufacturer_id = 0xc2, \
|
|
||||||
.memory_type = 0x28, \
|
|
||||||
.capacity = 0x18, \
|
|
||||||
.max_clock_speed_mhz = 33, /* 8 mhz for dual/quad */ \
|
|
||||||
.quad_enable_bit_mask = 0x80, \
|
|
||||||
.has_sector_protection = false, \
|
|
||||||
.supports_fast_read = true, \
|
|
||||||
.supports_qspi = true, \
|
|
||||||
.supports_qspi_writes = true, \
|
|
||||||
.write_status_register_split = false, \
|
|
||||||
.single_status_byte = true, \
|
|
||||||
}
|
|
||||||
|
|
||||||
// Settings for the Macronix MX25L51245G 64MiB SPI flash.
|
// Settings for the Macronix MX25L51245G 64MiB SPI flash.
|
||||||
// Datasheet: https://www.macronix.com/Lists/Datasheet/Attachments/7437/MX25L51245G,%203V,%20512Mb,%20v1.6.pdf
|
// Datasheet: https://www.macronix.com/Lists/Datasheet/Attachments/7437/MX25L51245G,%203V,%20512Mb,%20v1.6.pdf
|
||||||
#define MX25L51245G {\
|
#define MX25L51245G {\
|
||||||
|
@ -59,16 +59,16 @@ static supervisor_allocation* supervisor_cache = NULL;
|
|||||||
static bool wait_for_flash_ready(void) {
|
static bool wait_for_flash_ready(void) {
|
||||||
bool ok = true;
|
bool ok = true;
|
||||||
// Both the write enable and write in progress bits should be low.
|
// Both the write enable and write in progress bits should be low.
|
||||||
#ifdef EXTERNAL_FLASH_QSPI_SINGLE
|
if (flash_device->no_ready_bit){
|
||||||
// For NVM without a ready bit in status register
|
// For NVM without a ready bit in status register
|
||||||
return ok;
|
return ok;
|
||||||
#else
|
} else {
|
||||||
uint8_t read_status_response[1] = {0x00};
|
uint8_t read_status_response[1] = {0x00};
|
||||||
do {
|
do {
|
||||||
ok = spi_flash_read_command(CMD_READ_STATUS, read_status_response, 1);
|
ok = spi_flash_read_command(CMD_READ_STATUS, read_status_response, 1);
|
||||||
} while (ok && (read_status_response[0] & 0x3) != 0);
|
} while (ok && (read_status_response[0] & 0x3) != 0);
|
||||||
return ok;
|
return ok;
|
||||||
#endif
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Turn on the write enable bit so we can program and erase the flash.
|
// Turn on the write enable bit so we can program and erase the flash.
|
||||||
@ -96,7 +96,8 @@ static bool write_flash(uint32_t address, const uint8_t* data, uint32_t data_len
|
|||||||
}
|
}
|
||||||
// Don't bother writing if the data is all 1s. Thats equivalent to the flash
|
// Don't bother writing if the data is all 1s. Thats equivalent to the flash
|
||||||
// state after an erase.
|
// state after an erase.
|
||||||
#ifndef EXTERNAL_FLASH_QSPI_SINGLE
|
if (!flash_device->no_erase_cmd){
|
||||||
|
// Only do this if the device has an erase command
|
||||||
bool all_ones = true;
|
bool all_ones = true;
|
||||||
for (uint16_t i = 0; i < data_length; i++) {
|
for (uint16_t i = 0; i < data_length; i++) {
|
||||||
if (data[i] != 0xff) {
|
if (data[i] != 0xff) {
|
||||||
@ -107,7 +108,7 @@ static bool write_flash(uint32_t address, const uint8_t* data, uint32_t data_len
|
|||||||
if (all_ones) {
|
if (all_ones) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#endif
|
}
|
||||||
|
|
||||||
for (uint32_t bytes_written = 0;
|
for (uint32_t bytes_written = 0;
|
||||||
bytes_written < data_length;
|
bytes_written < data_length;
|
||||||
@ -127,29 +128,34 @@ static bool write_flash(uint32_t address, const uint8_t* data, uint32_t data_len
|
|||||||
static bool page_erased(uint32_t sector_address) {
|
static bool page_erased(uint32_t sector_address) {
|
||||||
// Check the first few bytes to catch the common case where there is data
|
// Check the first few bytes to catch the common case where there is data
|
||||||
// without using a bunch of memory.
|
// without using a bunch of memory.
|
||||||
uint8_t short_buffer[4];
|
if (flash_device->no_erase_cmd){
|
||||||
if (read_flash(sector_address, short_buffer, 4)) {
|
// skip this if device doesn't have an erase command.
|
||||||
for (uint16_t i = 0; i < 4; i++) {
|
return true;
|
||||||
if (short_buffer[i] != 0xff) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} else {
|
} else {
|
||||||
return false;
|
uint8_t short_buffer[4];
|
||||||
}
|
if (read_flash(sector_address, short_buffer, 4)) {
|
||||||
|
for (uint16_t i = 0; i < 4; i++) {
|
||||||
|
if (short_buffer[i] != 0xff) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// Now check the full length.
|
// Now check the full length.
|
||||||
uint8_t full_buffer[FILESYSTEM_BLOCK_SIZE];
|
uint8_t full_buffer[FILESYSTEM_BLOCK_SIZE];
|
||||||
if (read_flash(sector_address, full_buffer, FILESYSTEM_BLOCK_SIZE)) {
|
if (read_flash(sector_address, full_buffer, FILESYSTEM_BLOCK_SIZE)) {
|
||||||
for (uint16_t i = 0; i < FILESYSTEM_BLOCK_SIZE; i++) {
|
for (uint16_t i = 0; i < FILESYSTEM_BLOCK_SIZE; i++) {
|
||||||
if (short_buffer[i] != 0xff) {
|
if (short_buffer[i] != 0xff) {
|
||||||
return false;
|
return false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
} else {
|
return true;
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Erases the given sector. Make sure you copied all of the data out of it you
|
// Erases the given sector. Make sure you copied all of the data out of it you
|
||||||
@ -157,12 +163,20 @@ static bool page_erased(uint32_t sector_address) {
|
|||||||
static bool erase_sector(uint32_t sector_address) {
|
static bool erase_sector(uint32_t sector_address) {
|
||||||
// Before we erase the sector we need to wait for any writes to finish and
|
// Before we erase the sector we need to wait for any writes to finish and
|
||||||
// and then enable the write again.
|
// and then enable the write again.
|
||||||
if (!wait_for_flash_ready() || !write_enable()) {
|
if (flash_device->no_erase_cmd){
|
||||||
return false;
|
// skip this if device doesn't have an erase command.
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
if (!wait_for_flash_ready() || !write_enable()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (flash_device->no_erase_cmd) {
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
spi_flash_sector_command(CMD_SECTOR_ERASE, sector_address);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
spi_flash_sector_command(CMD_SECTOR_ERASE, sector_address);
|
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Sector is really 24 bits.
|
// Sector is really 24 bits.
|
||||||
@ -198,20 +212,31 @@ void supervisor_flash_init(void) {
|
|||||||
|
|
||||||
spi_flash_init();
|
spi_flash_init();
|
||||||
|
|
||||||
#ifdef EXTERNAL_FLASH_QSPI_SINGLE
|
#ifdef EXTERNAL_FLASH_NO_JEDEC
|
||||||
// For NVM that don't have JEDEC response
|
// For NVM that don't have JEDEC response
|
||||||
spi_flash_command(CMD_WAKE);
|
spi_flash_command(CMD_WAKE);
|
||||||
for (uint8_t i = 0; i < EXTERNAL_FLASH_DEVICE_COUNT; i++) {
|
for (uint8_t i = 0; i < EXTERNAL_FLASH_DEVICE_COUNT; i++) {
|
||||||
const external_flash_device* possible_device = &possible_devices[i];
|
const external_flash_device* possible_device = &possible_devices[i];
|
||||||
|
flash_device = possible_device;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
// The response will be 0xff if the flash needs more time to start up.
|
||||||
|
uint8_t jedec_id_response[3] = {0xff, 0xff, 0xff};
|
||||||
|
while (jedec_id_response[0] == 0xff) {
|
||||||
|
spi_flash_read_command(CMD_READ_JEDEC_ID, jedec_id_response, 3);
|
||||||
|
}
|
||||||
|
|
||||||
|
for (uint8_t i = 0; i < EXTERNAL_FLASH_DEVICE_COUNT; i++) {
|
||||||
|
const external_flash_device* possible_device = &possible_devices[i];
|
||||||
|
if (jedec_id_response[0] == possible_device->manufacturer_id &&
|
||||||
|
jedec_id_response[1] == possible_device->memory_type &&
|
||||||
|
jedec_id_response[2] == possible_device->capacity) {
|
||||||
flash_device = possible_device;
|
flash_device = possible_device;
|
||||||
break;
|
break;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
#else
|
#endif
|
||||||
// The response will be 0xff if the flash needs more time to start up.
|
|
||||||
uint8_t jedec_id_response[3] = {0xff, 0xff, 0xff};
|
|
||||||
while (jedec_id_response[0] == 0xff) {
|
|
||||||
spi_flash_read_command(CMD_READ_JEDEC_ID, jedec_id_response, 3);
|
|
||||||
}
|
|
||||||
|
|
||||||
for (uint8_t i = 0; i < EXTERNAL_FLASH_DEVICE_COUNT; i++) {
|
for (uint8_t i = 0; i < EXTERNAL_FLASH_DEVICE_COUNT; i++) {
|
||||||
const external_flash_device* possible_device = &possible_devices[i];
|
const external_flash_device* possible_device = &possible_devices[i];
|
||||||
@ -227,20 +252,23 @@ void supervisor_flash_init(void) {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// We don't know what state the flash is in so wait for any remaining writes and then reset.
|
// We don't know what state the flash is in so wait for any remaining writes and then reset.
|
||||||
uint8_t read_status_response[1] = {0x00};
|
uint8_t read_status_response[1] = {0x00};
|
||||||
// The write in progress bit should be low.
|
// The write in progress bit should be low.
|
||||||
do {
|
do {
|
||||||
spi_flash_read_command(CMD_READ_STATUS, read_status_response, 1);
|
spi_flash_read_command(CMD_READ_STATUS, read_status_response, 1);
|
||||||
} while ((read_status_response[0] & 0x1) != 0);
|
} while ((read_status_response[0] & 0x1) != 0);
|
||||||
#ifndef EXTERNAL_FLASH_QSPI_SINGLE
|
|
||||||
|
if (!(flash_device->no_reset_cmd)){
|
||||||
// The suspended write/erase bit should be low.
|
// The suspended write/erase bit should be low.
|
||||||
do {
|
do {
|
||||||
spi_flash_read_command(CMD_READ_STATUS2, read_status_response, 1);
|
spi_flash_read_command(CMD_READ_STATUS2, read_status_response, 1);
|
||||||
} while ((read_status_response[0] & 0x80) != 0);
|
} while ((read_status_response[0] & 0x80) != 0);
|
||||||
|
} else {
|
||||||
spi_flash_command(CMD_ENABLE_RESET);
|
spi_flash_command(CMD_ENABLE_RESET);
|
||||||
spi_flash_command(CMD_RESET);
|
spi_flash_command(CMD_RESET);
|
||||||
#endif
|
}
|
||||||
|
|
||||||
// Wait 30us for the reset
|
// Wait 30us for the reset
|
||||||
common_hal_mcu_delay_us(30);
|
common_hal_mcu_delay_us(30);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user