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