summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorNick Brassel <nick@tzarc.org>2022-07-02 15:18:50 +1000
committerGitHub <noreply@github.com>2022-07-02 15:18:50 +1000
commit5846b40f7444af96b0d8ddf3af9b558193c2475d (patch)
tree7bec13529ef3654ed290e68617eb1c659c05a49d
parent9f1c4f304d0597b7024d079eb358bb0c71be3ce8 (diff)
RP2040 emulated EEPROM. (#17519)
-rw-r--r--builddefs/common_features.mk10
-rw-r--r--builddefs/mcu_selection.mk2
-rw-r--r--docs/eeprom_driver.md17
-rw-r--r--docs/platformdev_rp2040.md22
-rw-r--r--platforms/chibios/boards/common/ld/RP2040_FLASH_TIMECRIT.ld117
-rw-r--r--platforms/chibios/boards/common/ld/RP2040_rules_data_with_timecrit.ld46
-rw-r--r--platforms/chibios/drivers/wear_leveling/wear_leveling_rp2040_flash.c221
-rw-r--r--platforms/chibios/drivers/wear_leveling/wear_leveling_rp2040_flash_config.h32
-rw-r--r--platforms/chibios/platform.mk3
-rw-r--r--platforms/chibios/vendors/RP/RP2040.mk2
-rw-r--r--platforms/chibios/vendors/RP/pico_sdk_shims.c4
-rw-r--r--platforms/chibios/vendors/RP/stage2_bootloaders.c12
-rw-r--r--quantum/wear_leveling/wear_leveling.c4
13 files changed, 470 insertions, 22 deletions
diff --git a/builddefs/common_features.mk b/builddefs/common_features.mk
index 2edc1bdef0..c11e5688e3 100644
--- a/builddefs/common_features.mk
+++ b/builddefs/common_features.mk
@@ -220,6 +220,11 @@ else
# True EEPROM on STM32L0xx, L1xx
OPT_DEFS += -DEEPROM_DRIVER -DEEPROM_STM32_L0_L1
SRC += eeprom_driver.c eeprom_stm32_L0_L1.c
+ else ifneq ($(filter $(MCU_SERIES),RP2040),)
+ # Wear-leveling EEPROM implementation, backed by RP2040 flash
+ OPT_DEFS += -DEEPROM_DRIVER -DEEPROM_WEAR_LEVELING
+ SRC += eeprom_driver.c eeprom_wear_leveling.c
+ WEAR_LEVELING_DRIVER = rp2040_flash
else ifneq ($(filter $(MCU_SERIES),KL2x K20x),)
# Teensy EEPROM implementations
OPT_DEFS += -DEEPROM_TEENSY
@@ -241,7 +246,7 @@ else
endif
endif
-VALID_WEAR_LEVELING_DRIVER_TYPES := custom embedded_flash spi_flash legacy
+VALID_WEAR_LEVELING_DRIVER_TYPES := custom embedded_flash spi_flash rp2040_flash legacy
WEAR_LEVELING_DRIVER ?= none
ifneq ($(strip $(WEAR_LEVELING_DRIVER)),none)
ifeq ($(filter $(WEAR_LEVELING_DRIVER),$(VALID_WEAR_LEVELING_DRIVER_TYPES)),)
@@ -262,6 +267,9 @@ ifneq ($(strip $(WEAR_LEVELING_DRIVER)),none)
FLASH_DRIVER := spi
SRC += wear_leveling_flash_spi.c
POST_CONFIG_H += $(DRIVER_PATH)/wear_leveling/wear_leveling_flash_spi_config.h
+ else ifeq ($(strip $(WEAR_LEVELING_DRIVER)), rp2040_flash)
+ SRC += wear_leveling_rp2040_flash.c
+ POST_CONFIG_H += $(DRIVER_PATH)/wear_leveling/wear_leveling_rp2040_flash_config.h
else ifeq ($(strip $(WEAR_LEVELING_DRIVER)), legacy)
COMMON_VPATH += $(PLATFORM_PATH)/$(PLATFORM_KEY)/$(DRIVER_DIR)/flash
SRC += flash_stm32.c wear_leveling_legacy.c
diff --git a/builddefs/mcu_selection.mk b/builddefs/mcu_selection.mk
index d676e0c06a..135f663c14 100644
--- a/builddefs/mcu_selection.mk
+++ b/builddefs/mcu_selection.mk
@@ -135,7 +135,7 @@ ifneq ($(findstring RP2040, $(MCU)),)
# - it should exist either in <chibios>/os/common/ports/ARMCMx/compilers/GCC/ld/
# or <keyboard_dir>/ld/
STARTUPLD_CONTRIB = $(CHIBIOS_CONTRIB)/os/common/startup/ARMCMx/compilers/GCC/ld
- MCU_LDSCRIPT ?= RP2040_FLASH
+ MCU_LDSCRIPT ?= RP2040_FLASH_TIMECRIT
LDFLAGS += -L $(STARTUPLD_CONTRIB)
# Startup code to use
diff --git a/docs/eeprom_driver.md b/docs/eeprom_driver.md
index de2eaf2e5b..50d8bcb7b3 100644
--- a/docs/eeprom_driver.md
+++ b/docs/eeprom_driver.md
@@ -92,6 +92,7 @@ Driver | Description
----------------------------------------|------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
`WEAR_LEVELING_DRIVER = embedded_flash` | This driver is used for emulating EEPROM by writing to embedded flash on the MCU.
`WEAR_LEVELING_DRIVER = spi_flash` | This driver is used to address external SPI NOR Flash peripherals.
+`WEAR_LEVELING_DRIVER = rp2040_flash` | This driver is used to write to the same storage the RP2040 executes code from.
`WEAR_LEVELING_DRIVER = legacy` | This driver is the "legacy" emulated EEPROM provided in historical revisions of QMK. Currently used for STM32F0xx and STM32F4x1, but slated for deprecation and removal once `embedded_flash` support for those MCU families is complete.
!> All wear-leveling drivers require an amount of RAM equivalent to the selected logical EEPROM size. Increasing the size to 32kB of EEPROM requires 32kB of RAM, which a significant number of MCUs simply do not have.
@@ -128,6 +129,20 @@ Configurable options in your keyboard's `config.h`:
!> There is currently a limit of 64kB for the EEPROM subsystem within QMK, so using a larger flash is not going to be beneficial as the logical size cannot be increased beyond 65536. The backing size may be increased to a larger value, but erase timing may suffer as a result.
+## Wear-leveling RP2040 Driver Configuration :id=wear_leveling-rp2040-driver-configuration
+
+This driver performs writes to the same underlying storage that the RP2040 executes its code.
+
+Configurable options in your keyboard's `config.h`:
+
+`config.h` override | Default | Description
+------------------------------------------|----------------------------|--------------------------------------------------------------------------------------------------------------------------------
+`#define WEAR_LEVELING_RP2040_FLASH_SIZE` | `PICO_FLASH_SIZE_BYTES` | Number of bytes of flash on the board.
+`#define WEAR_LEVELING_RP2040_FLASH_BASE` | `(flash_size-sector_size)` | The byte-wise location that the backing storage should be located.
+`#define WEAR_LEVELING_LOGICAL_SIZE` | `4096` | Number of bytes "exposed" to the rest of QMK and denotes the size of the usable EEPROM.
+`#define WEAR_LEVELING_BACKING_SIZE` | `8192` | Number of bytes used by the wear-leveling algorithm for its underlying storage, and needs to be a multiple of the logical size as well as the sector size.
+`#define BACKING_STORE_WRITE_SIZE` | `2` | The write width used whenever a write is performed on the external flash peripheral.
+
## Wear-leveling Legacy EEPROM Emulation Driver Configuration :id=wear_leveling-legacy-driver-configuration
This driver performs writes to the embedded flash storage embedded in the MCU much like the normal Embedded Flash Driver, and is only for use with STM32F0xx and STM32F4x1 devices. This flash implementation is still currently provided as the EFL driver is currently non-functional for the previously mentioned families.
@@ -142,4 +157,4 @@ STM32F072 | `1024` bytes | `2048` bytes
STM32F401 | `1024` bytes | `16384` bytes
STM32F411 | `1024` bytes | `16384` bytes
-Under normal circumstances configuration of this driver requires intimate knowledge of the MCU's flash structure -- reconfiguration is at your own risk and will require referring to the code. \ No newline at end of file
+Under normal circumstances configuration of this driver requires intimate knowledge of the MCU's flash structure -- reconfiguration is at your own risk and will require referring to the code.
diff --git a/docs/platformdev_rp2040.md b/docs/platformdev_rp2040.md
index 9426efa29a..d690ebebf8 100644
--- a/docs/platformdev_rp2040.md
+++ b/docs/platformdev_rp2040.md
@@ -2,17 +2,17 @@
The following table shows the current driver status for peripherals on RP2040 MCUs:
-| System | Support |
-| ------------------------------------ | ---------------------------------------------- |
-| [ADC driver](adc_driver.md) | Support planned (no ETA) |
-| [Audio](audio_driver.md) | Support planned (no ETA) |
-| [I2C driver](i2c_driver.md) | :heavy_check_mark: |
-| [SPI driver](spi_driver.md) | :heavy_check_mark: |
-| [WS2812 driver](ws2812_driver.md) | :heavy_check_mark: using `PIO` driver |
-| [External EEPROMs](eeprom_driver.md) | :heavy_check_mark: using `I2C` or `SPI` driver |
-| [EEPROM emulation](eeprom_driver.md) | Support planned (no ETA) |
-| [serial driver](serial_driver.md) | :heavy_check_mark: using `SIO` or `PIO` driver |
-| [UART driver](uart_driver.md) | Support planned (no ETA) |
+| System | Support |
+| ---------------------------------------------------------------- | ---------------------------------------------- |
+| [ADC driver](adc_driver.md) | Support planned (no ETA) |
+| [Audio](audio_driver.md) | Support planned (no ETA) |
+| [I2C driver](i2c_driver.md) | :heavy_check_mark: |
+| [SPI driver](spi_driver.md) | :heavy_check_mark: |
+| [WS2812 driver](ws2812_driver.md) | :heavy_check_mark: using `PIO` driver |
+| [External EEPROMs](eeprom_driver.md) | :heavy_check_mark: using `I2C` or `SPI` driver |
+| [EEPROM emulation](eeprom_driver.md#wear_leveling-configuration) | :heavy_check_mark: |
+| [serial driver](serial_driver.md) | :heavy_check_mark: using `SIO` or `PIO` driver |
+| [UART driver](uart_driver.md) | Support planned (no ETA) |
## GPIO
diff --git a/platforms/chibios/boards/common/ld/RP2040_FLASH_TIMECRIT.ld b/platforms/chibios/boards/common/ld/RP2040_FLASH_TIMECRIT.ld
new file mode 100644
index 0000000000..66ed4ce086
--- /dev/null
+++ b/platforms/chibios/boards/common/ld/RP2040_FLASH_TIMECRIT.ld
@@ -0,0 +1,117 @@
+/*
+ ChibiOS - Copyright (C) 2006..2021 Giovanni Di Sirio
+
+ Licensed under the Apache License, Version 2.0 (the "License");
+ you may not use this file except in compliance with the License.
+ You may obtain a copy of the License at
+
+ http://www.apache.org/licenses/LICENSE-2.0
+
+ Unless required by applicable law or agreed to in writing, software
+ distributed under the License is distributed on an "AS IS" BASIS,
+ WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ See the License for the specific language governing permissions and
+ limitations under the License.
+*/
+
+/*
+ * RP2040 memory setup.
+ */
+MEMORY
+{
+ flash0 (rx) : org = 0x00000000, len = 16k /* ROM */
+ flash1 (rx) : org = 0x10000000, len = DEFINED(FLASH_LEN) ? FLASH_LEN : 2048k /* XIP */
+ flash2 (rx) : org = 0x00000000, len = 0
+ flash3 (rx) : org = 0x00000000, len = 0
+ flash4 (rx) : org = 0x00000000, len = 0
+ flash5 (rx) : org = 0x00000000, len = 0
+ flash6 (rx) : org = 0x00000000, len = 0
+ flash7 (rx) : org = 0x00000000, len = 0
+ ram0 (wx) : org = 0x20000000, len = 256k /* SRAM0 striped */
+ ram1 (wx) : org = 0x00000000, len = 256k /* SRAM0 non striped */
+ ram2 (wx) : org = 0x00000000, len = 0
+ ram3 (wx) : org = 0x00000000, len = 0
+ ram4 (wx) : org = 0x20040000, len = 4k /* SRAM4 */
+ ram5 (wx) : org = 0x20041000, len = 4k /* SRAM5 */
+ ram6 (wx) : org = 0x00000000, len = 0
+ ram7 (wx) : org = 0x20041f00, len = 256 /* SRAM5 boot */
+}
+
+/* For each data/text section two region are defined, a virtual region
+ and a load region (_LMA suffix).*/
+
+/* Flash region to be used for exception vectors.*/
+REGION_ALIAS("VECTORS_FLASH", flash1);
+REGION_ALIAS("VECTORS_FLASH_LMA", flash1);
+
+/* Flash region to be used for constructors and destructors.*/
+REGION_ALIAS("XTORS_FLASH", flash1);
+REGION_ALIAS("XTORS_FLASH_LMA", flash1);
+
+/* Flash region to be used for code text.*/
+REGION_ALIAS("TEXT_FLASH", flash1);
+REGION_ALIAS("TEXT_FLASH_LMA", flash1);
+
+/* Flash region to be used for read only data.*/
+REGION_ALIAS("RODATA_FLASH", flash1);
+REGION_ALIAS("RODATA_FLASH_LMA", flash1);
+
+/* Flash region to be used for various.*/
+REGION_ALIAS("VARIOUS_FLASH", flash1);
+REGION_ALIAS("VARIOUS_FLASH_LMA", flash1);
+
+/* Flash region to be used for RAM(n) initialization data.*/
+REGION_ALIAS("RAM_INIT_FLASH_LMA", flash1);
+
+/* RAM region to be used for Main stack. This stack accommodates the processing
+ of all exceptions and interrupts.*/
+REGION_ALIAS("MAIN_STACK_RAM", ram4);
+
+/* RAM region to be used for the process stack. This is the stack used by
+ the main() function.*/
+REGION_ALIAS("PROCESS_STACK_RAM", ram4);
+
+/* RAM region to be used for Main stack. This stack accommodates the processing
+ of all exceptions and interrupts.*/
+REGION_ALIAS("C1_MAIN_STACK_RAM", ram5);
+
+/* RAM region to be used for the process stack. This is the stack used by
+ the main() function.*/
+REGION_ALIAS("C1_PROCESS_STACK_RAM", ram5);
+
+/* RAM region to be used for data segment.*/
+REGION_ALIAS("DATA_RAM", ram0);
+REGION_ALIAS("DATA_RAM_LMA", flash1);
+
+/* RAM region to be used for BSS segment.*/
+REGION_ALIAS("BSS_RAM", ram0);
+
+/* RAM region to be used for the default heap.*/
+REGION_ALIAS("HEAP_RAM", ram0);
+
+SECTIONS
+{
+ .flash_begin : {
+ __flash_binary_start = .;
+ } > flash1
+
+ .boot2 : {
+ __boot2_start__ = .;
+ KEEP (*(.boot2))
+ __boot2_end__ = .;
+ } > flash1
+}
+
+/* Generic rules inclusion.*/
+INCLUDE rules_stacks.ld
+INCLUDE rules_stacks_c1.ld
+INCLUDE RP2040_rules_code_with_boot2.ld
+INCLUDE RP2040_rules_data_with_timecrit.ld
+INCLUDE rules_memory.ld
+
+SECTIONS
+{
+ .flash_end : {
+ __flash_binary_end = .;
+ } > flash1
+}
diff --git a/platforms/chibios/boards/common/ld/RP2040_rules_data_with_timecrit.ld b/platforms/chibios/boards/common/ld/RP2040_rules_data_with_timecrit.ld
new file mode 100644
index 0000000000..a9a47be983
--- /dev/null
+++ b/platforms/chibios/boards/common/ld/RP2040_rules_data_with_timecrit.ld
@@ -0,0 +1,46 @@
+/*
+ ChibiOS - Copyright (C) 2006..2018 Giovanni Di Sirio
+
+ Licensed under the Apache License, Version 2.0 (the "License");
+ you may not use this file except in compliance with the License.
+ You may obtain a copy of the License at
+
+ http://www.apache.org/licenses/LICENSE-2.0
+
+ Unless required by applicable law or agreed to in writing, software
+ distributed under the License is distributed on an "AS IS" BASIS,
+ WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ See the License for the specific language governing permissions and
+ limitations under the License.
+*/
+
+SECTIONS
+{
+ .data : ALIGN(4)
+ {
+ PROVIDE(_textdata = LOADADDR(.data));
+ PROVIDE(_data = .);
+ __textdata_base__ = LOADADDR(.data);
+ __data_base__ = .;
+ *(vtable)
+ *(.time_critical*)
+ . = ALIGN(4);
+ *(.data)
+ *(.data.*)
+ *(.ramtext)
+ . = ALIGN(4);
+ PROVIDE(_edata = .);
+ __data_end__ = .;
+ } > DATA_RAM AT > DATA_RAM_LMA
+
+ .bss (NOLOAD) : ALIGN(4)
+ {
+ __bss_base__ = .;
+ *(.bss)
+ *(.bss.*)
+ *(COMMON)
+ . = ALIGN(4);
+ __bss_end__ = .;
+ PROVIDE(end = .);
+ } > BSS_RAM
+}
diff --git a/platforms/chibios/drivers/wear_leveling/wear_leveling_rp2040_flash.c b/platforms/chibios/drivers/wear_leveling/wear_leveling_rp2040_flash.c
new file mode 100644
index 0000000000..640628e1e9
--- /dev/null
+++ b/platforms/chibios/drivers/wear_leveling/wear_leveling_rp2040_flash.c
@@ -0,0 +1,221 @@
+/**
+ * Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
+ * Copyright (c) 2022 Nick Brassel (@tzarc)
+ * Copyright (c) 2022 Stefan Kerkmann (@KarlK90)
+ *
+ * SPDX-License-Identifier: BSD-3-Clause
+ */
+
+#include "pico/bootrom.h"
+#include "hardware/flash.h"
+#include "hardware/sync.h"
+#include "hardware/structs/ssi.h"
+#include "hardware/structs/ioqspi.h"
+
+#include <stdbool.h>
+#include "timer.h"
+#include "wear_leveling.h"
+#include "wear_leveling_internal.h"
+
+#ifndef WEAR_LEVELING_RP2040_FLASH_BULK_COUNT
+# define WEAR_LEVELING_RP2040_FLASH_BULK_COUNT 64
+#endif // WEAR_LEVELING_RP2040_FLASH_BULK_COUNT
+
+#define FLASHCMD_PAGE_PROGRAM 0x02
+#define FLASHCMD_READ_STATUS 0x05
+#define FLASHCMD_WRITE_ENABLE 0x06
+
+extern uint8_t BOOT2_ROM[256];
+static uint32_t BOOT2_ROM_RAM[64];
+
+static ssi_hw_t *const ssi = (ssi_hw_t *)XIP_SSI_BASE;
+
+// Sanity check
+check_hw_layout(ssi_hw_t, ssienr, SSI_SSIENR_OFFSET);
+check_hw_layout(ssi_hw_t, spi_ctrlr0, SSI_SPI_CTRLR0_OFFSET);
+
+static void __no_inline_not_in_flash_func(flash_enable_xip_via_boot2)(void) {
+ ((void (*)(void))BOOT2_ROM_RAM + 1)();
+}
+
+// Bitbanging the chip select using IO overrides, in case RAM-resident IRQs
+// are still running, and the FIFO bottoms out. (the bootrom does the same)
+static void __no_inline_not_in_flash_func(flash_cs_force)(bool high) {
+ uint32_t field_val = high ? IO_QSPI_GPIO_QSPI_SS_CTRL_OUTOVER_VALUE_HIGH : IO_QSPI_GPIO_QSPI_SS_CTRL_OUTOVER_VALUE_LOW;
+ hw_write_masked(&ioqspi_hw->io[1].ctrl, field_val << IO_QSPI_GPIO_QSPI_SS_CTRL_OUTOVER_LSB, IO_QSPI_GPIO_QSPI_SS_CTRL_OUTOVER_BITS);
+}
+
+// Also allow any unbounded loops to check whether the above abort condition
+// was asserted, and terminate early
+static int __no_inline_not_in_flash_func(flash_was_aborted)(void) {
+ return *(io_rw_32 *)(IO_QSPI_BASE + IO_QSPI_GPIO_QSPI_SD1_CTRL_OFFSET) & IO_QSPI_GPIO_QSPI_SD1_CTRL_INOVER_BITS;
+}
+
+// Put bytes from one buffer, and get bytes into another buffer.
+// These can be the same buffer.
+// If tx is NULL then send zeroes.
+// If rx is NULL then all read data will be dropped.
+//
+// If rx_skip is nonzero, this many bytes will first be consumed from the FIFO,
+// before reading a further count bytes into *rx.
+// E.g. if you have written a command+address just before calling this function.
+static void __no_inline_not_in_flash_func(flash_put_get)(const uint8_t *tx, uint8_t *rx, size_t count, size_t rx_skip) {
+ // Make sure there is never more data in flight than the depth of the RX
+ // FIFO. Otherwise, when we are interrupted for long periods, hardware
+ // will overflow the RX FIFO.
+ const uint max_in_flight = 16 - 2; // account for data internal to SSI
+ size_t tx_count = count;
+ size_t rx_count = count;
+ while (tx_count || rx_skip || rx_count) {
+ // NB order of reads, for pessimism rather than optimism
+ uint32_t tx_level = ssi_hw->txflr;
+ uint32_t rx_level = ssi_hw->rxflr;
+ bool did_something = false; // Expect this to be folded into control flow, not register
+ if (tx_count && tx_level + rx_level < max_in_flight) {
+ ssi->dr0 = (uint32_t)(tx ? *tx++ : 0);
+ --tx_count;
+ did_something = true;
+ }
+ if (rx_level) {
+ uint8_t rxbyte = ssi->dr0;
+ did_something = true;
+ if (rx_skip) {
+ --rx_skip;
+ } else {
+ if (rx) *rx++ = rxbyte;
+ --rx_count;
+ }
+ }
+ // APB load costs 4 cycles, so only do it on idle loops (our budget is
+ // 48 cyc/byte)
+ if (!did_something && __builtin_expect(flash_was_aborted(), 0)) break;
+ }
+ flash_cs_force(1);
+}
+
+// Convenience wrapper for above
+// (And it's hard for the debug host to get the tight timing between
+// cmd DR0 write and the remaining data)
+static void __no_inline_not_in_flash_func(_flash_do_cmd)(uint8_t cmd, const uint8_t *tx, uint8_t *rx, size_t count) {
+ flash_cs_force(0);
+ ssi->dr0 = cmd;
+ flash_put_get(tx, rx, count, 1);
+}
+
+// Timing of this one is critical, so do not expose the symbol to debugger etc
+static void __no_inline_not_in_flash_func(flash_put_cmd_addr)(uint8_t cmd, uint32_t addr) {
+ flash_cs_force(0);
+ addr |= cmd << 24;
+ for (int i = 0; i < 4; ++i) {
+ ssi->dr0 = addr >> 24;
+ addr <<= 8;
+ }
+}
+
+// Poll the flash status register until the busy bit (LSB) clears
+static void __no_inline_not_in_flash_func(flash_wait_ready)(void) {
+ uint8_t stat;
+ do {
+ _flash_do_cmd(FLASHCMD_READ_STATUS, NULL, &stat, 1);
+ } while (stat & 0x1 && !flash_was_aborted());
+}
+
+// Set the WEL bit (needed before any program/erase operation)
+static void __no_inline_not_in_flash_func(flash_enable_write)(void) {
+ _flash_do_cmd(FLASHCMD_WRITE_ENABLE, NULL, NULL, 0);
+}
+
+static void __no_inline_not_in_flash_func(pico_program_bulk)(uint32_t flash_address, backing_store_int_t *values, size_t item_count) {
+ rom_connect_internal_flash_fn connect_internal_flash = (rom_connect_internal_flash_fn)rom_func_lookup_inline(ROM_FUNC_CONNECT_INTERNAL_FLASH);
+ rom_flash_exit_xip_fn flash_exit_xip = (rom_flash_exit_xip_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_EXIT_XIP);
+ rom_flash_flush_cache_fn flash_flush_cache = (rom_flash_flush_cache_fn)rom_func_lookup_inline(ROM_FUNC_FLASH_FLUSH_CACHE);
+ assert(connect_internal_flash && flash_exit_xip && flash_flush_cache);
+
+ static backing_store_int_t bulk_write_buffer[WEAR_LEVELING_RP2040_FLASH_BULK_COUNT];
+
+ while (item_count) {
+ size_t batch_size = MIN(item_count, WEAR_LEVELING_RP2040_FLASH_BULK_COUNT);
+ for (size_t i = 0; i < batch_size; i++, values++, item_count--) {
+ bulk_write_buffer[i] = ~(*values);
+ }
+ __compiler_memory_barrier();
+
+ connect_internal_flash();
+ flash_exit_xip();
+ flash_enable_write();
+
+ flash_put_cmd_addr(FLASHCMD_PAGE_PROGRAM, flash_address);
+ flash_put_get((uint8_t *)bulk_write_buffer, NULL, batch_size * sizeof(backing_store_int_t), 4);
+ flash_wait_ready();
+ flash_address += batch_size * sizeof(backing_store_int_t);
+
+ flash_flush_cache();
+ flash_enable_xip_via_boot2();
+ }
+}
+
+////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// QMK Wear-Leveling Backing Store implementation
+
+static int interrupts;
+
+bool backing_store_init(void) {
+ bs_dprintf("Init\n");
+ memcpy(BOOT2_ROM_RAM, BOOT2_ROM, sizeof(BOOT2_ROM));
+ __compiler_memory_barrier();
+ return true;
+}
+
+bool backing_store_unlock(void) {
+ bs_dprintf("Unlock\n");
+ return true;
+}
+
+bool backing_store_erase(void) {
+#ifdef WEAR_LEVELING_DEBUG_OUTPUT
+ uint32_t start = timer_read32();
+#endif
+
+ // Ensure the backing size can be cleanly subtracted from the flash size without alignment issues.
+ _Static_assert((WEAR_LEVELING_BACKING_SIZE) % (FLASH_SECTOR_SIZE) == 0, "Backing size must be a multiple of FLASH_SECTOR_SIZE");
+
+ interrupts = save_and_disable_interrupts();
+ flash_range_erase((WEAR_LEVELING_RP2040_FLASH_BASE), (WEAR_LEVELING_BACKING_SIZE));
+ restore_interrupts(interrupts);
+
+ bs_dprintf("Backing store erase took %ldms to complete\n", ((long)(timer_read32() - start)));
+ return true;
+}
+
+bool backing_store_write(uint32_t address, backing_store_int_t value) {
+ return backing_store_write_bulk(address, &value, 1);
+}
+
+bool backing_store_write_bulk(uint32_t address, backing_store_int_t *values, size_t item_count) {
+ uint32_t offset = (WEAR_LEVELING_RP2040_FLASH_BASE) + address;
+ bs_dprintf("Write ");
+ wl_dump(offset, values, sizeof(backing_store_int_t) * item_count);
+ interrupts = save_and_disable_interrupts();
+ pico_program_bulk(offset, values, item_count);
+ restore_interrupts(interrupts);
+ return true;
+}
+
+bool backing_store_lock(void) {
+ return true;
+}
+
+bool backing_store_read(uint32_t address, backing_store_int_t *value) {
+ return backing_store_read_bulk(address, value, 1);
+}
+
+bool backing_store_read_bulk(uint32_t address, backing_store_int_t *values, size_t item_count) {
+ uint32_t offset = (WEAR_LEVELING_RP2040_FLASH_BASE) + address;
+ backing_store_int_t *loc = (backing_store_int_t *)((XIP_BASE) + offset);
+ for (size_t i = 0; i < item_count; ++i) {
+ values[i] = ~loc[i];
+ }
+ bs_dprintf("Read ");
+ wl_dump(offset, values, item_count * sizeof(backing_store_int_t));
+ return true;
+}
diff --git a/platforms/chibios/drivers/wear_leveling/wear_leveling_rp2040_flash_config.h b/platforms/chibios/drivers/wear_leveling/wear_leveling_rp2040_flash_config.h
new file mode 100644
index 0000000000..93a9aa0372
--- /dev/null
+++ b/platforms/chibios/drivers/wear_leveling/wear_leveling_rp2040_flash_config.h
@@ -0,0 +1,32 @@
+// Copyright 2022 Nick Brassel (@tzarc)
+// SPDX-License-Identifier: GPL-2.0-or-later
+#pragma once
+
+#ifndef __ASSEMBLER__
+# include "hardware/flash.h"
+#endif
+
+// 2-byte writes
+#ifndef BACKING_STORE_WRITE_SIZE
+# define BACKING_STORE_WRITE_SIZE 2
+#endif
+
+// 64kB backing space allocated
+#ifndef WEAR_LEVELING_BACKING_SIZE
+# define WEAR_LEVELING_BACKING_SIZE 8192
+#endif // WEAR_LEVELING_BACKING_SIZE
+
+// 32kB logical EEPROM
+#ifndef WEAR_LEVELING_LOGICAL_SIZE
+# define WEAR_LEVELING_LOGICAL_SIZE 4096
+#endif // WEAR_LEVELING_LOGICAL_SIZE
+
+// Define how much flash space we have (defaults to lib/pico-sdk/src/boards/include/boards/***)
+#ifndef WEAR_LEVELING_RP2040_FLASH_SIZE
+# define WEAR_LEVELING_RP2040_FLASH_SIZE (PICO_FLASH_SIZE_BYTES)
+#endif
+
+// Define the location of emulated EEPROM
+#ifndef WEAR_LEVELING_RP2040_FLASH_BASE
+# define WEAR_LEVELING_RP2040_FLASH_BASE ((WEAR_LEVELING_RP2040_FLASH_SIZE) - (WEAR_LEVELING_BACKING_SIZE))
+#endif
diff --git a/platforms/chibios/platform.mk b/platforms/chibios/platform.mk
index 32b8c5a946..63cc1a4b33 100644
--- a/platforms/chibios/platform.mk
+++ b/platforms/chibios/platform.mk
@@ -351,8 +351,11 @@ SHARED_CFLAGS = -fomit-frame-pointer \
-fno-common \
-fshort-wchar
+LDSCRIPT_PATH := $(shell dirname "$(LDSCRIPT)")
+
# Shared Linker flags for all toolchains
SHARED_LDFLAGS = -T $(LDSCRIPT) \
+ -L $(LDSCRIPT_PATH) \
-Wl,--gc-sections \
-nostartfiles
diff --git a/platforms/chibios/vendors/RP/RP2040.mk b/platforms/chibios/vendors/RP/RP2040.mk
index 1aa925cb15..de426c9c40 100644
--- a/platforms/chibios/vendors/RP/RP2040.mk
+++ b/platforms/chibios/vendors/RP/RP2040.mk
@@ -24,6 +24,7 @@ PICOSDKROOT := $(TOP_DIR)/lib/pico-sdk
PICOSDKSRC = $(PICOSDKROOT)/src/rp2_common/hardware_clocks/clocks.c \
$(PICOSDKROOT)/src/rp2_common/hardware_pll/pll.c \
$(PICOSDKROOT)/src/rp2_common/hardware_pio/pio.c \
+ $(PICOSDKROOT)/src/rp2_common/hardware_flash/flash.c \
$(PICOSDKROOT)/src/rp2_common/hardware_gpio/gpio.c \
$(PICOSDKROOT)/src/rp2_common/hardware_claim/claim.c \
$(PICOSDKROOT)/src/rp2_common/hardware_watchdog/watchdog.c \
@@ -36,6 +37,7 @@ PICOSDKINC = $(CHIBIOS)//os/various/pico_bindings/dumb/include \
$(PICOSDKROOT)/src/rp2_common/hardware_base/include \
$(PICOSDKROOT)/src/rp2_common/hardware_clocks/include \
$(PICOSDKROOT)/src/rp2_common/hardware_claim/include \
+ $(PICOSDKROOT)/src/rp2_common/hardware_flash/include \
$(PICOSDKROOT)/src/rp2_common/hardware_gpio/include \
$(PICOSDKROOT)/src/rp2_common/hardware_irq/include \
$(PICOSDKROOT)/src/rp2_common/hardware_pll/include \
diff --git a/platforms/chibios/vendors/RP/pico_sdk_shims.c b/platforms/chibios/vendors/RP/pico_sdk_shims.c
index f6e3943928..239155c086 100644
--- a/platforms/chibios/vendors/RP/pico_sdk_shims.c
+++ b/platforms/chibios/vendors/RP/pico_sdk_shims.c
@@ -7,3 +7,7 @@
void panic(const char *fmt, ...) {
chSysHalt(fmt);
}
+
+void hard_assertion_failure(void) {
+ panic("hard assert");
+}
diff --git a/platforms/chibios/vendors/RP/stage2_bootloaders.c b/platforms/chibios/vendors/RP/stage2_bootloaders.c
index af679a0dc7..e65b0a5802 100644
--- a/platforms/chibios/vendors/RP/stage2_bootloaders.c
+++ b/platforms/chibios/vendors/RP/stage2_bootloaders.c
@@ -13,7 +13,7 @@
#if defined(RP2040_FLASH_AT25SF128A)
-uint8_t BOOTLOADER_SECTION BOOT2_AT25SF128A[256] = {
+uint8_t BOOTLOADER_SECTION BOOT2_ROM[256] = {
0x00, 0xb5, 0x31, 0x4b, 0x21, 0x20, 0x58, 0x60, 0x98, 0x68, 0x02, 0x21,
0x88, 0x43, 0x98, 0x60, 0xd8, 0x60, 0x18, 0x61, 0x58, 0x61, 0x2d, 0x4b,
0x00, 0x21, 0x99, 0x60, 0x04, 0x21, 0x59, 0x61, 0x01, 0x21, 0xf0, 0x22,
@@ -40,7 +40,7 @@ uint8_t BOOTLOADER_SECTION BOOT2_AT25SF128A[256] = {
#elif defined(RP2040_FLASH_GD25Q64CS)
-uint8_t BOOTLOADER_SECTION BOOT2_GD25Q64CS[256] = {
+uint8_t BOOTLOADER_SECTION BOOT2_ROM[256] = {
0x00, 0xb5, 0x31, 0x4b, 0x21, 0x20, 0x58, 0x60, 0x98, 0x68, 0x02, 0x21,
0x88, 0x43, 0x98, 0x60, 0xd8, 0x60, 0x18, 0x61, 0x58, 0x61, 0x2d, 0x4b,
0x00, 0x21, 0x99, 0x60, 0x04, 0x21, 0x59, 0x61, 0x01, 0x21, 0xf0, 0x22,
@@ -67,7 +67,7 @@ uint8_t BOOTLOADER_SECTION BOOT2_GD25Q64CS[256] = {
#elif defined(RP2040_FLASH_W25X10CL)
-uint8_t BOOTLOADER_SECTION BOOT2_W25X10CL[256] = {
+uint8_t BOOTLOADER_SECTION BOOT2_ROM[256] = {
0x00, 0xb5, 0x14, 0x4b, 0x00, 0x21, 0x99, 0x60, 0x04, 0x21, 0x59, 0x61,
0x12, 0x49, 0x19, 0x60, 0x00, 0x21, 0x59, 0x60, 0x11, 0x49, 0x12, 0x48,
0x01, 0x60, 0x01, 0x21, 0x99, 0x60, 0xbb, 0x21, 0x19, 0x66, 0x02, 0x21,
@@ -94,7 +94,7 @@ uint8_t BOOTLOADER_SECTION BOOT2_W25X10CL[256] = {
#elif defined(RP2040_FLASH_IS25LP080)
-uint8_t BOOTLOADER_SECTION BOOT2_IS25LP080[256] = {
+uint8_t BOOTLOADER_SECTION BOOT2_ROM[256] = {
0x00, 0xb5, 0x2b, 0x4b, 0x00, 0x21, 0x99, 0x60, 0x04, 0x21, 0x59, 0x61,
0x29, 0x49, 0x19, 0x60, 0x01, 0x21, 0x99, 0x60, 0x28, 0x48, 0x00, 0xf0,
0x42, 0xf8, 0x28, 0x4a, 0x90, 0x42, 0x12, 0xd0, 0x06, 0x21, 0x19, 0x66,
@@ -121,7 +121,7 @@ uint8_t BOOTLOADER_SECTION BOOT2_IS25LP080[256] = {
#elif defined(RP2040_FLASH_GENERIC_03H)
-uint8_t BOOTLOADER_SECTION BOOT2_GENERIC_03H[256] = {
+uint8_t BOOTLOADER_SECTION BOOT2_ROM[256] = {
0x00, 0xb5, 0x0c, 0x4b, 0x00, 0x21, 0x99, 0x60, 0x04, 0x21, 0x59, 0x61,
0x0a, 0x49, 0x19, 0x60, 0x0a, 0x49, 0x0b, 0x48, 0x01, 0x60, 0x00, 0x21,
0x59, 0x60, 0x01, 0x21, 0x99, 0x60, 0x01, 0xbc, 0x00, 0x28, 0x00, 0xd0,
@@ -148,7 +148,7 @@ uint8_t BOOTLOADER_SECTION BOOT2_GENERIC_03H[256] = {
#else
-uint8_t BOOTLOADER_SECTION BOOT2_W25Q080[256] = {
+uint8_t BOOTLOADER_SECTION BOOT2_ROM[256] = {
0x00, 0xb5, 0x32, 0x4b, 0x21, 0x20, 0x58, 0x60, 0x98, 0x68, 0x02, 0x21,
0x88, 0x43, 0x98, 0x60, 0xd8, 0x60, 0x18, 0x61, 0x58, 0x61, 0x2e, 0x4b,
0x00, 0x21, 0x99, 0x60, 0x04, 0x21, 0x59, 0x61, 0x01, 0x21, 0xf0, 0x22,
diff --git a/quantum/wear_leveling/wear_leveling.c b/quantum/wear_leveling/wear_leveling.c
index 0a519639ea..429df45df5 100644
--- a/quantum/wear_leveling/wear_leveling.c
+++ b/quantum/wear_leveling/wear_leveling.c
@@ -421,7 +421,7 @@ static wear_leveling_status_t wear_leveling_write_raw(uint32_t address, const vo
#if BACKING_STORE_WRITE_SIZE == 2
// Small-write optimizations - uint16_t, 0 or 1, address is even, address <16384:
if (remaining >= 2 && address % 2 == 0 && address < 16384) {
- const uint16_t v = *(const uint16_t *)p;
+ const uint16_t v = ((uint16_t)p[1]) << 8 | p[0]; // don't just dereference a uint16_t here -- if unaligned it generates faults on some MCUs
if (v == 0 || v == 1) {
const write_log_entry_t log = LOG_ENTRY_MAKE_WORD_01(address, v);
status = wear_leveling_append_raw(log.raw16[0]);
@@ -765,4 +765,4 @@ __attribute__((weak)) bool backing_store_write_bulk(uint32_t address, backing_st
}
}
return true;
-} \ No newline at end of file
+}