aboutsummaryrefslogtreecommitdiffstats
diff options
context:
space:
mode:
-rw-r--r--src/Kconfig3
-rw-r--r--src/rp2040/Kconfig59
-rw-r--r--src/rp2040/Makefile48
-rw-r--r--src/rp2040/gpio.c119
-rw-r--r--src/rp2040/gpio.h22
-rw-r--r--src/rp2040/internal.h12
-rw-r--r--src/rp2040/main.c149
-rw-r--r--src/rp2040/rp2040_link.lds.S66
-rw-r--r--src/rp2040/serial.c92
-rw-r--r--src/rp2040/timer.c70
-rw-r--r--test/configs/rp2040.config2
11 files changed, 642 insertions, 0 deletions
diff --git a/src/Kconfig b/src/Kconfig
index 7278ada0..f1081907 100644
--- a/src/Kconfig
+++ b/src/Kconfig
@@ -21,6 +21,8 @@ choice
bool "LPC176x (Smoothieboard)"
config MACH_STM32
bool "STMicroelectronics STM32"
+ config MACH_RP2040
+ bool "Raspberry Pi RP2040"
config MACH_PRU
bool "Beaglebone PRU"
config MACH_LINUX
@@ -34,6 +36,7 @@ source "src/atsam/Kconfig"
source "src/atsamd/Kconfig"
source "src/lpc176x/Kconfig"
source "src/stm32/Kconfig"
+source "src/rp2040/Kconfig"
source "src/pru/Kconfig"
source "src/linux/Kconfig"
source "src/simulator/Kconfig"
diff --git a/src/rp2040/Kconfig b/src/rp2040/Kconfig
new file mode 100644
index 00000000..6375a7ff
--- /dev/null
+++ b/src/rp2040/Kconfig
@@ -0,0 +1,59 @@
+# Kconfig settings for STM32 processors
+
+if MACH_RP2040
+
+config RP2040_SELECT
+ bool
+ default y
+ select HAVE_GPIO
+ select HAVE_GPIO_BITBANGING
+ select HAVE_STRICT_TIMING
+
+config BOARD_DIRECTORY
+ string
+ default "rp2040"
+
+config MCU
+ string
+ default "rp2040"
+
+config CLOCK_FREQ
+ int
+ default 12000000
+
+config FLASH_SIZE
+ hex
+ default 0x200000
+
+config RAM_START
+ hex
+ default 0x20000000
+
+config RAM_SIZE
+ hex
+ default 0x42000
+
+config STACK_SIZE
+ int
+ default 512
+
+config FLASH_START
+ hex
+ default 0x10000000
+
+######################################################################
+# Communication inteface
+######################################################################
+
+config USBSERIAL
+ bool
+config SERIAL
+ bool
+choice
+ prompt "Communication interface"
+ config RP2040_SERIAL_UART0
+ bool "Serial (on UART0 GPIO1/GPIO0)"
+ select SERIAL
+endchoice
+
+endif
diff --git a/src/rp2040/Makefile b/src/rp2040/Makefile
new file mode 100644
index 00000000..1491b419
--- /dev/null
+++ b/src/rp2040/Makefile
@@ -0,0 +1,48 @@
+# Additional RP2040 build rules
+
+# Setup the toolchain
+CROSS_PREFIX=arm-none-eabi-
+
+dirs-y += src/rp2040 src/generic lib/rp2040/elf2uf2
+
+CFLAGS += -mcpu=cortex-m0plus -mthumb -Ilib/cmsis-core
+CFLAGS += -Ilib/rp2040 -Ilib/rp2040/cmsis_include
+
+CFLAGS_klipper.elf += --specs=nano.specs --specs=nosys.specs
+CFLAGS_klipper.elf += -T $(OUT)src/rp2040/rp2040_link.ld
+$(OUT)klipper.elf: $(OUT)stage2.o $(OUT)src/rp2040/rp2040_link.ld
+
+# Add source files
+src-y += rp2040/main.c rp2040/gpio.c generic/crc16_ccitt.c
+src-y += generic/armcm_boot.c generic/armcm_irq.c generic/armcm_reset.c
+src-y += generic/timer_irq.c rp2040/timer.c
+src-$(CONFIG_SERIAL) += rp2040/serial.c generic/serial_irq.c
+
+# rp2040 stage2 building
+$(OUT)stage2.o: lib/rp2040/boot_stage2/boot2_w25q080.S
+ @echo " Building rp2040 stage2 $@"
+ $(Q)$(CC) $(CFLAGS) -Ilib/rp2040/boot_stage2 -Ilib/rp2040/boot_stage2/asminclude -DPICO_FLASH_SPI_CLKDIV=2 -c $< -o $(OUT)stage2raw1.o
+ $(Q)$(LD) $(OUT)stage2raw1.o -nostartfiles --script=lib/rp2040/boot_stage2/boot_stage2.ld -o $(OUT)stage2raw.o
+ $(Q)$(OBJCOPY) -O binary $(OUT)stage2raw.o $(OUT)stage2raw.bin
+ $(Q)lib/rp2040/boot_stage2/pad_checksum -s 0xffffffff $(OUT)stage2raw.bin $(OUT)stage2.S
+ $(Q)$(CC) $(CFLAGS) -c $(OUT)stage2.S -o $(OUT)stage2.o
+OBJS_klipper.elf += $(OUT)stage2.o
+
+# Binary output file rules
+target-y += $(OUT)klipper.uf2
+
+$(OUT)lib/rp2040/elf2uf2/elf2uf2: lib/rp2040/elf2uf2/main.cpp
+ @echo " Building $@"
+ $(Q)g++ -g -O -Ilib/rp2040 $< -o $@
+
+$(OUT)klipper.uf2: $(OUT)klipper.elf $(OUT)lib/rp2040/elf2uf2/elf2uf2
+ @echo " Creating uf2 file $@"
+ $(Q)$(OUT)lib/rp2040/elf2uf2/elf2uf2 $< $@
+
+# Flash rules
+flash: $(OUT)klipper.uf2
+ @echo "Error: Flashing not supported on rp2040."
+ @echo "Place target board in bootloader mode (hold bootsel button"
+ @echo "during powerup), mount the device as a usb drive, and copy"
+ @echo "$< to the device."
+ @exit -1
diff --git a/src/rp2040/gpio.c b/src/rp2040/gpio.c
new file mode 100644
index 00000000..bac67d23
--- /dev/null
+++ b/src/rp2040/gpio.c
@@ -0,0 +1,119 @@
+// GPIO functions on rp2040
+//
+// Copyright (C) 2021 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include <string.h> // ffs
+#include "board/irq.h" // irq_save
+#include "command.h" // shutdown
+#include "gpio.h" // gpio_out_setup
+#include "hardware/structs/iobank0.h" // iobank0_hw
+#include "hardware/structs/padsbank0.h" // padsbank0_hw
+#include "hardware/structs/sio.h" // sio_hw
+#include "internal.h" // gpio_peripheral
+#include "sched.h" // sched_shutdown
+
+
+/****************************************************************
+ * Pin mappings
+ ****************************************************************/
+
+DECL_ENUMERATION_RANGE("pin", "gpio0", 0, 30);
+
+// Set the mode and extended function of a pin
+void
+gpio_peripheral(uint32_t gpio, int func, int pull_up)
+{
+ padsbank0_hw->io[gpio] = (
+ PADS_BANK0_GPIO0_IE_BITS
+ | (PADS_BANK0_GPIO0_DRIVE_VALUE_4MA << PADS_BANK0_GPIO0_DRIVE_MSB)
+ | (pull_up > 0 ? PADS_BANK0_GPIO0_PUE_BITS : 0)
+ | (pull_up < 0 ? PADS_BANK0_GPIO0_PDE_BITS : 0));
+ iobank0_hw->io[gpio].ctrl = func << IO_BANK0_GPIO0_CTRL_FUNCSEL_LSB;
+}
+
+// Convert a register and bit location back to an integer pin identifier
+static int
+mask_to_pin(uint32_t mask)
+{
+ return ffs(mask)-1;
+}
+
+
+/****************************************************************
+ * General Purpose Input Output (GPIO) pins
+ ****************************************************************/
+
+struct gpio_out
+gpio_out_setup(uint8_t pin, uint8_t val)
+{
+ if (pin > 30)
+ goto fail;
+ struct gpio_out g = { .bit=1<<pin };
+ gpio_out_reset(g, val);
+ return g;
+fail:
+ shutdown("Not an output pin");
+}
+
+void
+gpio_out_reset(struct gpio_out g, uint8_t val)
+{
+ int pin = mask_to_pin(g.bit);
+ irqstatus_t flag = irq_save();
+ gpio_out_write(g, val);
+ sio_hw->gpio_oe_set = g.bit;
+ gpio_peripheral(pin, 5, 0);
+ irq_restore(flag);
+}
+
+void
+gpio_out_toggle_noirq(struct gpio_out g)
+{
+ sio_hw->gpio_togl = g.bit;
+}
+
+void
+gpio_out_toggle(struct gpio_out g)
+{
+ gpio_out_toggle_noirq(g);
+}
+
+void
+gpio_out_write(struct gpio_out g, uint8_t val)
+{
+ if (val)
+ sio_hw->gpio_set = g.bit;
+ else
+ sio_hw->gpio_clr = g.bit;
+}
+
+
+struct gpio_in
+gpio_in_setup(uint8_t pin, int8_t pull_up)
+{
+ if (pin > 30)
+ goto fail;
+ struct gpio_in g = { .bit=1<<pin };
+ gpio_in_reset(g, pull_up);
+ return g;
+fail:
+ shutdown("Not an input pin");
+}
+
+void
+gpio_in_reset(struct gpio_in g, int8_t pull_up)
+{
+ int pin = mask_to_pin(g.bit);
+ irqstatus_t flag = irq_save();
+ gpio_peripheral(pin, 5, pull_up);
+ sio_hw->gpio_oe_clr = g.bit;
+ irq_restore(flag);
+}
+
+uint8_t
+gpio_in_read(struct gpio_in g)
+{
+ return !!(sio_hw->gpio_in & g.bit);
+}
diff --git a/src/rp2040/gpio.h b/src/rp2040/gpio.h
new file mode 100644
index 00000000..0f8507bd
--- /dev/null
+++ b/src/rp2040/gpio.h
@@ -0,0 +1,22 @@
+#ifndef __RP2040_GPIO_H
+#define __RP2040_GPIO_H
+
+#include <stdint.h> // uint32_t
+
+struct gpio_out {
+ uint32_t bit;
+};
+struct gpio_out gpio_out_setup(uint8_t pin, uint8_t val);
+void gpio_out_reset(struct gpio_out g, uint8_t val);
+void gpio_out_toggle_noirq(struct gpio_out g);
+void gpio_out_toggle(struct gpio_out g);
+void gpio_out_write(struct gpio_out g, uint8_t val);
+
+struct gpio_in {
+ uint32_t bit;
+};
+struct gpio_in gpio_in_setup(uint8_t pin, int8_t pull_up);
+void gpio_in_reset(struct gpio_in g, int8_t pull_up);
+uint8_t gpio_in_read(struct gpio_in g);
+
+#endif // gpio.h
diff --git a/src/rp2040/internal.h b/src/rp2040/internal.h
new file mode 100644
index 00000000..8c48640a
--- /dev/null
+++ b/src/rp2040/internal.h
@@ -0,0 +1,12 @@
+#ifndef __RP2040_INTERNAL_H
+#define __RP2040_INTERNAL_H
+// Local definitions for rp2040
+
+#include "RP2040.h"
+
+void enable_pclock(uint32_t reset_bit);
+int is_enabled_pclock(uint32_t reset_bit);
+uint32_t get_pclock_frequency(uint32_t reset_bit);
+void gpio_peripheral(uint32_t gpio, int func, int pull_up);
+
+#endif // internal.h
diff --git a/src/rp2040/main.c b/src/rp2040/main.c
new file mode 100644
index 00000000..35e4f55d
--- /dev/null
+++ b/src/rp2040/main.c
@@ -0,0 +1,149 @@
+// Startup code on rp2040
+//
+// Copyright (C) 2021 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include <stdint.h> // uint32_t
+#include "hardware/structs/clocks.h" // clock_hw_t
+#include "hardware/structs/pll.h" // pll_hw_t
+#include "hardware/structs/resets.h" // sio_hw
+#include "hardware/structs/watchdog.h" // watchdog_hw
+#include "hardware/structs/xosc.h" // xosc_hw
+#include "sched.h" // sched_main
+
+
+/****************************************************************
+ * watchdog handler
+ ****************************************************************/
+
+void
+watchdog_reset(void)
+{
+ watchdog_hw->load = 0x800000; // ~350ms
+}
+DECL_TASK(watchdog_reset);
+
+void
+watchdog_init(void)
+{
+ watchdog_reset();
+ watchdog_hw->ctrl = (WATCHDOG_CTRL_PAUSE_DBG0_BITS
+ | WATCHDOG_CTRL_PAUSE_DBG1_BITS
+ | WATCHDOG_CTRL_PAUSE_JTAG_BITS
+ | WATCHDOG_CTRL_ENABLE_BITS);
+}
+DECL_INIT(watchdog_init);
+
+
+/****************************************************************
+ * Clock setup
+ ****************************************************************/
+
+#define FREQ_XOSC 12000000
+#define FREQ_SYS 125000000
+
+void
+enable_pclock(uint32_t reset_bit)
+{
+ resets_hw->reset |= reset_bit;
+ resets_hw->reset &= ~reset_bit;
+ while (!(resets_hw->reset_done & reset_bit))
+ ;
+}
+
+int
+is_enabled_pclock(uint32_t reset_bit)
+{
+ return !(resets_hw->reset & reset_bit);
+}
+
+uint32_t
+get_pclock_frequency(uint32_t reset_bit)
+{
+ return FREQ_SYS;
+}
+
+static void
+xosc_setup(void)
+{
+ xosc_hw->startup = DIV_ROUND_UP(FREQ_XOSC, 1000 * 256); // 1ms
+ xosc_hw->ctrl = (XOSC_CTRL_FREQ_RANGE_VALUE_1_15MHZ
+ | (XOSC_CTRL_ENABLE_VALUE_ENABLE << XOSC_CTRL_ENABLE_LSB));
+ while(!(xosc_hw->status & XOSC_STATUS_STABLE_BITS))
+ ;
+}
+
+static void
+pll_setup(pll_hw_t *pll, uint32_t mul, uint32_t postdiv)
+{
+ // Setup pll
+ uint32_t refdiv = 1, fbdiv = mul, postdiv2 = 2, postdiv1 = postdiv/postdiv2;
+ pll->cs = refdiv;
+ pll->fbdiv_int = fbdiv;
+ pll->pwr = PLL_PWR_DSMPD_BITS | PLL_PWR_POSTDIVPD_BITS;
+ while (!(pll->cs & PLL_CS_LOCK_BITS))
+ ;
+
+ // Setup post divider
+ pll->prim = ((postdiv1 << PLL_PRIM_POSTDIV1_LSB)
+ | (postdiv2 << PLL_PRIM_POSTDIV2_LSB));
+ pll->pwr = PLL_PWR_DSMPD_BITS;
+}
+
+static void
+clk_aux_setup(uint32_t clk_id, uint32_t aux_id)
+{
+ clock_hw_t *clk = &clocks_hw->clk[clk_id];
+ clk->ctrl = 0;
+ clk->ctrl = aux_id | CLOCKS_CLK_PERI_CTRL_ENABLE_BITS;
+}
+
+static void
+clock_setup(void)
+{
+ // Set clk_sys and clk_ref to use internal clock
+ clock_hw_t *csys = &clocks_hw->clk[clk_sys];
+ csys->ctrl &= ~CLOCKS_CLK_SYS_CTRL_SRC_BITS;
+ while (csys->selected != 0x1)
+ ;
+ clock_hw_t *cref = &clocks_hw->clk[clk_ref];
+ cref->ctrl &= ~CLOCKS_CLK_REF_CTRL_SRC_BITS;
+ while (cref->selected != 0x1)
+ ;
+
+ // Reset peripherals (that can be)
+ resets_hw->reset = ~(RESETS_RESET_IO_QSPI_BITS
+ | RESETS_RESET_PADS_QSPI_BITS);
+
+ // Setup xosc, pll_sys, and switch clk_sys
+ xosc_setup();
+ enable_pclock(RESETS_RESET_PLL_SYS_BITS);
+ pll_setup(pll_sys_hw, 125, 125*FREQ_XOSC/FREQ_SYS);
+ csys->ctrl = 0;
+ csys->div = 1<<CLOCKS_CLK_SYS_DIV_INT_LSB;
+ csys->ctrl = CLOCKS_CLK_SYS_CTRL_SRC_VALUE_CLKSRC_CLK_SYS_AUX;
+ while (!(csys->selected & (1 << 1)))
+ ;
+
+ // Setup clk_peri
+ clk_aux_setup(clk_peri, CLOCKS_CLK_PERI_CTRL_AUXSRC_VALUE_CLK_SYS);
+
+ // Enable watchdog tick (at 12Mhz)
+ cref->div = 1<<CLOCKS_CLK_REF_DIV_INT_LSB;
+ cref->ctrl = CLOCKS_CLK_REF_CTRL_SRC_VALUE_XOSC_CLKSRC;
+ while (!(cref->selected & (1 << 2)))
+ ;
+ watchdog_hw->tick = 1 | WATCHDOG_TICK_ENABLE_BITS;
+
+ // Enable GPIO control
+ enable_pclock(RESETS_RESET_IO_BANK0_BITS | RESETS_RESET_PADS_BANK0_BITS);
+}
+
+// Main entry point - called from armcm_boot.c:ResetHandler()
+void
+armcm_main(void)
+{
+ clock_setup();
+ sched_main();
+}
diff --git a/src/rp2040/rp2040_link.lds.S b/src/rp2040/rp2040_link.lds.S
new file mode 100644
index 00000000..3ffcd909
--- /dev/null
+++ b/src/rp2040/rp2040_link.lds.S
@@ -0,0 +1,66 @@
+// rp2040 linker script (based on armcm_link.lds.S and customized for stage2)
+//
+// Copyright (C) 2019-2021 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "autoconf.h" // CONFIG_FLASH_START
+
+OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
+OUTPUT_ARCH(arm)
+
+MEMORY
+{
+ rom (rx) : ORIGIN = CONFIG_FLASH_START , LENGTH = CONFIG_FLASH_SIZE
+ ram (rwx) : ORIGIN = CONFIG_RAM_START , LENGTH = CONFIG_RAM_SIZE
+}
+
+SECTIONS
+{
+ .text : {
+ . = ALIGN(4);
+ KEEP(*(.boot2))
+ _text_vectortable_start = .;
+ KEEP(*(.vector_table))
+ _text_vectortable_end = .;
+ *(.text .text.*)
+ *(.rodata .rodata*)
+ } > rom
+
+ . = ALIGN(4);
+ _data_flash = .;
+
+ .data : AT (_data_flash)
+ {
+ . = ALIGN(4);
+ _data_start = .;
+ *(.ramfunc .ramfunc.*);
+ *(.data .data.*);
+ . = ALIGN(4);
+ _data_end = .;
+ } > ram
+
+ .bss (NOLOAD) :
+ {
+ . = ALIGN(4);
+ _bss_start = .;
+ *(.bss .bss.*)
+ *(COMMON)
+ . = ALIGN(4);
+ _bss_end = .;
+ } > ram
+
+ _stack_start = CONFIG_RAM_START + CONFIG_RAM_SIZE - CONFIG_STACK_SIZE ;
+ .stack _stack_start (NOLOAD) :
+ {
+ . = . + CONFIG_STACK_SIZE;
+ _stack_end = .;
+ } > ram
+
+ /DISCARD/ : {
+ // The .init/.fini sections are used by __libc_init_array(), but
+ // that isn't needed so no need to include them in the binary.
+ *(.init)
+ *(.fini)
+ }
+}
diff --git a/src/rp2040/serial.c b/src/rp2040/serial.c
new file mode 100644
index 00000000..abfdcb8b
--- /dev/null
+++ b/src/rp2040/serial.c
@@ -0,0 +1,92 @@
+// rp2040 serial
+//
+// Copyright (C) 2021 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include <stdint.h> // uint32_t
+#include "autoconf.h" // CONFIG_SERIAL
+#include "board/armcm_boot.h" // armcm_enable_irq
+#include "board/irq.h" // irq_save
+#include "board/serial_irq.h" // serial_rx_data
+#include "hardware/structs/resets.h" // RESETS_RESET_UART0_BITS
+#include "hardware/structs/uart.h" // UART0_BASE
+#include "internal.h" // UART0_IRQn
+#include "sched.h" // DECL_INIT
+
+#define UARTx uart0_hw
+#define UARTx_IRQn UART0_IRQ_IRQn
+#define GPIO_Rx 1
+#define GPIO_Tx 0
+
+// Write tx bytes to the serial port
+static void
+kick_tx(void)
+{
+ for (;;) {
+ if (UARTx->fr & UART_UARTFR_TXFF_BITS) {
+ // Output fifo full - enable tx irq
+ UARTx->imsc = (UART_UARTIMSC_RXIM_BITS | UART_UARTIMSC_RTIM_BITS
+ | UART_UARTIMSC_TXIM_BITS);
+ break;
+ }
+ uint8_t data;
+ int ret = serial_get_tx_byte(&data);
+ if (ret) {
+ // No more data to send - disable tx irq
+ UARTx->imsc = UART_UARTIMSC_RXIM_BITS | UART_UARTIMSC_RTIM_BITS;
+ break;
+ }
+ UARTx->dr = data;
+ }
+}
+
+void
+UARTx_IRQHandler(void)
+{
+ uint32_t mis = UARTx->mis;
+ if (mis & (UART_UARTMIS_RXMIS_BITS | UART_UARTMIS_RTMIS_BITS)) {
+ do {
+ serial_rx_byte(UARTx->dr);
+ } while (!(UARTx->fr & UART_UARTFR_RXFE_BITS));
+ } else if (mis & UART_UARTMIS_TXMIS_BITS) {
+ kick_tx();
+ }
+}
+
+void
+serial_enable_tx_irq(void)
+{
+ if (!(UARTx->fr & UART_UARTFR_TXFF_BITS)) {
+ irqstatus_t flag = irq_save();
+ kick_tx();
+ irq_restore(flag);
+ }
+}
+
+void
+serial_init(void)
+{
+ enable_pclock(RESETS_RESET_UART0_BITS);
+
+ // Setup baud
+ uint32_t pclk = get_pclock_frequency(RESETS_RESET_UART0_BITS);
+ uint32_t div = DIV_ROUND_CLOSEST(pclk * 4, CONFIG_SERIAL_BAUD);
+ UARTx->ibrd = div >> 6;
+ UARTx->fbrd = div & 0x3f;
+
+ // Enable fifo, set 8N1
+ UARTx->lcr_h = UART_UARTLCR_H_FEN_BITS | UART_UARTLCR_H_WLEN_BITS;
+ UARTx->ifls = 0;
+ UARTx->cr = (UART_UARTCR_RXE_BITS | UART_UARTCR_TXE_BITS
+ | UART_UARTCR_UARTEN_BITS);
+
+ // Setup pins
+ gpio_peripheral(GPIO_Rx, 2, 1);
+ gpio_peripheral(GPIO_Tx, 2, 0);
+
+ // Enable receive irq
+ armcm_enable_irq(UARTx_IRQHandler, UARTx_IRQn, 0);
+ UARTx->imsc = UART_UARTIMSC_RXIM_BITS | UART_UARTIMSC_RTIM_BITS;
+}
+DECL_INIT(serial_init);
diff --git a/src/rp2040/timer.c b/src/rp2040/timer.c
new file mode 100644
index 00000000..5401933e
--- /dev/null
+++ b/src/rp2040/timer.c
@@ -0,0 +1,70 @@
+// rp2040 timer support
+//
+// Copyright (C) 2021 Kevin O'Connor <kevin@koconnor.net>
+//
+// This file may be distributed under the terms of the GNU GPLv3 license.
+
+#include "board/armcm_boot.h" // armcm_enable_irq
+#include "board/irq.h" // irq_disable
+#include "board/misc.h" // timer_read_time
+#include "board/timer_irq.h" // timer_dispatch_many
+#include "command.h" // DECL_SHUTDOWN
+#include "hardware/structs/resets.h" // RESETS_RESET_UART0_BITS
+#include "hardware/structs/timer.h" // RESETS_RESET_UART0_BITS
+#include "internal.h" // enable_pclock
+#include "sched.h" // DECL_INIT
+
+
+/****************************************************************
+ * Low level timer code
+ ****************************************************************/
+
+// Return the current time (in absolute clock ticks).
+uint32_t
+timer_read_time(void)
+{
+ return timer_hw->timerawl;
+}
+
+static inline void
+timer_set(uint32_t next)
+{
+ timer_hw->alarm[0] = next;
+}
+
+// Activate timer dispatch as soon as possible
+void
+timer_kick(void)
+{
+ timer_set(timer_read_time() + 50);
+}
+
+
+/****************************************************************
+ * Setup and irqs
+ ****************************************************************/
+
+// Hardware timer IRQ handler - dispatch software timers
+void __aligned(16)
+TIMER0_IRQHandler(void)
+{
+ irq_disable();
+ timer_hw->intr = 1;
+ uint32_t next = timer_dispatch_many();
+ timer_set(next);
+ irq_enable();
+}
+
+void
+timer_init(void)
+{
+ irq_disable();
+ enable_pclock(RESETS_RESET_TIMER_BITS);
+ timer_hw->timelw = 0;
+ timer_hw->timehw = 0;
+ armcm_enable_irq(TIMER0_IRQHandler, TIMER_IRQ_0_IRQn, 2);
+ timer_hw->inte = 1;
+ timer_kick();
+ irq_enable();
+}
+DECL_INIT(timer_init);
diff --git a/test/configs/rp2040.config b/test/configs/rp2040.config
new file mode 100644
index 00000000..51fc1228
--- /dev/null
+++ b/test/configs/rp2040.config
@@ -0,0 +1,2 @@
+# Base config file for rp2040 boards
+CONFIG_MACH_RP2040=y