pico_explorer_base/
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 Raspberry Pi Pico.
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::hil::led::LedHigh;
23use kernel::hil::usb::Client;
24use kernel::platform::{KernelResources, SyscallDriverLookup};
25use kernel::scheduler::round_robin::RoundRobinSched;
26use kernel::{capabilities, create_capability, static_init, Kernel};
27use kernel::{debug, hil};
28
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::pio::Pio;
38use rp2040::pio_pwm::PioPwm;
39use rp2040::resets::Peripheral;
40use rp2040::spi::Spi;
41use rp2040::sysinfo;
42use rp2040::timer::RPTimer;
43
44mod io;
45
46mod flash_bootloader;
47
48/// Allocate memory for the stack
49#[no_mangle]
50#[link_section = ".stack_buffer"]
51pub static mut STACK_MEMORY: [u8; 0x1500] = [0; 0x1500];
52
53// Manually setting the boot header section that contains the FCB header
54#[used]
55#[link_section = ".flash_bootloader"]
56static FLASH_BOOTLOADER: [u8; 256] = flash_bootloader::FLASH_BOOTLOADER;
57
58// State for loading and holding applications.
59// How should the kernel respond when a process faults.
60const FAULT_RESPONSE: capsules_system::process_policies::PanicFaultPolicy =
61    capsules_system::process_policies::PanicFaultPolicy {};
62
63// Number of concurrent processes this platform supports.
64const NUM_PROCS: usize = 4;
65
66static mut PROCESSES: [Option<&'static dyn kernel::process::Process>; NUM_PROCS] =
67    [None; NUM_PROCS];
68
69static mut CHIP: Option<&'static Rp2040<Rp2040DefaultPeripherals>> = None;
70static mut PROCESS_PRINTER: Option<&'static capsules_system::process_printer::ProcessPrinterText> =
71    None;
72
73type TemperatureRp2040Sensor = components::temperature_rp2040::TemperatureRp2040ComponentType<
74    capsules_core::virtualizers::virtual_adc::AdcDevice<'static, rp2040::adc::Adc<'static>>,
75>;
76type TemperatureDriver = components::temperature::TemperatureComponentType<TemperatureRp2040Sensor>;
77
78/// Supported drivers by the platform
79pub struct PicoExplorerBase {
80    ipc: kernel::ipc::IPC<{ NUM_PROCS as u8 }>,
81    console: &'static capsules_core::console::Console<'static>,
82    alarm: &'static capsules_core::alarm::AlarmDriver<
83        'static,
84        VirtualMuxAlarm<'static, rp2040::timer::RPTimer<'static>>,
85    >,
86    gpio: &'static capsules_core::gpio::GPIO<'static, RPGpioPin<'static>>,
87    led: &'static capsules_core::led::LedDriver<'static, LedHigh<'static, RPGpioPin<'static>>, 1>,
88    adc: &'static capsules_core::adc::AdcVirtualized<'static>,
89    temperature: &'static TemperatureDriver,
90    buzzer_driver: &'static capsules_extra::buzzer_driver::Buzzer<
91        'static,
92        capsules_extra::buzzer_pwm::PwmBuzzer<
93            'static,
94            capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
95                'static,
96                rp2040::timer::RPTimer<'static>,
97            >,
98            capsules_core::virtualizers::virtual_pwm::PwmPinUser<
99                'static,
100                rp2040::pwm::Pwm<'static>,
101            >,
102        >,
103    >,
104    button: &'static capsules_core::button::Button<'static, RPGpioPin<'static>>,
105    screen: &'static capsules_extra::screen::Screen<'static>,
106
107    scheduler: &'static RoundRobinSched<'static>,
108    systick: cortexm0p::systick::SysTick,
109}
110
111impl SyscallDriverLookup for PicoExplorerBase {
112    fn with_driver<F, R>(&self, driver_num: usize, f: F) -> R
113    where
114        F: FnOnce(Option<&dyn kernel::syscall::SyscallDriver>) -> R,
115    {
116        match driver_num {
117            capsules_core::console::DRIVER_NUM => f(Some(self.console)),
118            capsules_core::alarm::DRIVER_NUM => f(Some(self.alarm)),
119            capsules_core::gpio::DRIVER_NUM => f(Some(self.gpio)),
120            capsules_core::led::DRIVER_NUM => f(Some(self.led)),
121            kernel::ipc::DRIVER_NUM => f(Some(&self.ipc)),
122            capsules_core::adc::DRIVER_NUM => f(Some(self.adc)),
123            capsules_extra::temperature::DRIVER_NUM => f(Some(self.temperature)),
124            capsules_extra::buzzer_driver::DRIVER_NUM => f(Some(self.buzzer_driver)),
125            capsules_core::button::DRIVER_NUM => f(Some(self.button)),
126            capsules_extra::screen::DRIVER_NUM => f(Some(self.screen)),
127            _ => f(None),
128        }
129    }
130}
131
132impl KernelResources<Rp2040<'static, Rp2040DefaultPeripherals<'static>>> for PicoExplorerBase {
133    type SyscallDriverLookup = Self;
134    type SyscallFilter = ();
135    type ProcessFault = ();
136    type Scheduler = RoundRobinSched<'static>;
137    type SchedulerTimer = cortexm0p::systick::SysTick;
138    type WatchDog = ();
139    type ContextSwitchCallback = ();
140
141    fn syscall_driver_lookup(&self) -> &Self::SyscallDriverLookup {
142        self
143    }
144    fn syscall_filter(&self) -> &Self::SyscallFilter {
145        &()
146    }
147    fn process_fault(&self) -> &Self::ProcessFault {
148        &()
149    }
150    fn scheduler(&self) -> &Self::Scheduler {
151        self.scheduler
152    }
153    fn scheduler_timer(&self) -> &Self::SchedulerTimer {
154        &self.systick
155    }
156    fn watchdog(&self) -> &Self::WatchDog {
157        &()
158    }
159    fn context_switch_callback(&self) -> &Self::ContextSwitchCallback {
160        &()
161    }
162}
163
164#[allow(dead_code)]
165extern "C" {
166    /// Entry point used for debugger
167    ///
168    /// When loaded using gdb, the Raspberry Pi Pico is not reset
169    /// by default. Without this function, gdb sets the PC to the
170    /// beginning of the flash. This is not correct, as the RP2040
171    /// has a more complex boot process.
172    ///
173    /// This function is set to be the entry point for gdb and is used
174    /// to send the RP2040 back in the bootloader so that all the boot
175    /// sequence is performed.
176    fn jump_to_bootloader();
177}
178
179#[cfg(any(doc, all(target_arch = "arm", target_os = "none")))]
180core::arch::global_asm!(
181    "
182    .section .jump_to_bootloader, \"ax\"
183    .global jump_to_bootloader
184    .thumb_func
185  jump_to_bootloader:
186    movs r0, #0
187    ldr r1, =(0xe0000000 + 0x0000ed08)
188    str r0, [r1]
189    ldmia r0!, {{r1, r2}}
190    msr msp, r1
191    bx r2
192    "
193);
194
195fn init_clocks(peripherals: &Rp2040DefaultPeripherals) {
196    // Start tick in watchdog
197    peripherals.watchdog.start_tick(12);
198
199    // Disable the Resus clock
200    peripherals.clocks.disable_resus();
201
202    // Setup the external Oscillator
203    peripherals.xosc.init();
204
205    // disable ref and sys clock aux sources
206    peripherals.clocks.disable_sys_aux();
207    peripherals.clocks.disable_ref_aux();
208
209    peripherals
210        .resets
211        .reset(&[Peripheral::PllSys, Peripheral::PllUsb]);
212    peripherals
213        .resets
214        .unreset(&[Peripheral::PllSys, Peripheral::PllUsb], true);
215
216    // Configure PLLs (from Pico SDK)
217    //                   REF     FBDIV VCO            POSTDIV
218    // PLL SYS: 12 / 1 = 12MHz * 125 = 1500MHZ / 6 / 2 = 125MHz
219    // PLL USB: 12 / 1 = 12MHz * 40  = 480 MHz / 5 / 2 =  48MHz
220
221    // It seems that the external osciallator is clocked at 12 MHz
222
223    peripherals
224        .clocks
225        .pll_init(PllClock::Sys, 12, 1, 1500 * 1000000, 6, 2);
226    peripherals
227        .clocks
228        .pll_init(PllClock::Usb, 12, 1, 480 * 1000000, 5, 2);
229
230    // pico-sdk: // CLK_REF = XOSC (12MHz) / 1 = 12MHz
231    peripherals.clocks.configure_reference(
232        ReferenceClockSource::Xosc,
233        ReferenceAuxiliaryClockSource::PllUsb,
234        12000000,
235        12000000,
236    );
237    // pico-sdk: CLK SYS = PLL SYS (125MHz) / 1 = 125MHz
238    peripherals.clocks.configure_system(
239        SystemClockSource::Auxiliary,
240        SystemAuxiliaryClockSource::PllSys,
241        125000000,
242        125000000,
243    );
244    // pico-sdk: CLK USB = PLL USB (48MHz) / 1 = 48MHz
245    peripherals
246        .clocks
247        .configure_usb(UsbAuxiliaryClockSource::PllSys, 48000000, 48000000);
248    // pico-sdk: CLK ADC = PLL USB (48MHZ) / 1 = 48MHz
249    peripherals
250        .clocks
251        .configure_adc(AdcAuxiliaryClockSource::PllUsb, 48000000, 48000000);
252    // pico-sdk: CLK RTC = PLL USB (48MHz) / 1024 = 46875Hz
253    peripherals
254        .clocks
255        .configure_rtc(RtcAuxiliaryClockSource::PllSys, 48000000, 46875);
256    // pico-sdk:
257    // CLK PERI = clk_sys. Used as reference clock for Peripherals. No dividers so just select and enable
258    // Normally choose clk_sys or clk_usb
259    peripherals
260        .clocks
261        .configure_peripheral(PeripheralAuxiliaryClockSource::System, 125000000);
262}
263
264/// This is in a separate, inline(never) function so that its stack frame is
265/// removed when this function returns. Otherwise, the stack space used for
266/// these static_inits is wasted.
267#[inline(never)]
268pub unsafe fn start() -> (
269    &'static kernel::Kernel,
270    PicoExplorerBase,
271    &'static rp2040::chip::Rp2040<'static, Rp2040DefaultPeripherals<'static>>,
272) {
273    // Loads relocations and clears BSS
274    rp2040::init();
275
276    let peripherals = static_init!(Rp2040DefaultPeripherals, Rp2040DefaultPeripherals::new());
277    peripherals.resolve_dependencies();
278
279    // Reset all peripherals except QSPI (we might be booting from Flash), PLL USB and PLL SYS
280    peripherals.resets.reset_all_except(&[
281        Peripheral::IOQSpi,
282        Peripheral::PadsQSpi,
283        Peripheral::PllUsb,
284        Peripheral::PllSys,
285    ]);
286
287    // Unreset all the peripherals that do not require clock setup as they run using the sys_clk or ref_clk
288    // Wait for the peripherals to reset
289    peripherals.resets.unreset_all_except(
290        &[
291            Peripheral::Adc,
292            Peripheral::Rtc,
293            Peripheral::Spi0,
294            Peripheral::Spi1,
295            Peripheral::Uart0,
296            Peripheral::Uart1,
297            Peripheral::UsbCtrl,
298        ],
299        true,
300    );
301
302    init_clocks(peripherals);
303
304    // Unreset all peripherals
305    peripherals.resets.unreset_all_except(&[], true);
306
307    //set RX and TX pins in UART mode
308    let gpio_tx = peripherals.pins.get_pin(RPGpio::GPIO0);
309    let gpio_rx = peripherals.pins.get_pin(RPGpio::GPIO1);
310    gpio_rx.set_function(GpioFunction::UART);
311    gpio_tx.set_function(GpioFunction::UART);
312
313    // Set the UART used for panic
314    (*addr_of_mut!(io::WRITER)).set_uart(&peripherals.uart0);
315
316    // Disable IE for pads 26-29 (the Pico SDK runtime does this, not sure why)
317    for pin in 26..30 {
318        peripherals
319            .pins
320            .get_pin(RPGpio::from_usize(pin).unwrap())
321            .deactivate_pads();
322    }
323
324    let chip = static_init!(
325        Rp2040<Rp2040DefaultPeripherals>,
326        Rp2040::new(peripherals, &peripherals.sio)
327    );
328
329    CHIP = Some(chip);
330
331    let board_kernel = static_init!(Kernel, Kernel::new(&*addr_of!(PROCESSES)));
332
333    let process_management_capability =
334        create_capability!(capabilities::ProcessManagementCapability);
335    let memory_allocation_capability = create_capability!(capabilities::MemoryAllocationCapability);
336
337    let mux_alarm = components::alarm::AlarmMuxComponent::new(&peripherals.timer)
338        .finalize(components::alarm_mux_component_static!(RPTimer));
339
340    let alarm = components::alarm::AlarmDriverComponent::new(
341        board_kernel,
342        capsules_core::alarm::DRIVER_NUM,
343        mux_alarm,
344    )
345    .finalize(components::alarm_component_static!(RPTimer));
346
347    // CDC
348    let strings = static_init!(
349        [&str; 3],
350        [
351            "Raspberry Pi",                // Manufacturer
352            "pico explorer base - TockOS", // Product
353            "00000000000000000",           // Serial number
354        ]
355    );
356
357    let cdc = components::cdc::CdcAcmComponent::new(
358        &peripherals.usb,
359        //capsules::usb::cdc::MAX_CTRL_PACKET_SIZE_RP2040,
360        64,
361        peripherals.sysinfo.get_manufacturer_rp2040(),
362        peripherals.sysinfo.get_part(),
363        strings,
364        mux_alarm,
365        None,
366    )
367    .finalize(components::cdc_acm_component_static!(
368        rp2040::usb::UsbCtrl,
369        rp2040::timer::RPTimer
370    ));
371
372    // UART
373    // Create a shared UART channel for kernel debug.
374    let uart_mux = components::console::UartMuxComponent::new(cdc, 115200)
375        .finalize(components::uart_mux_component_static!());
376
377    // Uncomment this to use UART as an output
378    // let uart_mux = components::console::UartMuxComponent::new(&peripherals.uart0, 115200)
379    //     .finalize(components::uart_mux_component_static!());
380
381    // Setup the console.
382    let console = components::console::ConsoleComponent::new(
383        board_kernel,
384        capsules_core::console::DRIVER_NUM,
385        uart_mux,
386    )
387    .finalize(components::console_component_static!());
388    // Create the debugger object that handles calls to `debug!()`.
389    components::debug_writer::DebugWriterComponent::new(uart_mux)
390        .finalize(components::debug_writer_component_static!());
391
392    cdc.enable();
393    cdc.attach();
394
395    let gpio = GpioComponent::new(
396        board_kernel,
397        capsules_core::gpio::DRIVER_NUM,
398        components::gpio_component_helper!(
399            RPGpioPin,
400            // Used for serial communication. Comment them in if you don't use serial.
401            // 0 => &peripherals.pins.get_pin(RPGpio::GPIO0),
402            // 1 => &peripherals.pins.get_pin(RPGpio::GPIO1),
403            // Used for Buzzer.
404            // 2 => &peripherals.pins.get_pin(RPGpio::GPIO2),
405            3 => peripherals.pins.get_pin(RPGpio::GPIO3),
406            4 => peripherals.pins.get_pin(RPGpio::GPIO4),
407            5 => peripherals.pins.get_pin(RPGpio::GPIO5),
408            6 => peripherals.pins.get_pin(RPGpio::GPIO6),
409            7 => peripherals.pins.get_pin(RPGpio::GPIO7),
410            20 => peripherals.pins.get_pin(RPGpio::GPIO20),
411            21 => peripherals.pins.get_pin(RPGpio::GPIO21),
412            22 => peripherals.pins.get_pin(RPGpio::GPIO22),
413        ),
414    )
415    .finalize(components::gpio_component_static!(RPGpioPin<'static>));
416
417    let led = LedsComponent::new().finalize(components::led_component_static!(
418        LedHigh<'static, RPGpioPin<'static>>,
419        LedHigh::new(peripherals.pins.get_pin(RPGpio::GPIO25))
420    ));
421
422    peripherals.adc.init();
423
424    // Set PWM function for Buzzer.
425    peripherals
426        .pins
427        .get_pin(RPGpio::GPIO2)
428        .set_function(GpioFunction::PWM);
429
430    let adc_mux = components::adc::AdcMuxComponent::new(&peripherals.adc)
431        .finalize(components::adc_mux_component_static!(Adc));
432
433    let temp_sensor = components::temperature_rp2040::TemperatureRp2040Component::new(
434        adc_mux,
435        Channel::Channel4,
436        1.721,
437        0.706,
438    )
439    .finalize(components::temperature_rp2040_adc_component_static!(
440        rp2040::adc::Adc
441    ));
442
443    let temp = components::temperature::TemperatureComponent::new(
444        board_kernel,
445        capsules_extra::temperature::DRIVER_NUM,
446        temp_sensor,
447    )
448    .finalize(components::temperature_component_static!(
449        TemperatureRp2040Sensor
450    ));
451
452    //set CLK, MOSI and CS pins in SPI mode
453    let spi_clk = peripherals.pins.get_pin(RPGpio::GPIO18);
454    let spi_csn = peripherals.pins.get_pin(RPGpio::GPIO17);
455    let spi_mosi = peripherals.pins.get_pin(RPGpio::GPIO19);
456    spi_clk.set_function(GpioFunction::SPI);
457    spi_csn.set_function(GpioFunction::SPI);
458    spi_mosi.set_function(GpioFunction::SPI);
459    let mux_spi = components::spi::SpiMuxComponent::new(&peripherals.spi0)
460        .finalize(components::spi_mux_component_static!(Spi));
461
462    let bus = components::bus::SpiMasterBusComponent::new(
463        mux_spi,
464        hil::spi::cs::IntoChipSelect::<_, hil::spi::cs::ActiveLow>::into_cs(
465            peripherals.pins.get_pin(RPGpio::GPIO17),
466        ),
467        20_000_000,
468        kernel::hil::spi::ClockPhase::SampleLeading,
469        kernel::hil::spi::ClockPolarity::IdleLow,
470    )
471    .finalize(components::spi_bus_component_static!(Spi));
472
473    let tft = components::st77xx::ST77XXComponent::new(
474        mux_alarm,
475        bus,
476        Some(peripherals.pins.get_pin(RPGpio::GPIO16)),
477        None,
478        &capsules_extra::st77xx::ST7789H2,
479    )
480    .finalize(components::st77xx_component_static!(
481        // bus type
482        capsules_extra::bus::SpiMasterBus<
483            'static,
484            capsules_core::virtualizers::virtual_spi::VirtualSpiMasterDevice<'static, Spi>,
485        >,
486        // timer type
487        RPTimer,
488        // pin type
489        RPGpioPin,
490    ));
491
492    let _ = tft.init();
493
494    let button = components::button::ButtonComponent::new(
495        board_kernel,
496        capsules_core::button::DRIVER_NUM,
497        components::button_component_helper!(
498            RPGpioPin,
499            (
500                peripherals.pins.get_pin(RPGpio::GPIO12),
501                kernel::hil::gpio::ActivationMode::ActiveLow,
502                kernel::hil::gpio::FloatingState::PullUp
503            ), // A
504            (
505                peripherals.pins.get_pin(RPGpio::GPIO13),
506                kernel::hil::gpio::ActivationMode::ActiveLow,
507                kernel::hil::gpio::FloatingState::PullUp
508            ), // B
509            (
510                peripherals.pins.get_pin(RPGpio::GPIO14),
511                kernel::hil::gpio::ActivationMode::ActiveLow,
512                kernel::hil::gpio::FloatingState::PullUp
513            ), // X
514            (
515                peripherals.pins.get_pin(RPGpio::GPIO15),
516                kernel::hil::gpio::ActivationMode::ActiveLow,
517                kernel::hil::gpio::FloatingState::PullUp
518            ), // Y
519        ),
520    )
521    .finalize(components::button_component_static!(RPGpioPin));
522
523    let screen = components::screen::ScreenComponent::new(
524        board_kernel,
525        capsules_extra::screen::DRIVER_NUM,
526        tft,
527        Some(tft),
528    )
529    .finalize(components::screen_component_static!(57600));
530
531    let adc_channel_0 = components::adc::AdcComponent::new(adc_mux, Channel::Channel0)
532        .finalize(components::adc_component_static!(Adc));
533
534    let adc_channel_1 = components::adc::AdcComponent::new(adc_mux, Channel::Channel1)
535        .finalize(components::adc_component_static!(Adc));
536
537    let adc_channel_2 = components::adc::AdcComponent::new(adc_mux, Channel::Channel2)
538        .finalize(components::adc_component_static!(Adc));
539
540    let adc_syscall =
541        components::adc::AdcVirtualComponent::new(board_kernel, capsules_core::adc::DRIVER_NUM)
542            .finalize(components::adc_syscall_component_helper!(
543                adc_channel_0,
544                adc_channel_1,
545                adc_channel_2,
546            ));
547
548    let process_printer = components::process_printer::ProcessPrinterTextComponent::new()
549        .finalize(components::process_printer_text_component_static!());
550    PROCESS_PRINTER = Some(process_printer);
551    // PROCESS CONSOLE
552    let process_console = components::process_console::ProcessConsoleComponent::new(
553        board_kernel,
554        uart_mux,
555        mux_alarm,
556        process_printer,
557        Some(cortexm0p::support::reset),
558    )
559    .finalize(components::process_console_component_static!(RPTimer));
560    let _ = process_console.start();
561
562    let scheduler = components::sched::round_robin::RoundRobinComponent::new(&*addr_of!(PROCESSES))
563        .finalize(components::round_robin_component_static!(NUM_PROCS));
564
565    //--------------------------------------------------------------------------
566    // BUZZER
567    //--------------------------------------------------------------------------
568    use kernel::hil::buzzer::Buzzer;
569    use kernel::hil::time::Alarm;
570
571    let mux_pwm = components::pwm::PwmMuxComponent::new(&peripherals.pwm)
572        .finalize(components::pwm_mux_component_static!(rp2040::pwm::Pwm));
573
574    let virtual_pwm_buzzer =
575        components::pwm::PwmPinUserComponent::new(mux_pwm, rp2040::gpio::RPGpio::GPIO2)
576            .finalize(components::pwm_pin_user_component_static!(rp2040::pwm::Pwm));
577
578    let virtual_alarm_buzzer = static_init!(
579        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
580            'static,
581            rp2040::timer::RPTimer,
582        >,
583        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm::new(mux_alarm)
584    );
585
586    virtual_alarm_buzzer.setup();
587
588    let pwm_buzzer = static_init!(
589        capsules_extra::buzzer_pwm::PwmBuzzer<
590            'static,
591            capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
592                'static,
593                rp2040::timer::RPTimer,
594            >,
595            capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, rp2040::pwm::Pwm>,
596        >,
597        capsules_extra::buzzer_pwm::PwmBuzzer::new(
598            virtual_pwm_buzzer,
599            virtual_alarm_buzzer,
600            capsules_extra::buzzer_pwm::DEFAULT_MAX_BUZZ_TIME_MS,
601        )
602    );
603
604    let buzzer_driver = static_init!(
605        capsules_extra::buzzer_driver::Buzzer<
606            'static,
607            capsules_extra::buzzer_pwm::PwmBuzzer<
608                'static,
609                capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
610                    'static,
611                    rp2040::timer::RPTimer,
612                >,
613                capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, rp2040::pwm::Pwm>,
614            >,
615        >,
616        capsules_extra::buzzer_driver::Buzzer::new(
617            pwm_buzzer,
618            capsules_extra::buzzer_driver::DEFAULT_MAX_BUZZ_TIME_MS,
619            board_kernel.create_grant(
620                capsules_extra::buzzer_driver::DRIVER_NUM,
621                &memory_allocation_capability
622            )
623        )
624    );
625
626    pwm_buzzer.set_client(buzzer_driver);
627
628    virtual_alarm_buzzer.set_alarm_client(pwm_buzzer);
629
630    let pico_explorer_base = PicoExplorerBase {
631        ipc: kernel::ipc::IPC::new(
632            board_kernel,
633            kernel::ipc::DRIVER_NUM,
634            &memory_allocation_capability,
635        ),
636        alarm,
637        gpio,
638        led,
639        console,
640        adc: adc_syscall,
641        temperature: temp,
642        buzzer_driver,
643        button,
644        screen,
645        scheduler,
646        systick: cortexm0p::systick::SysTick::new_with_calibration(125_000_000),
647    };
648
649    let platform_type = match peripherals.sysinfo.get_platform() {
650        sysinfo::Platform::Asic => "ASIC",
651        sysinfo::Platform::Fpga => "FPGA",
652    };
653
654    debug!(
655        "RP2040 Revision {} {}",
656        peripherals.sysinfo.get_revision(),
657        platform_type
658    );
659    debug!("Initialization complete. Enter main loop");
660
661    // These symbols are defined in the linker script.
662    extern "C" {
663        /// Beginning of the ROM region containing app images.
664        static _sapps: u8;
665        /// End of the ROM region containing app images.
666        static _eapps: u8;
667        /// Beginning of the RAM region for app memory.
668        static mut _sappmem: u8;
669        /// End of the RAM region for app memory.
670        static _eappmem: u8;
671    }
672
673    kernel::process::load_processes(
674        board_kernel,
675        chip,
676        core::slice::from_raw_parts(
677            core::ptr::addr_of!(_sapps),
678            core::ptr::addr_of!(_eapps) as usize - core::ptr::addr_of!(_sapps) as usize,
679        ),
680        core::slice::from_raw_parts_mut(
681            core::ptr::addr_of_mut!(_sappmem),
682            core::ptr::addr_of!(_eappmem) as usize - core::ptr::addr_of!(_sappmem) as usize,
683        ),
684        &mut *addr_of_mut!(PROCESSES),
685        &FAULT_RESPONSE,
686        &process_management_capability,
687    )
688    .unwrap_or_else(|err| {
689        debug!("Error loading processes!");
690        debug!("{:?}", err);
691    });
692
693    //--------------------------------------------------------------------------
694    // PIO
695    //--------------------------------------------------------------------------
696
697    let mut pio: Pio = Pio::new_pio0();
698
699    let _pio_pwm = PioPwm::new(&mut pio, &peripherals.clocks);
700    // This will start a PWM with PIO with the set frequency and duty cycle on the specified pin.
701    // pio_pwm
702    //     .start(
703    //         &RPGpio::GPIO7,
704    //         pio_pwm.get_maximum_frequency_hz() / 125000, /*1_000*/
705    //         pio_pwm.get_maximum_duty_cycle() / 2,
706    //     )
707    //     .unwrap();
708
709    (board_kernel, pico_explorer_base, chip)
710}
711
712/// Main function called after RAM initialized.
713#[no_mangle]
714pub unsafe fn main() {
715    let main_loop_capability = create_capability!(capabilities::MainLoopCapability);
716
717    let (board_kernel, platform, chip) = start();
718    board_kernel.kernel_loop(&platform, chip, Some(&platform.ipc), &main_loop_capability);
719}