aboutsummaryrefslogtreecommitdiffhomepage
path: root/src/machine
diff options
context:
space:
mode:
Diffstat (limited to 'src/machine')
-rw-r--r--src/machine/board_pico2.go88
-rw-r--r--src/machine/machine_rp2.go (renamed from src/machine/machine_rp2040.go)68
-rw-r--r--src/machine/machine_rp2040_i2c.go21
-rw-r--r--src/machine/machine_rp2040_rtc.go2
-rw-r--r--src/machine/machine_rp2350_rom.go153
-rw-r--r--src/machine/machine_rp2350_usb.go380
-rw-r--r--src/machine/machine_rp2_2040.go199
-rw-r--r--src/machine/machine_rp2_2350.go217
-rw-r--r--src/machine/machine_rp2_adc.go (renamed from src/machine/machine_rp2040_adc.go)2
-rw-r--r--src/machine/machine_rp2_clocks.go (renamed from src/machine/machine_rp2040_clocks.go)91
-rw-r--r--src/machine/machine_rp2_gpio.go (renamed from src/machine/machine_rp2040_gpio.go)135
-rw-r--r--src/machine/machine_rp2_pins.go (renamed from src/machine/machine_rp2040_pins.go)2
-rw-r--r--src/machine/machine_rp2_pll.go (renamed from src/machine/machine_rp2040_pll.go)2
-rw-r--r--src/machine/machine_rp2_resets.go (renamed from src/machine/machine_rp2040_resets.go)22
-rw-r--r--src/machine/machine_rp2_sync.go (renamed from src/machine/machine_rp2040_sync.go)35
-rw-r--r--src/machine/machine_rp2_timer.go (renamed from src/machine/machine_rp2040_timer.go)8
-rw-r--r--src/machine/machine_rp2_uart.go (renamed from src/machine/machine_rp2040_uart.go)4
-rw-r--r--src/machine/machine_rp2_watchdog.go (renamed from src/machine/machine_rp2040_watchdog.go)10
-rw-r--r--src/machine/machine_rp2_xosc.go (renamed from src/machine/machine_rp2040_xosc.go)4
-rw-r--r--src/machine/uart.go2
-rw-r--r--src/machine/usb.go2
-rw-r--r--src/machine/watchdog.go2
22 files changed, 1158 insertions, 291 deletions
diff --git a/src/machine/board_pico2.go b/src/machine/board_pico2.go
new file mode 100644
index 000000000..327c542fb
--- /dev/null
+++ b/src/machine/board_pico2.go
@@ -0,0 +1,88 @@
+//go:build pico2
+
+package machine
+
+// GPIO pins
+const (
+ GP0 Pin = GPIO0
+ GP1 Pin = GPIO1
+ GP2 Pin = GPIO2
+ GP3 Pin = GPIO3
+ GP4 Pin = GPIO4
+ GP5 Pin = GPIO5
+ GP6 Pin = GPIO6
+ GP7 Pin = GPIO7
+ GP8 Pin = GPIO8
+ GP9 Pin = GPIO9
+ GP10 Pin = GPIO10
+ GP11 Pin = GPIO11
+ GP12 Pin = GPIO12
+ GP13 Pin = GPIO13
+ GP14 Pin = GPIO14
+ GP15 Pin = GPIO15
+ GP16 Pin = GPIO16
+ GP17 Pin = GPIO17
+ GP18 Pin = GPIO18
+ GP19 Pin = GPIO19
+ GP20 Pin = GPIO20
+ GP21 Pin = GPIO21
+ GP22 Pin = GPIO22
+ GP26 Pin = GPIO26
+ GP27 Pin = GPIO27
+ GP28 Pin = GPIO28
+
+ // Onboard LED
+ LED Pin = GPIO25
+
+ // Onboard crystal oscillator frequency, in MHz.
+ xoscFreq = 12 // MHz
+)
+
+// I2C Default pins on Raspberry Pico.
+const (
+ I2C0_SDA_PIN = GP4
+ I2C0_SCL_PIN = GP5
+
+ I2C1_SDA_PIN = GP2
+ I2C1_SCL_PIN = GP3
+)
+
+// SPI default pins
+const (
+ // Default Serial Clock Bus 0 for SPI communications
+ SPI0_SCK_PIN = GPIO18
+ // Default Serial Out Bus 0 for SPI communications
+ SPI0_SDO_PIN = GPIO19 // Tx
+ // Default Serial In Bus 0 for SPI communications
+ SPI0_SDI_PIN = GPIO16 // Rx
+
+ // Default Serial Clock Bus 1 for SPI communications
+ SPI1_SCK_PIN = GPIO10
+ // Default Serial Out Bus 1 for SPI communications
+ SPI1_SDO_PIN = GPIO11 // Tx
+ // Default Serial In Bus 1 for SPI communications
+ SPI1_SDI_PIN = GPIO12 // Rx
+)
+
+// UART pins
+const (
+ UART0_TX_PIN = GPIO0
+ UART0_RX_PIN = GPIO1
+ UART1_TX_PIN = GPIO8
+ UART1_RX_PIN = GPIO9
+ UART_TX_PIN = UART0_TX_PIN
+ UART_RX_PIN = UART0_RX_PIN
+)
+
+var DefaultUART = UART0
+
+// USB identifiers
+const (
+ usb_STRING_PRODUCT = "Pico2"
+ usb_STRING_MANUFACTURER = "Raspberry Pi"
+)
+
+var (
+ usb_VID uint16 = 0x2E8A
+ usb_PID uint16 = 0x000A
+)
diff --git a/src/machine/machine_rp2040.go b/src/machine/machine_rp2.go
index 45f9f510f..6c09fedfe 100644
--- a/src/machine/machine_rp2040.go
+++ b/src/machine/machine_rp2.go
@@ -1,38 +1,55 @@
-//go:build rp2040
+//go:build rp2040 || rp2350
package machine
import (
"device/rp"
+ "runtime/interrupt"
"runtime/volatile"
"unsafe"
)
const deviceName = rp.Device
+const (
+ // Number of spin locks available
+ // Note: On RP2350, most spinlocks are unusable due to Errata 2
+ _NUMSPINLOCKS = 32
+ _PICO_SPINLOCK_ID_IRQ = 9
+)
+
+// UART on the RP2040
+var (
+ UART0 = &_UART0
+ _UART0 = UART{
+ Buffer: NewRingBuffer(),
+ Bus: rp.UART0,
+ }
+
+ UART1 = &_UART1
+ _UART1 = UART{
+ Buffer: NewRingBuffer(),
+ Bus: rp.UART1,
+ }
+)
+
+func init() {
+ UART0.Interrupt = interrupt.New(rp.IRQ_UART0_IRQ, _UART0.handleInterrupt)
+ UART1.Interrupt = interrupt.New(rp.IRQ_UART1_IRQ, _UART1.handleInterrupt)
+}
+
//go:linkname machineInit runtime.machineInit
func machineInit() {
// Reset all peripherals to put system into a known state,
// except for QSPI pads and the XIP IO bank, as this is fatal if running from flash
// and the PLLs, as this is fatal if clock muxing has not been reset on this boot
// and USB, syscfg, as this disturbs USB-to-SWD on core 1
- bits := ^uint32(rp.RESETS_RESET_IO_QSPI |
- rp.RESETS_RESET_PADS_QSPI |
- rp.RESETS_RESET_PLL_USB |
- rp.RESETS_RESET_USBCTRL |
- rp.RESETS_RESET_SYSCFG |
- rp.RESETS_RESET_PLL_SYS)
+ bits := ^uint32(initDontReset)
resetBlock(bits)
// Remove reset from peripherals which are clocked only by clkSys and
// clkRef. Other peripherals stay in reset until we've configured clocks.
- bits = ^uint32(rp.RESETS_RESET_ADC |
- rp.RESETS_RESET_RTC |
- rp.RESETS_RESET_SPI0 |
- rp.RESETS_RESET_SPI1 |
- rp.RESETS_RESET_UART0 |
- rp.RESETS_RESET_UART1 |
- rp.RESETS_RESET_USBCTRL)
+ bits = ^uint32(initUnreset)
unresetBlockWait(bits)
clocks.init()
@@ -94,4 +111,25 @@ const (
)
// DMA channels usable on the RP2040.
-var dmaChannels = (*[12]dmaChannel)(unsafe.Pointer(rp.DMA))
+var dmaChannels = (*[12 + 4*rp2350ExtraReg]dmaChannel)(unsafe.Pointer(rp.DMA))
+
+//go:inline
+func boolToBit(a bool) uint32 {
+ if a {
+ return 1
+ }
+ return 0
+}
+
+//go:inline
+func u32max(a, b uint32) uint32 {
+ if a > b {
+ return a
+ }
+ return b
+}
+
+//go:inline
+func isReservedI2CAddr(addr uint8) bool {
+ return (addr&0x78) == 0 || (addr&0x78) == 0x78
+}
diff --git a/src/machine/machine_rp2040_i2c.go b/src/machine/machine_rp2040_i2c.go
index b7dc63d2b..f34aa259f 100644
--- a/src/machine/machine_rp2040_i2c.go
+++ b/src/machine/machine_rp2040_i2c.go
@@ -631,24 +631,3 @@ func (b i2cAbortError) Reasons() (reasons []string) {
}
return reasons
}
-
-//go:inline
-func boolToBit(a bool) uint32 {
- if a {
- return 1
- }
- return 0
-}
-
-//go:inline
-func u32max(a, b uint32) uint32 {
- if a > b {
- return a
- }
- return b
-}
-
-//go:inline
-func isReservedI2CAddr(addr uint8) bool {
- return (addr&0x78) == 0 || (addr&0x78) == 0x78
-}
diff --git a/src/machine/machine_rp2040_rtc.go b/src/machine/machine_rp2040_rtc.go
index 192e187c0..072432fc0 100644
--- a/src/machine/machine_rp2040_rtc.go
+++ b/src/machine/machine_rp2040_rtc.go
@@ -97,7 +97,7 @@ func toAlarmTime(delay uint32) rtcTime {
func (rtc *rtcType) setDivider() {
// Get clk_rtc freq and make sure it is running
- rtcFreq := configuredFreq[clkRTC]
+ rtcFreq := configuredFreq[ClkRTC]
if rtcFreq == 0 {
panic("can not set RTC divider, clock is not running")
}
diff --git a/src/machine/machine_rp2350_rom.go b/src/machine/machine_rp2350_rom.go
new file mode 100644
index 000000000..4f3d4762a
--- /dev/null
+++ b/src/machine/machine_rp2350_rom.go
@@ -0,0 +1,153 @@
+//go:build tinygo && rp2350
+
+package machine
+
+import ()
+
+/*
+typedef unsigned char uint8_t;
+typedef unsigned short uint16_t;
+typedef unsigned long uint32_t;
+typedef unsigned long size_t;
+typedef unsigned long uintptr_t;
+
+#define false 0
+#define true 1
+typedef int bool;
+
+// https://github.com/raspberrypi/pico-sdk
+// src/rp2_common/pico_platform_compiler/include/pico/platform/compiler.h
+
+#define pico_default_asm_volatile(...) __asm volatile (".syntax unified\n" __VA_ARGS__)
+
+
+// https://github.com/raspberrypi/pico-sdk
+// src/rp2350/pico_platform/include/pico/platform.h
+
+static bool pico_processor_state_is_nonsecure(void) {
+// // todo add a define to disable NS checking at all?
+// // IDAU-Exempt addresses return S=1 when tested in the Secure state,
+// // whereas executing a tt in the NonSecure state will always return S=0.
+// uint32_t tt;
+// pico_default_asm_volatile (
+// "movs %0, #0\n"
+// "tt %0, %0\n"
+// : "=r" (tt) : : "cc"
+// );
+// return !(tt & (1u << 22));
+
+ return false;
+}
+
+
+// https://github.com/raspberrypi/pico-sdk
+// src/rp2_common/pico_bootrom/include/pico/bootrom_constants.h
+
+// RP2040 & RP2350
+#define ROM_DATA_SOFTWARE_GIT_REVISION ROM_TABLE_CODE('G', 'R')
+#define ROM_FUNC_FLASH_ENTER_CMD_XIP ROM_TABLE_CODE('C', 'X')
+#define ROM_FUNC_FLASH_EXIT_XIP ROM_TABLE_CODE('E', 'X')
+#define ROM_FUNC_FLASH_FLUSH_CACHE ROM_TABLE_CODE('F', 'C')
+#define ROM_FUNC_CONNECT_INTERNAL_FLASH ROM_TABLE_CODE('I', 'F')
+#define ROM_FUNC_FLASH_RANGE_ERASE ROM_TABLE_CODE('R', 'E')
+#define ROM_FUNC_FLASH_RANGE_PROGRAM ROM_TABLE_CODE('R', 'P')
+
+// RP2350 only
+#define ROM_FUNC_PICK_AB_PARTITION ROM_TABLE_CODE('A', 'B')
+#define ROM_FUNC_CHAIN_IMAGE ROM_TABLE_CODE('C', 'I')
+#define ROM_FUNC_EXPLICIT_BUY ROM_TABLE_CODE('E', 'B')
+#define ROM_FUNC_FLASH_RUNTIME_TO_STORAGE_ADDR ROM_TABLE_CODE('F', 'A')
+#define ROM_DATA_FLASH_DEVINFO16_PTR ROM_TABLE_CODE('F', 'D')
+#define ROM_FUNC_FLASH_OP ROM_TABLE_CODE('F', 'O')
+#define ROM_FUNC_GET_B_PARTITION ROM_TABLE_CODE('G', 'B')
+#define ROM_FUNC_GET_PARTITION_TABLE_INFO ROM_TABLE_CODE('G', 'P')
+#define ROM_FUNC_GET_SYS_INFO ROM_TABLE_CODE('G', 'S')
+#define ROM_FUNC_GET_UF2_TARGET_PARTITION ROM_TABLE_CODE('G', 'U')
+#define ROM_FUNC_LOAD_PARTITION_TABLE ROM_TABLE_CODE('L', 'P')
+#define ROM_FUNC_OTP_ACCESS ROM_TABLE_CODE('O', 'A')
+#define ROM_DATA_PARTITION_TABLE_PTR ROM_TABLE_CODE('P', 'T')
+#define ROM_FUNC_FLASH_RESET_ADDRESS_TRANS ROM_TABLE_CODE('R', 'A')
+#define ROM_FUNC_REBOOT ROM_TABLE_CODE('R', 'B')
+#define ROM_FUNC_SET_ROM_CALLBACK ROM_TABLE_CODE('R', 'C')
+#define ROM_FUNC_SECURE_CALL ROM_TABLE_CODE('S', 'C')
+#define ROM_FUNC_SET_NS_API_PERMISSION ROM_TABLE_CODE('S', 'P')
+#define ROM_FUNC_BOOTROM_STATE_RESET ROM_TABLE_CODE('S', 'R')
+#define ROM_FUNC_SET_BOOTROM_STACK ROM_TABLE_CODE('S', 'S')
+#define ROM_DATA_SAVED_XIP_SETUP_FUNC_PTR ROM_TABLE_CODE('X', 'F')
+#define ROM_FUNC_FLASH_SELECT_XIP_READ_MODE ROM_TABLE_CODE('X', 'M')
+#define ROM_FUNC_VALIDATE_NS_BUFFER ROM_TABLE_CODE('V', 'B')
+
+#define BOOTSEL_FLAG_GPIO_PIN_SPECIFIED 0x20
+
+#define BOOTROM_FUNC_TABLE_OFFSET 0x14
+
+// todo remove this (or #ifdef it for A1/A2)
+#define BOOTROM_IS_A2() ((*(volatile uint8_t *)0x13) == 2)
+#define BOOTROM_WELL_KNOWN_PTR_SIZE (BOOTROM_IS_A2() ? 2 : 4)
+
+#define BOOTROM_VTABLE_OFFSET 0x00
+#define BOOTROM_TABLE_LOOKUP_OFFSET (BOOTROM_FUNC_TABLE_OFFSET + BOOTROM_WELL_KNOWN_PTR_SIZE)
+
+// https://github.com/raspberrypi/pico-sdk
+// src/common/boot_picoboot_headers/include/boot/picoboot_constants.h
+
+// values 0-7 are secure/non-secure
+#define REBOOT2_FLAG_REBOOT_TYPE_NORMAL 0x0 // param0 = diagnostic partition
+#define REBOOT2_FLAG_REBOOT_TYPE_BOOTSEL 0x2 // param0 = bootsel_flags, param1 = gpio_config
+#define REBOOT2_FLAG_REBOOT_TYPE_RAM_IMAGE 0x3 // param0 = image_base, param1 = image_end
+#define REBOOT2_FLAG_REBOOT_TYPE_FLASH_UPDATE 0x4 // param0 = update_base
+
+#define REBOOT2_FLAG_NO_RETURN_ON_SUCCESS 0x100
+
+#define RT_FLAG_FUNC_ARM_SEC 0x0004
+#define RT_FLAG_FUNC_ARM_NONSEC 0x0010
+
+// https://github.com/raspberrypi/pico-sdk
+// src/rp2_common/pico_bootrom/include/pico/bootrom.h
+
+#define ROM_TABLE_CODE(c1, c2) ((c1) | ((c2) << 8))
+
+typedef void *(*rom_table_lookup_fn)(uint32_t code, uint32_t mask);
+
+__attribute__((always_inline))
+static void *rom_func_lookup_inline(uint32_t code) {
+ rom_table_lookup_fn rom_table_lookup = (rom_table_lookup_fn) (uintptr_t)*(uint16_t*)(BOOTROM_TABLE_LOOKUP_OFFSET);
+ if (pico_processor_state_is_nonsecure()) {
+ return rom_table_lookup(code, RT_FLAG_FUNC_ARM_NONSEC);
+ } else {
+ return rom_table_lookup(code, RT_FLAG_FUNC_ARM_SEC);
+ }
+}
+
+
+typedef int (*rom_reboot_fn)(uint32_t flags, uint32_t delay_ms, uint32_t p0, uint32_t p1);
+
+__attribute__((always_inline))
+int rom_reboot(uint32_t flags, uint32_t delay_ms, uint32_t p0, uint32_t p1) {
+ rom_reboot_fn func = (rom_reboot_fn) rom_func_lookup_inline(ROM_FUNC_REBOOT);
+ return func(flags, delay_ms, p0, p1);
+}
+
+
+// https://github.com/raspberrypi/pico-sdk
+// src/rp2_common/pico_bootrom/bootrom.c
+
+
+void reset_usb_boot(uint32_t usb_activity_gpio_pin_mask, uint32_t disable_interface_mask) {
+ uint32_t flags = disable_interface_mask;
+ if (usb_activity_gpio_pin_mask) {
+ flags |= BOOTSEL_FLAG_GPIO_PIN_SPECIFIED;
+ // the parameter is actually the gpio number, but we only care if BOOTSEL_FLAG_GPIO_PIN_SPECIFIED
+ usb_activity_gpio_pin_mask = (uint32_t)__builtin_ctz(usb_activity_gpio_pin_mask);
+ }
+ rom_reboot(REBOOT2_FLAG_REBOOT_TYPE_BOOTSEL | REBOOT2_FLAG_NO_RETURN_ON_SUCCESS, 10, flags, usb_activity_gpio_pin_mask);
+ __builtin_unreachable();
+}
+
+
+*/
+import "C"
+
+func enterBootloader() {
+ C.reset_usb_boot(0, 0)
+}
diff --git a/src/machine/machine_rp2350_usb.go b/src/machine/machine_rp2350_usb.go
new file mode 100644
index 000000000..9106b50f9
--- /dev/null
+++ b/src/machine/machine_rp2350_usb.go
@@ -0,0 +1,380 @@
+//go:build rp2350
+
+package machine
+
+import (
+ "device/rp"
+ "machine/usb"
+ "runtime/interrupt"
+ "runtime/volatile"
+ "unsafe"
+)
+
+var (
+ sendOnEP0DATADONE struct {
+ offset int
+ data []byte
+ pid uint32
+ }
+)
+
+// Configure the USB peripheral. The config is here for compatibility with the UART interface.
+func (dev *USBDevice) Configure(config UARTConfig) {
+ // Reset usb controller
+ resetBlock(rp.RESETS_RESET_USBCTRL)
+ unresetBlockWait(rp.RESETS_RESET_USBCTRL)
+
+ // Clear any previous state in dpram just in case
+ usbDPSRAM.clear()
+
+ // Enable USB interrupt at processor
+ rp.USB.INTE.Set(0)
+ intr := interrupt.New(rp.IRQ_USBCTRL_IRQ, handleUSBIRQ)
+ intr.SetPriority(0x00)
+ intr.Enable()
+ irqSet(rp.IRQ_USBCTRL_IRQ, true)
+
+ // Mux the controller to the onboard usb phy
+ rp.USB.USB_MUXING.Set(rp.USB_USB_MUXING_TO_PHY | rp.USB_USB_MUXING_SOFTCON)
+
+ // Force VBUS detect so the device thinks it is plugged into a host
+ rp.USB.USB_PWR.Set(rp.USB_USB_PWR_VBUS_DETECT | rp.USB_USB_PWR_VBUS_DETECT_OVERRIDE_EN)
+
+ // Enable the USB controller in device mode.
+ rp.USB.MAIN_CTRL.Set(rp.USB_MAIN_CTRL_CONTROLLER_EN)
+
+ // Enable an interrupt per EP0 transaction
+ rp.USB.SIE_CTRL.Set(rp.USB_SIE_CTRL_EP0_INT_1BUF)
+
+ // Enable interrupts for when a buffer is done, when the bus is reset,
+ // and when a setup packet is received
+ rp.USB.INTE.Set(rp.USB_INTE_BUFF_STATUS |
+ rp.USB_INTE_BUS_RESET |
+ rp.USB_INTE_SETUP_REQ)
+
+ // Present full speed device by enabling pull up on DP
+ rp.USB.SIE_CTRL.SetBits(rp.USB_SIE_CTRL_PULLUP_EN)
+
+ // 12.7.2 Disable phy isolation
+ rp.USB.SetMAIN_CTRL_PHY_ISO(0x0)
+}
+
+func handleUSBIRQ(intr interrupt.Interrupt) {
+ status := rp.USB.INTS.Get()
+
+ // Setup packet received
+ if (status & rp.USB_INTS_SETUP_REQ) > 0 {
+ rp.USB.SIE_STATUS.Set(rp.USB_SIE_STATUS_SETUP_REC)
+ setup := usb.NewSetup(usbDPSRAM.setupBytes())
+
+ ok := false
+ if (setup.BmRequestType & usb.REQUEST_TYPE) == usb.REQUEST_STANDARD {
+ // Standard Requests
+ ok = handleStandardSetup(setup)
+ } else {
+ // Class Interface Requests
+ if setup.WIndex < uint16(len(usbSetupHandler)) && usbSetupHandler[setup.WIndex] != nil {
+ ok = usbSetupHandler[setup.WIndex](setup)
+ }
+ }
+
+ if !ok {
+ // Stall endpoint?
+ sendStallViaEPIn(0)
+ }
+
+ }
+
+ // Buffer status, one or more buffers have completed
+ if (status & rp.USB_INTS_BUFF_STATUS) > 0 {
+ if sendOnEP0DATADONE.offset > 0 {
+ ep := uint32(0)
+ data := sendOnEP0DATADONE.data
+ count := len(data) - sendOnEP0DATADONE.offset
+ if ep == 0 && count > usb.EndpointPacketSize {
+ count = usb.EndpointPacketSize
+ }
+
+ sendViaEPIn(ep, data[sendOnEP0DATADONE.offset:], count)
+ sendOnEP0DATADONE.offset += count
+ if sendOnEP0DATADONE.offset == len(data) {
+ sendOnEP0DATADONE.offset = 0
+ }
+ }
+
+ s2 := rp.USB.BUFF_STATUS.Get()
+
+ // OUT (PC -> rp2040)
+ for i := 0; i < 16; i++ {
+ if s2&(1<<(i*2+1)) > 0 {
+ buf := handleEndpointRx(uint32(i))
+ if usbRxHandler[i] != nil {
+ usbRxHandler[i](buf)
+ }
+ handleEndpointRxComplete(uint32(i))
+ }
+ }
+
+ // IN (rp2040 -> PC)
+ for i := 0; i < 16; i++ {
+ if s2&(1<<(i*2)) > 0 {
+ if usbTxHandler[i] != nil {
+ usbTxHandler[i]()
+ }
+ }
+ }
+
+ rp.USB.BUFF_STATUS.Set(s2)
+ }
+
+ // Bus is reset
+ if (status & rp.USB_INTS_BUS_RESET) > 0 {
+ rp.USB.SIE_STATUS.Set(rp.USB_SIE_STATUS_BUS_RESET)
+ //fixRP2040UsbDeviceEnumeration()
+
+ rp.USB.ADDR_ENDP.Set(0)
+ initEndpoint(0, usb.ENDPOINT_TYPE_CONTROL)
+ }
+}
+
+func initEndpoint(ep, config uint32) {
+ val := uint32(usbEpControlEnable) | uint32(usbEpControlInterruptPerBuff)
+ offset := ep*2*USBBufferLen + 0x100
+ val |= offset
+
+ switch config {
+ case usb.ENDPOINT_TYPE_INTERRUPT | usb.EndpointIn:
+ val |= usbEpControlEndpointTypeInterrupt
+ usbDPSRAM.EPxControl[ep].In.Set(val)
+
+ case usb.ENDPOINT_TYPE_BULK | usb.EndpointOut:
+ val |= usbEpControlEndpointTypeBulk
+ usbDPSRAM.EPxControl[ep].Out.Set(val)
+ usbDPSRAM.EPxBufferControl[ep].Out.Set(USBBufferLen & usbBuf0CtrlLenMask)
+ usbDPSRAM.EPxBufferControl[ep].Out.SetBits(usbBuf0CtrlAvail)
+
+ case usb.ENDPOINT_TYPE_INTERRUPT | usb.EndpointOut:
+ val |= usbEpControlEndpointTypeInterrupt
+ usbDPSRAM.EPxControl[ep].Out.Set(val)
+ usbDPSRAM.EPxBufferControl[ep].Out.Set(USBBufferLen & usbBuf0CtrlLenMask)
+ usbDPSRAM.EPxBufferControl[ep].Out.SetBits(usbBuf0CtrlAvail)
+
+ case usb.ENDPOINT_TYPE_BULK | usb.EndpointIn:
+ val |= usbEpControlEndpointTypeBulk
+ usbDPSRAM.EPxControl[ep].In.Set(val)
+
+ case usb.ENDPOINT_TYPE_CONTROL:
+ val |= usbEpControlEndpointTypeControl
+ usbDPSRAM.EPxBufferControl[ep].Out.Set(usbBuf0CtrlData1Pid)
+ usbDPSRAM.EPxBufferControl[ep].Out.SetBits(usbBuf0CtrlAvail)
+
+ }
+}
+
+func handleUSBSetAddress(setup usb.Setup) bool {
+ sendUSBPacket(0, []byte{}, 0)
+
+ // last, set the device address to that requested by host
+ // wait for transfer to complete
+ timeout := 3000
+ rp.USB.SIE_STATUS.Set(rp.USB_SIE_STATUS_ACK_REC)
+ for (rp.USB.SIE_STATUS.Get() & rp.USB_SIE_STATUS_ACK_REC) == 0 {
+ timeout--
+ if timeout == 0 {
+ return true
+ }
+ }
+
+ rp.USB.ADDR_ENDP.Set(uint32(setup.WValueL) & rp.USB_ADDR_ENDP_ADDRESS_Msk)
+
+ return true
+}
+
+// SendUSBInPacket sends a packet for USB (interrupt in / bulk in).
+func SendUSBInPacket(ep uint32, data []byte) bool {
+ sendUSBPacket(ep, data, 0)
+ return true
+}
+
+//go:noinline
+func sendUSBPacket(ep uint32, data []byte, maxsize uint16) {
+ count := len(data)
+ if 0 < int(maxsize) && int(maxsize) < count {
+ count = int(maxsize)
+ }
+
+ if ep == 0 {
+ if count > usb.EndpointPacketSize {
+ count = usb.EndpointPacketSize
+
+ sendOnEP0DATADONE.offset = count
+ sendOnEP0DATADONE.data = data
+ } else {
+ sendOnEP0DATADONE.offset = 0
+ }
+ epXdata0[ep] = true
+ }
+
+ sendViaEPIn(ep, data, count)
+}
+
+func ReceiveUSBControlPacket() ([cdcLineInfoSize]byte, error) {
+ var b [cdcLineInfoSize]byte
+ ep := 0
+
+ for !usbDPSRAM.EPxBufferControl[ep].Out.HasBits(usbBuf0CtrlFull) {
+ // TODO: timeout
+ }
+
+ ctrl := usbDPSRAM.EPxBufferControl[ep].Out.Get()
+ usbDPSRAM.EPxBufferControl[ep].Out.Set(USBBufferLen & usbBuf0CtrlLenMask)
+ sz := ctrl & usbBuf0CtrlLenMask
+
+ copy(b[:], usbDPSRAM.EPxBuffer[ep].Buffer0[:sz])
+
+ usbDPSRAM.EPxBufferControl[ep].Out.SetBits(usbBuf0CtrlData1Pid)
+ usbDPSRAM.EPxBufferControl[ep].Out.SetBits(usbBuf0CtrlAvail)
+
+ return b, nil
+}
+
+func handleEndpointRx(ep uint32) []byte {
+ ctrl := usbDPSRAM.EPxBufferControl[ep].Out.Get()
+ usbDPSRAM.EPxBufferControl[ep].Out.Set(USBBufferLen & usbBuf0CtrlLenMask)
+ sz := ctrl & usbBuf0CtrlLenMask
+
+ return usbDPSRAM.EPxBuffer[ep].Buffer0[:sz]
+}
+
+func handleEndpointRxComplete(ep uint32) {
+ epXdata0[ep] = !epXdata0[ep]
+ if epXdata0[ep] || ep == 0 {
+ usbDPSRAM.EPxBufferControl[ep].Out.SetBits(usbBuf0CtrlData1Pid)
+ }
+
+ usbDPSRAM.EPxBufferControl[ep].Out.SetBits(usbBuf0CtrlAvail)
+}
+
+func SendZlp() {
+ sendUSBPacket(0, []byte{}, 0)
+}
+
+func sendViaEPIn(ep uint32, data []byte, count int) {
+ // Prepare buffer control register value
+ val := uint32(count) | usbBuf0CtrlAvail
+
+ // DATA0 or DATA1
+ epXdata0[ep&0x7F] = !epXdata0[ep&0x7F]
+ if !epXdata0[ep&0x7F] {
+ val |= usbBuf0CtrlData1Pid
+ }
+
+ // Mark as full
+ val |= usbBuf0CtrlFull
+
+ copy(usbDPSRAM.EPxBuffer[ep&0x7F].Buffer0[:], data[:count])
+ usbDPSRAM.EPxBufferControl[ep&0x7F].In.Set(val)
+}
+
+func sendStallViaEPIn(ep uint32) {
+ // Prepare buffer control register value
+ if ep == 0 {
+ rp.USB.EP_STALL_ARM.Set(rp.USB_EP_STALL_ARM_EP0_IN)
+ }
+ val := uint32(usbBuf0CtrlFull)
+ usbDPSRAM.EPxBufferControl[ep&0x7F].In.Set(val)
+ val |= uint32(usbBuf0CtrlStall)
+ usbDPSRAM.EPxBufferControl[ep&0x7F].In.Set(val)
+}
+
+type USBDPSRAM struct {
+ // Note that EPxControl[0] is not EP0Control but 8-byte setup data.
+ EPxControl [16]USBEndpointControlRegister
+
+ EPxBufferControl [16]USBBufferControlRegister
+
+ EPxBuffer [16]USBBuffer
+}
+
+type USBEndpointControlRegister struct {
+ In volatile.Register32
+ Out volatile.Register32
+}
+type USBBufferControlRegister struct {
+ In volatile.Register32
+ Out volatile.Register32
+}
+
+type USBBuffer struct {
+ Buffer0 [USBBufferLen]byte
+ Buffer1 [USBBufferLen]byte
+}
+
+var (
+ usbDPSRAM = (*USBDPSRAM)(unsafe.Pointer(uintptr(0x50100000)))
+ epXdata0 [16]bool
+ setupBytes [8]byte
+)
+
+func (d *USBDPSRAM) setupBytes() []byte {
+
+ data := d.EPxControl[usb.CONTROL_ENDPOINT].In.Get()
+ setupBytes[0] = byte(data)
+ setupBytes[1] = byte(data >> 8)
+ setupBytes[2] = byte(data >> 16)
+ setupBytes[3] = byte(data >> 24)
+
+ data = d.EPxControl[usb.CONTROL_ENDPOINT].Out.Get()
+ setupBytes[4] = byte(data)
+ setupBytes[5] = byte(data >> 8)
+ setupBytes[6] = byte(data >> 16)
+ setupBytes[7] = byte(data >> 24)
+
+ return setupBytes[:]
+}
+
+func (d *USBDPSRAM) clear() {
+ for i := 0; i < len(d.EPxControl); i++ {
+ d.EPxControl[i].In.Set(0)
+ d.EPxControl[i].Out.Set(0)
+ d.EPxBufferControl[i].In.Set(0)
+ d.EPxBufferControl[i].Out.Set(0)
+ }
+}
+
+const (
+ // DPRAM : Endpoint control register
+ usbEpControlEnable = 0x80000000
+ usbEpControlDoubleBuffered = 0x40000000
+ usbEpControlInterruptPerBuff = 0x20000000
+ usbEpControlInterruptPerDoubleBuff = 0x10000000
+ usbEpControlEndpointType = 0x0c000000
+ usbEpControlInterruptOnStall = 0x00020000
+ usbEpControlInterruptOnNak = 0x00010000
+ usbEpControlBufferAddress = 0x0000ffff
+
+ usbEpControlEndpointTypeControl = 0x00000000
+ usbEpControlEndpointTypeISO = 0x04000000
+ usbEpControlEndpointTypeBulk = 0x08000000
+ usbEpControlEndpointTypeInterrupt = 0x0c000000
+
+ // Endpoint buffer control bits
+ usbBuf1CtrlFull = 0x80000000
+ usbBuf1CtrlLast = 0x40000000
+ usbBuf1CtrlData0Pid = 0x20000000
+ usbBuf1CtrlData1Pid = 0x00000000
+ usbBuf1CtrlSel = 0x10000000
+ usbBuf1CtrlStall = 0x08000000
+ usbBuf1CtrlAvail = 0x04000000
+ usbBuf1CtrlLenMask = 0x03FF0000
+ usbBuf0CtrlFull = 0x00008000
+ usbBuf0CtrlLast = 0x00004000
+ usbBuf0CtrlData0Pid = 0x00000000
+ usbBuf0CtrlData1Pid = 0x00002000
+ usbBuf0CtrlSel = 0x00001000
+ usbBuf0CtrlStall = 0x00000800
+ usbBuf0CtrlAvail = 0x00000400
+ usbBuf0CtrlLenMask = 0x000003FF
+
+ USBBufferLen = 64
+)
diff --git a/src/machine/machine_rp2_2040.go b/src/machine/machine_rp2_2040.go
new file mode 100644
index 000000000..c82b08483
--- /dev/null
+++ b/src/machine/machine_rp2_2040.go
@@ -0,0 +1,199 @@
+//go:build rp2040
+
+package machine
+
+import (
+ "device/rp"
+ "runtime/volatile"
+ "unsafe"
+)
+
+const (
+ _NUMBANK0_GPIOS = 30
+ _NUMBANK0_IRQS = 4
+ _NUMIRQ = 32
+ rp2350ExtraReg = 0
+ RESETS_RESET_Msk = 0x01ffffff
+ initUnreset = rp.RESETS_RESET_ADC |
+ rp.RESETS_RESET_RTC |
+ rp.RESETS_RESET_SPI0 |
+ rp.RESETS_RESET_SPI1 |
+ rp.RESETS_RESET_UART0 |
+ rp.RESETS_RESET_UART1 |
+ rp.RESETS_RESET_USBCTRL
+ initDontReset = rp.RESETS_RESET_IO_QSPI |
+ rp.RESETS_RESET_PADS_QSPI |
+ rp.RESETS_RESET_PLL_USB |
+ rp.RESETS_RESET_USBCTRL |
+ rp.RESETS_RESET_SYSCFG |
+ rp.RESETS_RESET_PLL_SYS
+ padEnableMask = rp.PADS_BANK0_GPIO0_IE_Msk |
+ rp.PADS_BANK0_GPIO0_OD_Msk
+)
+
+const (
+ PinOutput PinMode = iota
+ PinInput
+ PinInputPulldown
+ PinInputPullup
+ PinAnalog
+ PinUART
+ PinPWM
+ PinI2C
+ PinSPI
+ PinPIO0
+ PinPIO1
+)
+
+const (
+ ClkGPOUT0 clockIndex = iota // GPIO Muxing 0
+ ClkGPOUT1 // GPIO Muxing 1
+ ClkGPOUT2 // GPIO Muxing 2
+ ClkGPOUT3 // GPIO Muxing 3
+ ClkRef // Watchdog and timers reference clock
+ ClkSys // Processors, bus fabric, memory, memory mapped registers
+ ClkPeri // Peripheral clock for UART and SPI
+ ClkUSB // USB clock
+ ClkADC // ADC clock
+ ClkRTC // Real time clock
+ NumClocks
+)
+
+func CalcClockDiv(srcFreq, freq uint32) uint32 {
+ // Div register is 24.8 int.frac divider so multiply by 2^8 (left shift by 8)
+ return uint32((uint64(srcFreq) << 8) / uint64(freq))
+}
+
+type clocksType struct {
+ clk [NumClocks]clockType
+ resus struct {
+ ctrl volatile.Register32
+ status volatile.Register32
+ }
+ fc0 fc
+ wakeEN0 volatile.Register32
+ wakeEN1 volatile.Register32
+ sleepEN0 volatile.Register32
+ sleepEN1 volatile.Register32
+ enabled0 volatile.Register32
+ enabled1 volatile.Register32
+ intR volatile.Register32
+ intE volatile.Register32
+ intF volatile.Register32
+ intS volatile.Register32
+}
+
+// GPIO function selectors
+const (
+ fnJTAG pinFunc = 0
+ fnSPI pinFunc = 1 // Connect one of the internal PL022 SPI peripherals to GPIO
+ fnUART pinFunc = 2
+ fnI2C pinFunc = 3
+ // Connect a PWM slice to GPIO. There are eight PWM slices,
+ // each with two outputchannels (A/B). The B pin can also be used as an input,
+ // for frequency and duty cyclemeasurement
+ fnPWM pinFunc = 4
+ // Software control of GPIO, from the single-cycle IO (SIO) block.
+ // The SIO function (F5)must be selected for the processors to drive a GPIO,
+ // but the input is always connected,so software can check the state of GPIOs at any time.
+ fnSIO pinFunc = 5
+ // Connect one of the programmable IO blocks (PIO) to GPIO. PIO can implement a widevariety of interfaces,
+ // and has its own internal pin mapping hardware, allowing flexibleplacement of digital interfaces on bank 0 GPIOs.
+ // The PIO function (F6, F7) must beselected for PIO to drive a GPIO, but the input is always connected,
+ // so the PIOs canalways see the state of all pins.
+ fnPIO0, fnPIO1 pinFunc = 6, 7
+ // General purpose clock inputs/outputs. Can be routed to a number of internal clock domains onRP2040,
+ // e.g. Input: to provide a 1 Hz clock for the RTC, or can be connected to an internalfrequency counter.
+ // e.g. Output: optional integer divide
+ fnGPCK pinFunc = 8
+ // USB power control signals to/from the internal USB controller
+ fnUSB pinFunc = 9
+ fnNULL pinFunc = 0x1f
+
+ fnXIP pinFunc = 0
+)
+
+// Configure configures the gpio pin as per mode.
+func (p Pin) Configure(config PinConfig) {
+ if p == NoPin {
+ return
+ }
+ p.init()
+ mask := uint32(1) << p
+ switch config.Mode {
+ case PinOutput:
+ p.setFunc(fnSIO)
+ rp.SIO.GPIO_OE_SET.Set(mask)
+ case PinInput:
+ p.setFunc(fnSIO)
+ p.pulloff()
+ case PinInputPulldown:
+ p.setFunc(fnSIO)
+ p.pulldown()
+ case PinInputPullup:
+ p.setFunc(fnSIO)
+ p.pullup()
+ case PinAnalog:
+ p.setFunc(fnNULL)
+ p.pulloff()
+ case PinUART:
+ p.setFunc(fnUART)
+ case PinPWM:
+ p.setFunc(fnPWM)
+ case PinI2C:
+ // IO config according to 4.3.1.3 of rp2040 datasheet.
+ p.setFunc(fnI2C)
+ p.pullup()
+ p.setSchmitt(true)
+ p.setSlew(false)
+ case PinSPI:
+ p.setFunc(fnSPI)
+ case PinPIO0:
+ p.setFunc(fnPIO0)
+ case PinPIO1:
+ p.setFunc(fnPIO1)
+ }
+}
+
+var (
+ timer = (*timerType)(unsafe.Pointer(rp.TIMER))
+)
+
+// Enable or disable a specific interrupt on the executing core.
+// num is the interrupt number which must be in [0,31].
+func irqSet(num uint32, enabled bool) {
+ if num >= _NUMIRQ {
+ return
+ }
+ irqSetMask(1<<num, enabled)
+}
+
+func irqSetMask(mask uint32, enabled bool) {
+ if enabled {
+ // Clear pending before enable
+ // (if IRQ is actually asserted, it will immediately re-pend)
+ rp.PPB.NVIC_ICPR.Set(mask)
+ rp.PPB.NVIC_ISER.Set(mask)
+ } else {
+ rp.PPB.NVIC_ICER.Set(mask)
+ }
+}
+
+func (clks *clocksType) initRTC() {
+ // ClkRTC = pllUSB (48MHz) / 1024 = 46875Hz
+ clkrtc := clks.clock(ClkRTC)
+ clkrtc.configure(0, // No GLMUX
+ rp.CLOCKS_CLK_RTC_CTRL_AUXSRC_CLKSRC_PLL_USB,
+ 48*MHz,
+ 46875)
+}
+
+func (clks *clocksType) initTicks() {} // No ticks on RP2040
+
+// startTick starts the watchdog tick.
+// cycles needs to be a divider that when applied to the xosc input,
+// produces a 1MHz clock. So if the xosc frequency is 12MHz,
+// this will need to be 12.
+func (wd *watchdogImpl) startTick(cycles uint32) {
+ rp.WATCHDOG.TICK.Set(cycles | rp.WATCHDOG_TICK_ENABLE)
+}
diff --git a/src/machine/machine_rp2_2350.go b/src/machine/machine_rp2_2350.go
new file mode 100644
index 000000000..54fc62b47
--- /dev/null
+++ b/src/machine/machine_rp2_2350.go
@@ -0,0 +1,217 @@
+//go:build rp2350
+
+package machine
+
+import (
+ "device/rp"
+ "runtime/volatile"
+ "unsafe"
+)
+
+const (
+ _NUMBANK0_GPIOS = 48
+ _NUMBANK0_IRQS = 6
+ rp2350ExtraReg = 1
+ _NUMIRQ = 51
+ notimpl = "rp2350: not implemented"
+ RESETS_RESET_Msk = 0x1fffffff
+ initUnreset = rp.RESETS_RESET_ADC |
+ rp.RESETS_RESET_SPI0 |
+ rp.RESETS_RESET_SPI1 |
+ rp.RESETS_RESET_UART0 |
+ rp.RESETS_RESET_UART1 |
+ rp.RESETS_RESET_USBCTRL
+ initDontReset = rp.RESETS_RESET_USBCTRL |
+ rp.RESETS_RESET_SYSCFG |
+ rp.RESETS_RESET_PLL_USB |
+ rp.RESETS_RESET_PLL_SYS |
+ rp.RESETS_RESET_PADS_QSPI |
+ rp.RESETS_RESET_IO_QSPI |
+ rp.RESETS_RESET_JTAG
+ padEnableMask = rp.PADS_BANK0_GPIO0_IE_Msk |
+ rp.PADS_BANK0_GPIO0_OD_Msk |
+ rp.PADS_BANK0_GPIO0_ISO_Msk
+)
+
+const (
+ PinOutput PinMode = iota
+ PinInput
+ PinInputPulldown
+ PinInputPullup
+ PinAnalog
+ PinUART
+ PinPWM
+ PinI2C
+ PinSPI
+ PinPIO0
+ PinPIO1
+ PinPIO2
+)
+
+const (
+ ClkGPOUT0 clockIndex = iota // GPIO Muxing 0
+ ClkGPOUT1 // GPIO Muxing 1
+ ClkGPOUT2 // GPIO Muxing 2
+ ClkGPOUT3 // GPIO Muxing 3
+ ClkRef // Watchdog and timers reference clock
+ ClkSys // Processors, bus fabric, memory, memory mapped registers
+ ClkPeri // Peripheral clock for UART and SPI
+ ClkHSTX // High speed interface
+ ClkUSB // USB clock
+ ClkADC // ADC clock
+ NumClocks
+)
+
+func CalcClockDiv(srcFreq, freq uint32) uint32 {
+ // Div register is 4.16 int.frac divider so multiply by 2^16 (left shift by 16)
+ return uint32((uint64(srcFreq) << 16) / uint64(freq))
+}
+
+type clocksType struct {
+ clk [NumClocks]clockType
+ dftclk_xosc_ctrl volatile.Register32
+ dftclk_rosc_ctrl volatile.Register32
+ dftclk_lposc_ctrl volatile.Register32
+ resus struct {
+ ctrl volatile.Register32
+ status volatile.Register32
+ }
+ fc0 fc
+ wakeEN0 volatile.Register32
+ wakeEN1 volatile.Register32
+ sleepEN0 volatile.Register32
+ sleepEN1 volatile.Register32
+ enabled0 volatile.Register32
+ enabled1 volatile.Register32
+ intR volatile.Register32
+ intE volatile.Register32
+ intF volatile.Register32
+ intS volatile.Register32
+}
+
+// GPIO function selectors
+const (
+ // Connect the high-speed transmit peripheral (HSTX) to GPIO.
+ fnHSTX pinFunc = 0
+ fnSPI pinFunc = 1 // Connect one of the internal PL022 SPI peripherals to GPIO
+ fnUART pinFunc = 2
+ fnI2C pinFunc = 3
+ // Connect a PWM slice to GPIO. There are eight PWM slices,
+ // each with two outputchannels (A/B). The B pin can also be used as an input,
+ // for frequency and duty cyclemeasurement
+ fnPWM pinFunc = 4
+ // Software control of GPIO, from the single-cycle IO (SIO) block.
+ // The SIO function (F5)must be selected for the processors to drive a GPIO,
+ // but the input is always connected,so software can check the state of GPIOs at any time.
+ fnSIO pinFunc = 5
+ // Connect one of the programmable IO blocks (PIO) to GPIO. PIO can implement a widevariety of interfaces,
+ // and has its own internal pin mapping hardware, allowing flexibleplacement of digital interfaces on bank 0 GPIOs.
+ // The PIO function (F6, F7, F8) must beselected for PIO to drive a GPIO, but the input is always connected,
+ // so the PIOs canalways see the state of all pins.
+ fnPIO0, fnPIO1, fnPIO2 pinFunc = 6, 7, 8
+ // General purpose clock outputs. Can drive a number of internal clocks (including PLL
+ // outputs) onto GPIOs, with optional integer divide.
+ fnGPCK pinFunc = 9
+ // QSPI memory interface peripheral, used for execute-in-place from external QSPI flash or PSRAM memory devices.
+ fnQMI pinFunc = 9
+ // USB power control signals to/from the internal USB controller.
+ fnUSB pinFunc = 10
+ fnUARTAlt pinFunc = 11
+ fnNULL pinFunc = 0x1f
+)
+
+// Configure configures the gpio pin as per mode.
+func (p Pin) Configure(config PinConfig) {
+ if p == NoPin {
+ return
+ }
+ p.init()
+ mask := uint32(1) << p
+ switch config.Mode {
+ case PinOutput:
+ p.setFunc(fnSIO)
+ rp.SIO.GPIO_OE_SET.Set(mask)
+ case PinInput:
+ p.setFunc(fnSIO)
+ p.pulloff()
+ case PinInputPulldown:
+ p.setFunc(fnSIO)
+ p.pulldown()
+ case PinInputPullup:
+ p.setFunc(fnSIO)
+ p.pullup()
+ case PinAnalog:
+ p.setFunc(fnNULL)
+ p.pulloff()
+ case PinUART:
+ p.setFunc(fnUART)
+ case PinPWM:
+ p.setFunc(fnPWM)
+ case PinI2C:
+ // IO config according to 4.3.1.3 of rp2040 datasheet.
+ p.setFunc(fnI2C)
+ p.pullup()
+ p.setSchmitt(true)
+ p.setSlew(false)
+ case PinSPI:
+ p.setFunc(fnSPI)
+ case PinPIO0:
+ p.setFunc(fnPIO0)
+ case PinPIO1:
+ p.setFunc(fnPIO1)
+ case PinPIO2:
+ p.setFunc(fnPIO2)
+ }
+}
+
+var (
+ timer = (*timerType)(unsafe.Pointer(rp.TIMER0))
+)
+
+// Enable or disable a specific interrupt on the executing core.
+// num is the interrupt number which must be in [0,_NUMIRQ).
+func irqSet(num uint32, enabled bool) {
+ if num >= _NUMIRQ {
+ return
+ }
+
+ register_index := num / 32
+ var mask uint32 = 1 << (num % 32)
+
+ if enabled {
+ // Clear pending before enable
+ //(if IRQ is actually asserted, it will immediately re-pend)
+ if register_index == 0 {
+ rp.PPB.NVIC_ICPR0.Set(mask)
+ rp.PPB.NVIC_ISER0.Set(mask)
+ } else {
+ rp.PPB.NVIC_ICPR1.Set(mask)
+ rp.PPB.NVIC_ISER1.Set(mask)
+ }
+ } else {
+ if register_index == 0 {
+ rp.PPB.NVIC_ICER0.Set(mask)
+ } else {
+ rp.PPB.NVIC_ICER1.Set(mask)
+ }
+ }
+}
+
+func (clks *clocksType) initRTC() {} // No RTC on RP2350.
+
+func (clks *clocksType) initTicks() {
+ rp.TICKS.SetTIMER0_CTRL_ENABLE(0)
+ rp.TICKS.SetTIMER0_CYCLES(12)
+ rp.TICKS.SetTIMER0_CTRL_ENABLE(1)
+}
+
+func EnterBootloader() {
+ enterBootloader()
+}
+
+// startTick starts the watchdog tick.
+// On RP2040, the watchdog contained a tick generator used to generate a 1μs tick for the watchdog. This was also
+// distributed to the system timer. On RP2350, the watchdog instead takes a tick input from the system-level ticks block. See Section 8.5.
+func (wd *watchdogImpl) startTick(cycles uint32) {
+ rp.TICKS.WATCHDOG_CTRL.SetBits(1)
+}
diff --git a/src/machine/machine_rp2040_adc.go b/src/machine/machine_rp2_adc.go
index 1f05684eb..13504d719 100644
--- a/src/machine/machine_rp2040_adc.go
+++ b/src/machine/machine_rp2_adc.go
@@ -1,4 +1,4 @@
-//go:build rp2040
+//go:build rp2040 || rp2350
package machine
diff --git a/src/machine/machine_rp2040_clocks.go b/src/machine/machine_rp2_clocks.go
index 57dfa68b0..ad2c6517f 100644
--- a/src/machine/machine_rp2040_clocks.go
+++ b/src/machine/machine_rp2_clocks.go
@@ -1,4 +1,4 @@
-//go:build rp2040
+//go:build rp2040 || rp2350
package machine
@@ -22,20 +22,6 @@ func cpuPeriod() uint32 {
// clockIndex identifies a hardware clock
type clockIndex uint8
-const (
- clkGPOUT0 clockIndex = iota // GPIO Muxing 0
- clkGPOUT1 // GPIO Muxing 1
- clkGPOUT2 // GPIO Muxing 2
- clkGPOUT3 // GPIO Muxing 3
- clkRef // Watchdog and timers reference clock
- clkSys // Processors, bus fabric, memory, memory mapped registers
- clkPeri // Peripheral clock for UART and SPI
- clkUSB // USB clock
- clkADC // ADC clock
- clkRTC // Real time clock
- numClocks
-)
-
type clockType struct {
ctrl volatile.Register32
div volatile.Register32
@@ -53,28 +39,9 @@ type fc struct {
result volatile.Register32
}
-type clocksType struct {
- clk [numClocks]clockType
- resus struct {
- ctrl volatile.Register32
- status volatile.Register32
- }
- fc0 fc
- wakeEN0 volatile.Register32
- wakeEN1 volatile.Register32
- sleepEN0 volatile.Register32
- sleepEN1 volatile.Register32
- enabled0 volatile.Register32
- enabled1 volatile.Register32
- intR volatile.Register32
- intE volatile.Register32
- intF volatile.Register32
- intS volatile.Register32
-}
-
var clocks = (*clocksType)(unsafe.Pointer(rp.CLOCKS))
-var configuredFreq [numClocks]uint32
+var configuredFreq [NumClocks]uint32
type clock struct {
*clockType
@@ -101,7 +68,7 @@ func (clks *clocksType) clock(cix clockIndex) clock {
//
// Not all clocks have both types of mux.
func (clk *clock) hasGlitchlessMux() bool {
- return clk.cix == clkSys || clk.cix == clkRef
+ return clk.cix == ClkSys || clk.cix == ClkRef
}
// configure configures the clock by selecting the main clock source src
@@ -113,8 +80,7 @@ func (clk *clock) configure(src, auxsrc, srcFreq, freq uint32) {
panic("clock frequency cannot be greater than source frequency")
}
- // Div register is 24.8 int.frac divider so multiply by 2^8 (left shift by 8)
- div := uint32((uint64(srcFreq) << 8) / uint64(freq))
+ div := CalcClockDiv(srcFreq, freq)
// If increasing divisor, set divisor before source. Otherwise set source
// before divisor. This avoids a momentary overspeed when e.g. switching
@@ -133,16 +99,16 @@ func (clk *clock) configure(src, auxsrc, srcFreq, freq uint32) {
} else
// If no glitchless mux, cleanly stop the clock to avoid glitches
// propagating when changing aux mux. Note it would be a really bad idea
- // to do this on one of the glitchless clocks (clkSys, clkRef).
+ // to do this on one of the glitchless clocks (ClkSys, ClkRef).
{
- // Disable clock. On clkRef and clkSys this does nothing,
+ // Disable clock. On ClkRef and ClkSys this does nothing,
// all other clocks have the ENABLE bit in the same position.
clk.ctrl.ClearBits(rp.CLOCKS_CLK_GPOUT0_CTRL_ENABLE_Msk)
if configuredFreq[clk.cix] > 0 {
// Delay for 3 cycles of the target clock, for ENABLE propagation.
// Note XOSC_COUNT is not helpful here because XOSC is not
// necessarily running, nor is timer... so, 3 cycles per loop:
- delayCyc := configuredFreq[clkSys]/configuredFreq[clk.cix] + 1
+ delayCyc := configuredFreq[ClkSys]/configuredFreq[clk.cix] + 1
for delayCyc != 0 {
// This could be done more efficiently but TinyGo inline
// assembly is not yet capable enough to express that. In the
@@ -164,7 +130,7 @@ func (clk *clock) configure(src, auxsrc, srcFreq, freq uint32) {
}
}
- // Enable clock. On clkRef and clkSys this does nothing,
+ // Enable clock. On ClkRef and ClkSys this does nothing,
// all other clocks have the ENABLE bit in the same position.
clk.ctrl.SetBits(rp.CLOCKS_CLK_GPOUT0_CTRL_ENABLE)
@@ -185,18 +151,18 @@ func (clks *clocksType) init() {
Watchdog.startTick(xoscFreq)
// Disable resus that may be enabled from previous software
- clks.resus.ctrl.Set(0)
+ rp.CLOCKS.SetCLK_SYS_RESUS_CTRL_CLEAR(0)
// Enable the xosc
xosc.init()
// Before we touch PLLs, switch sys and ref cleanly away from their aux sources.
- clks.clk[clkSys].ctrl.ClearBits(rp.CLOCKS_CLK_SYS_CTRL_SRC_Msk)
- for !clks.clk[clkSys].selected.HasBits(0x1) {
+ clks.clk[ClkSys].ctrl.ClearBits(rp.CLOCKS_CLK_SYS_CTRL_SRC_Msk)
+ for !clks.clk[ClkSys].selected.HasBits(0x1) {
}
- clks.clk[clkRef].ctrl.ClearBits(rp.CLOCKS_CLK_REF_CTRL_SRC_Msk)
- for !clks.clk[clkRef].selected.HasBits(0x1) {
+ clks.clk[ClkRef].ctrl.ClearBits(rp.CLOCKS_CLK_REF_CTRL_SRC_Msk)
+ for !clks.clk[ClkRef].selected.HasBits(0x1) {
}
// Configure PLLs
@@ -207,47 +173,44 @@ func (clks *clocksType) init() {
pllUSB.init(1, 480*MHz, 5, 2)
// Configure clocks
- // clkRef = xosc (12MHz) / 1 = 12MHz
- clkref := clks.clock(clkRef)
+ // ClkRef = xosc (12MHz) / 1 = 12MHz
+ clkref := clks.clock(ClkRef)
clkref.configure(rp.CLOCKS_CLK_REF_CTRL_SRC_XOSC_CLKSRC,
0, // No aux mux
12*MHz,
12*MHz)
- // clkSys = pllSys (125MHz) / 1 = 125MHz
- clksys := clks.clock(clkSys)
+ // ClkSys = pllSys (125MHz) / 1 = 125MHz
+ clksys := clks.clock(ClkSys)
clksys.configure(rp.CLOCKS_CLK_SYS_CTRL_SRC_CLKSRC_CLK_SYS_AUX,
rp.CLOCKS_CLK_SYS_CTRL_AUXSRC_CLKSRC_PLL_SYS,
125*MHz,
125*MHz)
- // clkUSB = pllUSB (48MHz) / 1 = 48MHz
- clkusb := clks.clock(clkUSB)
+ // ClkUSB = pllUSB (48MHz) / 1 = 48MHz
+ clkusb := clks.clock(ClkUSB)
clkusb.configure(0, // No GLMUX
rp.CLOCKS_CLK_USB_CTRL_AUXSRC_CLKSRC_PLL_USB,
48*MHz,
48*MHz)
- // clkADC = pllUSB (48MHZ) / 1 = 48MHz
- clkadc := clks.clock(clkADC)
+ // ClkADC = pllUSB (48MHZ) / 1 = 48MHz
+ clkadc := clks.clock(ClkADC)
clkadc.configure(0, // No GLMUX
rp.CLOCKS_CLK_ADC_CTRL_AUXSRC_CLKSRC_PLL_USB,
48*MHz,
48*MHz)
- // clkRTC = pllUSB (48MHz) / 1024 = 46875Hz
- clkrtc := clks.clock(clkRTC)
- clkrtc.configure(0, // No GLMUX
- rp.CLOCKS_CLK_RTC_CTRL_AUXSRC_CLKSRC_PLL_USB,
- 48*MHz,
- 46875)
+ clks.initRTC()
- // clkPeri = clkSys. Used as reference clock for Peripherals.
+ // ClkPeri = ClkSys. Used as reference clock for Peripherals.
// No dividers so just select and enable.
- // Normally choose clkSys or clkUSB.
- clkperi := clks.clock(clkPeri)
+ // Normally choose ClkSys or ClkUSB.
+ clkperi := clks.clock(ClkPeri)
clkperi.configure(0,
rp.CLOCKS_CLK_PERI_CTRL_AUXSRC_CLK_SYS,
125*MHz,
125*MHz)
+
+ clks.initTicks()
}
diff --git a/src/machine/machine_rp2040_gpio.go b/src/machine/machine_rp2_gpio.go
index 89c5f40b1..d49d12f2b 100644
--- a/src/machine/machine_rp2040_gpio.go
+++ b/src/machine/machine_rp2_gpio.go
@@ -1,4 +1,4 @@
-//go:build rp2040
+//go:build rp2040 || rp2350
package machine
@@ -15,14 +15,26 @@ type ioType struct {
}
type irqCtrl struct {
- intE [4]volatile.Register32
- intF [4]volatile.Register32
- intS [4]volatile.Register32
+ intE [_NUMBANK0_IRQS]volatile.Register32
+ intF [_NUMBANK0_IRQS]volatile.Register32
+ intS [_NUMBANK0_IRQS]volatile.Register32
+}
+
+type irqSummary struct {
+ proc [2]struct {
+ secure [2]volatile.Register32
+ nonsecure [2]volatile.Register32
+ }
+ comaWake struct {
+ secure [2]volatile.Register32
+ nonsecure [2]volatile.Register32
+ }
}
type ioBank0Type struct {
- io [30]ioType
- intR [4]volatile.Register32
+ io [_NUMBANK0_GPIOS]ioType
+ irqsum [rp2350ExtraReg]irqSummary
+ intR [_NUMBANK0_IRQS]volatile.Register32
proc0IRQctrl irqCtrl
proc1IRQctrl irqCtrl
dormantWakeIRQctrl irqCtrl
@@ -32,7 +44,7 @@ var ioBank0 = (*ioBank0Type)(unsafe.Pointer(rp.IO_BANK0))
type padsBank0Type struct {
voltageSelect volatile.Register32
- io [30]volatile.Register32
+ io [_NUMBANK0_GPIOS]volatile.Register32
}
var padsBank0 = (*padsBank0Type)(unsafe.Pointer(rp.PADS_BANK0))
@@ -45,50 +57,6 @@ var padsBank0 = (*padsBank0Type)(unsafe.Pointer(rp.PADS_BANK0))
// the peripheral sees the logical OR of these GPIO inputs.
type pinFunc uint8
-// GPIO function selectors
-const (
- fnJTAG pinFunc = 0
- fnSPI pinFunc = 1 // Connect one of the internal PL022 SPI peripherals to GPIO
- fnUART pinFunc = 2
- fnI2C pinFunc = 3
- // Connect a PWM slice to GPIO. There are eight PWM slices,
- // each with two outputchannels (A/B). The B pin can also be used as an input,
- // for frequency and duty cyclemeasurement
- fnPWM pinFunc = 4
- // Software control of GPIO, from the single-cycle IO (SIO) block.
- // The SIO function (F5)must be selected for the processors to drive a GPIO,
- // but the input is always connected,so software can check the state of GPIOs at any time.
- fnSIO pinFunc = 5
- // Connect one of the programmable IO blocks (PIO) to GPIO. PIO can implement a widevariety of interfaces,
- // and has its own internal pin mapping hardware, allowing flexibleplacement of digital interfaces on bank 0 GPIOs.
- // The PIO function (F6, F7) must beselected for PIO to drive a GPIO, but the input is always connected,
- // so the PIOs canalways see the state of all pins.
- fnPIO0, fnPIO1 pinFunc = 6, 7
- // General purpose clock inputs/outputs. Can be routed to a number of internal clock domains onRP2040,
- // e.g. Input: to provide a 1 Hz clock for the RTC, or can be connected to an internalfrequency counter.
- // e.g. Output: optional integer divide
- fnGPCK pinFunc = 8
- // USB power control signals to/from the internal USB controller
- fnUSB pinFunc = 9
- fnNULL pinFunc = 0x1f
-
- fnXIP pinFunc = 0
-)
-
-const (
- PinOutput PinMode = iota
- PinInput
- PinInputPulldown
- PinInputPullup
- PinAnalog
- PinUART
- PinPWM
- PinI2C
- PinSPI
- PinPIO0
- PinPIO1
-)
-
func (p Pin) PortMaskSet() (*uint32, uint32) {
return (*uint32)(unsafe.Pointer(&rp.SIO.GPIO_OUT_SET)), 1 << p
}
@@ -157,8 +125,7 @@ func (p Pin) setSchmitt(trigger bool) {
// setFunc will set pin function to fn.
func (p Pin) setFunc(fn pinFunc) {
// Set input enable, Clear output disable
- p.padCtrl().ReplaceBits(rp.PADS_BANK0_GPIO0_IE,
- rp.PADS_BANK0_GPIO0_IE_Msk|rp.PADS_BANK0_GPIO0_OD_Msk, 0)
+ p.padCtrl().ReplaceBits(rp.PADS_BANK0_GPIO0_IE, padEnableMask, 0)
// Zero all fields apart from fsel; we want this IO to do what the peripheral tells it.
// This doesn't affect e.g. pullup/pulldown, as these are in pad controls.
@@ -172,48 +139,6 @@ func (p Pin) init() {
p.clr()
}
-// Configure configures the gpio pin as per mode.
-func (p Pin) Configure(config PinConfig) {
- if p == NoPin {
- return
- }
- p.init()
- mask := uint32(1) << p
- switch config.Mode {
- case PinOutput:
- p.setFunc(fnSIO)
- rp.SIO.GPIO_OE_SET.Set(mask)
- case PinInput:
- p.setFunc(fnSIO)
- p.pulloff()
- case PinInputPulldown:
- p.setFunc(fnSIO)
- p.pulldown()
- case PinInputPullup:
- p.setFunc(fnSIO)
- p.pullup()
- case PinAnalog:
- p.setFunc(fnNULL)
- p.pulloff()
- case PinUART:
- p.setFunc(fnUART)
- case PinPWM:
- p.setFunc(fnPWM)
- case PinI2C:
- // IO config according to 4.3.1.3 of rp2040 datasheet.
- p.setFunc(fnI2C)
- p.pullup()
- p.setSchmitt(true)
- p.setSlew(false)
- case PinSPI:
- p.setFunc(fnSPI)
- case PinPIO0:
- p.setFunc(fnPIO0)
- case PinPIO1:
- p.setFunc(fnPIO1)
- }
-}
-
// Set drives the pin high if value is true else drives it low.
func (p Pin) Set(value bool) {
if p == NoPin {
@@ -331,23 +256,3 @@ func (p Pin) ioIntBit(change PinChange) uint32 {
func getIntChange(p Pin, status uint32) PinChange {
return PinChange(status>>(4*(p%8))) & 0xf
}
-
-// UART on the RP2040
-var (
- UART0 = &_UART0
- _UART0 = UART{
- Buffer: NewRingBuffer(),
- Bus: rp.UART0,
- }
-
- UART1 = &_UART1
- _UART1 = UART{
- Buffer: NewRingBuffer(),
- Bus: rp.UART1,
- }
-)
-
-func init() {
- UART0.Interrupt = interrupt.New(rp.IRQ_UART0_IRQ, _UART0.handleInterrupt)
- UART1.Interrupt = interrupt.New(rp.IRQ_UART1_IRQ, _UART1.handleInterrupt)
-}
diff --git a/src/machine/machine_rp2040_pins.go b/src/machine/machine_rp2_pins.go
index 9abbdb002..93f2d50a0 100644
--- a/src/machine/machine_rp2040_pins.go
+++ b/src/machine/machine_rp2_pins.go
@@ -1,4 +1,4 @@
-//go:build rp2040 || ae_rp2040 || badger2040 || challenger_rp2040 || feather_rp2040 || gopher_badge || kb2040 || macropad_rp2040 || nano_rp2040 || pico || qtpy_rp2040 || thingplus_rp2040 || thumby || tufty2040 || waveshare_rp2040_zero || xiao_rp2040
+//go:build rp2040 || rp2350 || ae_rp2040 || badger2040 || challenger_rp2040 || feather_rp2040 || gopher_badge || kb2040 || macropad_rp2040 || nano_rp2040 || pico || qtpy_rp2040 || thingplus_rp2040 || thumby || tufty2040 || waveshare_rp2040_zero || xiao_rp2040
package machine
diff --git a/src/machine/machine_rp2040_pll.go b/src/machine/machine_rp2_pll.go
index d611f2924..f409768ab 100644
--- a/src/machine/machine_rp2040_pll.go
+++ b/src/machine/machine_rp2_pll.go
@@ -1,4 +1,4 @@
-//go:build rp2040
+//go:build rp2040 || rp2350
package machine
diff --git a/src/machine/machine_rp2040_resets.go b/src/machine/machine_rp2_resets.go
index 6f15e9952..245436c47 100644
--- a/src/machine/machine_rp2040_resets.go
+++ b/src/machine/machine_rp2_resets.go
@@ -1,36 +1,24 @@
-//go:build rp2040
+//go:build rp2040 || rp2350
package machine
import (
"device/rp"
- "runtime/volatile"
"unsafe"
)
-// RESETS_RESET_Msk is bitmask to reset all peripherals
-//
-// TODO: This field is not available in the device file.
-const RESETS_RESET_Msk = 0x01ffffff
-
-type resetsType struct {
- reset volatile.Register32
- wdSel volatile.Register32
- resetDone volatile.Register32
-}
-
-var resets = (*resetsType)(unsafe.Pointer(rp.RESETS))
+var resets = (*rp.RESETS_Type)(unsafe.Pointer(rp.RESETS))
// resetBlock resets hardware blocks specified
// by the bit pattern in bits.
func resetBlock(bits uint32) {
- resets.reset.SetBits(bits)
+ resets.RESET.SetBits(bits)
}
// unresetBlock brings hardware blocks specified by the
// bit pattern in bits out of reset.
func unresetBlock(bits uint32) {
- resets.reset.ClearBits(bits)
+ resets.RESET.ClearBits(bits)
}
// unresetBlockWait brings specified hardware blocks
@@ -38,6 +26,6 @@ func unresetBlock(bits uint32) {
// out of reset and wait for completion.
func unresetBlockWait(bits uint32) {
unresetBlock(bits)
- for !resets.resetDone.HasBits(bits) {
+ for !resets.RESET_DONE.HasBits(bits) {
}
}
diff --git a/src/machine/machine_rp2040_sync.go b/src/machine/machine_rp2_sync.go
index 4c9b44323..5019552af 100644
--- a/src/machine/machine_rp2040_sync.go
+++ b/src/machine/machine_rp2_sync.go
@@ -1,24 +1,11 @@
-//go:build rp2040
+//go:build rp2040 || rp2350
package machine
-import (
- "device/rp"
-)
-
// machine_rp2040_sync.go contains interrupt and
// lock primitives similar to those found in Pico SDK's
// irq.c
-const (
- // Number of spin locks available
- _NUMSPINLOCKS = 32
- // Number of interrupt handlers available
- _NUMIRQ = 32
- _PICO_SPINLOCK_ID_IRQ = 9
- _NUMBANK0_GPIOS = 30
-)
-
// Clears interrupt flag on a pin
func (p Pin) acknowledgeInterrupt(change PinChange) {
ioBank0.intR[p>>3].Set(p.ioIntBit(change))
@@ -50,23 +37,3 @@ func (p Pin) ctrlSetInterrupt(change PinChange, enabled bool, base *irqCtrl) {
enReg.ClearBits(p.ioIntBit(change))
}
}
-
-// Enable or disable a specific interrupt on the executing core.
-// num is the interrupt number which must be in [0,31].
-func irqSet(num uint32, enabled bool) {
- if num >= _NUMIRQ {
- return
- }
- irqSetMask(1<<num, enabled)
-}
-
-func irqSetMask(mask uint32, enabled bool) {
- if enabled {
- // Clear pending before enable
- // (if IRQ is actually asserted, it will immediately re-pend)
- rp.PPB.NVIC_ICPR.Set(mask)
- rp.PPB.NVIC_ISER.Set(mask)
- } else {
- rp.PPB.NVIC_ICER.Set(mask)
- }
-}
diff --git a/src/machine/machine_rp2040_timer.go b/src/machine/machine_rp2_timer.go
index 56c012cd6..a78ed70bb 100644
--- a/src/machine/machine_rp2040_timer.go
+++ b/src/machine/machine_rp2_timer.go
@@ -1,13 +1,11 @@
-//go:build rp2040
+//go:build rp2040 || rp2350
package machine
import (
"device/arm"
- "device/rp"
"runtime/interrupt"
"runtime/volatile"
- "unsafe"
)
const numTimers = 4
@@ -31,14 +29,14 @@ type timerType struct {
timeRawL volatile.Register32
dbgPause volatile.Register32
pause volatile.Register32
+ locked [rp2350ExtraReg]volatile.Register32
+ source [rp2350ExtraReg]volatile.Register32
intR volatile.Register32
intE volatile.Register32
intF volatile.Register32
intS volatile.Register32
}
-var timer = (*timerType)(unsafe.Pointer(rp.TIMER))
-
// TimeElapsed returns time elapsed since power up, in microseconds.
func (tmr *timerType) timeElapsed() (us uint64) {
// Need to make sure that the upper 32 bits of the timer
diff --git a/src/machine/machine_rp2040_uart.go b/src/machine/machine_rp2_uart.go
index b0b039877..c984d4142 100644
--- a/src/machine/machine_rp2040_uart.go
+++ b/src/machine/machine_rp2_uart.go
@@ -1,4 +1,4 @@
-//go:build rp2040
+//go:build rp2040 || rp2350
package machine
@@ -39,7 +39,7 @@ func (uart *UART) Configure(config UARTConfig) error {
settings := uint32(rp.UART0_UARTCR_UARTEN |
rp.UART0_UARTCR_RXE |
rp.UART0_UARTCR_TXE)
-
+ const bits = rp.UART0_UARTCR_UARTEN | rp.UART0_UARTCR_TXE
if config.RTS != 0 {
settings |= rp.UART0_UARTCR_RTSEN
}
diff --git a/src/machine/machine_rp2040_watchdog.go b/src/machine/machine_rp2_watchdog.go
index a67df80ca..f776c5ca4 100644
--- a/src/machine/machine_rp2040_watchdog.go
+++ b/src/machine/machine_rp2_watchdog.go
@@ -1,4 +1,4 @@
-//go:build rp2040
+//go:build rp2040 || rp2350
package machine
@@ -60,11 +60,3 @@ func (wd *watchdogImpl) Start() error {
func (wd *watchdogImpl) Update() {
rp.WATCHDOG.LOAD.Set(wd.loadValue)
}
-
-// startTick starts the watchdog tick.
-// cycles needs to be a divider that when applied to the xosc input,
-// produces a 1MHz clock. So if the xosc frequency is 12MHz,
-// this will need to be 12.
-func (wd *watchdogImpl) startTick(cycles uint32) {
- rp.WATCHDOG.TICK.Set(cycles | rp.WATCHDOG_TICK_ENABLE)
-}
diff --git a/src/machine/machine_rp2040_xosc.go b/src/machine/machine_rp2_xosc.go
index 0acac1f1e..c9ce58300 100644
--- a/src/machine/machine_rp2040_xosc.go
+++ b/src/machine/machine_rp2_xosc.go
@@ -1,4 +1,4 @@
-//go:build rp2040
+//go:build rp2040 || rp2350
package machine
@@ -18,7 +18,7 @@ type xoscType struct {
status volatile.Register32
dormant volatile.Register32
startup volatile.Register32
- reserved [3]volatile.Register32
+ reserved [3 - 3*rp2350ExtraReg]volatile.Register32
count volatile.Register32
}
diff --git a/src/machine/uart.go b/src/machine/uart.go
index eeeb7d6a0..32462587b 100644
--- a/src/machine/uart.go
+++ b/src/machine/uart.go
@@ -1,4 +1,4 @@
-//go:build atmega || esp || nrf || sam || sifive || stm32 || k210 || nxp || rp2040
+//go:build atmega || esp || nrf || sam || sifive || stm32 || k210 || nxp || rp2040 || rp2350
package machine
diff --git a/src/machine/usb.go b/src/machine/usb.go
index 2f7755690..1c577b5f6 100644
--- a/src/machine/usb.go
+++ b/src/machine/usb.go
@@ -1,4 +1,4 @@
-//go:build sam || nrf52840 || rp2040
+//go:build sam || nrf52840 || rp2040 || rp2350
package machine
diff --git a/src/machine/watchdog.go b/src/machine/watchdog.go
index d1516350d..d818a0086 100644
--- a/src/machine/watchdog.go
+++ b/src/machine/watchdog.go
@@ -1,4 +1,4 @@
-//go:build nrf52840 || nrf52833 || rp2040 || atsamd51 || atsame5x || stm32
+//go:build nrf52840 || nrf52833 || rp2040 || rp2350 || atsamd51 || atsame5x || stm32
package machine