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