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