1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 04:15:44 +03:00

Adding RP2350 SDK and target framework (#13988)

* Adding RP2350 SDK and target framework

* Spacing

* Removing board definitions
This commit is contained in:
J Blackman 2024-10-23 10:02:48 +11:00 committed by GitHub
parent 462cb05930
commit 2dd6f95aad
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
576 changed files with 435012 additions and 0 deletions

View file

@ -0,0 +1,455 @@
/*
* Copyright (c) 2024 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _PICO_RUNTIME_INITS_H
#define _PICO_RUNTIME_INITS_H
#include "pico.h"
#include "pico/runtime.h"
#ifdef __cplusplus
extern "C" {
#endif
/** \file pico/runtime_init.h
* \defgroup pico_runtime_init pico_runtime_init
*
* \brief Main runtime initialization functions required to set up the runtime environment before entering main
*
* The runtime initialization is registration based:
*
* For each step of the initialization there is a 5 digit ordinal which indicates
* the ordering (alphabetic increasing sort of the 5 digits) of the steps.
*
* e.g. for the step "bootrom_reset", there is:
*
* \code
* #ifndef PICO_RUNTIME_INIT_BOOTROM_RESET
* #define PICO_RUNTIME_INIT_BOOTROM_RESET "00050"
* #endif
* \endcode
*
* The user can override the order if they wish, by redefining PICO_RUNTIME_INIT_BOOTROM_RESET
*
* For each step, the automatic initialization may be skipped by defining (in this case)
* PICO_RUNTIME_SKIP_INIT_BOOTROM_RESET = 1. The user can then choose to either omit the step
* completely or register their own replacement initialization.
*
* The default method used to perform the initialization is provided, in case the user
* wishes to call it manually; in this case:
*
* \code
* void runtime_init_bootrom_reset(void);
* \endcode
*
* If PICO_RUNTIME_NO_INIT_BOOTOROM_RESET define is set (NO vs SKIP above), then the function
* is not defined, allowing the user to provide a replacement (and also avoiding
* cases where the default implementation won't compile due to missing dependencies)
*/
// must have no dependency on any other initialization code
#define PICO_RUNTIME_INIT_EARLIEST "00001"
// -----------------------------------------------------------------------------------------------
// Reset of global bootrom state (can be skipped if boot path was via bootrom); not used on RP2040
// -----------------------------------------------------------------------------------------------
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_BOOTROM_RESET, Skip calling of `runtime_init_bootrom_reset` function during runtime init, type=bool, default=1 on RP2040, group=pico_runtime_init
// PICO_CONFIG: PICO_RUNTIME_NO_INIT_BOOTROM_RESET, Do not include SDK implementation of `runtime_init_bootrom_reset` function, type=bool, default=1 on RP2040, group=pico_runtime_init
#ifndef PICO_RUNTIME_INIT_BOOTROM_RESET
#define PICO_RUNTIME_INIT_BOOTROM_RESET "00050"
#endif
#ifndef PICO_RUNTIME_SKIP_INIT_BOOTROM_RESET
#if PICO_RP2040 || (!LIB_PICO_MULTICORE && PICO_NO_FLASH)
#define PICO_RUNTIME_SKIP_INIT_BOOTROM_RESET 1
#endif
#endif
#ifndef PICO_RUNTIME_NO_INIT_BOOTROM_RESET
#if PICO_RP2040 || (!LIB_PICO_MULTICORE && PICO_NO_FLASH)
#define PICO_RUNTIME_NO_INIT_BOOTROM_RESET 1
#endif
#endif
#ifndef __ASSEMBLER__
void runtime_init_bootrom_reset(void);
#endif
// ---------------------------------------------------------------------------------------
// Non-boot core eset of bootrom state, not needed if only using core 0 not used on RP2040
// ---------------------------------------------------------------------------------------
#ifndef PICO_RUNTIME_INIT_PER_CORE_BOOTROM_RESET
#define PICO_RUNTIME_INIT_PER_CORE_BOOTROM_RESET "00051"
#endif
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_PER_CORE_BOOTROM_RESET, Skip calling of `runtime_init_per_core_bootrom_reset` function during per-core init, type=bool, default=1 on RP2040, group=pico_runtime_init
// PICO_CONFIG: PICO_RUNTIME_NO_INIT_PER_CORE_BOOTROM_RESET, Do not include SDK implementation of `runtime_init_per_core_bootrom_reset` function, type=bool, default=1 on RP2040, group=pico_runtime_init
#ifndef PICO_RUNTIME_SKIP_INIT_PER_CORE_BOOTROM_RESET
#if PICO_RP2040
#define PICO_RUNTIME_SKIP_INIT_PER_CORE_BOOTROM_RESET 1
#endif
#endif
#ifndef PICO_RUNTIME_NO_INIT_PER_CORE_BOOTROM_RESET
#if PICO_RP2040
#define PICO_RUNTIME_NO_INIT_PER_CORE_BOOTROM_RESET 1
#endif
#endif
#ifndef __ASSEMBLER__
void runtime_init_per_core_bootrom_reset(void);
#endif
// ---------------------------
// Hazard3 processor IRQ setup
// ---------------------------
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_PER_CORE_H3_IRQ_REGISTERS, Skip calling of `runtime_init_per_core_h3_irq_registers` function during per-core init, type=bool, default=1 on non RISC-V, group=pico_runtime_init
#ifndef PICO_RUNTIME_INIT_PER_CORE_H3_IRQ_REGISTERS
#define PICO_RUNTIME_INIT_PER_CORE_H3_IRQ_REGISTERS "00060"
#endif
#ifndef PICO_RUNTIME_SKIP_INIT_PER_CORE_H3_IRQ_REGISTERS
#ifndef __riscv
#define PICO_RUNTIME_SKIP_INIT_PER_CORE_H3_IRQ_REGISTERS 1
#endif
#endif
// -------------------------------
// Earliest resets (no clocks yet)
// -------------------------------
#ifndef PICO_RUNTIME_INIT_EARLY_RESETS
#define PICO_RUNTIME_INIT_EARLY_RESETS "00100"
#endif
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_EARLY_RESETS, Skip calling of `runtime_init_early_resets` function during runtime init, type=bool, default=1 on RP2040, group=pico_runtime_init
// PICO_CONFIG: PICO_RUNTIME_NO_INIT_EARLY_RESETS, Do not include SDK implementation of `runtime_init_early_resets` function, type=bool, default=1 on RP2040, group=pico_runtime_init
#ifndef PICO_RUNTIME_SKIP_INIT_EARLY_RESETS
#define PICO_RUNTIME_SKIP_INIT_EARLY_RESETS 0
#endif
#ifndef PICO_RUNTIME_NO_INIT_EARLY_RESETS
#define PICO_RUNTIME_NO_INIT_EARLY_RESETS 0
#endif
#ifndef __ASSEMBLER__
void runtime_init_early_resets(void);
#endif
// --------------
// USB power down
// --------------
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_USB_POWER_DOWN, Skip calling of `runtime_init_usb_power_down` function during runtime init, type=bool, default=0, group=pico_runtime_init
// PICO_CONFIG: PICO_RUNTIME_NO_INIT_USB_POWER_DOWN, Do not include SDK implementation of `runtime_init_usb_power_down` function, type=bool, default=0, group=pico_runtime_init
#ifndef PICO_RUNTIME_INIT_USB_POWER_DOWN
#define PICO_RUNTIME_INIT_USB_POWER_DOWN "00101"
#endif
#ifndef PICO_RUNTIME_SKIP_INIT_USB_POWER_DOWN
#define PICO_RUNTIME_SKIP_INIT_USB_POWER_DOWN 0
#endif
#ifndef PICO_RUNTIME_NO_INIT_USB_POWER_DOWN
#define PICO_RUNTIME_NO_INIT_USB_POWER_DOWN 0
#endif
#ifndef __ASSEMBLER__
void runtime_init_usb_power_down(void);
#endif
// ------------------------------------
// per core co-processor initialization
// ------------------------------------
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_PER_CORE_ENABLE_COPROCESSORS, Skip calling of `runtime_init_per_core_enable_coprocessors` function during per-core init, type=bool, default=1 on RP2040 or RISC-V, group=pico_runtime_init
// PICO_CONFIG: PICO_RUNTIME_NO_INIT_PER_CORE_ENABLE_COPROCESSORS, Do not include SDK implementation of `runtime_init_per_core_enable_coprocessors` function, type=bool, default=1 on RP2040 or RISC-V, group=pico_runtime_init
#ifndef PICO_RUNTIME_INIT_PER_CORE_ENABLE_COPROCESSORS
#define PICO_RUNTIME_INIT_PER_CORE_ENABLE_COPROCESSORS "00200"
#endif
#ifndef PICO_RUNTIME_SKIP_INIT_PER_CORE_ENABLE_COPROCESSORS
#if PICO_RP2040 || defined(__riscv)
#define PICO_RUNTIME_SKIP_INIT_PER_CORE_ENABLE_COPROCESSORS 1
#endif
#endif
#ifndef PICO_RUNTIME_NO_INIT_PER_CORE_ENABLE_COPROCESSORS
#if PICO_RP2040 || defined(__riscv)
#define PICO_RUNTIME_NO_INIT_PER_CORE_ENABLE_COPROCESSORS 1
#endif
#endif
#ifndef __ASSEMBLER__
void runtime_init_per_core_enable_coprocessors(void);
#endif
// AEABI init; this initialization is auto-injected byte pico_aeebi_mem_ops if present
#ifndef PICO_RUNTIME_INIT_AEABI_MEM_OPS
// on RP2040 we need to get memcpy and memset hooked up to bootrom
#define PICO_RUNTIME_INIT_AEABI_MEM_OPS "00300"
#endif
// AEABI init; this initialization is auto-injected byte pico_aeebi_bit_ops if present
#ifndef PICO_RUNTIME_INIT_AEABI_BIT_OPS
#define PICO_RUNTIME_INIT_AEABI_BIT_OPS "00275"
#endif
// AEABI init; this initialization is auto-injected byte pico_aeebi_float if present
#ifndef PICO_RUNTIME_INIT_AEABI_FLOAT
#define PICO_RUNTIME_INIT_AEABI_FLOAT "00350"
#endif
// AEABI init; this initialization is auto-injected byte pico_aeebi_double if present
#ifndef PICO_RUNTIME_INIT_AEABI_DOUBLE
#define PICO_RUNTIME_INIT_AEABI_DOUBLE "00350"
#endif
// ------------------------
// Initialization of clocks
// ------------------------
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_CLOCKS, Skip calling of `runtime_init_clocks` function during runtime init, type=bool, default=0, group=pico_runtime_init
// PICO_CONFIG: PICO_RUNTIME_NO_INIT_CLOCKS, Do not include SDK implementation of `runtime_init_clocks` function, type=bool, default=0, group=pico_runtime_init
#ifndef PICO_RUNTIME_INIT_CLOCKS
// on RP2040 we need some of the AEABI init by this point to do clock math
#define PICO_RUNTIME_INIT_CLOCKS "00500"
#endif
#ifndef PICO_RUNTIME_SKIP_INIT_CLOCKS
#define PICO_RUNTIME_SKIP_INIT_CLOCKS 0
#endif
#ifndef PICO_RUNTIME_NO_INIT_CLOCKS
#define PICO_RUNTIME_NO_INIT_CLOCKS 0
#endif
#ifndef __ASSEMBLER__
void runtime_init_clocks(void);
/*! \brief Initialise the clock hardware
* \ingroup pico_runtime_init
*
* Must be called before any other clock function.
*/
static inline void clocks_init(void) {
// backwards compatibility with earlier SDK
runtime_init_clocks();
}
#endif
// ----------------------------------------
// Remaining h/w initialization post clocks
// ----------------------------------------
#ifndef PICO_RUNTIME_INIT_POST_CLOCK_RESETS
#define PICO_RUNTIME_INIT_POST_CLOCK_RESETS "00600"
#endif
// PICO_RUNTIME_INIT_POST_CLOCKS_RESETS defaults to 0
#ifndef __ASSEMBLER__
void runtime_init_post_clock_resets(void);
#endif
// ----------------------------------------
// RP2040 IE disable for GPIO 26-29
// ----------------------------------------
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_RP2040_GPIO_IE_DISABLE, Skip calling of `runtime_init_rp2040_gpio_ie_disable` function during runtime init, type=bool, default=0 on RP2040, group=pico_runtime_init
// PICO_CONFIG: PICO_RUNTIME_NO_INIT_RP2040_GPIO_IE_DISABLE, Do not include SDK implementation of `runtime_init_rp2040_gpio_ie_disable` function, type=bool, default=0 on RP2040, group=pico_runtime_init
#ifndef PICO_RUNTIME_INIT_RP2040_GPIO_IE_DISABLE
#define PICO_RUNTIME_INIT_RP2040_GPIO_IE_DISABLE "00700"
#endif
#ifndef PICO_RUNTIME_SKIP_INIT_RP2040_GPIO_IE_DISABLE
#if !PICO_RP2040 || PICO_IE_26_29_UNCHANGED_ON_RESET
#define PICO_RUNTIME_SKIP_INIT_RP2040_GPIO_IE_DISABLE 1
#endif
#endif
#ifndef PICO_RUNTIME_NO_INIT_RP2040_GPIO_IE_DISABLE
#if !PICO_RP2040
#define PICO_RUNTIME_NO_INIT_RP2040_GPIO_IE_DISABLE 1
#endif
#endif
#ifndef __ASSEMBLER__
void runtime_init_rp2040_gpio_ie_disable(void);
#endif
// -----------------------------
// Reset all spin SIO spin locks
// -----------------------------
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_SPIN_LOCKS_RESET, Skip calling of `runtime_init_spin_locks_reset` function during runtime init, type=bool, default=0, group=pico_runtime_init
// PICO_CONFIG: PICO_RUNTIME_NO_INIT_SPIN_LOCKS_RESET, Do not include SDK implementation of `runtime_init_spin_locks_reset` function, type=bool, default=0, group=pico_runtime_init
#ifndef PICO_RUNTIME_INIT_SPIN_LOCKS_RESET
// clearing of all spin locks
#define PICO_RUNTIME_INIT_SPIN_LOCKS_RESET "01000"
#endif
#ifndef PICO_RUNTIME_SKIP_INIT_SPIN_LOCKS_RESET
#define PICO_RUNTIME_SKIP_INIT_SPIN_LOCKS_RESET 0
#endif
#ifndef PICO_RUNTIME_NO_INIT_SPIN_LOCKS_RESET
#define PICO_RUNTIME_NO_INIT_SPIN_LOCKS_RESET 0
#endif
#ifndef __ASSEMBLER__
void runtime_init_spin_locks_reset(void);
#endif
// -----------------------------
// Reset all bootram boot locks
// -----------------------------
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_BOOT_LOCKS_RESET, Skip calling of `runtime_init_boot_locks_reset` function during runtime init, type=bool, default=0, group=pico_runtime_init
#ifndef PICO_RUNTIME_INIT_BOOT_LOCKS_RESET
// clearing of all spin locks
#define PICO_RUNTIME_INIT_BOOT_LOCKS_RESET "01000"
#endif
#ifndef PICO_RUNTIME_SKIP_INIT_BOOT_LOCKS_RESET
#define PICO_RUNTIME_SKIP_INIT_BOOT_LOCKS_RESET 0
#endif
#ifndef __ASSEMBLER__
void runtime_init_boot_locks_reset(void);
#endif
// ------------------------------
// Enable bootrom locking support
// ------------------------------
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_BOOTROM_LOCKING_ENABLE, Skip calling of `runtime_init_bootrom_locking_enable` function during runtime init, type=bool, default=0, group=pico_runtime_init
#ifndef PICO_RUNTIME_INIT_BOOTROM_LOCKING_ENABLE
// clearing of all spin locks
#define PICO_RUNTIME_INIT_BOOTROM_LOCKING_ENABLE "01010"
#endif
#ifndef PICO_RUNTIME_SKIP_INIT_BOOTROM_LOCKING_ENABLE
#define PICO_RUNTIME_SKIP_INIT_BOOTROM_LOCKING_ENABLE 0
#endif
#ifndef __ASSEMBLER__
void runtime_init_bootrom_locking_enable(void);
#endif
// PICO_RUNTIME_INIT_MUTEX is registered automatically by pico_sync
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_MUTEX, Skip calling of `runtime_init_mutex` function during runtime init, type=bool, default=0, group=pico_runtime_init
// PICO_CONFIG: PICO_RUNTIME_NO_INIT_MUTEX, Do not include SDK implementation of `runtime_init_mutex` function, type=bool, default=0, group=pico_runtime_init
#ifndef PICO_RUNTIME_INIT_MUTEX
// depends on SPIN_LOCKS
// initialize auto_init mutexes
#define PICO_RUNTIME_INIT_MUTEX "01100"
#endif
#ifndef PICO_RUNTIME_SKIP_INIT_MUTEX
#define PICO_RUNTIME_SKIP_INIT_MUTEX 0
#endif
#ifndef PICO_RUNTIME_NO_INIT_MUTEX
#define PICO_RUNTIME_NO_INIT_MUTEX 0
#endif
// ------------------------------------------------------------
// Initialization of IRQs, added by hardware_irq
// ------------------------------------------------------------
#ifndef PICO_RUNTIME_INIT_PER_CORE_IRQ_PRIORITIES
#define PICO_RUNTIME_INIT_PER_CORE_IRQ_PRIORITIES "01200"
#endif
// PICO_RUNTIME_SKIP_INIT_PER_CORE_TLS_SETUP defaults to 0
#ifndef PICO_RUNTIME_INIT_PER_CORE_TLS_SETUP
#define PICO_RUNTIME_INIT_PER_CORE_TLS_SETUP "10060"
#endif
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_INSTALL_RAM_VECTOR_TABLE, Skip calling of `runtime_init_install_ram_vector_table` function during runtime init, type=bool, default=0 unless RISC-V or RAM binary, group=pico_runtime_init
// PICO_CONFIG: PICO_RUNTIME_NO_INIT_INSTALL_RAM_VECTOR_TABLE, Do not include SDK implementation of `runtime_init_install_ram_vector_table` function, type=bool, default=0 unless RISC-V or RAM binary, group=pico_runtime_init
#ifndef PICO_RUNTIME_INIT_INSTALL_RAM_VECTOR_TABLE
#define PICO_RUNTIME_INIT_INSTALL_RAM_VECTOR_TABLE "10080"
#endif
// ------------------------------------------------------
// Copy of ROM vector table to RAM; not used on RISC-V or
// no_flash which has a RAM vector table anyway
// ------------------------------------------------------
#ifndef PICO_RUNTIME_SKIP_INIT_INSTALL_RAM_VECTOR_TABLE
#if PICO_NO_RAM_VECTOR_TABLE || PICO_NO_FLASH || defined(__riscv)
#define PICO_RUNTIME_SKIP_INIT_INSTALL_RAM_VECTOR_TABLE 1
#endif
#endif
#ifndef PICO_RUNTIME_NO_INIT_INSTALL_RAM_VECTOR_TABLE
#if PICO_NO_RAM_VECTOR_TABLE || PICO_NO_FLASH || defined(__riscv)
#define PICO_RUNTIME_NO_INIT_INSTALL_RAM_VECTOR_TABLE 1
#endif
#endif
// ------------------------------------------------------------
// Default alarm pool initialization, added by pico_time unless
// PICO_TIME_DEFAULT_ALARM_POOL_DISABLED == 1
// ------------------------------------------------------------
#ifndef PICO_RUNTIME_INIT_DEFAULT_ALARM_POOL
#define PICO_RUNTIME_INIT_DEFAULT_ALARM_POOL "11000"
#endif
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_DEFAULT_ALARM_POOL, Skip calling of `runtime_init_default_alarm_pool` function during runtime init, type=bool, default=1 if `PICO_TIME_DEFAULT_ALARM_POOL_DISABLED` is 1, group=pico_runtime_init
// PICO_CONFIG: PICO_RUNTIME_NO_INIT_DEFAULT_ALARM_POOL, Do not include SDK implementation of `runtime_init_default_alarm_pool` function, type=bool, default=1 if `PICO_TIME_DEFAULT_ALARM_POOL_DISABLED` is , group=pico_runtime_init
#ifndef PICO_RUNTIME_SKIP_INIT_DEFAULT_ALARM_POOL
#if PICO_TIME_DEFAULT_ALARM_POOL_DISABLED
#define PICO_RUNTIME_SKIP_INIT_DEFAULT_ALARM_POOL 1
#endif
#endif
#ifndef PICO_RUNTIME_NO_INIT_DEFAULT_ALARM_POOL
#if PICO_TIME_DEFAULT_ALARM_POOL_DISABLED
#define PICO_RUNTIME_NO_INIT_DEFAULT_ALARM_POOL 1
#endif
#endif
// ------------------------------------------------------------------------------------------------
// stack guard; these are a special case as they take a parameter; however the normal defines apply
// ------------------------------------------------------------------------------------------------
// PICO_CONFIG: PICO_RUNTIME_SKIP_INIT_PER_CORE_INSTALL_STACK_GUARD, Skip calling of `runtime_init_per_core_install_stack_guard` function during runtime init, type=bool, default=1 unless `PICO_USE_STACK_GUARDS` is 1, group=pico_runtime_init
// PICO_CONFIG: PICO_RUNTIME_NO_INIT_PER_CORE_INSTALL_STACK_GUARD, Do not include SDK implementation of `runtime_init_per_core_install_stack_guard` function, type=bool, default=1 unless `PICO_USE_STACK_GUARDS` is 1, group=pico_runtime_init
#ifndef PICO_RUNTIME_INIT_PER_CORE_INSTALL_STACK_GUARD
#define PICO_RUNTIME_INIT_PER_CORE_INSTALL_STACK_GUARD "10050"
#endif
#ifndef PICO_RUNTIME_SKIP_INIT_PER_CORE_INSTALL_STACK_GUARD
#if !PICO_USE_STACK_GUARDS
#define PICO_RUNTIME_SKIP_INIT_PER_CORE_INSTALL_STACK_GUARD 1
#endif
#endif
#ifndef PICO_RUNTIME_NO_INIT_PER_CORE_INSTALL_STACK_GUARD
#if !PICO_USE_STACK_GUARDS
#define PICO_RUNTIME_NO_INIT_PER_CORE_INSTALL_STACK_GUARD 1
#endif
#endif
#ifndef __ASSEMBLER__
void runtime_init_per_core_install_stack_guard(void *stack_bottom);
// backwards compatibility
static __force_inline void runtime_install_stack_guard(void *stack_bottom) {
runtime_init_per_core_install_stack_guard(stack_bottom);
}
#endif
#ifdef __cplusplus
}
#endif
#endif

View file

@ -0,0 +1,224 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "pico/runtime_init.h"
// This file is sorted in the order of initialization
// -------------------------------------
// 00050 PICO_RUNTIME_INIT_BOOTROM_RESET
// -------------------------------------
#if !PICO_RUNTIME_NO_INIT_BOOTROM_RESET
#include "pico/bootrom.h"
void __weak runtime_init_bootrom_reset(void) {
// todo can we tell if we came in thru the bootrom where this is not necessary (this is necessary for debugger)
rom_bootrom_state_reset_fn state_reset = rom_func_lookup(ROM_FUNC_BOOTROM_STATE_RESET);
state_reset(BOOTROM_STATE_RESET_GLOBAL_STATE);
}
#endif
#if !PICO_RUNTIME_SKIP_INIT_BOOTROM_RESET
PICO_RUNTIME_INIT_FUNC_RUNTIME(runtime_init_bootrom_reset, PICO_RUNTIME_INIT_BOOTROM_RESET);
#endif
// ----------------------------------------------
// 00051 PICO_RUNTIME_INIT_PER_CORE_BOOTROM_RESET
// ----------------------------------------------
#if !PICO_RUNTIME_NO_INIT_PER_CORE_BOOTROM_RESET
#include "pico/bootrom.h"
void __weak runtime_init_per_core_bootrom_reset(void) {
// todo can we tell if we came in thru the bootrom where this is not necessary (this is necessary for debugger)
rom_bootrom_state_reset_fn state_reset = rom_func_lookup(ROM_FUNC_BOOTROM_STATE_RESET);
state_reset(BOOTROM_STATE_RESET_CURRENT_CORE);
}
#endif
#if !PICO_RUNTIME_SKIP_INIT_PER_CORE_BOOTROM_RESET
PICO_RUNTIME_INIT_FUNC_PER_CORE(runtime_init_per_core_bootrom_reset, PICO_RUNTIME_INIT_PER_CORE_BOOTROM_RESET);
#endif
// ------------------------------------
// 00060 PICO_RUNTIME_INIT_H3_IRQ_REGISTERS
// ------------------------------------
#if !PICO_RUNTIME_SKIP_INIT_PER_CORE_H3_IRQ_REGISTERS
extern void runtime_init_per_core_h3_irq_registers(void);
PICO_RUNTIME_INIT_FUNC_PER_CORE(runtime_init_per_core_h3_irq_registers, PICO_RUNTIME_INIT_PER_CORE_H3_IRQ_REGISTERS);
#endif
// ------------------------------------
// 00100 PICO_RUNTIME_INIT_EARLY_RESETS
// ------------------------------------
#if !PICO_RUNTIME_NO_INIT_EARLY_RESETS
#include "hardware/resets.h"
void __weak runtime_init_early_resets(void) {
static_assert(NUM_RESETS <= 32, "");
// 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
reset_block_mask(~(
(1u << RESET_IO_QSPI) |
(1u << RESET_PADS_QSPI) |
(1u << RESET_PLL_USB) |
(1u << RESET_USBCTRL) |
(1u << RESET_SYSCFG) |
(1u << RESET_PLL_SYS)
));
// Remove reset from peripherals which are clocked only by clk_sys and
// clk_ref. Other peripherals stay in reset until we've configured clocks.
unreset_block_mask_wait_blocking(RESETS_RESET_BITS & ~(
#if !PICO_RP2040
(1u << RESET_HSTX) |
#endif
(1u << RESET_ADC) |
#if PICO_RP2040
(1u << RESET_RTC) |
#endif
(1u << RESET_SPI0) |
(1u << RESET_SPI1) |
(1u << RESET_UART0) |
(1u << RESET_UART1) |
(1u << RESET_USBCTRL)
));
}
#endif
#if !PICO_RUNTIME_SKIP_INIT_EARLY_RESETS
PICO_RUNTIME_INIT_FUNC_HW(runtime_init_early_resets, PICO_RUNTIME_INIT_EARLY_RESETS);
#endif
#if !PICO_RUNTIME_NO_INIT_USB_POWER_DOWN
#include "hardware/structs/usb.h"
void __weak runtime_init_usb_power_down(void) {
// Ensure USB PHY is in low-power state -- must be cleared before beginning USB operations. Only
// do this if USB appears to be in the reset state, to avoid breaking core1-as-debugger.
if (usb_hw->sie_ctrl == USB_SIE_CTRL_RESET) {
hw_set_bits(&usb_hw->sie_ctrl, USB_SIE_CTRL_TRANSCEIVER_PD_BITS);
}
}
#endif
#if !PICO_RUNTIME_SKIP_INIT_USB_POWER_DOWN
PICO_RUNTIME_INIT_FUNC_HW(runtime_init_usb_power_down, PICO_RUNTIME_INIT_USB_POWER_DOWN);
#endif
#if !PICO_RUNTIME_NO_INIT_PER_CORE_ENABLE_COPROCESSORS
#include "hardware/gpio.h" // PICO_USE_GPIO_COPROCESSOR is defined here
#include "hardware/structs/m33.h"
// ----------------------------------------------------
// 00200 PICO_RUNTIME_INIT_PER_CORE_ENABLE_COPROCESSORS
// ----------------------------------------------------
void __weak runtime_init_per_core_enable_coprocessors(void) {
// VFP copro (float)
uint32_t cpacr = M33_CPACR_CP10_BITS;
#if HAS_DOUBLE_COPROCESSOR
cpacr |= M33_CPACR_CP4_BITS;
#endif
#if PICO_USE_GPIO_COPROCESSOR
cpacr |= M33_CPACR_CP0_BITS;
#endif
arm_cpu_hw->cpacr |= cpacr;
#if HAS_DOUBLE_COPROCESSOR
asm volatile ("mrc p4,#0,r0,c0,c0,#1" : : : "r0"); // clear engaged flag via RCMP
#endif
}
#endif
#if !PICO_RUNTIME_SKIP_INIT_PER_CORE_ENABLE_COPROCESSORS
PICO_RUNTIME_INIT_FUNC_PER_CORE(runtime_init_per_core_enable_coprocessors, PICO_RUNTIME_INIT_PER_CORE_ENABLE_COPROCESSORS);
#endif
// ----------------------------------------------------
// 00500 PICO_RUNTIME_INIT_CLOCKS
// ----------------------------------------------------
#if !PICO_RUNTIME_SKIP_INIT_CLOCKS
PICO_RUNTIME_INIT_FUNC_HW(runtime_init_clocks, PICO_RUNTIME_INIT_CLOCKS);
#endif
// ----------------------------------------------------
// 00600 PICO_RUNTIME_INIT_POST_CLOCK_RESETS
// ----------------------------------------------------
#if !PICO_RUNTIME_NO_INIT_POST_CLOCK_RESETS
#include "hardware/resets.h"
void __weak runtime_init_post_clock_resets(void) {
// Peripheral clocks should now all be running
static_assert(NUM_RESETS <= 32, "");
unreset_block_mask_wait_blocking(RESETS_RESET_BITS);
}
#endif
#if !PICO_RUNTIME_SKIP_POST_CLOCK_RESETS
PICO_RUNTIME_INIT_FUNC_HW(runtime_init_post_clock_resets, PICO_RUNTIME_INIT_POST_CLOCK_RESETS);
#endif
// ----------------------------------------------------
// 00700 PICO_RUNTIME_INIT_RP2040_GPIO_IE_DISABLE
// ----------------------------------------------------
#if !PICO_RUNTIME_NO_INIT_RP2040_GPIO_IE_DISABLE
#include "hardware/structs/pads_bank0.h"
void __weak runtime_init_rp2040_gpio_ie_disable(void) {
#if PICO_RP2040 && !PICO_IE_26_29_UNCHANGED_ON_RESET
// after resetting BANK0 we should disable IE on 26-29 as these may have mid-rail voltages when
// ADC is in use (on RP2040 B2 and later, and non-RP2040 chips, ADC pins should already have
// the correct reset state):
pads_bank0_hw_t *pads_bank0_hw_clear = (pads_bank0_hw_t *)hw_clear_alias_untyped(pads_bank0_hw);
pads_bank0_hw_clear->io[26] = pads_bank0_hw_clear->io[27] =
pads_bank0_hw_clear->io[28] = pads_bank0_hw_clear->io[29] = PADS_BANK0_GPIO0_IE_BITS;
#endif
}
#endif
#if !PICO_RUNTIME_SKIP_INIT_RP2040_GPIO_IE_DISABLE
PICO_RUNTIME_INIT_FUNC_HW(runtime_init_rp2040_gpio_ie_disable, PICO_RUNTIME_INIT_RP2040_GPIO_IE_DISABLE);
#endif
#if !PICO_RUNTIME_NO_INIT_SPIN_LOCKS_RESET
#include "hardware/sync.h"
void __weak runtime_init_spin_locks_reset(void) {
spin_locks_reset();
}
#endif
#if !PICO_RUNTIME_SKIP_INIT_SPIN_LOCKS_RESET
PICO_RUNTIME_INIT_FUNC_RUNTIME(runtime_init_spin_locks_reset, PICO_RUNTIME_INIT_SPIN_LOCKS_RESET);
#endif
// On RISC-V the vector table is not relocatable since it contains PC-relative
// jump instructions, so rather than copying it into a RAM-resident array, we
// just link it in an initialised RAM section. Note there is no requirement on
// RISC-V to have an initial flash-resident vector table at a well-known
// location, unlike Cortex-M which can take an NMI on cycle 0.
#ifndef __riscv
#if !PICO_RUNTIME_NO_INIT_INSTALL_RAM_VECTOR_TABLE
uint32_t __attribute__((section(".ram_vector_table"))) ram_vector_table[PICO_RAM_VECTOR_TABLE_SIZE];
#include "hardware/structs/scb.h"
void runtime_init_install_ram_vector_table(void) {
// Note on RISC-V the RAM vector table is initialised during crt0
#if !(PICO_NO_RAM_VECTOR_TABLE || PICO_NO_FLASH) && !defined(__riscv)
#if !PICO_NO_STORED_VECTOR_TABLE
__builtin_memcpy(ram_vector_table, (uint32_t *) scb_hw->vtor, sizeof(ram_vector_table));
#else
__builtin_memcpy(ram_vector_table, (uint32_t *) scb_hw->vtor, MIN(VTABLE_FIRST_IRQ, sizeof(ram_vector_table)));
for(uint i = VTABLE_FIRST_IRQ; i<count_of(ram_vector_table); i++) {
ram_vector_table[i] = (uintptr_t)__unhandled_user_irq;
}
#endif
scb_hw->vtor = (uintptr_t) ram_vector_table;
#endif
}
#endif
#endif
#if !PICO_RUNTIME_SKIP_INIT_INSTALL_RAM_VECTOR_TABLE
// todo this wants to be per core if we decide to support per core vector tables
PICO_RUNTIME_INIT_FUNC_RUNTIME(runtime_init_install_ram_vector_table, PICO_RUNTIME_INIT_INSTALL_RAM_VECTOR_TABLE);
#endif

View file

@ -0,0 +1,148 @@
/*
* Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "pico/runtime_init.h"
#if !PICO_RUNTIME_NO_INIT_CLOCKS
#include "hardware/clocks.h"
#include "hardware/pll.h"
#include "hardware/ticks.h"
#include "hardware/xosc.h"
#if PICO_RP2040
#include "hardware/regs/rtc.h"
#endif
#if PICO_RP2040
// The RTC clock frequency is 48MHz divided by power of 2 (to ensure an integer
// division ratio will be used in the clocks block). A divisor of 1024 generates
// an RTC clock tick of 46875Hz. This frequency is relatively close to the
// customary 32 or 32.768kHz 'slow clock' crystals and provides good timing resolution.
#define RTC_CLOCK_FREQ_HZ (USB_CLK_HZ / 1024)
#endif
static void start_all_ticks(void) {
uint32_t cycles = clock_get_hz(clk_ref) / MHZ;
// Note RP2040 has a single tick generator in the watchdog which serves
// watchdog, system timer and M0+ SysTick; The tick generator is clocked from clk_ref
// but is now adapted by the hardware_ticks library for compatibility with RP2350
// npte: hardware_ticks library now provides an adapter for RP2040
for (int i = 0; i < (int)TICK_COUNT; ++i) {
tick_start((tick_gen_num_t)i, cycles);
}
}
void __weak runtime_init_clocks(void) {
// Note: These need setting *before* the ticks are started
if (running_on_fpga()) {
for (uint i = 0; i < CLK_COUNT; i++) {
clock_set_reported_hz(i, 48 * MHZ);
}
// clk_ref is 12MHz in both RP2040 and RP2350 FPGA
clock_set_reported_hz(clk_ref, 12 * MHZ);
// RP2040 has an extra clock, the rtc
#if HAS_RP2040_RTC
clock_set_reported_hz(clk_rtc, RTC_CLOCK_FREQ_HZ);
#endif
} else {
// Disable resus that may be enabled from previous software
clocks_hw->resus.ctrl = 0;
// Enable the xosc
xosc_init();
// Before we touch PLLs, switch sys and ref cleanly away from their aux sources.
hw_clear_bits(&clocks_hw->clk[clk_sys].ctrl, CLOCKS_CLK_SYS_CTRL_SRC_BITS);
while (clocks_hw->clk[clk_sys].selected != 0x1)
tight_loop_contents();
hw_clear_bits(&clocks_hw->clk[clk_ref].ctrl, CLOCKS_CLK_REF_CTRL_SRC_BITS);
while (clocks_hw->clk[clk_ref].selected != 0x1)
tight_loop_contents();
/// \tag::pll_init[]
pll_init(pll_sys, PLL_SYS_REFDIV, PLL_SYS_VCO_FREQ_HZ, PLL_SYS_POSTDIV1, PLL_SYS_POSTDIV2);
pll_init(pll_usb, PLL_USB_REFDIV, PLL_USB_VCO_FREQ_HZ, PLL_USB_POSTDIV1, PLL_USB_POSTDIV2);
/// \end::pll_init[]
// Configure clocks
// RP2040 CLK_REF = XOSC (usually) 12MHz / 1 = 12MHz
// RP2350 CLK_REF = XOSC (XOSC_MHZ) / N (1,2,4) = 12MHz
// clk_ref aux select is 0 because:
//
// - RP2040: no aux mux on clk_ref, so this field is don't-care.
//
// - RP2350: there is an aux mux, but we are selecting one of the
// non-aux inputs to the glitchless mux, so the aux select doesn't
// matter. The value of 0 here happens to be the sys PLL.
clock_configure_undivided(clk_ref,
CLOCKS_CLK_REF_CTRL_SRC_VALUE_XOSC_CLKSRC,
0,
XOSC_HZ);
/// \tag::configure_clk_sys[]
// CLK SYS = PLL SYS (usually) 125MHz / 1 = 125MHz
clock_configure_undivided(clk_sys,
CLOCKS_CLK_SYS_CTRL_SRC_VALUE_CLKSRC_CLK_SYS_AUX,
CLOCKS_CLK_SYS_CTRL_AUXSRC_VALUE_CLKSRC_PLL_SYS,
SYS_CLK_HZ);
/// \end::configure_clk_sys[]
// CLK USB = PLL USB 48MHz / 1 = 48MHz
clock_configure_undivided(clk_usb,
0, // No GLMUX
CLOCKS_CLK_USB_CTRL_AUXSRC_VALUE_CLKSRC_PLL_USB,
USB_CLK_HZ);
// CLK ADC = PLL USB 48MHZ / 1 = 48MHz
clock_configure_undivided(clk_adc,
0, // No GLMUX
CLOCKS_CLK_ADC_CTRL_AUXSRC_VALUE_CLKSRC_PLL_USB,
USB_CLK_HZ);
#if HAS_RP2040_RTC
// CLK RTC = PLL USB 48MHz / 1024 = 46875Hz
#if (USB_CLK_HZ % RTC_CLOCK_FREQ_HZ == 0)
// this doesn't pull in 64 bit arithmetic
clock_configure_int_divider(clk_rtc,
0, // No GLMUX
CLOCKS_CLK_RTC_CTRL_AUXSRC_VALUE_CLKSRC_PLL_USB,
USB_CLK_HZ,
USB_CLK_HZ / RTC_CLOCK_FREQ_HZ);
#else
clock_configure(clk_rtc,
0, // No GLMUX
CLOCKS_CLK_RTC_CTRL_AUXSRC_VALUE_CLKSRC_PLL_USB,
USB_CLK_HZ,
RTC_CLOCK_FREQ_HZ);
#endif
#endif
// CLK PERI = clk_sys. Used as reference clock for UART and SPI serial.
clock_configure_undivided(clk_peri,
0,
CLOCKS_CLK_PERI_CTRL_AUXSRC_VALUE_CLK_SYS,
SYS_CLK_HZ);
#if HAS_HSTX
// CLK_HSTX = clk_sys. Transmit bit clock for the HSTX peripheral.
clock_configure_undivided(clk_hstx,
0,
CLOCKS_CLK_HSTX_CTRL_AUXSRC_VALUE_CLK_SYS,
SYS_CLK_HZ);
#endif
}
// Finally, all clocks are configured so start the ticks
// The ticks use clk_ref so now that is configured we can start them
start_all_ticks();
}
#endif

View file

@ -0,0 +1,77 @@
#include "pico/runtime.h"
#if !PICO_RUNTIME_NO_INIT_PER_CORE_INSTALL_STACK_GUARD
#if PICO_RP2040
#include "hardware/structs/mpu.h"
#elif defined(__riscv)
#include "hardware/riscv.h"
#endif
// this is called for each thread since they have their own MPU
void runtime_init_per_core_install_stack_guard(void *stack_bottom) {
// this is called b4 runtime_init is complete, so beware printf or assert
uintptr_t addr = (uintptr_t) stack_bottom;
// the minimum we can protect is 32 bytes on a 32 byte boundary, so round up which will
// just shorten the valid stack range a tad
addr = (addr + 31u) & ~31u;
#if PICO_RP2040
// Armv6-M MPU
// make sure no one is using the MPU yet
if (mpu_hw->ctrl) {
// Note that it would be tempting to change this to a panic, but it happens so early, printing is not a good idea
__breakpoint();
}
// mask is 1 bit per 32 bytes of the 256 byte range... clear the bit for the segment we want
uint32_t subregion_select = 0xffu ^ (1u << ((addr >> 5u) & 7u));
mpu_hw->ctrl = 5; // enable mpu with background default map
mpu_hw->rbar = (addr & (uint)~0xff) | M0PLUS_MPU_RBAR_VALID_BITS | 0;
mpu_hw->rasr = 1 // enable region
| (0x7 << 1) // size 2^(7 + 1) = 256
| (subregion_select << 8)
| 0x10000000; // XN = disable instruction fetch; no other bits means no permissions
#elif defined(__riscv)
#if !PICO_RP2350
#error "Check PMP configuration for new platform"
#endif
// RISC-V PMP, RP2350 configuration of Hazard3: 8 non-hardwired regions,
// NAPOT only, 32-byte granule, with nonstandard PMPCFGM0 register to
// apply regions to M-mode without locking them.
// Make sure no one is using the PMP yet
bool dirty_pmp =
riscv_read_csr(pmpcfg0) != 0 ||
riscv_read_csr(pmpcfg1) != 0 ||
riscv_read_csr(RVCSR_PMPCFGM0_OFFSET) != 0;
if (dirty_pmp) {
__breakpoint();
}
// Note pmpaddr is in units of 4 bytes, so right-shift 2.
riscv_write_csr(pmpaddr0, (addr | 0x0fu) >> 2);
// Make this region inaccessible in both M-mode and U-mode (but don't lock it)
riscv_write_csr(RVCSR_PMPCFGM0_OFFSET, 0x1u);
riscv_write_csr(pmpcfg0, RVCSR_PMPCFG0_R0_A_VALUE_NAPOT << RVCSR_PMPCFG0_R0_A_LSB);
#else
// // Armv8-M MPU
// // make sure no one is using the MPU yet
// if (mpu_hw->ctrl) {
// __breakpoint();
// }
// mpu_hw->rnr = 0;
// // Read-only, privileged-only, nonexecutable. (Good enough because stack
// // is usually written first, on a stack push)
// mpu_hw->rbar = addr | (2u << M33_MPU_RBAR_AP_LSB) | (M33_MPU_RBAR_XN_BITS);
// mpu_hw->rlar = addr | M33_MPU_RLAR_EN_BITS;
// // Enable MPU (and leave default attributes applied even for privileged software)
// mpu_hw->ctrl = M33_MPU_CTRL_PRIVDEFENA_BITS | M33_MPU_CTRL_ENABLE_BITS;
pico_default_asm_volatile(
"msr msplim, %0"
:
: "r" (stack_bottom));
#endif
}
#endif