nano_rp2040_connect/
main.rs

1// Licensed under the Apache License, Version 2.0 or the MIT License.
2// SPDX-License-Identifier: Apache-2.0 OR MIT
3// Copyright Tock Contributors 2022.
4
5//! Tock kernel for the Arduino Nano RP2040 Connect.
6//!
7//! It is based on RP2040SoC SoC (Cortex M0+).
8
9#![no_std]
10// Disable this attribute when documenting, as a workaround for
11// https://github.com/rust-lang/rust/issues/62184.
12#![cfg_attr(not(doc), no_main)]
13#![deny(missing_docs)]
14
15use core::ptr::{addr_of, addr_of_mut};
16
17use capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm;
18use components::gpio::GpioComponent;
19use components::led::LedsComponent;
20use enum_primitive::cast::FromPrimitive;
21use kernel::component::Component;
22use kernel::debug;
23use kernel::hil::led::LedHigh;
24use kernel::hil::usb::Client;
25use kernel::platform::{KernelResources, SyscallDriverLookup};
26use kernel::scheduler::round_robin::RoundRobinSched;
27use kernel::syscall::SyscallDriver;
28use kernel::{capabilities, create_capability, static_init, Kernel};
29use rp2040::adc::{Adc, Channel};
30use rp2040::chip::{Rp2040, Rp2040DefaultPeripherals};
31use rp2040::clocks::{
32    AdcAuxiliaryClockSource, PeripheralAuxiliaryClockSource, PllClock,
33    ReferenceAuxiliaryClockSource, ReferenceClockSource, RtcAuxiliaryClockSource,
34    SystemAuxiliaryClockSource, SystemClockSource, UsbAuxiliaryClockSource,
35};
36use rp2040::gpio::{GpioFunction, RPGpio, RPGpioPin};
37use rp2040::resets::Peripheral;
38use rp2040::timer::RPTimer;
39mod io;
40
41use rp2040::sysinfo;
42
43mod flash_bootloader;
44
45/// Allocate memory for the stack
46#[no_mangle]
47#[link_section = ".stack_buffer"]
48pub static mut STACK_MEMORY: [u8; 0x1500] = [0; 0x1500];
49
50// Manually setting the boot header section that contains the FCB header
51#[used]
52#[link_section = ".flash_bootloader"]
53static FLASH_BOOTLOADER: [u8; 256] = flash_bootloader::FLASH_BOOTLOADER;
54
55// State for loading and holding applications.
56// How should the kernel respond when a process faults.
57const FAULT_RESPONSE: capsules_system::process_policies::PanicFaultPolicy =
58    capsules_system::process_policies::PanicFaultPolicy {};
59
60// Number of concurrent processes this platform supports.
61const NUM_PROCS: usize = 4;
62
63static mut PROCESSES: [Option<&'static dyn kernel::process::Process>; NUM_PROCS] =
64    [None; NUM_PROCS];
65
66static mut CHIP: Option<&'static Rp2040<Rp2040DefaultPeripherals>> = None;
67static mut PROCESS_PRINTER: Option<&'static capsules_system::process_printer::ProcessPrinterText> =
68    None;
69
70type TemperatureRp2040Sensor = components::temperature_rp2040::TemperatureRp2040ComponentType<
71    capsules_core::virtualizers::virtual_adc::AdcDevice<'static, rp2040::adc::Adc<'static>>,
72>;
73type TemperatureDriver = components::temperature::TemperatureComponentType<TemperatureRp2040Sensor>;
74
75/// Supported drivers by the platform
76pub struct NanoRP2040Connect {
77    ipc: kernel::ipc::IPC<{ NUM_PROCS as u8 }>,
78    console: &'static capsules_core::console::Console<'static>,
79    alarm: &'static capsules_core::alarm::AlarmDriver<
80        'static,
81        VirtualMuxAlarm<'static, rp2040::timer::RPTimer<'static>>,
82    >,
83    gpio: &'static capsules_core::gpio::GPIO<'static, RPGpioPin<'static>>,
84    led: &'static capsules_core::led::LedDriver<'static, LedHigh<'static, RPGpioPin<'static>>, 1>,
85    adc: &'static capsules_core::adc::AdcVirtualized<'static>,
86    temperature: &'static TemperatureDriver,
87    ninedof: &'static capsules_extra::ninedof::NineDof<'static>,
88    lsm6dsoxtr: &'static capsules_extra::lsm6dsoxtr::Lsm6dsoxtrI2C<
89        'static,
90        capsules_core::virtualizers::virtual_i2c::I2CDevice<
91            'static,
92            rp2040::i2c::I2c<'static, 'static>,
93        >,
94    >,
95
96    scheduler: &'static RoundRobinSched<'static>,
97    systick: cortexm0p::systick::SysTick,
98}
99
100impl SyscallDriverLookup for NanoRP2040Connect {
101    fn with_driver<F, R>(&self, driver_num: usize, f: F) -> R
102    where
103        F: FnOnce(Option<&dyn SyscallDriver>) -> R,
104    {
105        match driver_num {
106            capsules_core::console::DRIVER_NUM => f(Some(self.console)),
107            capsules_core::alarm::DRIVER_NUM => f(Some(self.alarm)),
108            capsules_core::gpio::DRIVER_NUM => f(Some(self.gpio)),
109            capsules_core::led::DRIVER_NUM => f(Some(self.led)),
110            kernel::ipc::DRIVER_NUM => f(Some(&self.ipc)),
111            capsules_core::adc::DRIVER_NUM => f(Some(self.adc)),
112            capsules_extra::temperature::DRIVER_NUM => f(Some(self.temperature)),
113            capsules_extra::lsm6dsoxtr::DRIVER_NUM => f(Some(self.lsm6dsoxtr)),
114            capsules_extra::ninedof::DRIVER_NUM => f(Some(self.ninedof)),
115            _ => f(None),
116        }
117    }
118}
119
120impl KernelResources<Rp2040<'static, Rp2040DefaultPeripherals<'static>>> for NanoRP2040Connect {
121    type SyscallDriverLookup = Self;
122    type SyscallFilter = ();
123    type ProcessFault = ();
124    type Scheduler = RoundRobinSched<'static>;
125    type SchedulerTimer = cortexm0p::systick::SysTick;
126    type WatchDog = ();
127    type ContextSwitchCallback = ();
128
129    fn syscall_driver_lookup(&self) -> &Self::SyscallDriverLookup {
130        self
131    }
132    fn syscall_filter(&self) -> &Self::SyscallFilter {
133        &()
134    }
135    fn process_fault(&self) -> &Self::ProcessFault {
136        &()
137    }
138    fn scheduler(&self) -> &Self::Scheduler {
139        self.scheduler
140    }
141    fn scheduler_timer(&self) -> &Self::SchedulerTimer {
142        &self.systick
143    }
144    fn watchdog(&self) -> &Self::WatchDog {
145        &()
146    }
147    fn context_switch_callback(&self) -> &Self::ContextSwitchCallback {
148        &()
149    }
150}
151
152#[allow(dead_code)]
153extern "C" {
154    /// Entry point used for debugger
155    ///
156    /// When loaded using gdb, the Arduino Nano RP2040 Connect is not reset
157    /// by default. Without this function, gdb sets the PC to the
158    /// beginning of the flash. This is not correct, as the RP2040
159    /// has a more complex boot process.
160    ///
161    /// This function is set to be the entry point for gdb and is used
162    /// to send the RP2040 back in the bootloader so that all the boot
163    /// sequence is performed.
164    fn jump_to_bootloader();
165}
166
167#[cfg(any(doc, all(target_arch = "arm", target_os = "none")))]
168core::arch::global_asm!(
169    "
170    .section .jump_to_bootloader, \"ax\"
171    .global jump_to_bootloader
172    .thumb_func
173  jump_to_bootloader:
174    movs r0, #0
175    ldr r1, =(0xe0000000 + 0x0000ed08)
176    str r0, [r1]
177    ldmia r0!, {{r1, r2}}
178    msr msp, r1
179    bx r2
180    "
181);
182
183fn init_clocks(peripherals: &Rp2040DefaultPeripherals) {
184    // Start tick in watchdog
185    peripherals.watchdog.start_tick(12);
186
187    // Disable the Resus clock
188    peripherals.clocks.disable_resus();
189
190    // Setup the external Osciallator
191    peripherals.xosc.init();
192
193    // disable ref and sys clock aux sources
194    peripherals.clocks.disable_sys_aux();
195    peripherals.clocks.disable_ref_aux();
196
197    peripherals
198        .resets
199        .reset(&[Peripheral::PllSys, Peripheral::PllUsb]);
200    peripherals
201        .resets
202        .unreset(&[Peripheral::PllSys, Peripheral::PllUsb], true);
203
204    // Configure PLLs (from Pico SDK)
205    //                   REF     FBDIV VCO            POSTDIV
206    // PLL SYS: 12 / 1 = 12MHz * 125 = 1500MHZ / 6 / 2 = 125MHz
207    // PLL USB: 12 / 1 = 12MHz * 40  = 480 MHz / 5 / 2 =  48MHz
208
209    // It seems that the external osciallator is clocked at 12 MHz
210
211    peripherals
212        .clocks
213        .pll_init(PllClock::Sys, 12, 1, 1500 * 1000000, 6, 2);
214    peripherals
215        .clocks
216        .pll_init(PllClock::Usb, 12, 1, 480 * 1000000, 5, 2);
217
218    // pico-sdk: // CLK_REF = XOSC (12MHz) / 1 = 12MHz
219    peripherals.clocks.configure_reference(
220        ReferenceClockSource::Xosc,
221        ReferenceAuxiliaryClockSource::PllUsb,
222        12000000,
223        12000000,
224    );
225    // pico-sdk: CLK SYS = PLL SYS (125MHz) / 1 = 125MHz
226    peripherals.clocks.configure_system(
227        SystemClockSource::Auxiliary,
228        SystemAuxiliaryClockSource::PllSys,
229        125000000,
230        125000000,
231    );
232    // pico-sdk: CLK USB = PLL USB (48MHz) / 1 = 48MHz
233    peripherals
234        .clocks
235        .configure_usb(UsbAuxiliaryClockSource::PllSys, 48000000, 48000000);
236    // pico-sdk: CLK ADC = PLL USB (48MHZ) / 1 = 48MHz
237    peripherals
238        .clocks
239        .configure_adc(AdcAuxiliaryClockSource::PllUsb, 48000000, 48000000);
240    // pico-sdk: CLK RTC = PLL USB (48MHz) / 1024 = 46875Hz
241    peripherals
242        .clocks
243        .configure_rtc(RtcAuxiliaryClockSource::PllSys, 48000000, 46875);
244    // pico-sdk:
245    // CLK PERI = clk_sys. Used as reference clock for Peripherals. No dividers so just select and enable
246    // Normally choose clk_sys or clk_usb
247    peripherals
248        .clocks
249        .configure_peripheral(PeripheralAuxiliaryClockSource::System, 125000000);
250}
251
252/// This is in a separate, inline(never) function so that its stack frame is
253/// removed when this function returns. Otherwise, the stack space used for
254/// these static_inits is wasted.
255#[inline(never)]
256pub unsafe fn start() -> (
257    &'static kernel::Kernel,
258    NanoRP2040Connect,
259    &'static rp2040::chip::Rp2040<'static, Rp2040DefaultPeripherals<'static>>,
260) {
261    // Loads relocations and clears BSS
262    rp2040::init();
263
264    let peripherals = static_init!(Rp2040DefaultPeripherals, Rp2040DefaultPeripherals::new());
265    peripherals.resolve_dependencies();
266
267    // Reset all peripherals except QSPI (we might be booting from Flash), PLL USB and PLL SYS
268    peripherals.resets.reset_all_except(&[
269        Peripheral::IOQSpi,
270        Peripheral::PadsQSpi,
271        Peripheral::PllUsb,
272        Peripheral::PllSys,
273    ]);
274
275    // Unreset all the peripherals that do not require clock setup as they run using the sys_clk or ref_clk
276    // Wait for the peripherals to reset
277    peripherals.resets.unreset_all_except(
278        &[
279            Peripheral::Adc,
280            Peripheral::Rtc,
281            Peripheral::Spi0,
282            Peripheral::Spi1,
283            Peripheral::Uart0,
284            Peripheral::Uart1,
285            Peripheral::UsbCtrl,
286        ],
287        true,
288    );
289
290    init_clocks(peripherals);
291
292    // Unreset all peripherals
293    peripherals.resets.unreset_all_except(&[], true);
294
295    // Set the UART used for panic
296    (*addr_of_mut!(io::WRITER)).set_uart(&peripherals.uart0);
297
298    //set RX and TX pins in UART mode
299    let gpio_tx = peripherals.pins.get_pin(RPGpio::GPIO0);
300    let gpio_rx = peripherals.pins.get_pin(RPGpio::GPIO1);
301    gpio_rx.set_function(GpioFunction::UART);
302    gpio_tx.set_function(GpioFunction::UART);
303
304    // Disable IE for pads 26-29 (the Pico SDK runtime does this, not sure why)
305    for pin in 26..30 {
306        peripherals
307            .pins
308            .get_pin(RPGpio::from_usize(pin).unwrap())
309            .deactivate_pads();
310    }
311
312    let chip = static_init!(
313        Rp2040<Rp2040DefaultPeripherals>,
314        Rp2040::new(peripherals, &peripherals.sio)
315    );
316
317    CHIP = Some(chip);
318
319    let board_kernel = static_init!(Kernel, Kernel::new(&*addr_of!(PROCESSES)));
320
321    let process_management_capability =
322        create_capability!(capabilities::ProcessManagementCapability);
323    let memory_allocation_capability = create_capability!(capabilities::MemoryAllocationCapability);
324
325    let mux_alarm = components::alarm::AlarmMuxComponent::new(&peripherals.timer)
326        .finalize(components::alarm_mux_component_static!(RPTimer));
327
328    let alarm = components::alarm::AlarmDriverComponent::new(
329        board_kernel,
330        capsules_core::alarm::DRIVER_NUM,
331        mux_alarm,
332    )
333    .finalize(components::alarm_component_static!(RPTimer));
334
335    // CDC
336    let strings = static_init!(
337        [&str; 3],
338        [
339            "Arduino",                      // Manufacturer
340            "Nano RP2040 Connect - TockOS", // Product
341            "00000000000000000",            // Serial number
342        ]
343    );
344
345    let cdc = components::cdc::CdcAcmComponent::new(
346        &peripherals.usb,
347        //capsules::usb::cdc::MAX_CTRL_PACKET_SIZE_RP2040,
348        64,
349        0x0,
350        0x1,
351        strings,
352        mux_alarm,
353        None,
354    )
355    .finalize(components::cdc_acm_component_static!(
356        rp2040::usb::UsbCtrl,
357        rp2040::timer::RPTimer
358    ));
359
360    // UART
361    // Create a shared UART channel for kernel debug.
362    let uart_mux = components::console::UartMuxComponent::new(cdc, 115200)
363        .finalize(components::uart_mux_component_static!());
364
365    // Uncomment this to use UART as an output
366    // let uart_mux2 = components::console::UartMuxComponent::new(
367    //     &peripherals.uart0,
368    //     115200,
369    // )
370    // .finalize(components::uart_mux_component_static!());
371
372    // Setup the console.
373    let console = components::console::ConsoleComponent::new(
374        board_kernel,
375        capsules_core::console::DRIVER_NUM,
376        uart_mux,
377    )
378    .finalize(components::console_component_static!());
379    // Create the debugger object that handles calls to `debug!()`.
380    components::debug_writer::DebugWriterComponent::new(uart_mux)
381        .finalize(components::debug_writer_component_static!());
382
383    cdc.enable();
384    cdc.attach();
385
386    let gpio = GpioComponent::new(
387        board_kernel,
388        capsules_core::gpio::DRIVER_NUM,
389        components::gpio_component_helper!(
390            RPGpioPin,
391            // Used for serial communication. Comment them in if you don't use serial.
392            // 0 => peripherals.pins.get_pin(RPGpio::GPIO0),
393            // 1 => peripherals.pins.get_pin(RPGpio::GPIO1),
394            2 => peripherals.pins.get_pin(RPGpio::GPIO2),
395            3 => peripherals.pins.get_pin(RPGpio::GPIO3),
396            // 4 => peripherals.pins.get_pin(RPGpio::GPIO4),
397            5 => peripherals.pins.get_pin(RPGpio::GPIO5),
398            // 6 => peripherals.pins.get_pin(RPGpio::GPIO6),
399            // 7 => peripherals.pins.get_pin(RPGpio::GPIO7),
400            8 => peripherals.pins.get_pin(RPGpio::GPIO8),
401            9 => peripherals.pins.get_pin(RPGpio::GPIO9),
402            10 => peripherals.pins.get_pin(RPGpio::GPIO10),
403            11 => peripherals.pins.get_pin(RPGpio::GPIO11),
404            // 12 => peripherals.pins.get_pin(RPGpio::GPIO12),
405            // 13 => peripherals.pins.get_pin(RPGpio::GPIO13),
406            14 => peripherals.pins.get_pin(RPGpio::GPIO14),
407            15 => peripherals.pins.get_pin(RPGpio::GPIO15),
408            16 => peripherals.pins.get_pin(RPGpio::GPIO16),
409            17 => peripherals.pins.get_pin(RPGpio::GPIO17),
410            18 => peripherals.pins.get_pin(RPGpio::GPIO18),
411            19 => peripherals.pins.get_pin(RPGpio::GPIO19),
412            20 => peripherals.pins.get_pin(RPGpio::GPIO20),
413            21 => peripherals.pins.get_pin(RPGpio::GPIO21),
414            22 => peripherals.pins.get_pin(RPGpio::GPIO22),
415            23 => peripherals.pins.get_pin(RPGpio::GPIO23),
416            24 => peripherals.pins.get_pin(RPGpio::GPIO24),
417            // LED pin
418            // 25 => peripherals.pins.get_pin(RPGpio::GPIO25),
419
420            // Uncomment to use these as GPIO pins instead of ADC pins
421            // 26 => peripherals.pins.get_pin(RPGpio::GPIO26),
422            // 27 => peripherals.pins.get_pin(RPGpio::GPIO27),
423            // 28 => peripherals.pins.get_pin(RPGpio::GPIO28),
424            // 29 => peripherals.pins.get_pin(RPGpio::GPIO29)
425        ),
426    )
427    .finalize(components::gpio_component_static!(RPGpioPin<'static>));
428
429    let led = LedsComponent::new().finalize(components::led_component_static!(
430        LedHigh<'static, RPGpioPin<'static>>,
431        LedHigh::new(peripherals.pins.get_pin(RPGpio::GPIO6))
432    ));
433
434    peripherals.adc.init();
435
436    let adc_mux = components::adc::AdcMuxComponent::new(&peripherals.adc)
437        .finalize(components::adc_mux_component_static!(Adc));
438
439    let temp_sensor = components::temperature_rp2040::TemperatureRp2040Component::new(
440        adc_mux,
441        Channel::Channel4,
442        1.721,
443        0.706,
444    )
445    .finalize(components::temperature_rp2040_adc_component_static!(
446        rp2040::adc::Adc
447    ));
448
449    peripherals.i2c0.init(100 * 1000);
450    //set SDA and SCL pins in I2C mode
451    let gpio_sda = peripherals.pins.get_pin(RPGpio::GPIO12);
452    let gpio_scl = peripherals.pins.get_pin(RPGpio::GPIO13);
453    gpio_sda.set_function(GpioFunction::I2C);
454    gpio_scl.set_function(GpioFunction::I2C);
455    let mux_i2c = components::i2c::I2CMuxComponent::new(&peripherals.i2c0, None).finalize(
456        components::i2c_mux_component_static!(rp2040::i2c::I2c<'static, 'static>),
457    );
458
459    let lsm6dsoxtr = components::lsm6dsox::Lsm6dsoxtrI2CComponent::new(
460        mux_i2c,
461        capsules_extra::lsm6dsoxtr::ACCELEROMETER_BASE_ADDRESS,
462        board_kernel,
463        capsules_extra::lsm6dsoxtr::DRIVER_NUM,
464    )
465    .finalize(components::lsm6ds_i2c_component_static!(
466        rp2040::i2c::I2c<'static, 'static>
467    ));
468
469    let ninedof = components::ninedof::NineDofComponent::new(
470        board_kernel,
471        capsules_extra::ninedof::DRIVER_NUM,
472    )
473    .finalize(components::ninedof_component_static!(lsm6dsoxtr));
474
475    let temp = components::temperature::TemperatureComponent::new(
476        board_kernel,
477        capsules_extra::temperature::DRIVER_NUM,
478        temp_sensor,
479    )
480    .finalize(components::temperature_component_static!(
481        TemperatureRp2040Sensor
482    ));
483
484    let _ = lsm6dsoxtr
485        .configure(
486            capsules_extra::lsm6dsoxtr::LSM6DSOXGyroDataRate::LSM6DSOX_GYRO_RATE_12_5_HZ,
487            capsules_extra::lsm6dsoxtr::LSM6DSOXAccelDataRate::LSM6DSOX_ACCEL_RATE_12_5_HZ,
488            capsules_extra::lsm6dsoxtr::LSM6DSOXAccelRange::LSM6DSOX_ACCEL_RANGE_2_G,
489            capsules_extra::lsm6dsoxtr::LSM6DSOXTRGyroRange::LSM6DSOX_GYRO_RANGE_250_DPS,
490            true,
491        )
492        .map_err(|e| {
493            panic!(
494                "ERROR Failed to start LSM6DSOXTR sensor configuration ({:?})",
495                e
496            )
497        });
498
499    // The Nano_RP2040 board has its own integrated temperature sensor, as well as a temperature sensor integrated in the lsm6dsoxtr sensor.
500    // There is only a single driver, thus either for userspace is exclusive.
501    // Uncomment this block in order to use the temperature sensor from lsm6dsoxtr
502
503    // let temp = static_init!(
504    //     capsules_extra::temperature::TemperatureSensor<'static>,
505    //     capsules_extra::temperature::TemperatureSensor::new(lsm6dsoxtr, grant_temperature)
506    // );
507
508    kernel::hil::sensors::TemperatureDriver::set_client(temp_sensor, temp);
509
510    let adc_channel_0 = components::adc::AdcComponent::new(adc_mux, Channel::Channel0)
511        .finalize(components::adc_component_static!(Adc));
512
513    let adc_channel_1 = components::adc::AdcComponent::new(adc_mux, Channel::Channel1)
514        .finalize(components::adc_component_static!(Adc));
515
516    let adc_channel_2 = components::adc::AdcComponent::new(adc_mux, Channel::Channel2)
517        .finalize(components::adc_component_static!(Adc));
518
519    let adc_channel_3 = components::adc::AdcComponent::new(adc_mux, Channel::Channel3)
520        .finalize(components::adc_component_static!(Adc));
521
522    let adc_syscall =
523        components::adc::AdcVirtualComponent::new(board_kernel, capsules_core::adc::DRIVER_NUM)
524            .finalize(components::adc_syscall_component_helper!(
525                adc_channel_0,
526                adc_channel_1,
527                adc_channel_2,
528                adc_channel_3,
529            ));
530
531    let process_printer = components::process_printer::ProcessPrinterTextComponent::new()
532        .finalize(components::process_printer_text_component_static!());
533    PROCESS_PRINTER = Some(process_printer);
534
535    // PROCESS CONSOLE
536    let process_console = components::process_console::ProcessConsoleComponent::new(
537        board_kernel,
538        uart_mux,
539        mux_alarm,
540        process_printer,
541        Some(cortexm0p::support::reset),
542    )
543    .finalize(components::process_console_component_static!(RPTimer));
544    let _ = process_console.start();
545
546    let scheduler = components::sched::round_robin::RoundRobinComponent::new(&*addr_of!(PROCESSES))
547        .finalize(components::round_robin_component_static!(NUM_PROCS));
548
549    let nano_rp2040_connect = NanoRP2040Connect {
550        ipc: kernel::ipc::IPC::new(
551            board_kernel,
552            kernel::ipc::DRIVER_NUM,
553            &memory_allocation_capability,
554        ),
555        alarm,
556        gpio,
557        led,
558        console,
559        adc: adc_syscall,
560        temperature: temp,
561
562        lsm6dsoxtr,
563        ninedof,
564
565        scheduler,
566        systick: cortexm0p::systick::SysTick::new_with_calibration(125_000_000),
567    };
568
569    let platform_type = match peripherals.sysinfo.get_platform() {
570        sysinfo::Platform::Asic => "ASIC",
571        sysinfo::Platform::Fpga => "FPGA",
572    };
573
574    debug!(
575        "RP2040 Revision {} {}",
576        peripherals.sysinfo.get_revision(),
577        platform_type
578    );
579    debug!("Initialization complete. Enter main loop");
580
581    // These symbols are defined in the linker script.
582    extern "C" {
583        /// Beginning of the ROM region containing app images.
584        static _sapps: u8;
585        /// End of the ROM region containing app images.
586        static _eapps: u8;
587        /// Beginning of the RAM region for app memory.
588        static mut _sappmem: u8;
589        /// End of the RAM region for app memory.
590        static _eappmem: u8;
591    }
592
593    kernel::process::load_processes(
594        board_kernel,
595        chip,
596        core::slice::from_raw_parts(
597            core::ptr::addr_of!(_sapps),
598            core::ptr::addr_of!(_eapps) as usize - core::ptr::addr_of!(_sapps) as usize,
599        ),
600        core::slice::from_raw_parts_mut(
601            core::ptr::addr_of_mut!(_sappmem),
602            core::ptr::addr_of!(_eappmem) as usize - core::ptr::addr_of!(_sappmem) as usize,
603        ),
604        &mut *addr_of_mut!(PROCESSES),
605        &FAULT_RESPONSE,
606        &process_management_capability,
607    )
608    .unwrap_or_else(|err| {
609        debug!("Error loading processes!");
610        debug!("{:?}", err);
611    });
612
613    (board_kernel, nano_rp2040_connect, chip)
614}
615
616/// Main function called after RAM initialized.
617#[no_mangle]
618pub unsafe fn main() {
619    let main_loop_capability = create_capability!(capabilities::MainLoopCapability);
620
621    let (board_kernel, platform, chip) = start();
622    board_kernel.kernel_loop(&platform, chip, Some(&platform.ipc), &main_loop_capability);
623}