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