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