Adding RP2350 SDK and target framework (#13988)
[betaflight.git] / lib / main / pico-sdk / rp2_common / pico_runtime_init / runtime_init.c
blob2b69c8069fa765e393b5cb9827421b0fee9944f1
1 /*
2 * Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
4 * SPDX-License-Identifier: BSD-3-Clause
5 */
7 #include "pico/runtime_init.h"
9 // This file is sorted in the order of initialization
11 // -------------------------------------
12 // 00050 PICO_RUNTIME_INIT_BOOTROM_RESET
13 // -------------------------------------
14 #if !PICO_RUNTIME_NO_INIT_BOOTROM_RESET
15 #include "pico/bootrom.h"
16 void __weak runtime_init_bootrom_reset(void) {
17 // todo can we tell if we came in thru the bootrom where this is not necessary (this is necessary for debugger)
18 rom_bootrom_state_reset_fn state_reset = rom_func_lookup(ROM_FUNC_BOOTROM_STATE_RESET);
19 state_reset(BOOTROM_STATE_RESET_GLOBAL_STATE);
21 #endif
23 #if !PICO_RUNTIME_SKIP_INIT_BOOTROM_RESET
24 PICO_RUNTIME_INIT_FUNC_RUNTIME(runtime_init_bootrom_reset, PICO_RUNTIME_INIT_BOOTROM_RESET);
25 #endif
27 // ----------------------------------------------
28 // 00051 PICO_RUNTIME_INIT_PER_CORE_BOOTROM_RESET
29 // ----------------------------------------------
30 #if !PICO_RUNTIME_NO_INIT_PER_CORE_BOOTROM_RESET
31 #include "pico/bootrom.h"
32 void __weak runtime_init_per_core_bootrom_reset(void) {
33 // todo can we tell if we came in thru the bootrom where this is not necessary (this is necessary for debugger)
34 rom_bootrom_state_reset_fn state_reset = rom_func_lookup(ROM_FUNC_BOOTROM_STATE_RESET);
35 state_reset(BOOTROM_STATE_RESET_CURRENT_CORE);
37 #endif
39 #if !PICO_RUNTIME_SKIP_INIT_PER_CORE_BOOTROM_RESET
40 PICO_RUNTIME_INIT_FUNC_PER_CORE(runtime_init_per_core_bootrom_reset, PICO_RUNTIME_INIT_PER_CORE_BOOTROM_RESET);
41 #endif
43 // ------------------------------------
44 // 00060 PICO_RUNTIME_INIT_H3_IRQ_REGISTERS
45 // ------------------------------------
46 #if !PICO_RUNTIME_SKIP_INIT_PER_CORE_H3_IRQ_REGISTERS
47 extern void runtime_init_per_core_h3_irq_registers(void);
48 PICO_RUNTIME_INIT_FUNC_PER_CORE(runtime_init_per_core_h3_irq_registers, PICO_RUNTIME_INIT_PER_CORE_H3_IRQ_REGISTERS);
49 #endif
51 // ------------------------------------
52 // 00100 PICO_RUNTIME_INIT_EARLY_RESETS
53 // ------------------------------------
54 #if !PICO_RUNTIME_NO_INIT_EARLY_RESETS
55 #include "hardware/resets.h"
56 void __weak runtime_init_early_resets(void) {
57 static_assert(NUM_RESETS <= 32, "");
58 // Reset all peripherals to put system into a known state,
59 // - except for QSPI pads and the XIP IO bank, as this is fatal if running from flash
60 // - and the PLLs, as this is fatal if clock muxing has not been reset on this boot
61 // - and USB, syscfg, as this disturbs USB-to-SWD on core 1
62 reset_block_mask(~(
63 (1u << RESET_IO_QSPI) |
64 (1u << RESET_PADS_QSPI) |
65 (1u << RESET_PLL_USB) |
66 (1u << RESET_USBCTRL) |
67 (1u << RESET_SYSCFG) |
68 (1u << RESET_PLL_SYS)
69 ));
71 // Remove reset from peripherals which are clocked only by clk_sys and
72 // clk_ref. Other peripherals stay in reset until we've configured clocks.
73 unreset_block_mask_wait_blocking(RESETS_RESET_BITS & ~(
74 #if !PICO_RP2040
75 (1u << RESET_HSTX) |
76 #endif
77 (1u << RESET_ADC) |
78 #if PICO_RP2040
79 (1u << RESET_RTC) |
80 #endif
81 (1u << RESET_SPI0) |
82 (1u << RESET_SPI1) |
83 (1u << RESET_UART0) |
84 (1u << RESET_UART1) |
85 (1u << RESET_USBCTRL)
86 ));
89 #endif
91 #if !PICO_RUNTIME_SKIP_INIT_EARLY_RESETS
92 PICO_RUNTIME_INIT_FUNC_HW(runtime_init_early_resets, PICO_RUNTIME_INIT_EARLY_RESETS);
93 #endif
95 #if !PICO_RUNTIME_NO_INIT_USB_POWER_DOWN
96 #include "hardware/structs/usb.h"
97 void __weak runtime_init_usb_power_down(void) {
98 // Ensure USB PHY is in low-power state -- must be cleared before beginning USB operations. Only
99 // do this if USB appears to be in the reset state, to avoid breaking core1-as-debugger.
100 if (usb_hw->sie_ctrl == USB_SIE_CTRL_RESET) {
101 hw_set_bits(&usb_hw->sie_ctrl, USB_SIE_CTRL_TRANSCEIVER_PD_BITS);
104 #endif
106 #if !PICO_RUNTIME_SKIP_INIT_USB_POWER_DOWN
107 PICO_RUNTIME_INIT_FUNC_HW(runtime_init_usb_power_down, PICO_RUNTIME_INIT_USB_POWER_DOWN);
108 #endif
110 #if !PICO_RUNTIME_NO_INIT_PER_CORE_ENABLE_COPROCESSORS
111 #include "hardware/gpio.h" // PICO_USE_GPIO_COPROCESSOR is defined here
112 #include "hardware/structs/m33.h"
113 // ----------------------------------------------------
114 // 00200 PICO_RUNTIME_INIT_PER_CORE_ENABLE_COPROCESSORS
115 // ----------------------------------------------------
116 void __weak runtime_init_per_core_enable_coprocessors(void) {
117 // VFP copro (float)
118 uint32_t cpacr = M33_CPACR_CP10_BITS;
119 #if HAS_DOUBLE_COPROCESSOR
120 cpacr |= M33_CPACR_CP4_BITS;
121 #endif
122 #if PICO_USE_GPIO_COPROCESSOR
123 cpacr |= M33_CPACR_CP0_BITS;
124 #endif
125 arm_cpu_hw->cpacr |= cpacr;
126 #if HAS_DOUBLE_COPROCESSOR
127 asm volatile ("mrc p4,#0,r0,c0,c0,#1" : : : "r0"); // clear engaged flag via RCMP
128 #endif
130 #endif
132 #if !PICO_RUNTIME_SKIP_INIT_PER_CORE_ENABLE_COPROCESSORS
133 PICO_RUNTIME_INIT_FUNC_PER_CORE(runtime_init_per_core_enable_coprocessors, PICO_RUNTIME_INIT_PER_CORE_ENABLE_COPROCESSORS);
134 #endif
136 // ----------------------------------------------------
137 // 00500 PICO_RUNTIME_INIT_CLOCKS
138 // ----------------------------------------------------
139 #if !PICO_RUNTIME_SKIP_INIT_CLOCKS
140 PICO_RUNTIME_INIT_FUNC_HW(runtime_init_clocks, PICO_RUNTIME_INIT_CLOCKS);
141 #endif
143 // ----------------------------------------------------
144 // 00600 PICO_RUNTIME_INIT_POST_CLOCK_RESETS
145 // ----------------------------------------------------
146 #if !PICO_RUNTIME_NO_INIT_POST_CLOCK_RESETS
147 #include "hardware/resets.h"
148 void __weak runtime_init_post_clock_resets(void) {
149 // Peripheral clocks should now all be running
150 static_assert(NUM_RESETS <= 32, "");
151 unreset_block_mask_wait_blocking(RESETS_RESET_BITS);
153 #endif
155 #if !PICO_RUNTIME_SKIP_POST_CLOCK_RESETS
156 PICO_RUNTIME_INIT_FUNC_HW(runtime_init_post_clock_resets, PICO_RUNTIME_INIT_POST_CLOCK_RESETS);
157 #endif
159 // ----------------------------------------------------
160 // 00700 PICO_RUNTIME_INIT_RP2040_GPIO_IE_DISABLE
161 // ----------------------------------------------------
163 #if !PICO_RUNTIME_NO_INIT_RP2040_GPIO_IE_DISABLE
164 #include "hardware/structs/pads_bank0.h"
165 void __weak runtime_init_rp2040_gpio_ie_disable(void) {
166 #if PICO_RP2040 && !PICO_IE_26_29_UNCHANGED_ON_RESET
167 // after resetting BANK0 we should disable IE on 26-29 as these may have mid-rail voltages when
168 // ADC is in use (on RP2040 B2 and later, and non-RP2040 chips, ADC pins should already have
169 // the correct reset state):
170 pads_bank0_hw_t *pads_bank0_hw_clear = (pads_bank0_hw_t *)hw_clear_alias_untyped(pads_bank0_hw);
171 pads_bank0_hw_clear->io[26] = pads_bank0_hw_clear->io[27] =
172 pads_bank0_hw_clear->io[28] = pads_bank0_hw_clear->io[29] = PADS_BANK0_GPIO0_IE_BITS;
173 #endif
175 #endif
177 #if !PICO_RUNTIME_SKIP_INIT_RP2040_GPIO_IE_DISABLE
178 PICO_RUNTIME_INIT_FUNC_HW(runtime_init_rp2040_gpio_ie_disable, PICO_RUNTIME_INIT_RP2040_GPIO_IE_DISABLE);
179 #endif
181 #if !PICO_RUNTIME_NO_INIT_SPIN_LOCKS_RESET
182 #include "hardware/sync.h"
183 void __weak runtime_init_spin_locks_reset(void) {
184 spin_locks_reset();
186 #endif
188 #if !PICO_RUNTIME_SKIP_INIT_SPIN_LOCKS_RESET
189 PICO_RUNTIME_INIT_FUNC_RUNTIME(runtime_init_spin_locks_reset, PICO_RUNTIME_INIT_SPIN_LOCKS_RESET);
190 #endif
192 // On RISC-V the vector table is not relocatable since it contains PC-relative
193 // jump instructions, so rather than copying it into a RAM-resident array, we
194 // just link it in an initialised RAM section. Note there is no requirement on
195 // RISC-V to have an initial flash-resident vector table at a well-known
196 // location, unlike Cortex-M which can take an NMI on cycle 0.
197 #ifndef __riscv
199 #if !PICO_RUNTIME_NO_INIT_INSTALL_RAM_VECTOR_TABLE
200 uint32_t __attribute__((section(".ram_vector_table"))) ram_vector_table[PICO_RAM_VECTOR_TABLE_SIZE];
202 #include "hardware/structs/scb.h"
203 void runtime_init_install_ram_vector_table(void) {
204 // Note on RISC-V the RAM vector table is initialised during crt0
205 #if !(PICO_NO_RAM_VECTOR_TABLE || PICO_NO_FLASH) && !defined(__riscv)
206 #if !PICO_NO_STORED_VECTOR_TABLE
207 __builtin_memcpy(ram_vector_table, (uint32_t *) scb_hw->vtor, sizeof(ram_vector_table));
208 #else
209 __builtin_memcpy(ram_vector_table, (uint32_t *) scb_hw->vtor, MIN(VTABLE_FIRST_IRQ, sizeof(ram_vector_table)));
210 for(uint i = VTABLE_FIRST_IRQ; i<count_of(ram_vector_table); i++) {
211 ram_vector_table[i] = (uintptr_t)__unhandled_user_irq;
213 #endif
215 scb_hw->vtor = (uintptr_t) ram_vector_table;
216 #endif
218 #endif
219 #endif
221 #if !PICO_RUNTIME_SKIP_INIT_INSTALL_RAM_VECTOR_TABLE
222 // todo this wants to be per core if we decide to support per core vector tables
223 PICO_RUNTIME_INIT_FUNC_RUNTIME(runtime_init_install_ram_vector_table, PICO_RUNTIME_INIT_INSTALL_RAM_VECTOR_TABLE);
224 #endif