diff --git a/ports/nrf/Makefile b/ports/nrf/Makefile index 0e9d224be722d..7bf3cf1284dff 100755 --- a/ports/nrf/Makefile +++ b/ports/nrf/Makefile @@ -87,17 +87,18 @@ LIBS := -L $(dir $(LIBM_FILE_NAME)) -lm LIBS += -L $(dir $(LIBC_FILE_NAME)) -lc LIBS += -L $(dir $(LIBGCC_FILE_NAME)) -lgcc -SRC_NRFX = $(addprefix nrfx/,\ +SRC_NRFX += $(addprefix nrfx/,\ drivers/src/nrfx_power.c \ drivers/src/nrfx_spim.c \ drivers/src/nrfx_twim.c \ drivers/src/nrfx_uart.c \ + hal/nrf_nvmc.c \ + mdk/system_$(MCU_SUB_VARIANT).c \ ) SRC_C += \ background.c \ fatfs_port.c \ - internal_flash.c \ mphalport.c \ tick.c \ boards/$(BOARD)/board.c \ @@ -105,6 +106,8 @@ SRC_C += \ device/$(MCU_VARIANT)/startup_$(MCU_SUB_VARIANT).c \ drivers/bluetooth/ble_drv.c \ drivers/bluetooth/ble_uart.c \ + flash_api/internal_flash.c \ + flash_api/flash_api.c \ lib/libc/string0.c \ lib/mp-readline/readline.c \ lib/oofatfs/ff.c \ @@ -116,14 +119,18 @@ SRC_C += \ lib/utils/pyexec.c \ lib/utils/stdout_helpers.c \ lib/utils/sys_stdio_mphal.c \ - nrfx/hal/nrf_nvmc.c \ - nrfx/mdk/system_$(MCU_SUB_VARIANT).c \ peripherals/nrf/cache.c \ peripherals/nrf/clocks.c \ peripherals/nrf/$(MCU_CHIP)/pins.c \ peripherals/nrf/$(MCU_CHIP)/power.c \ supervisor/shared/memory.c +ifeq ($(QSPI_FLASH_FILESYSTEM),1) +SRC_C += flash_api/qspi_flash.c +SRC_NRFX += nrfx/drivers/src/nrfx_qspi.c +CFLAGS += -DQSPI_FLASH_FILESYSTEM +endif + DRIVERS_SRC_C += $(addprefix modules/,\ ubluepy/modubluepy.c \ ubluepy/ubluepy_peripheral.c \ diff --git a/ports/nrf/boards/feather_nrf52840_express/board.c b/ports/nrf/boards/feather_nrf52840_express/board.c index a6d050fce2cd7..5eef0cf050866 100644 --- a/ports/nrf/boards/feather_nrf52840_express/board.c +++ b/ports/nrf/boards/feather_nrf52840_express/board.c @@ -25,10 +25,9 @@ */ #include "boards/board.h" -#include "usb.h" void board_init(void) { - usb_init(); + } bool board_requests_safe_mode(void) { diff --git a/ports/nrf/boards/feather_nrf52840_express/mpconfigboard.h b/ports/nrf/boards/feather_nrf52840_express/mpconfigboard.h index 81818741d1a52..b689246bfb2eb 100644 --- a/ports/nrf/boards/feather_nrf52840_express/mpconfigboard.h +++ b/ports/nrf/boards/feather_nrf52840_express/mpconfigboard.h @@ -27,45 +27,47 @@ #define FEATHER52840 -#define MICROPY_HW_BOARD_NAME "Adafruit Feather nRF52840 Express" -#define MICROPY_HW_MCU_NAME "nRF52840" -#define MICROPY_PY_SYS_PLATFORM "Feather52840Express" +#define MICROPY_HW_BOARD_NAME "Adafruit Feather nRF52840 Express" +#define MICROPY_HW_MCU_NAME "nRF52840" +#define MICROPY_PY_SYS_PLATFORM "Feather52840Express" -#define MICROPY_HW_NEOPIXEL (&pin_P0_13) +#define MICROPY_HW_NEOPIXEL (&pin_P0_13) -#define MICROPY_QSPI_DATA0 (&pin_P1_09) -#define MICROPY_QSPI_DATA1 (&pin_P0_11) -#define MICROPY_QSPI_DATA2 (&pin_P0_12) -#define MICROPY_QSPI_DATA3 (&pin_P0_14) -#define MICROPY_QSPI_SCK (&pin_P0_08) -#define MICROPY_QSPI_CS (&pin_P1_08) +#define MICROPY_HW_LED_MSC NRF_GPIO_PIN_MAP(0, 13) +#define MICROPY_HW_LED_MSC_ACTIVE_LEVEL 1 + +// Flash operation mode is determined by MICROPY_QSPI_DATAn pin configuration. +// A pin config is valid if it is defined and its value is not 0xFF. +// Quad mode: If all DATA0 --> DATA3 are valid +// Dual mode: If DATA0 and DATA1 are valid while either DATA2 and/or DATA3 are invalid +// Single mode: If only DATA0 is valid +#define MICROPY_QSPI_DATA0 NRF_GPIO_PIN_MAP(1, 9) +#define MICROPY_QSPI_DATA1 NRF_GPIO_PIN_MAP(0, 11) +#define MICROPY_QSPI_DATA2 NRF_GPIO_PIN_MAP(0, 12) +#define MICROPY_QSPI_DATA3 NRF_GPIO_PIN_MAP(0, 14) +#define MICROPY_QSPI_SCK NRF_GPIO_PIN_MAP(0, 8) +#define MICROPY_QSPI_CS NRF_GPIO_PIN_MAP(1, 8) #define CIRCUITPY_AUTORELOAD_DELAY_MS 500 // If you change this, then make sure to update the linker scripts as well to // make sure you don't overwrite code -#define PORT_HEAP_SIZE (128 * 1024) +#define PORT_HEAP_SIZE (128 * 1024) // TODO #define CIRCUITPY_INTERNAL_NVM_SIZE 8192 -#define BOARD_FLASH_SIZE (FLASH_SIZE - 0x4000 - CIRCUITPY_INTERNAL_NVM_SIZE) - -// TODO #include "external_flash/devices.h" - -#define EXTERNAL_FLASH_DEVICE_COUNT 1 -#define EXTERNAL_FLASH_DEVICES GD25Q16C - -#define EXTERNAL_FLASH_QSPI_DUAL +#define BOARD_FLASH_SIZE (FLASH_SIZE - 0x4000 - CIRCUITPY_INTERNAL_NVM_SIZE) -// TODO include "external_flash/external_flash.h" +// On-board QSPI Flash +#define EXTERNAL_FLASH_DEVICES GD25Q16C -#define BOARD_HAS_CRYSTAL 1 +#define BOARD_HAS_CRYSTAL 1 -#define DEFAULT_I2C_BUS_SCL (&pin_P1_11) -#define DEFAULT_I2C_BUS_SDA (&pin_P1_12) +#define DEFAULT_I2C_BUS_SCL (&pin_P1_11) +#define DEFAULT_I2C_BUS_SDA (&pin_P1_12) -#define DEFAULT_SPI_BUS_SCK (&pin_P0_20) -#define DEFAULT_SPI_BUS_MOSI (&pin_P0_23) -#define DEFAULT_SPI_BUS_MISO (&pin_P0_22) +#define DEFAULT_SPI_BUS_SCK (&pin_P0_20) +#define DEFAULT_SPI_BUS_MOSI (&pin_P0_23) +#define DEFAULT_SPI_BUS_MISO (&pin_P0_22) -#define DEFAULT_UART_BUS_RX (&pin_P1_0) -#define DEFAULT_UART_BUS_TX (&pin_P0_24) +#define DEFAULT_UART_BUS_RX (&pin_P1_0) +#define DEFAULT_UART_BUS_TX (&pin_P0_24) diff --git a/ports/nrf/boards/feather_nrf52840_express/mpconfigboard.mk b/ports/nrf/boards/feather_nrf52840_express/mpconfigboard.mk index caf580ec4d124..0541e03236f44 100644 --- a/ports/nrf/boards/feather_nrf52840_express/mpconfigboard.mk +++ b/ports/nrf/boards/feather_nrf52840_express/mpconfigboard.mk @@ -6,6 +6,7 @@ SD ?= s140 SOFTDEV_VERSION ?= 6.1.0 BOOT_SETTING_ADDR = 0xFF000 +QSPI_FLASH_FILESYSTEM = 1 ifeq ($(SD),) LD_FILE = boards/nrf52840_1M_256k.ld diff --git a/ports/nrf/boards/pca10056/board.c b/ports/nrf/boards/pca10056/board.c index a6d050fce2cd7..d18a54c95fc27 100644 --- a/ports/nrf/boards/pca10056/board.c +++ b/ports/nrf/boards/pca10056/board.c @@ -25,10 +25,10 @@ */ #include "boards/board.h" -#include "usb.h" +#include "nrf_gpio.h" void board_init(void) { - usb_init(); + } bool board_requests_safe_mode(void) { @@ -36,5 +36,15 @@ bool board_requests_safe_mode(void) { } void reset_board(void) { + // LEDs + for ( int i = 13; i <= 16; i++ ) { + nrf_gpio_cfg_output(i); + nrf_gpio_pin_set(i); + } + // Buttons + nrf_gpio_cfg_input(11, NRF_GPIO_PIN_PULLUP); + nrf_gpio_cfg_input(12, NRF_GPIO_PIN_PULLUP); + nrf_gpio_cfg_input(24, NRF_GPIO_PIN_PULLUP); + nrf_gpio_cfg_input(25, NRF_GPIO_PIN_PULLUP); } diff --git a/ports/nrf/boards/pca10056/mpconfigboard.h b/ports/nrf/boards/pca10056/mpconfigboard.h index de4545d6201eb..9f266626eb866 100644 --- a/ports/nrf/boards/pca10056/mpconfigboard.h +++ b/ports/nrf/boards/pca10056/mpconfigboard.h @@ -24,27 +24,47 @@ * THE SOFTWARE. */ -#define MICROPY_HW_BOARD_NAME "PCA10056 nRF52840-DK" -#define MICROPY_HW_MCU_NAME "nRF52840" -#define MICROPY_PY_SYS_PLATFORM "nRF52840-DK" +#define MICROPY_HW_BOARD_NAME "PCA10056 nRF52840-DK" +#define MICROPY_HW_MCU_NAME "nRF52840" +#define MICROPY_PY_SYS_PLATFORM "nRF52840-DK" // See legend on bottom of board -#define MICROPY_HW_UART_RX NRF_GPIO_PIN_MAP(0, 8) -#define MICROPY_HW_UART_TX NRF_GPIO_PIN_MAP(0, 6) -#define MICROPY_HW_UART_HWFC (0) +#define MICROPY_HW_UART_RX NRF_GPIO_PIN_MAP(0, 8) +#define MICROPY_HW_UART_TX NRF_GPIO_PIN_MAP(0, 6) +#define MICROPY_HW_UART_HWFC (0) -#define PORT_HEAP_SIZE (128 * 1024) -#define CIRCUITPY_AUTORELOAD_DELAY_MS 500 +#define MICROPY_HW_LED_MSC NRF_GPIO_PIN_MAP(0, 13) +#define MICROPY_HW_LED_MSC_ACTIVE_LEVEL 0 + +#define PORT_HEAP_SIZE (128 * 1024) +#define CIRCUITPY_AUTORELOAD_DELAY_MS 500 // Temp (could be removed) 0: usb cdc (default), 1 : hwuart (jlink) -#define CFG_HWUART_FOR_SERIAL 0 +#define CFG_HWUART_FOR_SERIAL 0 + +#define DEFAULT_I2C_BUS_SCL (&pin_P0_27) +#define DEFAULT_I2C_BUS_SDA (&pin_P0_26) + +#define DEFAULT_SPI_BUS_SCK (&pin_P1_15) +#define DEFAULT_SPI_BUS_MOSI (&pin_P1_13) +#define DEFAULT_SPI_BUS_MISO (&pin_P1_14) + +#define DEFAULT_UART_BUS_RX (&pin_P1_01) +#define DEFAULT_UART_BUS_TX (&pin_P1_02) + +// On-board QSPI Flash +#define EXTERNAL_FLASH_DEVICES MX25R6435F -#define DEFAULT_I2C_BUS_SCL (&pin_P0_27) -#define DEFAULT_I2C_BUS_SDA (&pin_P0_26) +// Flash operation mode is determined by MICROPY_QSPI_DATAn pin configuration. +// A pin config is valid if it is defined and its value is not 0xFF. +// Quad mode: If all DATA0 --> DATA3 are valid +// Dual mode: If DATA0 and DATA1 are valid while either DATA2 and/or DATA3 are invalid +// Single mode: If only DATA0 is valid +#define MICROPY_QSPI_DATA0 NRF_GPIO_PIN_MAP(0, 20) +#define MICROPY_QSPI_DATA1 NRF_GPIO_PIN_MAP(0, 21) +#define MICROPY_QSPI_DATA2 NRF_GPIO_PIN_MAP(0, 22) +#define MICROPY_QSPI_DATA3 NRF_GPIO_PIN_MAP(0, 23) +#define MICROPY_QSPI_SCK NRF_GPIO_PIN_MAP(0, 19) +#define MICROPY_QSPI_CS NRF_GPIO_PIN_MAP(0, 17) -#define DEFAULT_SPI_BUS_SCK (&pin_P1_15) -#define DEFAULT_SPI_BUS_MOSI (&pin_P1_13) -#define DEFAULT_SPI_BUS_MISO (&pin_P1_14) -#define DEFAULT_UART_BUS_RX (&pin_P1_01) -#define DEFAULT_UART_BUS_TX (&pin_P1_02) diff --git a/ports/nrf/boards/pca10056/mpconfigboard.mk b/ports/nrf/boards/pca10056/mpconfigboard.mk index caf580ec4d124..0541e03236f44 100644 --- a/ports/nrf/boards/pca10056/mpconfigboard.mk +++ b/ports/nrf/boards/pca10056/mpconfigboard.mk @@ -6,6 +6,7 @@ SD ?= s140 SOFTDEV_VERSION ?= 6.1.0 BOOT_SETTING_ADDR = 0xFF000 +QSPI_FLASH_FILESYSTEM = 1 ifeq ($(SD),) LD_FILE = boards/nrf52840_1M_256k.ld diff --git a/ports/nrf/boards/pca10059/board.c b/ports/nrf/boards/pca10059/board.c index cbb4ef3b6db91..c1db7b309a724 100644 --- a/ports/nrf/boards/pca10059/board.c +++ b/ports/nrf/boards/pca10059/board.c @@ -28,10 +28,8 @@ #include #include "boards/board.h" #include "nrfx.h" -#include "usb.h" void board_init(void) { - usb_init(); } bool board_requests_safe_mode(void) { diff --git a/ports/nrf/flash_api/flash_api.c b/ports/nrf/flash_api/flash_api.c new file mode 100644 index 0000000000000..619264fa1f54c --- /dev/null +++ b/ports/nrf/flash_api/flash_api.c @@ -0,0 +1,268 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2018 hathach for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include +#include "nrf_gpio.h" +#include "flash_api.h" +#include "internal_flash.h" +#include "qspi_flash.h" + +#include "py/mphal.h" +#include "py/obj.h" +#include "py/runtime.h" + +//--------------------------------------------------------------------+ +// Block API with caching +//--------------------------------------------------------------------+ +#define NO_CACHE 0xffffffff + +static uint32_t _cache_addr = NO_CACHE; +static uint8_t _cache_buf[FLASH_API_PAGE_SIZE] __attribute__((aligned(4))); + +static inline uint32_t page_addr_of (uint32_t addr) { + return addr & ~(FLASH_API_PAGE_SIZE - 1); +} + +static inline uint32_t page_offset_of (uint32_t addr) { + return addr & (FLASH_API_PAGE_SIZE - 1); +} + +mp_uint_t flash_read_blocks (uint8_t* dst, uint32_t lba, uint32_t count) { + flash_hal_read(dst, lba * FLASH_API_BLOCK_SIZE, count * FLASH_API_BLOCK_SIZE); + return 0; +} + +mp_uint_t flash_write_blocks (const uint8_t *src, uint32_t lba, uint32_t num_blocks) { + // Program blocks up to page boundary each loop + while ( num_blocks ) { + const uint32_t dst = lba * FLASH_API_BLOCK_SIZE; + const uint32_t page_addr = page_addr_of(dst); + const uint32_t offset = page_offset_of(dst); + + uint32_t wr_blocks = FLASH_API_BLOCK_PER_PAGE - (lba % FLASH_API_BLOCK_PER_PAGE); // up to page boundary + wr_blocks = MIN(num_blocks, wr_blocks); + + const uint32_t wr_bytes = wr_blocks * FLASH_API_BLOCK_SIZE; + + // Page changes, flush old and update new cache + if ( page_addr != _cache_addr ) { + flash_flush(); + _cache_addr = page_addr; + + // read existing flash to cache except those we are writing + if ( offset ) { + flash_hal_read(_cache_buf, page_addr, offset); + } + + const uint32_t last_byte = offset + wr_bytes; + if ( last_byte < FLASH_API_PAGE_SIZE ) { + flash_hal_read(_cache_buf + last_byte, page_addr + last_byte, FLASH_API_PAGE_SIZE - last_byte); + } + } + + memcpy(_cache_buf + offset, src, wr_bytes); + + // adjust for next run + src += wr_bytes; + lba += wr_blocks; + num_blocks -= wr_blocks; + } + + return 0; +} + +void flash_flush (void) { + if ( _cache_addr == NO_CACHE ) return; + + flash_hal_erase(_cache_addr); + flash_hal_program(_cache_addr, _cache_buf, FLASH_API_PAGE_SIZE); + + _cache_addr = NO_CACHE; +} + +//--------------------------------------------------------------------+ +// Flash HAL +//--------------------------------------------------------------------+ + + +void flash_init (void) { +#ifdef QSPI_FLASH_FILESYSTEM + qspi_flash_init(); + + // Flash device is not detected, fall back to internal flash + if (!qspi_flash_detected() ) +#endif + { + internal_flash_init(); + } +} + +uint32_t flash_get_block_count (void) { +#ifdef QSPI_FLASH_FILESYSTEM + // Flash device is not detected, fall back to internal flash + if ( qspi_flash_detected() ) { + return qspi_flash_get_block_count(); + } + else +#endif + { + return internal_flash_get_block_count(); + } +} + +void flash_hal_erase (uint32_t addr) { +#ifdef QSPI_FLASH_FILESYSTEM + // Flash device is not detected, fall back to internal flash + if ( qspi_flash_detected() ) { + return qspi_flash_hal_erase(addr); + } + else +#endif + { + internal_flash_hal_erase(addr); + } +} + +void flash_hal_program (uint32_t dst, const void * src, uint32_t len) { +#ifdef QSPI_FLASH_FILESYSTEM + // Flash device is not detected, fall back to internal flash + if ( qspi_flash_detected() ) { + qspi_flash_hal_program(dst, src, len); + } + else +#endif + { + internal_flash_hal_program(dst, src, len); + } +} + +void flash_hal_read (void* dst, uint32_t src, uint32_t len) { +#ifdef QSPI_FLASH_FILESYSTEM + // Flash device is not detected, fall back to internal flash + if ( qspi_flash_detected() ) { + qspi_flash_hal_read(dst, src, len); + } + else +#endif + { + internal_flash_hal_read(dst, src, len); + } +} + +/******************************************************************************/ +// MicroPython bindings +// +// Expose the flash as an object with the block protocol. +// there is a singleton Flash object +/******************************************************************************/ +extern const struct _mp_obj_type_t _flash_type; // forward declaration + +const STATIC mp_obj_base_t _flash_obj = { &_flash_type }; + +STATIC mp_obj_t flash_obj_make_new (const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *args) { + // check arguments + mp_arg_check_num(n_args, n_kw, 0, 0, false); + + // return singleton object + return (mp_obj_t) &_flash_obj; +} + +STATIC mp_obj_t flash_obj_readblocks (mp_obj_t self, mp_obj_t block_num, mp_obj_t buf) { + mp_buffer_info_t bufinfo; + mp_get_buffer_raise(buf, &bufinfo, MP_BUFFER_WRITE); + mp_uint_t ret = flash_read_blocks(bufinfo.buf, mp_obj_get_int(block_num), bufinfo.len / FLASH_API_BLOCK_SIZE); + return MP_OBJ_NEW_SMALL_INT(ret); +} +STATIC MP_DEFINE_CONST_FUN_OBJ_3(flash_obj_readblocks_obj, flash_obj_readblocks); + +STATIC mp_obj_t flash_obj_writeblocks (mp_obj_t self, mp_obj_t block_num, mp_obj_t buf) { + mp_buffer_info_t bufinfo; + mp_get_buffer_raise(buf, &bufinfo, MP_BUFFER_READ); + mp_uint_t ret = flash_write_blocks(bufinfo.buf, mp_obj_get_int(block_num), bufinfo.len / FLASH_API_BLOCK_SIZE); + return MP_OBJ_NEW_SMALL_INT(ret); +} +STATIC MP_DEFINE_CONST_FUN_OBJ_3(flash_obj_writeblocks_obj, flash_obj_writeblocks); + +STATIC mp_obj_t flash_obj_ioctl (mp_obj_t self, mp_obj_t cmd_in, mp_obj_t arg_in) { + mp_int_t cmd = mp_obj_get_int(cmd_in); + switch ( cmd ) { + case BP_IOCTL_INIT: + flash_init(); + return MP_OBJ_NEW_SMALL_INT(0); + case BP_IOCTL_DEINIT: + flash_flush(); + return MP_OBJ_NEW_SMALL_INT(0); // TODO properly + case BP_IOCTL_SYNC: + flash_flush(); + return MP_OBJ_NEW_SMALL_INT(0); + case BP_IOCTL_SEC_COUNT: + return MP_OBJ_NEW_SMALL_INT(flash_get_block_count()); + case BP_IOCTL_SEC_SIZE: + return MP_OBJ_NEW_SMALL_INT(FLASH_API_BLOCK_SIZE); + default: + return mp_const_none; + } +} +STATIC MP_DEFINE_CONST_FUN_OBJ_3(flash_obj_ioctl_obj, flash_obj_ioctl); + + const STATIC mp_rom_map_elem_t flash_obj_locals_dict_table[] = { + { MP_ROM_QSTR(MP_QSTR_readblocks), MP_ROM_PTR(&flash_obj_readblocks_obj) }, + { MP_ROM_QSTR(MP_QSTR_writeblocks), MP_ROM_PTR(&flash_obj_writeblocks_obj) }, + { MP_ROM_QSTR(MP_QSTR_ioctl), MP_ROM_PTR(&flash_obj_ioctl_obj) }, +}; + +STATIC MP_DEFINE_CONST_DICT(flash_obj_locals_dict, flash_obj_locals_dict_table); + +const mp_obj_type_t _flash_type = { + { &mp_type_type }, + .name = MP_QSTR_Flash, + .make_new = flash_obj_make_new, + .locals_dict = (mp_obj_t) &flash_obj_locals_dict, +}; + +void flash_init_vfs (fs_user_mount_t *vfs) { + vfs->base.type = &mp_fat_vfs_type; + vfs->flags |= FSUSER_NATIVE | FSUSER_HAVE_IOCTL; + vfs->fatfs.drv = vfs; + +// vfs->fatfs.part = 1; // flash filesystem lives on first partition + vfs->readblocks[0] = (mp_obj_t) &flash_obj_readblocks_obj; + vfs->readblocks[1] = (mp_obj_t) &_flash_obj; + vfs->readblocks[2] = (mp_obj_t) flash_read_blocks; // native version + + vfs->writeblocks[0] = (mp_obj_t) &flash_obj_writeblocks_obj; + vfs->writeblocks[1] = (mp_obj_t) &_flash_obj; + vfs->writeblocks[2] = (mp_obj_t) flash_write_blocks; // native version + + vfs->u.ioctl[0] = (mp_obj_t) &flash_obj_ioctl_obj; + vfs->u.ioctl[1] = (mp_obj_t) &_flash_obj; + + // Activity LED for flash writes. +#ifdef MICROPY_HW_LED_MSC + nrf_gpio_cfg_output(MICROPY_HW_LED_MSC); + nrf_gpio_pin_write(MICROPY_HW_LED_MSC, 1 - MICROPY_HW_LED_MSC_ACTIVE_LEVEL); +#endif +} diff --git a/ports/nrf/flash_api/flash_api.h b/ports/nrf/flash_api/flash_api.h new file mode 100644 index 0000000000000..3dd51c1bb1e83 --- /dev/null +++ b/ports/nrf/flash_api/flash_api.h @@ -0,0 +1,64 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2018 hathach for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef FLASH_API_H_ +#define FLASH_API_H_ + +#include "extmod/vfs_fat.h" + +#define FLASH_API_BLOCK_SIZE FILESYSTEM_BLOCK_SIZE +#define FLASH_API_PAGE_SIZE 4096 +#define FLASH_API_BLOCK_PER_PAGE (FLASH_API_PAGE_SIZE/FLASH_API_BLOCK_SIZE) + +enum { + FLASH_STATE_IDLE, + FLASH_STATE_BUSY, + FLASH_STATE_COMPLETE +}; + +#ifdef __cplusplus + extern "C" { +#endif + +// Low level flash hal +void flash_init (void); +uint32_t flash_get_block_count (void); +void flash_hal_erase (uint32_t addr); +void flash_hal_program (uint32_t dst, const void* src, uint32_t len); +void flash_hal_read (void* dst, uint32_t src, uint32_t len); + +void flash_init_vfs (struct _fs_user_mount_t *vfs); + +mp_uint_t flash_read_blocks (uint8_t* dst, uint32_t lba, uint32_t count); +mp_uint_t flash_write_blocks (const uint8_t *src, uint32_t lba, uint32_t count); +void flash_flush (void); + + +#ifdef __cplusplus + } +#endif + +#endif /* FLASH_API_H_ */ diff --git a/ports/nrf/flash_api/flash_devices.h b/ports/nrf/flash_api/flash_devices.h new file mode 100644 index 0000000000000..1f8edae5ab762 --- /dev/null +++ b/ports/nrf/flash_api/flash_devices.h @@ -0,0 +1,73 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2018 hathach for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef FLASH_DEVICES_H_ +#define FLASH_DEVICES_H_ + +#include +#include + +#ifdef __cplusplus + extern "C" { +#endif + +typedef struct { + uint32_t total_size; + + // Three response bytes to 0x90 JEDEC REMS ID command. + uint8_t manufacturer_id; + uint8_t device_id; + + // Status register value enable quad mode + uint16_t status_quad_enable; + +} qspi_flash_device_t; + +// All supported devices +#define ALL_EXTERNAL_FLASH_DEVICES GD25Q16C, MX25R6435F + + +// Settings for the Gigadevice GD25Q16C 2MiB SPI flash. +// Datasheet: http://www.gigadevice.com/wp-content/uploads/2017/12/DS-00086-GD25Q16C-Rev2.6.pdf +#define GD25Q16C {\ + .total_size = 2*1024*1024, \ + .manufacturer_id = 0xc8, \ + .device_id = 0x14, \ + .status_quad_enable = (1 << 9)\ +} + +#define MX25R6435F {\ + .total_size = 8*1024*1024, \ + .manufacturer_id = 0xc2, \ + .device_id = 0x17, \ + .status_quad_enable = (1 << 6)\ +} + +#ifdef __cplusplus + } +#endif + +#endif /* FLASH_DEVICES_H_ */ diff --git a/ports/nrf/flash_api/internal_flash.c b/ports/nrf/flash_api/internal_flash.c new file mode 100644 index 0000000000000..1f3b5894194ae --- /dev/null +++ b/ports/nrf/flash_api/internal_flash.c @@ -0,0 +1,68 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2013, 2014 Damien P. George + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include +#include + +#include "flash_api/flash_api.h" +#include "lib/oofatfs/ff.h" +#include "supervisor/shared/rgb_led_status.h" + +#include "nrf_nvmc.h" + +#ifdef BLUETOOTH_SD +#include "nrf_sdm.h" +#endif + +// defined in linker +extern uint32_t __fatfs_flash_start_addr[]; +extern uint32_t __fatfs_flash_length[]; + +static inline uint32_t log2phy_addr (uint32_t addr) { + return ((uint32_t) __fatfs_flash_start_addr) + addr; +} + +void internal_flash_init(void) { + +} + +uint32_t internal_flash_get_block_count(void) { + return ((uint32_t) __fatfs_flash_length) / FLASH_API_BLOCK_SIZE; +} + +// TODO support flashing with SD enabled +void internal_flash_hal_erase (uint32_t addr) { + nrf_nvmc_page_erase(log2phy_addr(addr)); +} + +void internal_flash_hal_program (uint32_t dst, const void * src, uint32_t len) { + nrf_nvmc_write_words(log2phy_addr(dst), (uint32_t *) src, len / sizeof(uint32_t)); +} + +void internal_flash_hal_read (void* dst, uint32_t src, uint32_t len) { + memcpy(dst, (void*) log2phy_addr(src), len); +} + diff --git a/ports/nrf/internal_flash.h b/ports/nrf/flash_api/internal_flash.h similarity index 64% rename from ports/nrf/internal_flash.h rename to ports/nrf/flash_api/internal_flash.h index 3811815e291b9..3855890c60d80 100644 --- a/ports/nrf/internal_flash.h +++ b/ports/nrf/flash_api/internal_flash.h @@ -31,29 +31,13 @@ #include "mpconfigport.h" -#define FLASH_ROOT_POINTERS - -#define FLASH_PAGE_SIZE 0x1000 #define CIRCUITPY_INTERNAL_NVM_SIZE 0 -#define INTERNAL_FLASH_SYSTICK_MASK (0x1ff) // 512ms -#define INTERNAL_FLASH_IDLE_TICK(tick) (((tick) & INTERNAL_FLASH_SYSTICK_MASK) == 2) - -void internal_flash_init(void); -uint32_t internal_flash_get_block_size(void); -uint32_t internal_flash_get_block_count(void); -void internal_flash_irq_handler(void); -void internal_flash_flush(void); - -// these return 0 on success, non-zero on error -mp_uint_t internal_flash_read_blocks(uint8_t *dest, uint32_t block_num, uint32_t num_blocks); -mp_uint_t internal_flash_write_blocks(const uint8_t *src, uint32_t block_num, uint32_t num_blocks); - -extern const struct _mp_obj_type_t internal_flash_type; - -struct _fs_user_mount_t; +void internal_flash_init (void); +uint32_t internal_flash_get_block_count (void); -void flash_init_vfs(struct _fs_user_mount_t *vfs); -void flash_flush(void); +void internal_flash_hal_erase (uint32_t addr); +void internal_flash_hal_program (uint32_t dst, const void * src, uint32_t len); +void internal_flash_hal_read (void* dst, uint32_t src, uint32_t len); #endif // MICROPY_INCLUDED_NRF_INTERNAL_FLASH_H diff --git a/ports/nrf/flash_api/qspi_flash.c b/ports/nrf/flash_api/qspi_flash.c new file mode 100644 index 0000000000000..12677a9f14198 --- /dev/null +++ b/ports/nrf/flash_api/qspi_flash.c @@ -0,0 +1,185 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2018 hathach for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include + +#include "mpconfigboard.h" +#include "nrf_gpio.h" +#include "nrfx_qspi.h" +#include "flash_api.h" +#include "qspi_flash.h" +#include "flash_devices.h" + +#define _VALID_PIN(n) (defined(MICROPY_QSPI_DATA##n) && (MICROPY_QSPI_DATA##n != 0xff)) + +#define QSPI_FLASH_MODE \ + (( _VALID_PIN(0) && _VALID_PIN(1) && _VALID_PIN(2) && _VALID_PIN(3) ) ? 4 : \ + ( _VALID_PIN(0) && _VALID_PIN(1) ) ? 2 : \ + ( _VALID_PIN(0) ) ? 1 : 0) + +#if !QSPI_FLASH_MODE +#error MICROPY_QSPI_DATAn must be defined +#endif + +enum { + QSPI_CMD_RSTEN = 0x66, + QSPI_CMD_RST = 0x99, + QSPI_CMD_WRSR = 0x01, + QSPI_CMD_READID = 0x90 +}; + +const qspi_flash_device_t _flash_devices_arr[] = { EXTERNAL_FLASH_DEVICES }; + +enum { + FLASH_DEVICE_COUNT = ARRAY_SIZE(_flash_devices_arr) +}; + +const qspi_flash_device_t* _flash_dev = NULL; + +void qspi_flash_init (void) { + // Init QSPI flash + nrfx_qspi_config_t qspi_cfg = { + .xip_offset = 0, + .pins = { + .sck_pin = MICROPY_QSPI_SCK, + .csn_pin = MICROPY_QSPI_CS, + .io0_pin = MICROPY_QSPI_DATA0, + .io1_pin = NRF_QSPI_PIN_NOT_CONNECTED, + .io2_pin = NRF_QSPI_PIN_NOT_CONNECTED, + .io3_pin = NRF_QSPI_PIN_NOT_CONNECTED, + + }, + .prot_if = { + .readoc = NRF_QSPI_READOC_FASTREAD, + .writeoc = NRF_QSPI_WRITEOC_PP, + .addrmode = NRF_QSPI_ADDRMODE_24BIT, + .dpmconfig = false + }, + .phy_if = { + .sck_freq = NRF_QSPI_FREQ_32MDIV1, + .sck_delay = 1, // min time CS must stay high before going low again. in unit of 62.5 ns + .spi_mode = NRF_QSPI_MODE_0, + .dpmen = false + }, + .irq_priority = 7, + }; + +#if QSPI_FLASH_MODE > 1 + qspi_cfg.pins.io1_pin = MICROPY_QSPI_DATA1; + qspi_cfg.prot_if.readoc = NRF_QSPI_READOC_READ2IO; + qspi_cfg.prot_if.writeoc = NRF_QSPI_WRITEOC_PP2O; +#if QSPI_FLASH_MODE > 2 + qspi_cfg.pins.io2_pin = MICROPY_QSPI_DATA2; + qspi_cfg.pins.io3_pin = MICROPY_QSPI_DATA3; + qspi_cfg.prot_if.readoc = NRF_QSPI_READOC_READ4IO; + qspi_cfg.prot_if.writeoc = NRF_QSPI_WRITEOC_PP4IO; +#endif +#endif + + // No callback for blocking API + nrfx_qspi_init(&qspi_cfg, NULL, NULL); + + nrf_qspi_cinstr_conf_t cinstr_cfg = { + .opcode = 0, + .length = 0, + .io2_level = true, + .io3_level = true, + .wipwait = false, + .wren = false + }; + + // Send reset enable + cinstr_cfg.opcode = QSPI_CMD_RSTEN; + cinstr_cfg.length = 1; + nrfx_qspi_cinstr_xfer(&cinstr_cfg, NULL, NULL); + + // Send reset command + cinstr_cfg.opcode = QSPI_CMD_RST; + cinstr_cfg.length = 1; + nrfx_qspi_cinstr_xfer(&cinstr_cfg, NULL, NULL); + + NRFX_DELAY_US(100); // wait for flash device to reset + + // Send (Read ID + 3 dummy bytes) + Receive 2 bytes of (Manufacture + Device ID) + uint8_t dummy[6] = {0}; + uint8_t id_resp[6] = { 0 }; + cinstr_cfg.opcode = QSPI_CMD_READID; + cinstr_cfg.length = 6; + + // Bug with -nrf_qspi_cinstrdata_get() didn't combine data. + // https://devzone.nordicsemi.com/f/nordic-q-a/38540/bug-nrf_qspi_cinstrdata_get-didn-t-collect-data-from-both-cinstrdat1-and-cinstrdat0 + nrfx_qspi_cinstr_xfer(&cinstr_cfg, dummy, id_resp); + + // Due to the bug, we collect data manually + uint8_t dev_id = (uint8_t) NRF_QSPI->CINSTRDAT1; + uint8_t mfgr_id = (uint8_t) ( NRF_QSPI->CINSTRDAT0 >> 24); + + // Look up the flash device in supported array + for ( int i = 0; i < FLASH_DEVICE_COUNT; i++ ) { + // Match ID + if ( _flash_devices_arr[i].manufacturer_id == mfgr_id && _flash_devices_arr[i].device_id == dev_id ) { + _flash_dev = &_flash_devices_arr[i]; + break; + } + } + + if ( _flash_dev ) { + // Enable quad mode if needed +#if QSPI_FLASH_MODE == 4 + cinstr_cfg.opcode = QSPI_CMD_WRSR; + cinstr_cfg.length = 3; + cinstr_cfg.wipwait = cinstr_cfg.wren = true; + nrfx_qspi_cinstr_xfer(&cinstr_cfg, &_flash_dev->status_quad_enable, NULL); +#endif + + // Enable high performance mode + uint8_t sts_cfg[] = { 0x40, 0x00, 0x01 }; + cinstr_cfg.opcode = QSPI_CMD_WRSR; + cinstr_cfg.length = 4; + cinstr_cfg.wipwait = cinstr_cfg.wren = true; + nrfx_qspi_cinstr_xfer(&cinstr_cfg, sts_cfg, NULL); + } +} + +bool qspi_flash_detected (void) { + return _flash_dev != NULL; +} + +uint32_t qspi_flash_get_block_count (void) { + return _flash_dev ? (_flash_dev->total_size / FLASH_API_BLOCK_SIZE) : 0; +} + +void qspi_flash_hal_erase (uint32_t addr) { + if ( !(NRFX_SUCCESS == nrfx_qspi_erase(NRF_QSPI_ERASE_LEN_4KB, addr)) ) return; +} + +void qspi_flash_hal_program (uint32_t dst, const void* src, uint32_t len) { + if ( !(NRFX_SUCCESS == nrfx_qspi_write(src, len, dst)) ) return; +} + +void qspi_flash_hal_read (void* dst, uint32_t src, uint32_t len) { + nrfx_qspi_read(dst, len, src); +} diff --git a/ports/nrf/flash_api/qspi_flash.h b/ports/nrf/flash_api/qspi_flash.h new file mode 100644 index 0000000000000..8df0bf90988af --- /dev/null +++ b/ports/nrf/flash_api/qspi_flash.h @@ -0,0 +1,47 @@ +/* + * This file is part of the MicroPython project, http://micropython.org/ + * + * The MIT License (MIT) + * + * Copyright (c) 2018 hathach for Adafruit Industries + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#ifndef QSPI_FLASH_H_ +#define QSPI_FLASH_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +void qspi_flash_init (void); +bool qspi_flash_detected (void); +uint32_t qspi_flash_get_block_count (void); + +void qspi_flash_hal_erase (uint32_t addr); +void qspi_flash_hal_program (uint32_t dst, const void * src, uint32_t len); +void qspi_flash_hal_read (void* dst, uint32_t src, uint32_t len); + + +#ifdef __cplusplus + } +#endif + +#endif /* QSPI_FLASH_H_ */ diff --git a/ports/nrf/internal_flash.c b/ports/nrf/internal_flash.c deleted file mode 100644 index 812ef4d3f576d..0000000000000 --- a/ports/nrf/internal_flash.c +++ /dev/null @@ -1,226 +0,0 @@ -/* - * This file is part of the MicroPython project, http://micropython.org/ - * - * The MIT License (MIT) - * - * Copyright (c) 2013, 2014 Damien P. George - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ -#include "internal_flash.h" - -#include -#include - -#include "extmod/vfs.h" -#include "extmod/vfs_fat.h" -#include "py/mphal.h" -#include "py/obj.h" -#include "py/runtime.h" -#include "lib/oofatfs/ff.h" -#include "supervisor/shared/rgb_led_status.h" - -#include "nrf_nvmc.h" - -#ifdef BLUETOOTH_SD -#include "nrf_sdm.h" -#endif - -// defined in linker -extern uint32_t __fatfs_flash_start_addr[]; -extern uint32_t __fatfs_flash_length[]; - -#define NO_CACHE 0xffffffff -#define FL_PAGE_SZ 4096 - -uint8_t _flash_cache[FL_PAGE_SZ] __attribute__((aligned(4))); -uint32_t _flash_page_addr = NO_CACHE; - - -/*------------------------------------------------------------------*/ -/* Internal Flash API - *------------------------------------------------------------------*/ -static inline uint32_t lba2addr(uint32_t block) { - return ((uint32_t)__fatfs_flash_start_addr) + block * FILESYSTEM_BLOCK_SIZE; -} - -void internal_flash_init(void) { - // Activity LED for flash writes. -#ifdef MICROPY_HW_LED_MSC - struct port_config pin_conf; - port_get_config_defaults(&pin_conf); - - pin_conf.direction = PORT_PIN_DIR_OUTPUT; - port_pin_set_config(MICROPY_HW_LED_MSC, &pin_conf); - port_pin_set_output_level(MICROPY_HW_LED_MSC, false); -#endif -} - -uint32_t internal_flash_get_block_size(void) { - return FILESYSTEM_BLOCK_SIZE; -} - -uint32_t internal_flash_get_block_count(void) { - return ((uint32_t) __fatfs_flash_length) / FILESYSTEM_BLOCK_SIZE ; -} - -// TODO support flashing with SD enabled -void internal_flash_flush(void) { - if (_flash_page_addr == NO_CACHE) return; - - // Skip if data is the same - if (memcmp(_flash_cache, (void *)_flash_page_addr, FL_PAGE_SZ) != 0) { -// _is_flashing = true; - nrf_nvmc_page_erase(_flash_page_addr); - nrf_nvmc_write_words(_flash_page_addr, (uint32_t *)_flash_cache, FL_PAGE_SZ / sizeof(uint32_t)); - } - - _flash_page_addr = NO_CACHE; -} - -mp_uint_t internal_flash_read_blocks(uint8_t *dest, uint32_t block, uint32_t num_blocks) { - uint32_t src = lba2addr(block); - memcpy(dest, (uint8_t*) src, FILESYSTEM_BLOCK_SIZE*num_blocks); - return 0; // success -} - -mp_uint_t internal_flash_write_blocks(const uint8_t *src, uint32_t lba, uint32_t num_blocks) { - -#ifdef MICROPY_HW_LED_MSC - port_pin_set_output_level(MICROPY_HW_LED_MSC, true); -#endif - - while (num_blocks) { - uint32_t const addr = lba2addr(lba); - uint32_t const page_addr = addr & ~(FL_PAGE_SZ - 1); - - uint32_t count = 8 - (lba % 8); // up to page boundary - count = MIN(num_blocks, count); - - if (page_addr != _flash_page_addr) { - internal_flash_flush(); - - // writing previous cached data, skip current data until flashing is done - // tinyusb stack will invoke write_block() with the same parameters later on - // if ( _is_flashing ) return; - - _flash_page_addr = page_addr; - memcpy(_flash_cache, (void *)page_addr, FL_PAGE_SZ); - } - - memcpy(_flash_cache + (addr & (FL_PAGE_SZ - 1)), src, count * FILESYSTEM_BLOCK_SIZE); - - // adjust for next run - lba += count; - src += count * FILESYSTEM_BLOCK_SIZE; - num_blocks -= count; - } - -#ifdef MICROPY_HW_LED_MSC - port_pin_set_output_level(MICROPY_HW_LED_MSC, false); -#endif - - return 0; // success -} - -/******************************************************************************/ -// MicroPython bindings -// -// Expose the flash as an object with the block protocol. - -// there is a singleton Flash object -STATIC const mp_obj_base_t internal_flash_obj = {&internal_flash_type}; - -STATIC mp_obj_t internal_flash_obj_make_new(const mp_obj_type_t *type, size_t n_args, size_t n_kw, const mp_obj_t *args) { - // check arguments - mp_arg_check_num(n_args, n_kw, 0, 0, false); - - // return singleton object - return (mp_obj_t)&internal_flash_obj; -} - -STATIC mp_obj_t internal_flash_obj_readblocks(mp_obj_t self, mp_obj_t block_num, mp_obj_t buf) { - mp_buffer_info_t bufinfo; - mp_get_buffer_raise(buf, &bufinfo, MP_BUFFER_WRITE); - mp_uint_t ret = internal_flash_read_blocks(bufinfo.buf, mp_obj_get_int(block_num), bufinfo.len / FILESYSTEM_BLOCK_SIZE); - return MP_OBJ_NEW_SMALL_INT(ret); -} -STATIC MP_DEFINE_CONST_FUN_OBJ_3(internal_flash_obj_readblocks_obj, internal_flash_obj_readblocks); - -STATIC mp_obj_t internal_flash_obj_writeblocks(mp_obj_t self, mp_obj_t block_num, mp_obj_t buf) { - mp_buffer_info_t bufinfo; - mp_get_buffer_raise(buf, &bufinfo, MP_BUFFER_READ); - mp_uint_t ret = internal_flash_write_blocks(bufinfo.buf, mp_obj_get_int(block_num), bufinfo.len / FILESYSTEM_BLOCK_SIZE); - return MP_OBJ_NEW_SMALL_INT(ret); -} -STATIC MP_DEFINE_CONST_FUN_OBJ_3(internal_flash_obj_writeblocks_obj, internal_flash_obj_writeblocks); - -STATIC mp_obj_t internal_flash_obj_ioctl(mp_obj_t self, mp_obj_t cmd_in, mp_obj_t arg_in) { - mp_int_t cmd = mp_obj_get_int(cmd_in); - switch (cmd) { - case BP_IOCTL_INIT: internal_flash_init(); return MP_OBJ_NEW_SMALL_INT(0); - case BP_IOCTL_DEINIT: internal_flash_flush(); return MP_OBJ_NEW_SMALL_INT(0); // TODO properly - case BP_IOCTL_SYNC: internal_flash_flush(); return MP_OBJ_NEW_SMALL_INT(0); - case BP_IOCTL_SEC_COUNT: return MP_OBJ_NEW_SMALL_INT(internal_flash_get_block_count()); - case BP_IOCTL_SEC_SIZE: return MP_OBJ_NEW_SMALL_INT(internal_flash_get_block_size()); - default: return mp_const_none; - } -} -STATIC MP_DEFINE_CONST_FUN_OBJ_3(internal_flash_obj_ioctl_obj, internal_flash_obj_ioctl); - -STATIC const mp_rom_map_elem_t internal_flash_obj_locals_dict_table[] = { - { MP_ROM_QSTR(MP_QSTR_readblocks), MP_ROM_PTR(&internal_flash_obj_readblocks_obj) }, - { MP_ROM_QSTR(MP_QSTR_writeblocks), MP_ROM_PTR(&internal_flash_obj_writeblocks_obj) }, - { MP_ROM_QSTR(MP_QSTR_ioctl), MP_ROM_PTR(&internal_flash_obj_ioctl_obj) }, -}; - -STATIC MP_DEFINE_CONST_DICT(internal_flash_obj_locals_dict, internal_flash_obj_locals_dict_table); - -const mp_obj_type_t internal_flash_type = { - { &mp_type_type }, - .name = MP_QSTR_InternalFlash, - .make_new = internal_flash_obj_make_new, - .locals_dict = (mp_obj_t)&internal_flash_obj_locals_dict, -}; - -/*------------------------------------------------------------------*/ -/* Flash API - *------------------------------------------------------------------*/ - -void flash_init_vfs(fs_user_mount_t *vfs) { - vfs->base.type = &mp_fat_vfs_type; - vfs->flags |= FSUSER_NATIVE | FSUSER_HAVE_IOCTL; - vfs->fatfs.drv = vfs; - -// vfs->fatfs.part = 1; // flash filesystem lives on first partition - vfs->readblocks[0] = (mp_obj_t)&internal_flash_obj_readblocks_obj; - vfs->readblocks[1] = (mp_obj_t)&internal_flash_obj; - vfs->readblocks[2] = (mp_obj_t)internal_flash_read_blocks; // native version - - vfs->writeblocks[0] = (mp_obj_t)&internal_flash_obj_writeblocks_obj; - vfs->writeblocks[1] = (mp_obj_t)&internal_flash_obj; - vfs->writeblocks[2] = (mp_obj_t)internal_flash_write_blocks; // native version - - vfs->u.ioctl[0] = (mp_obj_t)&internal_flash_obj_ioctl_obj; - vfs->u.ioctl[1] = (mp_obj_t)&internal_flash_obj; -} - -void flash_flush(void) { - internal_flash_flush(); -} diff --git a/ports/nrf/nrfx_config.h b/ports/nrf/nrfx_config.h index fb603a896da2d..be4a739aec21a 100644 --- a/ports/nrf/nrfx_config.h +++ b/ports/nrf/nrfx_config.h @@ -2,47 +2,50 @@ #define NRFX_CONFIG_H__ // Power -#define NRFX_POWER_ENABLED 1 -#define NRFX_POWER_CONFIG_IRQ_PRIORITY 7 +#define NRFX_POWER_ENABLED 1 +#define NRFX_POWER_CONFIG_IRQ_PRIORITY 7 // SPI -#define NRFX_SPIM_ENABLED 1 +#define NRFX_SPIM_ENABLED 1 #ifdef NRF52840_XXAA - #define NRFX_SPIM3_ENABLED 1 +#define NRFX_SPIM3_ENABLED 1 #else - #define NRFX_SPIM2_ENABLED 1 +#define NRFX_SPIM2_ENABLED 1 #endif -#define NRFX_SPIM_DEFAULT_CONFIG_IRQ_PRIORITY 7 -#define NRFX_SPIM_MISO_PULL_CFG 1 +#define NRFX_SPIM_DEFAULT_CONFIG_IRQ_PRIORITY 7 +#define NRFX_SPIM_MISO_PULL_CFG 1 + +// QSPI +#define NRFX_QSPI_ENABLED 1 // TWI aka. I2C -#define NRFX_TWIM_ENABLED 1 -#define NRFX_TWIM0_ENABLED 1 +#define NRFX_TWIM_ENABLED 1 +#define NRFX_TWIM0_ENABLED 1 -#define NRFX_TWIM_DEFAULT_CONFIG_IRQ_PRIORITY 7 -#define NRFX_TWIM_DEFAULT_CONFIG_FREQUENCY NRF_TWIM_FREQ_400K -#define NRFX_TWIM_DEFAULT_CONFIG_HOLD_BUS_UNINIT 0 +#define NRFX_TWIM_DEFAULT_CONFIG_IRQ_PRIORITY 7 +#define NRFX_TWIM_DEFAULT_CONFIG_FREQUENCY NRF_TWIM_FREQ_400K +#define NRFX_TWIM_DEFAULT_CONFIG_HOLD_BUS_UNINIT 0 // UART -#define NRFX_UART_ENABLED 1 -#define NRFX_UART0_ENABLED 1 +#define NRFX_UART_ENABLED 1 +#define NRFX_UART0_ENABLED 1 -#define NRFX_UART_DEFAULT_CONFIG_IRQ_PRIORITY 7 -#define NRFX_UART_DEFAULT_CONFIG_HWFC NRF_UART_HWFC_DISABLED -#define NRFX_UART_DEFAULT_CONFIG_PARITY NRF_UART_PARITY_EXCLUDED -#define NRFX_UART_DEFAULT_CONFIG_BAUDRATE NRF_UART_BAUDRATE_115200 +#define NRFX_UART_DEFAULT_CONFIG_IRQ_PRIORITY 7 +#define NRFX_UART_DEFAULT_CONFIG_HWFC NRF_UART_HWFC_DISABLED +#define NRFX_UART_DEFAULT_CONFIG_PARITY NRF_UART_PARITY_EXCLUDED +#define NRFX_UART_DEFAULT_CONFIG_BAUDRATE NRF_UART_BAUDRATE_115200 // PWM -#define NRFX_PWM0_ENABLED 1 -#define NRFX_PWM1_ENABLED 1 -#define NRFX_PWM2_ENABLED 1 +#define NRFX_PWM0_ENABLED 1 +#define NRFX_PWM1_ENABLED 1 +#define NRFX_PWM2_ENABLED 1 #ifdef NRF_PWM3 -#define NRFX_PWM3_ENABLED 1 +#define NRFX_PWM3_ENABLED 1 #else -#define NRFX_PWM3_ENABLED 0 +#define NRFX_PWM3_ENABLED 0 #endif #endif diff --git a/ports/nrf/supervisor/filesystem.c b/ports/nrf/supervisor/filesystem.c index 1a3165a2d7ad7..7705e099be824 100644 --- a/ports/nrf/supervisor/filesystem.c +++ b/ports/nrf/supervisor/filesystem.c @@ -29,16 +29,14 @@ #include "lib/oofatfs/diskio.h" #include "py/mpstate.h" - -#include "internal_flash.h" +#include "flash_api/flash_api.h" static mp_vfs_mount_t _mp_vfs; -static fs_user_mount_t _internal_vfs; - +static fs_user_mount_t _user_vfs; void filesystem_init(bool create_allowed) { // init the vfs object - fs_user_mount_t *int_vfs = &_internal_vfs; + fs_user_mount_t *int_vfs = &_user_vfs; int_vfs->flags = 0; flash_init_vfs(int_vfs); @@ -83,7 +81,7 @@ void filesystem_flush(void) { } void filesystem_writable_by_python(bool writable) { - fs_user_mount_t *vfs = &_internal_vfs; + fs_user_mount_t *vfs = &_user_vfs; if (writable) { vfs->flags |= FSUSER_USB_WRITABLE; diff --git a/ports/nrf/supervisor/port.c b/ports/nrf/supervisor/port.c index e6bb2545832dc..5657a934fd294 100644 --- a/ports/nrf/supervisor/port.c +++ b/ports/nrf/supervisor/port.c @@ -32,6 +32,10 @@ #include "nrf/clocks.h" #include "nrf/power.h" +#ifdef NRF52840_XXAA +#include "usb/usb.h" +#endif + #include "shared-module/gamepad/__init__.h" #include "common-hal/microcontroller/Pin.h" #include "common-hal/pulseio/PWMOut.h" @@ -59,9 +63,12 @@ safe_mode_t port_init(void) { #endif #endif - // Will do usb_init() if chip supports USB. board_init(); +#ifdef NRF52840_XXAA + usb_init(); +#endif + #if 0 if (board_requests_safe_mode()) { return USER_SAFE_MODE; diff --git a/ports/nrf/usb/tusb_config.h b/ports/nrf/usb/tusb_config.h index 626b99eeb290f..4cb0b0694bf4e 100644 --- a/ports/nrf/usb/tusb_config.h +++ b/ports/nrf/usb/tusb_config.h @@ -97,7 +97,8 @@ #define CFG_TUD_MSC_MAXLUN 1 // Number of Blocks -#define CFG_TUD_MSC_BLOCK_NUM (256*1024)/512 +extern unsigned long flash_get_block_count (void); +#define CFG_TUD_MSC_BLOCK_NUM flash_get_block_count() // Block size #define CFG_TUD_MSC_BLOCK_SZ 512 diff --git a/ports/nrf/usb/usb_msc_flash.c b/ports/nrf/usb/usb_msc_flash.c index 2d0e9bec7f8eb..943e684d126ba 100644 --- a/ports/nrf/usb/usb_msc_flash.c +++ b/ports/nrf/usb/usb_msc_flash.c @@ -35,7 +35,8 @@ /**************************************************************************/ #include "tusb.h" -#include "internal_flash.h" +#include "nrf_gpio.h" +#include "flash_api/flash_api.h" // For updating fatfs's cache #include "extmod/vfs.h" @@ -43,21 +44,11 @@ #include "lib/oofatfs/ff.h" #include "py/mpstate.h" -/*------------------------------------------------------------------*/ -/* MACRO TYPEDEF CONSTANT ENUM - *------------------------------------------------------------------*/ -#define MSC_FLASH_ADDR_END 0xED000 -#define MSC_FLASH_SIZE (256*1024) -#define MSC_FLASH_ADDR_START (MSC_FLASH_ADDR_END-MSC_FLASH_SIZE) -#define MSC_FLASH_BLOCK_SIZE 512 - -#define FL_PAGE_SZ 4096 - // Callback invoked when received an SCSI command not in built-in list below // - READ_CAPACITY10, READ_FORMAT_CAPACITY, INQUIRY, MODE_SENSE6, REQUEST_SENSE // - READ10 and WRITE10 has their own callbacks -int32_t tud_msc_scsi_cb (uint8_t lun, uint8_t const scsi_cmd[16], void* buffer, uint16_t bufsize) { - void const* response = NULL; +int32_t tud_msc_scsi_cb (uint8_t lun, const uint8_t scsi_cmd[16], void* buffer, uint16_t bufsize) { + const void* response = NULL; uint16_t resplen = 0; switch ( scsi_cmd[0] ) { @@ -110,11 +101,11 @@ int32_t tud_msc_read10_cb (uint8_t lun, uint32_t lba, uint32_t offset, void* buf (void) lun; (void) offset; - uint32_t const block_count = bufsize / MSC_FLASH_BLOCK_SIZE; + const uint32_t block_count = bufsize / FLASH_API_BLOCK_SIZE; - internal_flash_read_blocks(buffer, lba, block_count); + flash_read_blocks(buffer, lba, block_count); - return block_count * MSC_FLASH_BLOCK_SIZE; + return block_count * FLASH_API_BLOCK_SIZE; } // Callback invoked when received WRITE10 command. @@ -123,19 +114,26 @@ int32_t tud_msc_write10_cb (uint8_t lun, uint32_t lba, uint32_t offset, void* bu (void) lun; (void) offset; - uint32_t const block_count = bufsize / MSC_FLASH_BLOCK_SIZE; +#ifdef MICROPY_HW_LED_MSC + nrf_gpio_pin_write(MICROPY_HW_LED_MSC, MICROPY_HW_LED_MSC_ACTIVE_LEVEL); +#endif - // bufsize <= CFG_TUD_MSC_BUFSIZE (4096) - internal_flash_write_blocks(buffer, lba, block_count); + const uint32_t block_count = bufsize / FLASH_API_BLOCK_SIZE; + + flash_write_blocks(buffer, lba, block_count); // update fatfs's cache if address matches fs_user_mount_t* vfs = MP_STATE_VM(vfs_mount_table)->obj; - if ( (lba <= vfs->fatfs.winsect) && (vfs->fatfs.winsect <= (lba + bufsize / MSC_FLASH_BLOCK_SIZE)) ) { - memcpy(vfs->fatfs.win, buffer + MSC_FLASH_BLOCK_SIZE * (vfs->fatfs.winsect - lba), MSC_FLASH_BLOCK_SIZE); + if ( (lba <= vfs->fatfs.winsect) && (vfs->fatfs.winsect <= (lba + bufsize / FLASH_API_BLOCK_SIZE)) ) { + memcpy(vfs->fatfs.win, buffer + FLASH_API_BLOCK_SIZE * (vfs->fatfs.winsect - lba), FLASH_API_BLOCK_SIZE); } - return block_count * MSC_FLASH_BLOCK_SIZE; +#ifdef MICROPY_HW_LED_MSC + nrf_gpio_pin_write(MICROPY_HW_LED_MSC, 1 - MICROPY_HW_LED_MSC_ACTIVE_LEVEL); +#endif + + return block_count * FLASH_API_BLOCK_SIZE; } // Callback invoked when WRITE10 command is completed (status received and accepted by host). @@ -144,5 +142,5 @@ void tud_msc_write10_complete_cb (uint8_t lun) { (void) lun; // flush pending cache when write10 is complete - internal_flash_flush(); + flash_flush(); }