microbit_v2/
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 Micro:bit v2.
6//!
7//! It is based on nRF52833 SoC (Cortex M4 core with a BLE).
8
9#![no_std]
10#![no_main]
11#![deny(missing_docs)]
12
13use core::ptr::addr_of;
14
15use kernel::capabilities;
16use kernel::component::Component;
17use kernel::debug::PanicResources;
18use kernel::hil::time::Counter;
19use kernel::platform::{KernelResources, SyscallDriverLookup};
20use kernel::scheduler::round_robin::RoundRobinSched;
21use kernel::utilities::single_thread_value::SingleThreadValue;
22
23#[allow(unused_imports)]
24use kernel::{create_capability, debug, debug_gpio, debug_verbose, static_init};
25
26use nrf52833::gpio::Pin;
27use nrf52833::interrupt_service::Nrf52833DefaultPeripherals;
28
29// Kernel LED (same as microphone LED)
30const LED_KERNEL_PIN: Pin = Pin::P0_20;
31const LED_MICROPHONE_PIN: Pin = Pin::P0_20;
32
33// Buttons
34const BUTTON_A: Pin = Pin::P0_14;
35const BUTTON_B: Pin = Pin::P0_23;
36const TOUCH_LOGO: Pin = Pin::P1_04;
37
38// GPIOs
39
40// P0, P1 and P2 are used as ADC, comment them in the ADC section to use them as GPIO
41const _GPIO_P0: Pin = Pin::P0_02;
42const _GPIO_P1: Pin = Pin::P0_03;
43const _GPIO_P2: Pin = Pin::P0_04;
44const GPIO_P8: Pin = Pin::P0_10;
45const GPIO_P9: Pin = Pin::P0_09;
46const GPIO_P16: Pin = Pin::P1_02;
47
48const UART_TX_PIN: Pin = Pin::P0_06;
49const UART_RX_PIN: Pin = Pin::P1_08;
50
51/// LED matrix
52const LED_MATRIX_COLS: [Pin; 5] = [Pin::P0_28, Pin::P0_11, Pin::P0_31, Pin::P1_05, Pin::P0_30];
53const LED_MATRIX_ROWS: [Pin; 5] = [Pin::P0_21, Pin::P0_22, Pin::P0_15, Pin::P0_24, Pin::P0_19];
54
55// Speaker
56
57const SPEAKER_PIN: Pin = Pin::P0_00;
58
59/// I2C pins for all of the sensors.
60const I2C_SDA_PIN: Pin = Pin::P0_16;
61const I2C_SCL_PIN: Pin = Pin::P0_08;
62
63/// UART Writer for panic!()s.
64pub mod io;
65
66// State for loading and holding applications.
67// How should the kernel respond when a process faults.
68const FAULT_RESPONSE: capsules_system::process_policies::PanicFaultPolicy =
69    capsules_system::process_policies::PanicFaultPolicy {};
70
71// Number of concurrent processes this platform supports.
72const NUM_PROCS: usize = 4;
73
74type ChipHw = nrf52833::chip::NRF52<'static, Nrf52833DefaultPeripherals<'static>>;
75type ProcessPrinterInUse = capsules_system::process_printer::ProcessPrinterText;
76
77/// Resources for when a board panics used by io.rs.
78static PANIC_RESOURCES: SingleThreadValue<PanicResources<ChipHw, ProcessPrinterInUse>> =
79    SingleThreadValue::new(PanicResources::new());
80
81kernel::stack_size! {0x2000}
82
83type TemperatureDriver =
84    components::temperature::TemperatureComponentType<nrf52::temperature::Temp<'static>>;
85type RngDriver = components::rng::RngComponentType<nrf52833::trng::Trng<'static>>;
86type Ieee802154RawDriver =
87    components::ieee802154::Ieee802154RawComponentType<nrf52833::ieee802154_radio::Radio<'static>>;
88
89/// Supported drivers by the platform
90pub struct MicroBit {
91    ble_radio: &'static capsules_extra::ble_advertising_driver::BLE<
92        'static,
93        nrf52::ble_radio::Radio<'static>,
94        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
95            'static,
96            nrf52::rtc::Rtc<'static>,
97        >,
98    >,
99    eui64: &'static capsules_extra::eui64::Eui64,
100    ieee802154: &'static Ieee802154RawDriver,
101    console: &'static capsules_core::console::Console<'static>,
102    gpio: &'static capsules_core::gpio::GPIO<'static, nrf52::gpio::GPIOPin<'static>>,
103    led: &'static capsules_core::led::LedDriver<
104        'static,
105        capsules_extra::led_matrix::LedMatrixLed<
106            'static,
107            nrf52::gpio::GPIOPin<'static>,
108            capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
109                'static,
110                nrf52::rtc::Rtc<'static>,
111            >,
112        >,
113        25,
114    >,
115    button: &'static capsules_core::button::Button<'static, nrf52::gpio::GPIOPin<'static>>,
116    rng: &'static RngDriver,
117    ninedof: &'static capsules_extra::ninedof::NineDof<'static>,
118    lsm303agr: &'static capsules_extra::lsm303agr::Lsm303agrI2C<
119        'static,
120        capsules_core::virtualizers::virtual_i2c::I2CDevice<'static, nrf52833::i2c::TWI<'static>>,
121    >,
122    temperature: &'static TemperatureDriver,
123    ipc: kernel::ipc::IPC<{ NUM_PROCS as u8 }>,
124    adc: &'static capsules_core::adc::AdcVirtualized<'static>,
125    alarm: &'static capsules_core::alarm::AlarmDriver<
126        'static,
127        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
128            'static,
129            nrf52::rtc::Rtc<'static>,
130        >,
131    >,
132    buzzer_driver: &'static capsules_extra::buzzer_driver::Buzzer<
133        'static,
134        capsules_extra::buzzer_pwm::PwmBuzzer<
135            'static,
136            capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
137                'static,
138                nrf52833::rtc::Rtc<'static>,
139            >,
140            capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, nrf52833::pwm::Pwm>,
141        >,
142    >,
143    pwm: &'static capsules_extra::pwm::Pwm<'static, 1>,
144    app_flash: &'static capsules_extra::app_flash_driver::AppFlash<'static>,
145    sound_pressure: &'static capsules_extra::sound_pressure::SoundPressureSensor<'static>,
146
147    scheduler: &'static RoundRobinSched<'static>,
148    systick: cortexm4::systick::SysTick,
149}
150
151impl SyscallDriverLookup for MicroBit {
152    fn with_driver<F, R>(&self, driver_num: usize, f: F) -> R
153    where
154        F: FnOnce(Option<&dyn kernel::syscall::SyscallDriver>) -> R,
155    {
156        match driver_num {
157            capsules_core::console::DRIVER_NUM => f(Some(self.console)),
158            capsules_core::gpio::DRIVER_NUM => f(Some(self.gpio)),
159            capsules_core::alarm::DRIVER_NUM => f(Some(self.alarm)),
160            capsules_core::button::DRIVER_NUM => f(Some(self.button)),
161            capsules_core::led::DRIVER_NUM => f(Some(self.led)),
162            capsules_extra::ninedof::DRIVER_NUM => f(Some(self.ninedof)),
163            capsules_core::adc::DRIVER_NUM => f(Some(self.adc)),
164            capsules_extra::temperature::DRIVER_NUM => f(Some(self.temperature)),
165            capsules_extra::lsm303agr::DRIVER_NUM => f(Some(self.lsm303agr)),
166            capsules_core::rng::DRIVER_NUM => f(Some(self.rng)),
167            capsules_extra::ble_advertising_driver::DRIVER_NUM => f(Some(self.ble_radio)),
168            capsules_extra::buzzer_driver::DRIVER_NUM => f(Some(self.buzzer_driver)),
169            capsules_extra::pwm::DRIVER_NUM => f(Some(self.pwm)),
170            capsules_extra::app_flash_driver::DRIVER_NUM => f(Some(self.app_flash)),
171            capsules_extra::sound_pressure::DRIVER_NUM => f(Some(self.sound_pressure)),
172            capsules_extra::eui64::DRIVER_NUM => f(Some(self.eui64)),
173            capsules_extra::ieee802154::DRIVER_NUM => f(Some(self.ieee802154)),
174            kernel::ipc::DRIVER_NUM => f(Some(&self.ipc)),
175            _ => f(None),
176        }
177    }
178}
179
180impl KernelResources<nrf52833::chip::NRF52<'static, Nrf52833DefaultPeripherals<'static>>>
181    for MicroBit
182{
183    type SyscallDriverLookup = Self;
184    type SyscallFilter = ();
185    type ProcessFault = ();
186    type Scheduler = RoundRobinSched<'static>;
187    type SchedulerTimer = cortexm4::systick::SysTick;
188    type WatchDog = ();
189    type ContextSwitchCallback = ();
190
191    fn syscall_driver_lookup(&self) -> &Self::SyscallDriverLookup {
192        self
193    }
194    fn syscall_filter(&self) -> &Self::SyscallFilter {
195        &()
196    }
197    fn process_fault(&self) -> &Self::ProcessFault {
198        &()
199    }
200    fn scheduler(&self) -> &Self::Scheduler {
201        self.scheduler
202    }
203    fn scheduler_timer(&self) -> &Self::SchedulerTimer {
204        &self.systick
205    }
206    fn watchdog(&self) -> &Self::WatchDog {
207        &()
208    }
209    fn context_switch_callback(&self) -> &Self::ContextSwitchCallback {
210        &()
211    }
212}
213
214/// This is in a separate, inline(never) function so that its stack frame is
215/// removed when this function returns. Otherwise, the stack space used for
216/// these static_inits is wasted.
217#[inline(never)]
218unsafe fn start() -> (
219    &'static kernel::Kernel,
220    MicroBit,
221    &'static nrf52833::chip::NRF52<'static, Nrf52833DefaultPeripherals<'static>>,
222) {
223    nrf52833::init();
224
225    // Initialize deferred calls very early.
226    kernel::deferred_call::initialize_deferred_call_state::<
227        <ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider,
228    >();
229
230    // Bind global variables to this thread.
231    PANIC_RESOURCES.bind_to_thread::<<ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider>();
232
233    let ieee802154_ack_buf = static_init!(
234        [u8; nrf52833::ieee802154_radio::ACK_BUF_SIZE],
235        [0; nrf52833::ieee802154_radio::ACK_BUF_SIZE]
236    );
237    // Initialize chip peripheral drivers
238    let nrf52833_peripherals = static_init!(
239        Nrf52833DefaultPeripherals,
240        Nrf52833DefaultPeripherals::new(ieee802154_ack_buf)
241    );
242
243    // set up circular peripheral dependencies
244    nrf52833_peripherals.init();
245
246    let base_peripherals = &nrf52833_peripherals.nrf52;
247
248    // Create an array to hold process references.
249    let processes = components::process_array::ProcessArrayComponent::new()
250        .finalize(components::process_array_component_static!(NUM_PROCS));
251    PANIC_RESOURCES.get().map(|resources| {
252        resources.processes.put(processes.as_slice());
253    });
254
255    // Setup space to store the core kernel data structure.
256    let board_kernel = static_init!(kernel::Kernel, kernel::Kernel::new(processes.as_slice()));
257
258    //--------------------------------------------------------------------------
259    // RAW 802.15.4
260    //--------------------------------------------------------------------------
261
262    let device_id = (*addr_of!(nrf52833::ficr::FICR_INSTANCE)).id();
263
264    let eui64 = components::eui64::Eui64Component::new(u64::from_le_bytes(device_id))
265        .finalize(components::eui64_component_static!());
266
267    let ieee802154 = components::ieee802154::Ieee802154RawComponent::new(
268        board_kernel,
269        capsules_extra::ieee802154::DRIVER_NUM,
270        &nrf52833_peripherals.ieee802154_radio,
271    )
272    .finalize(components::ieee802154_raw_component_static!(
273        nrf52833::ieee802154_radio::Radio,
274    ));
275    //--------------------------------------------------------------------------
276    // CAPABILITIES
277    //--------------------------------------------------------------------------
278
279    // Create capabilities that the board needs to call certain protected kernel
280    // functions.
281    let process_management_capability =
282        create_capability!(capabilities::ProcessManagementCapability);
283    let memory_allocation_capability = create_capability!(capabilities::MemoryAllocationCapability);
284
285    //--------------------------------------------------------------------------
286    // DEBUG GPIO
287    //--------------------------------------------------------------------------
288
289    // Configure kernel debug GPIOs as early as possible. These are used by the
290    // `debug_gpio!(0, toggle)` macro. We configure these early so that the
291    // macro is available during most of the setup code and kernel execution.
292    let debug_gpios = static_init!(
293        [&'static dyn kernel::hil::gpio::Pin; 1],
294        [&nrf52833_peripherals.gpio_port[LED_KERNEL_PIN]]
295    );
296    kernel::debug::initialize_debug_gpio::<
297        <ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider,
298    >();
299    kernel::debug::assign_gpios(debug_gpios);
300
301    //--------------------------------------------------------------------------
302    // GPIO
303    //--------------------------------------------------------------------------
304
305    let gpio = components::gpio::GpioComponent::new(
306        board_kernel,
307        capsules_core::gpio::DRIVER_NUM,
308        components::gpio_component_helper!(
309            nrf52833::gpio::GPIOPin,
310            // Used as ADC, comment them out in the ADC section to use them as GPIO
311            // 0 => &nrf52833_peripherals.gpio_port[GPIO_P0],
312            // 1 => &nrf52833_peripherals.gpio_port[_GPIO_P1],
313            // 2 => &nrf52833_peripherals.gpio_port[_GPIO_P2],
314            // Used as PWM, comment them out in the PWM section to use them as GPIO
315            //8 => &nrf52833_peripherals.gpio_port[GPIO_P8],
316            9 => &nrf52833_peripherals.gpio_port[GPIO_P9],
317            16 => &nrf52833_peripherals.gpio_port[GPIO_P16],
318        ),
319    )
320    .finalize(components::gpio_component_static!(nrf52833::gpio::GPIOPin));
321
322    //--------------------------------------------------------------------------
323    // Buttons
324    //--------------------------------------------------------------------------
325    let button = components::button::ButtonComponent::new(
326        board_kernel,
327        capsules_core::button::DRIVER_NUM,
328        components::button_component_helper!(
329            nrf52833::gpio::GPIOPin,
330            (
331                &nrf52833_peripherals.gpio_port[BUTTON_A],
332                kernel::hil::gpio::ActivationMode::ActiveLow,
333                kernel::hil::gpio::FloatingState::PullNone
334            ), // A
335            (
336                &nrf52833_peripherals.gpio_port[BUTTON_B],
337                kernel::hil::gpio::ActivationMode::ActiveLow,
338                kernel::hil::gpio::FloatingState::PullNone
339            ), // B
340            (
341                &nrf52833_peripherals.gpio_port[TOUCH_LOGO],
342                kernel::hil::gpio::ActivationMode::ActiveLow,
343                kernel::hil::gpio::FloatingState::PullNone
344            ), // Touch Logo
345        ),
346    )
347    .finalize(components::button_component_static!(
348        nrf52833::gpio::GPIOPin
349    ));
350
351    //--------------------------------------------------------------------------
352    // ALARM & TIMER
353    //--------------------------------------------------------------------------
354
355    let rtc = &base_peripherals.rtc;
356    let _ = rtc.start();
357
358    let mux_alarm = components::alarm::AlarmMuxComponent::new(rtc)
359        .finalize(components::alarm_mux_component_static!(nrf52::rtc::Rtc));
360    let alarm = components::alarm::AlarmDriverComponent::new(
361        board_kernel,
362        capsules_core::alarm::DRIVER_NUM,
363        mux_alarm,
364    )
365    .finalize(components::alarm_component_static!(nrf52::rtc::Rtc));
366
367    //--------------------------------------------------------------------------
368    // PWM & BUZZER
369    //--------------------------------------------------------------------------
370
371    use kernel::hil::buzzer::Buzzer;
372    use kernel::hil::time::Alarm;
373
374    let mux_pwm = components::pwm::PwmMuxComponent::new(&base_peripherals.pwm0)
375        .finalize(components::pwm_mux_component_static!(nrf52833::pwm::Pwm));
376
377    let virtual_pwm_buzzer = components::pwm::PwmPinUserComponent::new(
378        mux_pwm,
379        nrf52833::pinmux::Pinmux::new(SPEAKER_PIN as u32),
380    )
381    .finalize(components::pwm_pin_user_component_static!(
382        nrf52833::pwm::Pwm
383    ));
384
385    let virtual_alarm_buzzer = static_init!(
386        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<'static, nrf52833::rtc::Rtc>,
387        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm::new(mux_alarm)
388    );
389    virtual_alarm_buzzer.setup();
390
391    let pwm_buzzer = static_init!(
392        capsules_extra::buzzer_pwm::PwmBuzzer<
393            'static,
394            capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
395                'static,
396                nrf52833::rtc::Rtc,
397            >,
398            capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, nrf52833::pwm::Pwm>,
399        >,
400        capsules_extra::buzzer_pwm::PwmBuzzer::new(
401            virtual_pwm_buzzer,
402            virtual_alarm_buzzer,
403            capsules_extra::buzzer_pwm::DEFAULT_MAX_BUZZ_TIME_MS,
404        )
405    );
406
407    let buzzer_driver = static_init!(
408        capsules_extra::buzzer_driver::Buzzer<
409            'static,
410            capsules_extra::buzzer_pwm::PwmBuzzer<
411                'static,
412                capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
413                    'static,
414                    nrf52833::rtc::Rtc,
415                >,
416                capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, nrf52833::pwm::Pwm>,
417            >,
418        >,
419        capsules_extra::buzzer_driver::Buzzer::new(
420            pwm_buzzer,
421            capsules_extra::buzzer_driver::DEFAULT_MAX_BUZZ_TIME_MS,
422            board_kernel.create_grant(
423                capsules_extra::buzzer_driver::DRIVER_NUM,
424                &memory_allocation_capability
425            )
426        )
427    );
428
429    pwm_buzzer.set_client(buzzer_driver);
430
431    virtual_alarm_buzzer.set_alarm_client(pwm_buzzer);
432
433    let virtual_pwm_driver = components::pwm::PwmPinUserComponent::new(
434        mux_pwm,
435        nrf52833::pinmux::Pinmux::new(GPIO_P8 as u32),
436    )
437    .finalize(components::pwm_pin_user_component_static!(
438        nrf52833::pwm::Pwm
439    ));
440
441    let pwm =
442        components::pwm::PwmDriverComponent::new(board_kernel, capsules_extra::pwm::DRIVER_NUM)
443            .finalize(components::pwm_driver_component_helper!(virtual_pwm_driver));
444
445    //--------------------------------------------------------------------------
446    // UART & CONSOLE & DEBUG
447    //--------------------------------------------------------------------------
448
449    base_peripherals.uarte0.initialize(
450        nrf52::pinmux::Pinmux::new(UART_TX_PIN as u32),
451        nrf52::pinmux::Pinmux::new(UART_RX_PIN as u32),
452        None,
453        None,
454    );
455
456    // Create a shared UART channel for the console and for kernel debug.
457    let uart_mux = components::console::UartMuxComponent::new(&base_peripherals.uarte0, 115200)
458        .finalize(components::uart_mux_component_static!());
459
460    // Setup the console.
461    let console = components::console::ConsoleComponent::new(
462        board_kernel,
463        capsules_core::console::DRIVER_NUM,
464        uart_mux,
465    )
466    .finalize(components::console_component_static!());
467    // Create the debugger object that handles calls to `debug!()`.
468    components::debug_writer::DebugWriterComponent::new::<
469        <ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider,
470    >(
471        uart_mux,
472        create_capability!(capabilities::SetDebugWriterCapability),
473    )
474    .finalize(components::debug_writer_component_static!());
475
476    //--------------------------------------------------------------------------
477    // RANDOM NUMBERS
478    //--------------------------------------------------------------------------
479
480    let rng = components::rng::RngComponent::new(
481        board_kernel,
482        capsules_core::rng::DRIVER_NUM,
483        &base_peripherals.trng,
484    )
485    .finalize(components::rng_component_static!(nrf52833::trng::Trng));
486
487    //--------------------------------------------------------------------------
488    // SENSORS
489    //--------------------------------------------------------------------------
490
491    base_peripherals.twi1.configure(
492        nrf52833::pinmux::Pinmux::new(I2C_SCL_PIN as u32),
493        nrf52833::pinmux::Pinmux::new(I2C_SDA_PIN as u32),
494    );
495
496    let sensors_i2c_bus = components::i2c::I2CMuxComponent::new(&base_peripherals.twi1, None)
497        .finalize(components::i2c_mux_component_static!(
498            nrf52833::i2c::TWI<'static>
499        ));
500
501    // LSM303AGR
502
503    let lsm303agr = components::lsm303agr::Lsm303agrI2CComponent::new(
504        sensors_i2c_bus,
505        None,
506        None,
507        board_kernel,
508        capsules_extra::lsm303agr::DRIVER_NUM,
509    )
510    .finalize(components::lsm303agr_component_static!(
511        nrf52833::i2c::TWI<'static>
512    ));
513
514    if let Err(error) = lsm303agr.configure(
515        capsules_extra::lsm303xx::Lsm303AccelDataRate::DataRate25Hz,
516        false,
517        capsules_extra::lsm303xx::Lsm303Scale::Scale2G,
518        false,
519        true,
520        capsules_extra::lsm303xx::Lsm303MagnetoDataRate::DataRate3_0Hz,
521        capsules_extra::lsm303xx::Lsm303Range::Range1_9G,
522    ) {
523        debug!("Failed to configure LSM303AGR sensor ({:?})", error);
524    }
525
526    let ninedof = components::ninedof::NineDofComponent::new(
527        board_kernel,
528        capsules_extra::ninedof::DRIVER_NUM,
529    )
530    .finalize(components::ninedof_component_static!(lsm303agr));
531
532    // Temperature
533
534    let temperature = components::temperature::TemperatureComponent::new(
535        board_kernel,
536        capsules_extra::temperature::DRIVER_NUM,
537        &base_peripherals.temp,
538    )
539    .finalize(components::temperature_component_static!(
540        nrf52833::temperature::Temp
541    ));
542
543    //--------------------------------------------------------------------------
544    // ADC
545    //--------------------------------------------------------------------------
546    base_peripherals.adc.calibrate();
547
548    let adc_mux = components::adc::AdcMuxComponent::new(&base_peripherals.adc)
549        .finalize(components::adc_mux_component_static!(nrf52833::adc::Adc));
550
551    // Comment out the following to use P0, P1 and P2 as GPIO
552    let adc_syscall =
553        components::adc::AdcVirtualComponent::new(board_kernel, capsules_core::adc::DRIVER_NUM)
554            .finalize(components::adc_syscall_component_helper!(
555                // ADC Ring 0 (P0)
556                components::adc::AdcComponent::new(
557                    adc_mux,
558                    nrf52833::adc::AdcChannelSetup::new(nrf52833::adc::AdcChannel::AnalogInput0)
559                )
560                .finalize(components::adc_component_static!(nrf52833::adc::Adc)),
561                // ADC Ring 1 (P1)
562                components::adc::AdcComponent::new(
563                    adc_mux,
564                    nrf52833::adc::AdcChannelSetup::new(nrf52833::adc::AdcChannel::AnalogInput1)
565                )
566                .finalize(components::adc_component_static!(nrf52833::adc::Adc)),
567                // ADC Ring 2 (P2)
568                components::adc::AdcComponent::new(
569                    adc_mux,
570                    nrf52833::adc::AdcChannelSetup::new(nrf52833::adc::AdcChannel::AnalogInput2)
571                )
572                .finalize(components::adc_component_static!(nrf52833::adc::Adc))
573            ));
574
575    // Microphone
576
577    let adc_microphone = components::adc_microphone::AdcMicrophoneComponent::new(
578        adc_mux,
579        nrf52833::adc::AdcChannelSetup::setup(
580            nrf52833::adc::AdcChannel::AnalogInput3,
581            nrf52833::adc::AdcChannelGain::Gain4,
582            nrf52833::adc::AdcChannelResistor::Bypass,
583            nrf52833::adc::AdcChannelResistor::Pulldown,
584            nrf52833::adc::AdcChannelSamplingTime::us3,
585        ),
586        Some(&nrf52833_peripherals.gpio_port[LED_MICROPHONE_PIN]),
587    )
588    .finalize(components::adc_microphone_component_static!(
589        // adc
590        nrf52833::adc::Adc,
591        // buffer size
592        50,
593        // gpio
594        nrf52833::gpio::GPIOPin
595    ));
596
597    nrf52833_peripherals.gpio_port[LED_MICROPHONE_PIN].set_high_drive(true);
598
599    let sound_pressure = components::sound_pressure::SoundPressureComponent::new(
600        board_kernel,
601        capsules_extra::sound_pressure::DRIVER_NUM,
602        adc_microphone,
603    )
604    .finalize(components::sound_pressure_component_static!());
605
606    //--------------------------------------------------------------------------
607    // STORAGE
608    //--------------------------------------------------------------------------
609
610    let mux_flash = components::flash::FlashMuxComponent::new(&base_peripherals.nvmc).finalize(
611        components::flash_mux_component_static!(nrf52833::nvmc::Nvmc),
612    );
613
614    // App Flash
615
616    let virtual_app_flash = components::flash::FlashUserComponent::new(mux_flash).finalize(
617        components::flash_user_component_static!(nrf52833::nvmc::Nvmc),
618    );
619
620    let app_flash = components::app_flash_driver::AppFlashComponent::new(
621        board_kernel,
622        capsules_extra::app_flash_driver::DRIVER_NUM,
623        virtual_app_flash,
624    )
625    .finalize(components::app_flash_component_static!(
626        capsules_core::virtualizers::virtual_flash::FlashUser<'static, nrf52833::nvmc::Nvmc>,
627        512
628    ));
629
630    //--------------------------------------------------------------------------
631    // WIRELESS
632    //--------------------------------------------------------------------------
633
634    let ble_radio = components::ble::BLEComponent::new(
635        board_kernel,
636        capsules_extra::ble_advertising_driver::DRIVER_NUM,
637        &base_peripherals.ble_radio,
638        mux_alarm,
639    )
640    .finalize(components::ble_component_static!(
641        nrf52833::rtc::Rtc,
642        nrf52833::ble_radio::Radio
643    ));
644
645    //--------------------------------------------------------------------------
646    // LED Matrix
647    //--------------------------------------------------------------------------
648
649    let led_matrix = components::led_matrix::LedMatrixComponent::new(
650        mux_alarm,
651        components::led_line_component_static!(
652            nrf52833::gpio::GPIOPin,
653            &nrf52833_peripherals.gpio_port[LED_MATRIX_COLS[0]],
654            &nrf52833_peripherals.gpio_port[LED_MATRIX_COLS[1]],
655            &nrf52833_peripherals.gpio_port[LED_MATRIX_COLS[2]],
656            &nrf52833_peripherals.gpio_port[LED_MATRIX_COLS[3]],
657            &nrf52833_peripherals.gpio_port[LED_MATRIX_COLS[4]],
658        ),
659        components::led_line_component_static!(
660            nrf52833::gpio::GPIOPin,
661            &nrf52833_peripherals.gpio_port[LED_MATRIX_ROWS[0]],
662            &nrf52833_peripherals.gpio_port[LED_MATRIX_ROWS[1]],
663            &nrf52833_peripherals.gpio_port[LED_MATRIX_ROWS[2]],
664            &nrf52833_peripherals.gpio_port[LED_MATRIX_ROWS[3]],
665            &nrf52833_peripherals.gpio_port[LED_MATRIX_ROWS[4]],
666        ),
667        kernel::hil::gpio::ActivationMode::ActiveLow,
668        kernel::hil::gpio::ActivationMode::ActiveHigh,
669        60,
670    )
671    .finalize(components::led_matrix_component_static!(
672        nrf52833::gpio::GPIOPin,
673        nrf52::rtc::Rtc<'static>,
674        5,
675        5
676    ));
677
678    let led = static_init!(
679        capsules_core::led::LedDriver<
680            'static,
681            capsules_extra::led_matrix::LedMatrixLed<
682                'static,
683                nrf52::gpio::GPIOPin<'static>,
684                capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
685                    'static,
686                    nrf52::rtc::Rtc<'static>,
687                >,
688            >,
689            25,
690        >,
691        capsules_core::led::LedDriver::new(components::led_matrix_leds!(
692            nrf52::gpio::GPIOPin<'static>,
693            capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
694                'static,
695                nrf52::rtc::Rtc<'static>,
696            >,
697            led_matrix,
698            (0, 0),
699            (1, 0),
700            (2, 0),
701            (3, 0),
702            (4, 0),
703            (0, 1),
704            (1, 1),
705            (2, 1),
706            (3, 1),
707            (4, 1),
708            (0, 2),
709            (1, 2),
710            (2, 2),
711            (3, 2),
712            (4, 2),
713            (0, 3),
714            (1, 3),
715            (2, 3),
716            (3, 3),
717            (4, 3),
718            (0, 4),
719            (1, 4),
720            (2, 4),
721            (3, 4),
722            (4, 4)
723        )),
724    );
725
726    //--------------------------------------------------------------------------
727    // Process Console
728    //--------------------------------------------------------------------------
729    let process_printer = components::process_printer::ProcessPrinterTextComponent::new()
730        .finalize(components::process_printer_text_component_static!());
731    PANIC_RESOURCES.get().map(|resources| {
732        resources.printer.put(process_printer);
733    });
734
735    let _process_console = components::process_console::ProcessConsoleComponent::new(
736        board_kernel,
737        uart_mux,
738        mux_alarm,
739        process_printer,
740        Some(cortexm4::support::reset),
741    )
742    .finalize(components::process_console_component_static!(
743        nrf52833::rtc::Rtc
744    ));
745    let _ = _process_console.start();
746
747    //--------------------------------------------------------------------------
748    // FINAL SETUP AND BOARD BOOT
749    //--------------------------------------------------------------------------
750
751    // it seems that microbit v2 has no external clock
752    base_peripherals.clock.low_stop();
753    base_peripherals.clock.high_stop();
754    base_peripherals.clock.low_start();
755    base_peripherals.clock.high_start();
756    while !base_peripherals.clock.low_started() {}
757    while !base_peripherals.clock.high_started() {}
758
759    let scheduler = components::sched::round_robin::RoundRobinComponent::new(processes)
760        .finalize(components::round_robin_component_static!(NUM_PROCS));
761
762    let microbit = MicroBit {
763        ble_radio,
764        ieee802154,
765        eui64,
766        console,
767        gpio,
768        button,
769        led,
770        rng,
771        temperature,
772        lsm303agr,
773        ninedof,
774        buzzer_driver,
775        pwm,
776        sound_pressure,
777        adc: adc_syscall,
778        alarm,
779        app_flash,
780        ipc: kernel::ipc::IPC::new(
781            board_kernel,
782            kernel::ipc::DRIVER_NUM,
783            &memory_allocation_capability,
784        ),
785
786        scheduler,
787        systick: cortexm4::systick::SysTick::new_with_calibration(64000000),
788    };
789
790    let chip = static_init!(
791        nrf52833::chip::NRF52<Nrf52833DefaultPeripherals>,
792        nrf52833::chip::NRF52::new(nrf52833_peripherals)
793    );
794    PANIC_RESOURCES.get().map(|resources| {
795        resources.chip.put(chip);
796    });
797
798    debug!("Initialization complete. Entering main loop.");
799
800    //--------------------------------------------------------------------------
801    // PROCESSES AND MAIN LOOP
802    //--------------------------------------------------------------------------
803
804    // These symbols are defined in the linker script.
805    extern "C" {
806        /// Beginning of the ROM region containing app images.
807        static _sapps: u8;
808        /// End of the ROM region containing app images.
809        static _eapps: u8;
810        /// Beginning of the RAM region for app memory.
811        static mut _sappmem: u8;
812        /// End of the RAM region for app memory.
813        static _eappmem: u8;
814    }
815
816    kernel::process::load_processes(
817        board_kernel,
818        chip,
819        core::slice::from_raw_parts(
820            core::ptr::addr_of!(_sapps),
821            core::ptr::addr_of!(_eapps) as usize - core::ptr::addr_of!(_sapps) as usize,
822        ),
823        core::slice::from_raw_parts_mut(
824            core::ptr::addr_of_mut!(_sappmem),
825            core::ptr::addr_of!(_eappmem) as usize - core::ptr::addr_of!(_sappmem) as usize,
826        ),
827        &FAULT_RESPONSE,
828        &process_management_capability,
829    )
830    .unwrap_or_else(|err| {
831        debug!("Error loading processes!");
832        debug!("{:?}", err);
833    });
834
835    (board_kernel, microbit, chip)
836}
837
838/// Main function called after RAM initialized.
839#[no_mangle]
840pub unsafe fn main() {
841    let main_loop_capability = create_capability!(capabilities::MainLoopCapability);
842
843    let (board_kernel, board, chip) = start();
844    board_kernel.kernel_loop(&board, chip, Some(&board.ipc), &main_loop_capability);
845}