1
0
mirror of https://github.com/RIOT-OS/RIOT.git synced 2025-12-25 14:33:52 +01:00

cpu: Add RP2350 Support

This commit is contained in:
AnnsAnn 2025-06-10 12:02:00 +02:00
parent 95871247c5
commit 014b17250b
24 changed files with 787 additions and 0 deletions

View File

@ -53,6 +53,7 @@ SECTIONS
_sfixed = .;
_isr_vectors = DEFINED(_isr_vectors) ? _isr_vectors : . ;
KEEP(*(SORT(.vectors*)))
KEEP(*(SORT(.picobin_block*))) /* Keep picobin block used by RP2350 */
*(.text .text.* .gnu.linkonce.t.*)
*(.glue_7t) *(.glue_7)
*(.rodata .rodata* .gnu.linkonce.r.*)

26
cpu/rp2350/Kconfig Normal file
View File

@ -0,0 +1,26 @@
# Copyright (C) 2021 Otto-von-Guericke-Universität Magdeburg
#
# This file is subject to the terms and conditions of the GNU Lesser
# General Public License v2.1. See the file LICENSE in the top level
# directory for more details.
#
config CPU_FAM_RP2350
bool
select CPU_CORE_CORTEX_M33
config CPU_FAM
default "RP2350" if CPU_FAM_RP2350
config CPU_MODEL_RP2350
bool
select CPU_FAM_RP2350
config CPU_MODEL
default "RP2350" if CPU_MODEL_RP2350
config CPU
default "rp2350" if CPU_FAM_RP2350
source "$(RIOTCPU)/cortexm_common/Kconfig"

13
cpu/rp2350/Makefile Normal file
View File

@ -0,0 +1,13 @@
MODULE = cpu
USEPKG += picosdk
DIRS = $(RIOTCPU)/cortexm_common periph
include $(RIOTBASE)/Makefile.base
# Check if picosdk directory exists, otherwise build it
ifeq (,$(wildcard $(RIOTBASE)/dist/tools/picosdk/picosdk))
$(info Building picosdk...)
$(shell $(MAKE) -C $(RIOTBASE)/dist/tools/picosdk)
endif

2
cpu/rp2350/Makefile.dep Normal file
View File

@ -0,0 +1,2 @@
include $(RIOTCPU)/cortexm_common/Makefile.dep

View File

@ -0,0 +1,7 @@
CPU_CORE := cortex-m33
CPU_FAM := RP2350
include $(RIOTCPU)/cortexm_common/Makefile.features
FEATURES_PROVIDED += periph_gpio
FEATURES_PROVIDED += periph_uart

View File

@ -0,0 +1,36 @@
ROM_LEN ?= 2097152 # = 2 MiB used in the RPi Pico
ROM_OFFSET := 0 # bootloader size
RAM_LEN := 0x82000 # 520kB = 532479 used in the RPi Pico 2350
ROM_START_ADDR := 0x10000000 # XIP Non-Secure address for rp2350
RAM_START_ADDR := 0x20000000 # Non-Secure RAM address for rp2350
# Specify CPU and FPU options
CPU_ARCH = armv8m
CPU_MODEL ?= rp2350
# CPU and architecture specific flags
CFLAGS += -D$(CPU_MODEL)
CFLAGS += -DROM_START_ADDR=$(ROM_START_ADDR)
CFLAGS += -DRAM_START_ADDR=$(RAM_START_ADDR)
CFLAGS += -Wno-error
# Include paths
INCLUDES += -I$(RIOTCPU)/rp2350/include
INCLUDES += -isystem$(RIOTBASE)/dist/tools/picosdk/picosdk/src/rp2_common/cmsis/stub/CMSIS/Core/Include
INCLUDES += -isystem$(RIOTBASE)/dist/tools/picosdk/picosdk/src/rp2_common/cmsis/stub/CMSIS/Device/RP2350/Include
# Linker flags
LINKFLAGS += -mcpu=$(CPU_ARCH) -mthumb
LINKFLAGS += -Wl,--gc-sections
LINKFLAGS += -Wl,--start-group -lc -lm -Wl,--end-group
# Vector table configuration
VECTORS_O ?= $(BINDIR)/cpu/vectors.o
VECTORS_FILE := $(RIOTCPU)/rp2350/vectors.c
# Supported programmers and debuggers
PROGRAMMERS_SUPPORTED := picotool openocd jlink
PROGRAMMER ?= openocd
OPENOCD_DEBUG_ADAPTER ?= dap
# Include the base Cortex-M makefile
include $(RIOTMAKE)/arch/cortexm.inc.mk

51
cpu/rp2350/clock.c Normal file
View File

@ -0,0 +1,51 @@
#include "periph_cpu.h"
void clock_reset(void) {
// Reset the clock system
reset_component(RESET_PLL_SYS, RESET_PLL_SYS);
}
/**
* @brief Configures the XOSC and then sets CLK_SYS, PLL_SYS and CLK_PERI to it
* @warning Make sure to call clock_reset() before this function to reset the clock system
* @note RP2350 Docs Chapter 8, mostly 8.2 for more details
*/
void cpu_clock_init(void) {
// Enable the XOSC
xosc_start();
/**
* Setup the PLL using the XOSC as the reference clock.
*/
//PLL_SYS->CS = REF_DIV; // Set the reference divider
PLL_SYS->FBDIV_INT = 125; // Set the feedback divider
/**
* Set the post-dividers for the PLL output.
*/
PLL_SYS->PRIM = PDIV;
// Turn on PLL
atomic_clear(&PLL_SYS->PWR, PLL_PWR_PD_BITS | PLL_PWR_VCOPD_BITS | PLL_PWR_POSTDIVPD_BITS);
// sleep 10ms to allow the PLL to stabilize
xosc_sleep(10);
// // Wait for lock
// while (!(PLL_SYS->CS & PLL_CS_LOCK_BITS)) {
// // Wait for the PLL to lock
// }
// AUXSRC = 0x0 7:5 && SRC == 0x0 0
// CLOCKS: CLK_SYS_CTRL CLK_PERI_CTRL_ENABLE_BIT
CLOCKS->CLK_SYS_CTRL = 1;
// This register contains one decoded bit for each of the clock sources enumerated in the CTRL SRC field.
// The bit does not directly correlate with the value of the SRC field
// For example 0x0 is the first bit while 0x1 is the second bit
// In some way this makes sense, in some way I lost too much time on this
while (CLOCKS->CLK_SYS_SELECTED != 2) {}
// src: CLOCKS: CLK_PERI_CTRL
// AUXSRC = 0x0 -> CLK_SYS Indirectly through lower line
CLOCKS->CLK_PERI_CTRL = CLK_PERI_CTRL_ENABLE_BIT;
}

33
cpu/rp2350/cpu.c Normal file
View File

@ -0,0 +1,33 @@
#include "cpu.h"
#include "RP2350.h"
#include "board.h"
#include "kernel_init.h"
#include "macros/units.h"
#include "periph/gpio.h"
#include "periph/init.h"
#include "periph_cpu.h"
#include "stdio_base.h"
#define DEBUG_WITH_OSC
void gpio_reset(void) {
reset_component(RESET_PADS_BANK0, RESET_PADS_BANK0);
reset_component(RESET_IO_BANK0, RESET_IO_BANK0);
}
void cpu_init(void) {
/* initialize the Cortex-M core */
//cortexm_init();
gpio_reset();
//_cpu_reset();
/* initialize stdio prior to periph_init() to allow use of DEBUG() there */
early_init();
clock_reset();
cpu_clock_init();
/* trigger static peripheral initialization */
periph_init();
}

8
cpu/rp2350/doc.txt Normal file
View File

@ -0,0 +1,8 @@
/**
@defgroup cpu_rp23xx RP23xx MCUs
@ingroup cpu
@brief RP23xx MCU code and definitions
This module contains the code and definitions for MCUs of the RP23xx family used by the Pi Pico 2
*/

View File

@ -0,0 +1,93 @@
#pragma once
#include "RP2350.h"
// Based on hardware/regs/xosc.h and 8.2.8
#define XOSC_CTRL_FREQ_RANGE_VALUE_1_15MHZ 0xaa0u
#define XOSC_CTRL_FREQ_RANGE_VALUE_10_30MHZ 0xaa1u
#define XOSC_CTRL_FREQ_RANGE_VALUE_25_60MHZ 0xaa2u
#define XOSC_CTRL_FREQ_RANGE_VALUE_40_100MHZ 0xaa3u
#define XOSC_CTRL_ENABLE_VALUE_DISABLE 0xd1eu
#define XOSC_CTRL_ENABLE_VALUE_ENABLE 0xfabu
#define XOSC_CTRL_ENABLE_LSB 12u
#define XOSC_STATUS_STABLE_BITS 0x80000000u
#define XOSC_HZ MHZ(12)
#define REF_DIV 2
#define VCO_FREQ 750000000u
#define PD1 6
#define PD2 2
#define PLL_PWR_PD_BITS 0x00000001u
#define PLL_PWR_VCOPD_BITS 0x00000020u
#define PLL_CS_LOCK_BITS 0x80000000u
#define PLL_PRIM_POSTDIV1_LSB 16u
#define PLL_PRIM_POSTDIV2_LSB 12u
#define PLL_PWR_POSTDIVPD_BITS 0x00000008u
#define CLK_PERI_CTRL_ENABLE_BIT 1 << 11
#define XOSC_FREQ 12000000
#define POSTDIV1 6
#define POSTDIV2 2
#define CPUFREQ 125000000
#define CLOCK_XOSC_MAX MHZ(15) /**< Maximum crystal frequency */
#define CLOCK_XOSC_MIN MHZ(5) /**< Minimum crystal frequency */
#define CLOCK_XOSC (XOSC_HZ) /**< Crystal frequency */
#define PLL_POSTDIV_MIN (1U) /**< Minimum value of the post PLL clock divers */
#define PLL_POSTDIV_MAX (7U) /**< Maximum value of the post PLL clock divers */
#define PLL_VCO_FEEDBACK_SCALE_MIN (16U) /**< Minimum value of the PLL VCO feedback scaler */
#define PLL_VCO_FEEDBACK_SCALE_MAX (320U) /**< Maximum value of the PLL VCO feedback scaler */
#define PLL_REF_DIV_MIN (1U) /**< Minimum value of the clock divider applied before
* feeding in the reference clock into the PLL */
#define PLL_REF_DIV_MAX (1U) /**< Minimum value of the clock divider applied before
* feeding in the reference clock into the PLL */
#if (PLL_VCO_FEEDBACK_SCALE_MIN < PLL_VCO_FEEDBACK_SCALE_MIN) || (PLL_VCO_FEEDBACK_SCALE_MAX > PLL_VCO_FEEDBACK_SCALE_MAX)
#error "Value for PLL_VCO_FEEDBACK_SCALE out of range, check config"
#endif
#if (PLL_REF_DIV_MIN < PLL_REF_DIV_MIN) || (PLL_REF_DIV_MAX > PLL_REF_DIV_MAX)
#error "Value for PLLxosc_sleep_REF_DIV out of range, check config"
#endif
#if (PLL_POSTDIV_MIN < PLL_POSTDIV_MIN) || (PLL_POSTDIV_MAX > PLL_POSTDIV_MAX)
#error "Value for PLL_POSTDIV out of range, check config"
#endif
#if ((CLOCK_XOSC > CLOCK_XOSC_MAX) || (CLOCK_XOSC < CLOCK_XOSC_MIN))
#error "Value for CLOCK_XOSC out of range, check config"
#endif
#define PDIV ((PD1 << PLL_PRIM_POSTDIV1_LSB) | (PD2 << PLL_PRIM_POSTDIV2_LSB))
#define FBDIV ((VCO_FREQ / XOSC_HZ) / REF_DIV)
/**
* @brief Configures the Crystal to run.
*
* @param f_ref Desired frequency in Hz
*
* @pre 1 MHz <= @p f_ref <= 15 MHz.
*
* The reference hardware manual suggests to use a 12 MHz crystal.
*/
void xosc_start(void);
/**
* @brief Stop the crystal.
*/
void xosc_stop(void);
/**
* @brief Sleep for a given number of cycles.
*/
void xosc_sleep(int32_t cycles);
/**
* @brief Reset the clock system.
*
* This function resets the clock system to a known state.
* It is recommended to call this function before configuring the clock system.
*/
void clock_reset(void);
/**
* @brief Configures the XOSC and then sets CLK_SYS, PLL_SYS and CLK_PERI to it
* @warning Make sure to call clock_reset() before this function to reset the clock system
* @note RP2350 Docs Chapter 8, mostly 8.2 for more details
*/
void cpu_clock_init(void);

View File

@ -0,0 +1,18 @@
#pragma once
#include "cpu_conf_common.h"
#include "RP2350.h"
#include "core_cm33.h"
#define __CHECK_DEVICE_DEFINES
#define CPU_DEFAULT_IRQ_PRIO (1U)
#define CPU_IRQ_NUMOF (52U)
#ifdef __cplusplus
extern "C" {
#endif
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,23 @@
#pragma once
/**
* @brief Possible function values for @ref gpio_io_ctrl_t::function_select
*/
typedef enum {
FUNCTION_SELECT_SPI = 1, /**< connect pin to the SPI peripheral
* (MISO/MOSI/SCK depends on pin) */
FUNCTION_SELECT_UART = 2, /**< connect pin to the UART peripheral
* (TXD/RXD depends on pin) */
FUNCTION_SELECT_I2C = 3, /**< connect pin to the I2C peripheral
* (SCL/SDA depends on pin) */
FUNCTION_SELECT_PWM = 4, /**< connect pin to the timer for PWM
* (channel depends on pin) */
FUNCTION_SELECT_SIO = 5, /**< use pin as vanilla GPIO */
FUNCTION_SELECT_PIO0 = 6, /**< connect pin to the first PIO peripheral */
FUNCTION_SELECT_PIO1 = 7, /**< connect pin to the second PIO peripheral */
FUNCTION_SELECT_CLOCK = 8, /**< connect pin to the timer (depending on pin: external clock,
* clock output, or not supported) */
FUNCTION_SELECT_USB = 9, /**< connect pin to the USB peripheral
* (function depends on pin) */
FUNCTION_SELECT_NONE = 31, /**< Reset value, pin unconnected */
} gpio_function_select_t;

View File

@ -0,0 +1,48 @@
#pragma once
#include "RP2350.h"
#define ATOMIC_XOR_WRITE 0x1000
#define ATOMIC_BITMASK_SET_WRITE 0x2000
#define ATOMIC_BITMASK_CLEAR_WRITE 0x3000
/**
* @brief Perform an atomic XOR write to a register
*
* @param[in] reg Pointer to the target register
* @param[in] val Value to be XORed with the register
*/
static inline void atomic_xor(volatile uint32_t *reg, uint32_t val)
{
*(volatile uint32_t *)((uintptr_t)reg | ATOMIC_XOR_WRITE) = val;
}
/**
* @brief Set bits in a register atomically
*
* @param[in] reg Pointer to the target register
* @param[in] val Bit mask of bits to set
*/
static inline void atomic_set(volatile uint32_t *reg, uint32_t val)
{
*(volatile uint32_t *)((uintptr_t)reg | ATOMIC_BITMASK_SET_WRITE) = val;
}
/**
* @brief Clear bits in a register atomically
*
* @param[in] reg Pointer to the target register
* @param[in] val Bit mask of bits to clear
*/
static inline void atomic_clear(volatile uint32_t *reg, uint32_t val)
{
*(volatile uint32_t *)((uintptr_t)reg | ATOMIC_BITMASK_CLEAR_WRITE) = val;
}
static inline void reset_component(uint32_t reset_value, uint32_t reset_done_value)
{
atomic_clear(&RESETS->RESET, reset_value);
while(~RESETS->RESET_DONE & reset_done_value) {
// Wait for the reset to complete
}
}

View File

@ -0,0 +1,56 @@
#pragma once
#include <stdbool.h>
#include <stdint.h>
#include "cpu.h"
#include "RP2350.h"
#include "uart_conf.h"
#include "clock_conf.h"
#include "gpio_conf.h"
#include "helpers.h"
// Overwrite the default GPIO type to use uint32_t
#define HAVE_GPIO_T
typedef uint32_t gpio_t;
#define LED0_PIN_ID 25
#define OSC_DEBUG_PIN_ID 15
#define RESET_PLL_SYS 1 << 14
#define RESET_PADS_BANK0 1 << 9
#define RESET_UART0 1 << 26
#define RESET_UART1 1 << 27
#define RESET_IO_BANK0 1 << 6
#define PADS_BANK0_GPIO0_IE_BITS 1<<6
#define PADS_BANK0_ISO_BITS 1<<8
#ifdef __cplusplus
extern "C" {
#endif
static inline volatile uint32_t calculate_gpio_pad_register_addr(gpio_t pin) {
// Each pin has a 4 byte register, so we can calculate the address
// by adding 4 bytes for each pin, starting at the base address of PADS_BANK0
// and adding 4 bytes to skip VOLTAGE_SELECT
return PADS_BANK0_BASE + 4 * (pin + 1);
}
static volatile uint32_t calculate_gpio_io_status_register_addr(gpio_t pin) {
// Each status register is followed by a ctrl register,
return IO_BANK0_BASE + 8 * pin;
}
static inline volatile uint32_t calculate_gpio_io_ctrl_register_addr(gpio_t pin) {
// Each pin has a 8 byte register (4 Bytes of Status, 4 Bytes of CTRL),
// so we can calculate the address by adding 8 bytes for each pin,
// starting at the base address of IO_BANK0
return calculate_gpio_io_status_register_addr(pin) + 4;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,24 @@
#pragma once
#include "periph_cpu.h"
#include "macros/units.h"
#include "RP2350.h"
#ifdef __cplusplus
extern "C" {
#endif
#define BAUDRATE 115200
#define IBRD ((8*CPUFREQ + BAUDRATE)/(2*BAUDRATE))/64
#define FBRD ((8*CPUFREQ + BAUDRATE)/(2*BAUDRATE))%64
#define UART_UARTCR_UARTEN_BITS 1<<0
#define UART_UARTCR_RXE_BITS 1<<9
#define UART_UARTCR_TXE_BITS 1<<8
#define UART_UARTFR_RXFF_BITS 1<<6
#define UART_UARTFR_TXFE_BITS 1<<7
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1 @@
INCLUDE cortexm.ld

View File

@ -0,0 +1 @@
include $(RIOTMAKE)/periph.mk

65
cpu/rp2350/periph/gpio.c Normal file
View File

@ -0,0 +1,65 @@
#include "periph/gpio.h"
#include <errno.h>
#include "board.h"
#include "irq.h"
#include "periph_conf.h"
#include "periph_cpu.h"
#define ENABLE_DEBUG 0
#include "debug.h"
#define GPIO_PIN_NUMOF 30U
int gpio_init(gpio_t pin, gpio_mode_t mode) {
// Check if we exceed the maximum number of GPIO pins
assert(pin < GPIO_PIN_NUMOF);
// Clear the pin's output enable and output state
SIO->GPIO_OE_CLR = 1LU << pin;
SIO->GPIO_OUT_CLR = 1LU << pin;
switch (mode) {
case GPIO_OUT:
*(uint32_t*)calculate_gpio_io_ctrl_register_addr(pin) = FUNCTION_SELECT_SIO;
volatile uint32_t* pad_reg = (uint32_t*)calculate_gpio_pad_register_addr(pin);
// We clear all bits except the drive strength bit
// We set that to the highest one possible (12mA)
// to mimic the behavior of the pico1 GPIO driver
// (Not too sure why we do this, but it seems to be the standard)
*pad_reg = 0x3 << 4;
SIO->GPIO_OE_SET = 1 << pin; // Set the pin as output
break;
default:
// Unsupported mode
return -ENOTSUP;
}
}
bool gpio_read(gpio_t pin) {}
void gpio_set(gpio_t pin) {
SIO->GPIO_OUT_SET = 1 << pin; // Set the pin to HIGH
}
void gpio_clear(gpio_t pin) {
SIO->GPIO_OUT_CLR = 1 << pin; // Set the pin to LOW
}
void gpio_toggle(gpio_t pin) {
SIO->GPIO_OUT_XOR = 1 << pin; // Toggle the pin state (XOR)
}
void gpio_write(gpio_t pin, bool value) {
if (value) {
gpio_set(pin); // Set the pin to HIGH
} else {
gpio_clear(pin); // Set the pin to LOW
}
}

52
cpu/rp2350/periph/uart.c Normal file
View File

@ -0,0 +1,52 @@
#include "periph/uart.h"
#include "periph_cpu.h"
int uart_init(uart_t uart, uint32_t baud, uart_rx_cb_t rx_cb, void *arg) {
// Set the UART pins to the correct function
IO_BANK0->GPIO0_CTRL = FUNCTION_SELECT_UART;
IO_BANK0->GPIO1_CTRL = FUNCTION_SELECT_UART;
// Clear the ISO bits
atomic_clear(&PADS_BANK0->GPIO0, PADS_BANK0_ISO_BITS);
atomic_clear(&PADS_BANK0->GPIO1, PADS_BANK0_ISO_BITS);
// Set IE bit for gpio1
PADS_BANK0->GPIO1 = PADS_BANK0->GPIO1 | PADS_BANK0_GPIO0_IE_BITS;
// We reset UART0 here, so we can be sure it is in a known state
reset_component(RESET_UART0, RESET_UART0);
UART0->UARTIBRD = IBRD;
UART0->UARTFBRD = FBRD;
}
int uart_mode(uart_t uart, uart_data_bits_t data_bits, uart_parity_t parity,
uart_stop_bits_t stop_bits) {
atomic_clear(&UART0->UARTCR, UART_UARTCR_UARTEN_BITS | UART_UARTCR_RXE_BITS |
UART_UARTCR_TXE_BITS);
// Set the data bits, parity, and stop bits
UART0->UARTLCR_H = (uint32_t)data_bits << 5;
switch (parity) {
case UART_PARITY_NONE:
break;
default:
// @todo: Implement other parity modes lel
return UART_NOMODE;
}
UART0->UARTCR =
UART_UARTCR_RXE_BITS | UART_UARTCR_TXE_BITS | UART_UARTCR_UARTEN_BITS;
return UART_OK;
}
void uart_write(uart_t uart, const uint8_t *data, size_t len) {
for (size_t i = 0; i < len; i++) {
UART0->UARTDR = data[i];
// Wait until the TX FIFO is empty before sending the next byte
while (!(UART0->UARTFR & UART_UARTFR_TXFE_BITS));
}
}
void uart_poweron(uart_t uart) {}
void uart_poweroff(uart_t uart) {}

View File

@ -0,0 +1,28 @@
// Picobin block required for the binary
// This defines the minimum viable image metadata to be recognized by the RP2350 bootloader
// based on RP2350 Chapter 5.9.1
.section .picobin_block, "a" // "a" means "allocatable" (can be moved by the linker)
// PICOBIN_BLOCK_MARKER_START
.word 0xffffded3
// ITEM 0 START based on 5.9.3.1
.byte 0x42 // (size_flag == 0, item_type == PICOBIN_BLOCK_ITEM_1BS_IMAGE_TYPE)
.byte 0x1 // Block Size in words
// image_type_flags (2 bytes) [See 5.9.3.1 / p419]
// 15 -> 0 (1 for "Try before you buy" image [Wacky]
// 12-14 -> 001 (RP2350 = 1)
// 11 -> 0 (Reserved)
// 8-10 -> 000 (EXE_CPU_ARM = 0), **WARNING** if I ever want to support RISC-V this needs to be 001 (EXE_CPU_RISCV)
// 6-7 -> 00 (Reserved)
// 4-5 -> 10 (2) EXE Security (As far as I understand we cant run in EXE_SECURITY_NS on the RP2350 [Appears to be correct]) thus EXE_SECURITY_S = 2
// 0-3 // 0001 IMAGE_TYPE_EXE
.hword 0b0001000000100001
// ITEM 0 END see 5.1.5.1 for explanation and 5.9.5.1 for the value / structure
.byte 0xff // PICOBIN_BLOCK_ITEM_2BS_LAST
.hword 0x0001 // Size of the item in words (predefined value)
.byte 0x00 // Padding
// Next Block Pointer
.word 0x00000000 // Next block pointer (0 means no more blocks)
// PICOBIN_BLOCK_MARKER_END
.word 0xab123579 // Marker for the end of the picobin block

140
cpu/rp2350/vectors.c Normal file
View File

@ -0,0 +1,140 @@
/*
* Copyright (C) 2021 Ishraq Ibne Ashraf
*
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup cpu_ro2040
* @{
*
* @file vectors.c
* @brief Startup code and interrupt vector definition
*
* @author Ishraq Ibne Ashraf <ishraq.i.ashraf@gmail.com>
*
* @}
*/
#include "cpu_conf.h"
#include "vectors_cortexm.h"
#include "RP2350.h"
/* define a local dummy handler as it needs to be in the same compilation unit
* as the alias definition */
void dummy_handler(void) {
dummy_handler_default();
}
/* rp2350 specific interrupt vector */
WEAK_DEFAULT void isr_timer0_0(void);
WEAK_DEFAULT void isr_timer0_1(void);
WEAK_DEFAULT void isr_timer0_2(void);
WEAK_DEFAULT void isr_timer0_3(void);
WEAK_DEFAULT void isr_timer1_0(void);
WEAK_DEFAULT void isr_timer1_1(void);
WEAK_DEFAULT void isr_timer1_2(void);
WEAK_DEFAULT void isr_timer1_3(void);
WEAK_DEFAULT void isr_pwm_wrap_0(void);
WEAK_DEFAULT void isr_pwm_wrap_1(void);
WEAK_DEFAULT void isr_dma_0(void);
WEAK_DEFAULT void isr_dma_1(void);
WEAK_DEFAULT void isr_dma_2(void);
WEAK_DEFAULT void isr_dma_3(void);
WEAK_DEFAULT void isr_usbctrl(void);
WEAK_DEFAULT void isr_pio0_0(void);
WEAK_DEFAULT void isr_pio0_1(void);
WEAK_DEFAULT void isr_pio1_0(void);
WEAK_DEFAULT void isr_pio1_1(void);
WEAK_DEFAULT void isr_pio2_0(void);
WEAK_DEFAULT void isr_pio2_1(void);
WEAK_DEFAULT void isr_io_bank0(void);
WEAK_DEFAULT void isr_io_bank0_ns(void);
WEAK_DEFAULT void isr_io_qspi(void);
WEAK_DEFAULT void isr_io_qspi_ns(void);
WEAK_DEFAULT void isr_sio_fifo(void);
WEAK_DEFAULT void isr_sio_bell(void);
WEAK_DEFAULT void isr_sio_fifo_ns(void);
WEAK_DEFAULT void isr_sio_bell_ns(void);
WEAK_DEFAULT void isr_sio_mtimecmp(void);
WEAK_DEFAULT void isr_clocks(void);
WEAK_DEFAULT void isr_spi0(void);
WEAK_DEFAULT void isr_spi1(void);
WEAK_DEFAULT void isr_uart0(void);
WEAK_DEFAULT void isr_uart1(void);
WEAK_DEFAULT void isr_adc_fifo(void);
WEAK_DEFAULT void isr_i2c0(void);
WEAK_DEFAULT void isr_i2c1(void);
WEAK_DEFAULT void isr_otp(void);
WEAK_DEFAULT void isr_trng(void);
WEAK_DEFAULT void isr_proc0_cti(void);
WEAK_DEFAULT void isr_proc1_cti(void);
WEAK_DEFAULT void isr_pll_sys(void);
WEAK_DEFAULT void isr_pll_usb(void);
WEAK_DEFAULT void isr_powman_pow(void);
WEAK_DEFAULT void isr_powman_timer(void);
WEAK_DEFAULT void isr_spareirq_0(void);
WEAK_DEFAULT void isr_spareirq_1(void);
WEAK_DEFAULT void isr_spareirq_2(void);
WEAK_DEFAULT void isr_spareirq_3(void);
WEAK_DEFAULT void isr_spareirq_4(void);
WEAK_DEFAULT void isr_spareirq_5(void);
/* CPU specific interrupt vector table */
ISR_VECTOR(1) const isr_t vector_cpu[CPU_IRQ_NUMOF] = {
(void*) isr_timer0_0, /* 0 TIMER0_IRQ_0 */
(void*) isr_timer0_1, /* 1 TIMER0_IRQ_1 */
(void*) isr_timer0_2, /* 2 TIMER0_IRQ_2 */
(void*) isr_timer0_3, /* 3 TIMER0_IRQ_3 */
(void*) isr_timer1_0, /* 4 TIMER1_IRQ_0 */
(void*) isr_timer1_1, /* 5 TIMER1_IRQ_1 */
(void*) isr_timer1_2, /* 6 TIMER1_IRQ_2 */
(void*) isr_timer1_3, /* 7 TIMER1_IRQ_3 */
(void*) isr_pwm_wrap_0, /* 8 PWM_IRQ_WRAP_0 */
(void*) isr_pwm_wrap_1, /* 9 PWM_IRQ_WRAP_1 */
(void*) isr_dma_0, /* 10 DMA_IRQ_0 */
(void*) isr_dma_1, /* 11 DMA_IRQ_1 */
(void*) isr_dma_2, /* 12 DMA_IRQ_2 */
(void*) isr_dma_3, /* 13 DMA_IRQ_3 */
(void*) isr_usbctrl, /* 14 USBCTRL_IRQ */
(void*) isr_pio0_0, /* 15 PIO0_IRQ_0 */
(void*) isr_pio0_1, /* 16 PIO0_IRQ_1 */
(void*) isr_pio1_0, /* 17 PIO1_IRQ_0 */
(void*) isr_pio1_1, /* 18 PIO1_IRQ_1 */
(void*) isr_pio2_0, /* 19 PIO2_IRQ_0 */
(void*) isr_pio2_1, /* 20 PIO2_IRQ_1 */
(void*) isr_io_bank0, /* 21 IO_IRQ_BANK0 */
(void*) isr_io_bank0_ns, /* 22 IO_IRQ_BANK0_NS */
(void*) isr_io_qspi, /* 23 IO_IRQ_QSPI */
(void*) isr_io_qspi_ns, /* 24 IO_IRQ_QSPI_NS */
(void*) isr_sio_fifo, /* 25 SIO_IRQ_FIFO */
(void*) isr_sio_bell, /* 26 SIO_IRQ_BELL */
(void*) isr_sio_fifo_ns, /* 27 SIO_IRQ_FIFO_NS */
(void*) isr_sio_bell_ns, /* 28 SIO_IRQ_BELL_NS */
(void*) isr_sio_mtimecmp, /* 29 SIO_IRQ_MTIMECMP */
(void*) isr_clocks, /* 30 CLOCKS_IRQ */
(void*) isr_spi0, /* 31 SPI0_IRQ */
(void*) isr_spi1, /* 32 SPI1_IRQ */
(void*) isr_uart0, /* 33 UART0_IRQ */
(void*) isr_uart1, /* 34 UART1_IRQ */
(void*) isr_adc_fifo, /* 35 ADC_IRQ_FIFO */
(void*) isr_i2c0, /* 36 I2C0_IRQ */
(void*) isr_i2c1, /* 37 I2C1_IRQ */
(void*) isr_otp, /* 38 OTP_IRQ */
(void*) isr_trng, /* 39 TRNG_IRQ */
(void*) isr_proc0_cti, /* 40 PROC0_IRQ_CTI */
(void*) isr_proc1_cti, /* 41 PROC1_IRQ_CTI */
(void*) isr_pll_sys, /* 42 PLL_SYS_IRQ */
(void*) isr_pll_usb, /* 43 PLL_USB_IRQ */
(void*) isr_powman_pow, /* 44 POWMAN_IRQ_POW */
(void*) isr_powman_timer, /* 45 POWMAN_IRQ_TIMER */
(void*) isr_spareirq_0, /* 46 SPAREIRQ_IRQ_0 */
(void*) isr_spareirq_1, /* 47 SPAREIRQ_IRQ_1 */
(void*) isr_spareirq_2, /* 48 SPAREIRQ_IRQ_2 */
(void*) isr_spareirq_3, /* 49 SPAREIRQ_IRQ_3 */
(void*) isr_spareirq_4, /* 50 SPAREIRQ_IRQ_4 */
(void*) isr_spareirq_5, /* 51 SPAREIRQ_IRQ_5 */
};

58
cpu/rp2350/xosc.c Normal file
View File

@ -0,0 +1,58 @@
/*
* Copyright (C) 2021 Otto-von-Guericke Universität Magdeburg
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup cpu_rpx0xx
* @{
*
* @file
* @brief Implementation of the crystal oscillator (XOSC)
*
* @author Marian Buschsieweke <marian.buschsieweke@ovgu.de>
* @author Fabian Hüßler <fabian.huessler@ovgu.de>
*
* @}
*/
#include <assert.h>
#include "RP2350.h"
#include "board.h"
#include "macros/units.h"
#include "periph_cpu.h"
// Based on datasheet 8.2.4 (1ms wait time)
#define STARTUP_DELAY 47
#define MAX_XOSC_COUNTER_SIZE 0xFFFF
#define Sleep100HzSpeed 60000
#define CYCLES_PER_MS (Sleep100HzSpeed / 1000)
void xosc_start(void) {
// Set the FREQ_RANGE
XOSC->CTRL = XOSC_CTRL_FREQ_RANGE_VALUE_1_15MHZ;
// Set the startup delay (default 1ms)
XOSC->STARTUP = STARTUP_DELAY;
// set enable bit
atomic_set(&XOSC->CTRL, XOSC_CTRL_ENABLE_VALUE_ENABLE << XOSC_CTRL_ENABLE_LSB);
while (!(XOSC->STATUS & XOSC_STATUS_STABLE_BITS)) {
// Wait for the crystal to stabilize
}
}
void xosc_sleep(int32_t milliseconds) {
for (int32_t i = 0; i < milliseconds; i++) {
XOSC->COUNT = CYCLES_PER_MS* milliseconds;
while (XOSC->COUNT != 0) {
}
}
}
void xosc_stop(void) {
// @TODO
}

View File

@ -283,6 +283,8 @@ groups:
features:
- name: cpu_rpx0xx
help: The MCU is part of the Raspberry PI RPx0xx family.
- name: cpu_rp2350
help: The MCU is a Raspberry Pi RP2350
- title: Silicon Laboratories EFM32 Grouping
features:

View File

@ -86,6 +86,7 @@ FEATURES_EXISTING := \
cpu_nrf9160 \
cpu_qn908x \
cpu_rpx0xx \
cpu_rp2350 \
cpu_sam3 \
cpu_sam4s \
cpu_samd21 \