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