clue_nrf52840/
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 Adafruit CLUE nRF52480 Express.
6//!
7//! It is based on nRF52840 Express SoC (Cortex M4 core with a BLE + IEEE 802.15.4 transceiver).
8
9#![no_std]
10#![no_main]
11#![deny(missing_docs)]
12
13use core::ptr::addr_of;
14
15use capsules_core::virtualizers::virtual_aes_ccm::MuxAES128CCM;
16
17use kernel::capabilities;
18use kernel::component::Component;
19use kernel::debug::PanicResources;
20use kernel::hil;
21use kernel::hil::buzzer::Buzzer;
22use kernel::hil::i2c::I2CMaster;
23use kernel::hil::led::LedHigh;
24use kernel::hil::symmetric_encryption::AES128;
25use kernel::hil::time::Alarm;
26use kernel::hil::time::Counter;
27use kernel::hil::usb::Client;
28use kernel::platform::chip::Chip;
29use kernel::platform::{KernelResources, SyscallDriverLookup};
30use kernel::scheduler::round_robin::RoundRobinSched;
31use kernel::utilities::cells::MapCell;
32use kernel::utilities::single_thread_value::SingleThreadValue;
33#[allow(unused_imports)]
34use kernel::{create_capability, debug, debug_gpio, debug_verbose, static_init};
35
36use nrf52840::gpio::Pin;
37use nrf52840::interrupt_service::Nrf52840DefaultPeripherals;
38
39// LEDs.
40const LED_RED_PIN: Pin = Pin::P1_01;
41const LED_WHITE_PIN: Pin = Pin::P0_10;
42
43const LED_KERNEL_PIN: Pin = Pin::P1_01;
44
45// Speaker
46const SPEAKER_PIN: Pin = Pin::P1_00;
47
48// Buttons
49const BUTTON_LEFT: Pin = Pin::P1_02;
50const BUTTON_RIGHT: Pin = Pin::P1_10;
51
52#[allow(dead_code)]
53const GPIO_D0: Pin = Pin::P0_04;
54#[allow(dead_code)]
55const GPIO_D1: Pin = Pin::P0_05;
56#[allow(dead_code)]
57const GPIO_D2: Pin = Pin::P0_03;
58#[allow(dead_code)]
59const GPIO_D3: Pin = Pin::P0_28;
60#[allow(dead_code)]
61const GPIO_D4: Pin = Pin::P0_02;
62
63const GPIO_D6: Pin = Pin::P1_09;
64const GPIO_D7: Pin = Pin::P0_07;
65const GPIO_D8: Pin = Pin::P1_07;
66const GPIO_D9: Pin = Pin::P0_27;
67
68#[allow(dead_code)]
69const GPIO_D10: Pin = Pin::P0_30;
70#[allow(dead_code)]
71const GPIO_D12: Pin = Pin::P0_31;
72
73const GPIO_D13: Pin = Pin::P0_08;
74const GPIO_D14: Pin = Pin::P0_06;
75const GPIO_D15: Pin = Pin::P0_26;
76const GPIO_D16: Pin = Pin::P0_29;
77
78const _UART_TX_PIN: Pin = Pin::P0_05;
79const _UART_RX_PIN: Pin = Pin::P0_04;
80
81/// I2C pins for all of the sensors.
82const I2C_SDA_PIN: Pin = Pin::P0_24;
83const I2C_SCL_PIN: Pin = Pin::P0_25;
84
85/// Interrupt pin for the APDS9960 sensor.
86const APDS9960_PIN: Pin = Pin::P0_09;
87
88/// Personal Area Network ID for the IEEE 802.15.4 radio
89const PAN_ID: u16 = 0xABCD;
90
91/// TFT ST7789H2
92const ST7789H2_SCK: Pin = Pin::P0_14;
93const ST7789H2_MOSI: Pin = Pin::P0_15;
94const ST7789H2_MISO: Pin = Pin::P0_26; // ST7789H2 has no MISO Pin, but SPI requires a MISO Pin
95const ST7789H2_CS: Pin = Pin::P0_12;
96const ST7789H2_DC: Pin = Pin::P0_13;
97const ST7789H2_RESET: Pin = Pin::P1_03;
98
99/// TFT backlight
100const _ST7789H2_LITE: Pin = Pin::P1_05;
101
102/// UART Writer for panic!()s.
103pub mod io;
104
105// State for loading and holding applications.
106// How should the kernel respond when a process faults.
107const FAULT_RESPONSE: capsules_system::process_policies::StopWithDebugFaultPolicy =
108    capsules_system::process_policies::StopWithDebugFaultPolicy {};
109
110// Number of concurrent processes this platform supports.
111const NUM_PROCS: usize = 8;
112
113type ChipHw = nrf52840::chip::NRF52<'static, Nrf52840DefaultPeripherals<'static>>;
114type ProcessPrinter = capsules_system::process_printer::ProcessPrinterText;
115
116static mut CDC_REF_FOR_PANIC: Option<
117    &'static capsules_extra::usb::cdc::CdcAcm<
118        'static,
119        nrf52::usbd::Usbd,
120        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<'static, nrf52::rtc::Rtc>,
121    >,
122> = None;
123/// Resources for when a board panics used by io.rs.
124static PANIC_RESOURCES: SingleThreadValue<PanicResources<ChipHw, ProcessPrinter>> =
125    SingleThreadValue::new(PanicResources::new());
126static NRF52_POWER: SingleThreadValue<MapCell<&'static nrf52840::power::Power>> =
127    SingleThreadValue::new(MapCell::empty());
128
129kernel::stack_size! {0x1000}
130
131// Function for the CDC/USB stack to use to enter the Adafruit nRF52 Bootloader
132fn baud_rate_reset_bootloader_enter() {
133    unsafe {
134        // 0x4e is the magic value the Adafruit nRF52 Bootloader expects
135        // as defined by https://github.com/adafruit/Adafruit_nRF52_Bootloader/blob/master/src/main.c
136        NRF52_POWER.get().map(|power_cell| {
137            power_cell.map(|power| {
138                power.set_gpregret(0x90);
139            });
140        });
141        // uncomment to use with Adafruit nRF52 Bootloader
142        // NRF52_POWER.unwrap().set_gpregret(0x4e);
143        cortexm4::scb::reset();
144    }
145}
146
147type SHT3xSensor = components::sht3x::SHT3xComponentType<
148    capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<'static, nrf52::rtc::Rtc<'static>>,
149    capsules_core::virtualizers::virtual_i2c::I2CDevice<'static, nrf52840::i2c::TWI<'static>>,
150>;
151type TemperatureDriver = components::temperature::TemperatureComponentType<SHT3xSensor>;
152type HumidityDriver = components::humidity::HumidityComponentType<SHT3xSensor>;
153type RngDriver = components::rng::RngComponentType<nrf52840::trng::Trng<'static>>;
154
155type Ieee802154Driver = components::ieee802154::Ieee802154ComponentType<
156    nrf52840::ieee802154_radio::Radio<'static>,
157    nrf52840::aes::AesECB<'static>,
158>;
159
160/// Supported drivers by the platform
161pub struct Platform {
162    ble_radio: &'static capsules_extra::ble_advertising_driver::BLE<
163        'static,
164        nrf52::ble_radio::Radio<'static>,
165        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
166            'static,
167            nrf52::rtc::Rtc<'static>,
168        >,
169    >,
170    ieee802154_radio: &'static Ieee802154Driver,
171    console: &'static capsules_core::console::Console<'static>,
172    proximity: &'static capsules_extra::proximity::ProximitySensor<'static>,
173    gpio: &'static capsules_core::gpio::GPIO<'static, nrf52::gpio::GPIOPin<'static>>,
174    led: &'static capsules_core::led::LedDriver<
175        'static,
176        LedHigh<'static, nrf52::gpio::GPIOPin<'static>>,
177        2,
178    >,
179    button: &'static capsules_core::button::Button<'static, nrf52::gpio::GPIOPin<'static>>,
180    screen: &'static capsules_extra::screen::screen::Screen<'static>,
181    rng: &'static RngDriver,
182    ipc: kernel::ipc::IPC<{ NUM_PROCS as u8 }>,
183    alarm: &'static capsules_core::alarm::AlarmDriver<
184        'static,
185        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
186            'static,
187            nrf52::rtc::Rtc<'static>,
188        >,
189    >,
190    buzzer: &'static capsules_extra::buzzer_driver::Buzzer<
191        'static,
192        capsules_extra::buzzer_pwm::PwmBuzzer<
193            'static,
194            capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
195                'static,
196                nrf52840::rtc::Rtc<'static>,
197            >,
198            capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, nrf52840::pwm::Pwm>,
199        >,
200    >,
201    adc: &'static capsules_core::adc::AdcVirtualized<'static>,
202    temperature: &'static TemperatureDriver,
203    humidity: &'static HumidityDriver,
204    scheduler: &'static RoundRobinSched<'static>,
205    systick: cortexm4::systick::SysTick,
206}
207
208impl SyscallDriverLookup for Platform {
209    fn with_driver<F, R>(&self, driver_num: usize, f: F) -> R
210    where
211        F: FnOnce(Option<&dyn kernel::syscall::SyscallDriver>) -> R,
212    {
213        match driver_num {
214            capsules_core::console::DRIVER_NUM => f(Some(self.console)),
215            capsules_extra::proximity::DRIVER_NUM => f(Some(self.proximity)),
216            capsules_core::gpio::DRIVER_NUM => f(Some(self.gpio)),
217            capsules_core::alarm::DRIVER_NUM => f(Some(self.alarm)),
218            capsules_core::led::DRIVER_NUM => f(Some(self.led)),
219            capsules_core::button::DRIVER_NUM => f(Some(self.button)),
220            capsules_core::adc::DRIVER_NUM => f(Some(self.adc)),
221            capsules_extra::screen::screen::DRIVER_NUM => f(Some(self.screen)),
222            capsules_core::rng::DRIVER_NUM => f(Some(self.rng)),
223            capsules_extra::ble_advertising_driver::DRIVER_NUM => f(Some(self.ble_radio)),
224            capsules_extra::ieee802154::DRIVER_NUM => f(Some(self.ieee802154_radio)),
225            capsules_extra::buzzer_driver::DRIVER_NUM => f(Some(self.buzzer)),
226            kernel::ipc::DRIVER_NUM => f(Some(&self.ipc)),
227            capsules_extra::temperature::DRIVER_NUM => f(Some(self.temperature)),
228            capsules_extra::humidity::DRIVER_NUM => f(Some(self.humidity)),
229            _ => f(None),
230        }
231    }
232}
233
234impl KernelResources<nrf52::chip::NRF52<'static, Nrf52840DefaultPeripherals<'static>>>
235    for Platform
236{
237    type SyscallDriverLookup = Self;
238    type SyscallFilter = ();
239    type ProcessFault = ();
240    type Scheduler = RoundRobinSched<'static>;
241    type SchedulerTimer = cortexm4::systick::SysTick;
242    type WatchDog = ();
243    type ContextSwitchCallback = ();
244
245    fn syscall_driver_lookup(&self) -> &Self::SyscallDriverLookup {
246        self
247    }
248    fn syscall_filter(&self) -> &Self::SyscallFilter {
249        &()
250    }
251    fn process_fault(&self) -> &Self::ProcessFault {
252        &()
253    }
254    fn scheduler(&self) -> &Self::Scheduler {
255        self.scheduler
256    }
257    fn scheduler_timer(&self) -> &Self::SchedulerTimer {
258        &self.systick
259    }
260    fn watchdog(&self) -> &Self::WatchDog {
261        &()
262    }
263    fn context_switch_callback(&self) -> &Self::ContextSwitchCallback {
264        &()
265    }
266}
267
268/// This is in a separate, inline(never) function so that its stack frame is
269/// removed when this function returns. Otherwise, the stack space used for
270/// these static_inits is wasted.
271#[inline(never)]
272unsafe fn start() -> (
273    &'static kernel::Kernel,
274    Platform,
275    &'static nrf52840::chip::NRF52<'static, Nrf52840DefaultPeripherals<'static>>,
276) {
277    nrf52840::init();
278
279    // Initialize deferred calls very early.
280    kernel::deferred_call::initialize_deferred_call_state::<
281        <ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider,
282    >();
283
284    // Bind global variables to this thread.
285    PANIC_RESOURCES.bind_to_thread::<<ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider>();
286    NRF52_POWER.bind_to_thread::<<ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider>();
287
288    let ieee802154_ack_buf = static_init!(
289        [u8; nrf52840::ieee802154_radio::ACK_BUF_SIZE],
290        [0; nrf52840::ieee802154_radio::ACK_BUF_SIZE]
291    );
292    // Initialize chip peripheral drivers
293    let nrf52840_peripherals = static_init!(
294        Nrf52840DefaultPeripherals,
295        Nrf52840DefaultPeripherals::new(ieee802154_ack_buf)
296    );
297
298    // set up circular peripheral dependencies
299    nrf52840_peripherals.init();
300
301    let base_peripherals = &nrf52840_peripherals.nrf52;
302
303    // Save a reference to the power module for resetting the board into the
304    // bootloader.
305    NRF52_POWER.get().map(|power_cell| {
306        power_cell.put(&base_peripherals.pwr_clk);
307    });
308
309    // Create an array to hold process references.
310    let processes = components::process_array::ProcessArrayComponent::new()
311        .finalize(components::process_array_component_static!(NUM_PROCS));
312    PANIC_RESOURCES.get().map(|resources| {
313        resources.processes.put(processes.as_slice());
314    });
315
316    // Setup space to store the core kernel data structure.
317    let board_kernel = static_init!(kernel::Kernel, kernel::Kernel::new(processes.as_slice()));
318
319    //--------------------------------------------------------------------------
320    // CAPABILITIES
321    //--------------------------------------------------------------------------
322
323    // Create capabilities that the board needs to call certain protected kernel
324    // functions.
325    let process_management_capability =
326        create_capability!(capabilities::ProcessManagementCapability);
327    let memory_allocation_capability = create_capability!(capabilities::MemoryAllocationCapability);
328
329    //--------------------------------------------------------------------------
330    // DEBUG GPIO
331    //--------------------------------------------------------------------------
332
333    // Configure kernel debug GPIOs as early as possible. These are used by the
334    // `debug_gpio!(0, toggle)` macro. We configure these early so that the
335    // macro is available during most of the setup code and kernel execution.
336    let debug_gpios = static_init!(
337        [&'static dyn kernel::hil::gpio::Pin; 1],
338        [&nrf52840_peripherals.gpio_port[LED_KERNEL_PIN]]
339    );
340    kernel::debug::initialize_debug_gpio::<
341        <ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider,
342    >();
343    kernel::debug::assign_gpios(debug_gpios);
344
345    //--------------------------------------------------------------------------
346    // GPIO
347    //--------------------------------------------------------------------------
348
349    let gpio = components::gpio::GpioComponent::new(
350        board_kernel,
351        capsules_core::gpio::DRIVER_NUM,
352        components::gpio_component_helper!(
353            nrf52840::gpio::GPIOPin,
354            // uncomment the following to use pins D0, D1, D2, D3 and D4 as gpio
355            // instead of A2, A3, A4, A5 and A6
356            // 0 => &nrf52840_peripherals.gpio_port[GPIO_D0],
357            // 1 => &nrf52840_peripherals.gpio_port[GPIO_D1],
358            // 2 => &nrf52840_peripherals.gpio_port[GPIO_D2],
359            // 3 => &nrf52840_peripherals.gpio_port[GPIO_D3],
360            // 4 => &nrf52840_peripherals.gpio_port[GPIO_D4],
361
362            6 => &nrf52840_peripherals.gpio_port[GPIO_D6],
363            7 => &nrf52840_peripherals.gpio_port[GPIO_D7],
364            8 => &nrf52840_peripherals.gpio_port[GPIO_D8],
365            9 => &nrf52840_peripherals.gpio_port[GPIO_D9],
366
367            // uncomment the following to use pins D10 as gpio instead of A7
368            // 10 => &nrf52840_peripherals.gpio_port[GPIO_D10],
369
370            // uncomment the following to use pins D12 as gpio instead of A0
371            // 12 => &nrf52840_peripherals.gpio_port[GPIO_D12],
372
373            13 => &nrf52840_peripherals.gpio_port[GPIO_D13],
374            14 => &nrf52840_peripherals.gpio_port[GPIO_D14],
375            15 => &nrf52840_peripherals.gpio_port[GPIO_D15],
376            16 => &nrf52840_peripherals.gpio_port[GPIO_D16]
377        ),
378    )
379    .finalize(components::gpio_component_static!(nrf52840::gpio::GPIOPin));
380
381    //--------------------------------------------------------------------------
382    // LEDs
383    //--------------------------------------------------------------------------
384
385    let led = components::led::LedsComponent::new().finalize(components::led_component_static!(
386        LedHigh<'static, nrf52840::gpio::GPIOPin>,
387        LedHigh::new(&nrf52840_peripherals.gpio_port[LED_RED_PIN]),
388        LedHigh::new(&nrf52840_peripherals.gpio_port[LED_WHITE_PIN])
389    ));
390
391    //--------------------------------------------------------------------------
392    // Buttons
393    //--------------------------------------------------------------------------
394    let button = components::button::ButtonComponent::new(
395        board_kernel,
396        capsules_core::button::DRIVER_NUM,
397        components::button_component_helper!(
398            nrf52840::gpio::GPIOPin,
399            (
400                &nrf52840_peripherals.gpio_port[BUTTON_LEFT],
401                kernel::hil::gpio::ActivationMode::ActiveLow,
402                kernel::hil::gpio::FloatingState::PullUp
403            ), // Left
404            (
405                &nrf52840_peripherals.gpio_port[BUTTON_RIGHT],
406                kernel::hil::gpio::ActivationMode::ActiveLow,
407                kernel::hil::gpio::FloatingState::PullUp
408            ) // Right
409        ),
410    )
411    .finalize(components::button_component_static!(
412        nrf52840::gpio::GPIOPin
413    ));
414
415    //--------------------------------------------------------------------------
416    // ALARM & TIMER
417    //--------------------------------------------------------------------------
418
419    let rtc = &base_peripherals.rtc;
420    let _ = rtc.start();
421
422    let mux_alarm = components::alarm::AlarmMuxComponent::new(rtc)
423        .finalize(components::alarm_mux_component_static!(nrf52::rtc::Rtc));
424    let alarm = components::alarm::AlarmDriverComponent::new(
425        board_kernel,
426        capsules_core::alarm::DRIVER_NUM,
427        mux_alarm,
428    )
429    .finalize(components::alarm_component_static!(nrf52::rtc::Rtc));
430
431    //--------------------------------------------------------------------------
432    // PWM & BUZZER
433    //--------------------------------------------------------------------------
434
435    let mux_pwm = static_init!(
436        capsules_core::virtualizers::virtual_pwm::MuxPwm<'static, nrf52840::pwm::Pwm>,
437        capsules_core::virtualizers::virtual_pwm::MuxPwm::new(&base_peripherals.pwm0)
438    );
439    let virtual_pwm_buzzer = static_init!(
440        capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, nrf52840::pwm::Pwm>,
441        capsules_core::virtualizers::virtual_pwm::PwmPinUser::new(
442            mux_pwm,
443            nrf52840::pinmux::Pinmux::new(SPEAKER_PIN as u32)
444        )
445    );
446    virtual_pwm_buzzer.add_to_mux();
447
448    let virtual_alarm_buzzer = static_init!(
449        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<'static, nrf52840::rtc::Rtc>,
450        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm::new(mux_alarm)
451    );
452    virtual_alarm_buzzer.setup();
453
454    let pwm_buzzer = static_init!(
455        capsules_extra::buzzer_pwm::PwmBuzzer<
456            'static,
457            capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
458                'static,
459                nrf52840::rtc::Rtc,
460            >,
461            capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, nrf52840::pwm::Pwm>,
462        >,
463        capsules_extra::buzzer_pwm::PwmBuzzer::new(
464            virtual_pwm_buzzer,
465            virtual_alarm_buzzer,
466            capsules_extra::buzzer_pwm::DEFAULT_MAX_BUZZ_TIME_MS,
467        )
468    );
469
470    let buzzer = static_init!(
471        capsules_extra::buzzer_driver::Buzzer<
472            'static,
473            capsules_extra::buzzer_pwm::PwmBuzzer<
474                'static,
475                capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
476                    'static,
477                    nrf52840::rtc::Rtc,
478                >,
479                capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, nrf52840::pwm::Pwm>,
480            >,
481        >,
482        capsules_extra::buzzer_driver::Buzzer::new(
483            pwm_buzzer,
484            capsules_extra::buzzer_driver::DEFAULT_MAX_BUZZ_TIME_MS,
485            board_kernel.create_grant(
486                capsules_extra::buzzer_driver::DRIVER_NUM,
487                &memory_allocation_capability
488            )
489        )
490    );
491
492    pwm_buzzer.set_client(buzzer);
493
494    virtual_alarm_buzzer.set_alarm_client(pwm_buzzer);
495
496    //--------------------------------------------------------------------------
497    // UART & CONSOLE & DEBUG
498    //--------------------------------------------------------------------------
499
500    // Setup the CDC-ACM over USB driver that we will use for UART.
501    // We use the Adafruit Vendor ID and Product ID since the device is the same.
502
503    // Create the strings we include in the USB descriptor. We use the hardcoded
504    // DEVICEADDR register on the nRF52 to set the serial number.
505    let serial_number_buf = static_init!([u8; 17], [0; 17]);
506    let serial_number_string: &'static str =
507        (*addr_of!(nrf52::ficr::FICR_INSTANCE)).address_str(serial_number_buf);
508    let strings = static_init!(
509        [&str; 3],
510        [
511            "Adafruit",               // Manufacturer
512            "CLUE nRF52840 - TockOS", // Product
513            serial_number_string,     // Serial number
514        ]
515    );
516
517    let cdc = components::cdc::CdcAcmComponent::new(
518        &nrf52840_peripherals.usbd,
519        capsules_extra::usb::cdc::MAX_CTRL_PACKET_SIZE_NRF52840,
520        0x239a,
521        0x8071,
522        strings,
523        mux_alarm,
524        Some(&baud_rate_reset_bootloader_enter),
525    )
526    .finalize(components::cdc_acm_component_static!(
527        nrf52::usbd::Usbd,
528        nrf52::rtc::Rtc
529    ));
530    CDC_REF_FOR_PANIC = Some(cdc); //for use by panic handler
531
532    // Create a shared UART channel for the console and for kernel debug.
533    let uart_mux = components::console::UartMuxComponent::new(cdc, 115200)
534        .finalize(components::uart_mux_component_static!());
535
536    // Setup the console.
537    let console = components::console::ConsoleComponent::new(
538        board_kernel,
539        capsules_core::console::DRIVER_NUM,
540        uart_mux,
541    )
542    .finalize(components::console_component_static!());
543    // Create the debugger object that handles calls to `debug!()`.
544    components::debug_writer::DebugWriterComponent::new::<
545        <ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider,
546    >(
547        uart_mux,
548        create_capability!(capabilities::SetDebugWriterCapability),
549    )
550    .finalize(components::debug_writer_component_static!());
551
552    //--------------------------------------------------------------------------
553    // RANDOM NUMBERS
554    //--------------------------------------------------------------------------
555
556    let rng = components::rng::RngComponent::new(
557        board_kernel,
558        capsules_core::rng::DRIVER_NUM,
559        &base_peripherals.trng,
560    )
561    .finalize(components::rng_component_static!(nrf52840::trng::Trng));
562
563    //--------------------------------------------------------------------------
564    // ADC
565    //--------------------------------------------------------------------------
566    base_peripherals.adc.calibrate();
567
568    let adc_mux = components::adc::AdcMuxComponent::new(&base_peripherals.adc)
569        .finalize(components::adc_mux_component_static!(nrf52840::adc::Adc));
570
571    let adc_syscall =
572        components::adc::AdcVirtualComponent::new(board_kernel, capsules_core::adc::DRIVER_NUM)
573            .finalize(components::adc_syscall_component_helper!(
574                // A0
575                components::adc::AdcComponent::new(
576                    adc_mux,
577                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput7)
578                )
579                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
580                // A1
581                components::adc::AdcComponent::new(
582                    adc_mux,
583                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput5)
584                )
585                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
586                // A2
587                components::adc::AdcComponent::new(
588                    adc_mux,
589                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput2)
590                )
591                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
592                // A3
593                components::adc::AdcComponent::new(
594                    adc_mux,
595                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput3)
596                )
597                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
598                // A4
599                components::adc::AdcComponent::new(
600                    adc_mux,
601                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput1)
602                )
603                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
604                // A5
605                components::adc::AdcComponent::new(
606                    adc_mux,
607                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput4)
608                )
609                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
610                // A6
611                components::adc::AdcComponent::new(
612                    adc_mux,
613                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput0)
614                )
615                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
616            ));
617
618    //--------------------------------------------------------------------------
619    // SENSORS
620    //--------------------------------------------------------------------------
621
622    let sensors_i2c_bus = static_init!(
623        capsules_core::virtualizers::virtual_i2c::MuxI2C<'static, nrf52840::i2c::TWI>,
624        capsules_core::virtualizers::virtual_i2c::MuxI2C::new(&base_peripherals.twi1, None,)
625    );
626    kernel::deferred_call::DeferredCallClient::register(sensors_i2c_bus);
627    base_peripherals.twi1.configure(
628        nrf52840::pinmux::Pinmux::new(I2C_SCL_PIN as u32),
629        nrf52840::pinmux::Pinmux::new(I2C_SDA_PIN as u32),
630    );
631    base_peripherals.twi1.set_master_client(sensors_i2c_bus);
632
633    let apds9960 = components::apds9960::Apds9960Component::new(
634        sensors_i2c_bus,
635        0x39,
636        &nrf52840_peripherals.gpio_port[APDS9960_PIN],
637    )
638    .finalize(components::apds9960_component_static!(nrf52840::i2c::TWI));
639    let proximity = components::proximity::ProximityComponent::new(
640        apds9960,
641        board_kernel,
642        capsules_extra::proximity::DRIVER_NUM,
643    )
644    .finalize(components::proximity_component_static!());
645
646    let sht3x = components::sht3x::SHT3xComponent::new(
647        sensors_i2c_bus,
648        capsules_extra::sht3x::BASE_ADDR,
649        mux_alarm,
650    )
651    .finalize(components::sht3x_component_static!(
652        nrf52::rtc::Rtc<'static>,
653        nrf52840::i2c::TWI
654    ));
655
656    let temperature = components::temperature::TemperatureComponent::new(
657        board_kernel,
658        capsules_extra::temperature::DRIVER_NUM,
659        sht3x,
660    )
661    .finalize(components::temperature_component_static!(SHT3xSensor));
662
663    let humidity = components::humidity::HumidityComponent::new(
664        board_kernel,
665        capsules_extra::humidity::DRIVER_NUM,
666        sht3x,
667    )
668    .finalize(components::humidity_component_static!(SHT3xSensor));
669
670    //--------------------------------------------------------------------------
671    // TFT
672    //--------------------------------------------------------------------------
673
674    let spi_mux = components::spi::SpiMuxComponent::new(&base_peripherals.spim0)
675        .finalize(components::spi_mux_component_static!(nrf52840::spi::SPIM));
676
677    base_peripherals.spim0.configure(
678        nrf52840::pinmux::Pinmux::new(ST7789H2_MOSI as u32),
679        nrf52840::pinmux::Pinmux::new(ST7789H2_MISO as u32),
680        nrf52840::pinmux::Pinmux::new(ST7789H2_SCK as u32),
681    );
682
683    let bus = components::bus::SpiMasterBusComponent::new(
684        spi_mux,
685        hil::spi::cs::IntoChipSelect::<_, hil::spi::cs::ActiveLow>::into_cs(
686            &nrf52840_peripherals.gpio_port[ST7789H2_CS],
687        ),
688        20_000_000,
689        kernel::hil::spi::ClockPhase::SampleLeading,
690        kernel::hil::spi::ClockPolarity::IdleLow,
691    )
692    .finalize(components::spi_bus_component_static!(nrf52840::spi::SPIM));
693
694    let tft = components::st77xx::ST77XXComponent::new(
695        mux_alarm,
696        bus,
697        Some(&nrf52840_peripherals.gpio_port[ST7789H2_DC]),
698        Some(&nrf52840_peripherals.gpio_port[ST7789H2_RESET]),
699        &capsules_extra::st77xx::ST7789H2,
700    )
701    .finalize(components::st77xx_component_static!(
702        // bus type
703        capsules_extra::bus::SpiMasterBus<
704            'static,
705            capsules_core::virtualizers::virtual_spi::VirtualSpiMasterDevice<
706                'static,
707                nrf52840::spi::SPIM,
708            >,
709        >,
710        // timer type
711        nrf52840::rtc::Rtc,
712        // pin type
713        nrf52::gpio::GPIOPin<'static>
714    ));
715
716    let _ = tft.init();
717
718    let screen = components::screen::ScreenComponent::new(
719        board_kernel,
720        capsules_extra::screen::screen::DRIVER_NUM,
721        tft,
722        Some(tft),
723    )
724    .finalize(components::screen_component_static!(57600));
725
726    //--------------------------------------------------------------------------
727    // WIRELESS
728    //--------------------------------------------------------------------------
729
730    let ble_radio = components::ble::BLEComponent::new(
731        board_kernel,
732        capsules_extra::ble_advertising_driver::DRIVER_NUM,
733        &base_peripherals.ble_radio,
734        mux_alarm,
735    )
736    .finalize(components::ble_component_static!(
737        nrf52840::rtc::Rtc,
738        nrf52840::ble_radio::Radio
739    ));
740
741    let aes_mux = static_init!(
742        MuxAES128CCM<'static, nrf52840::aes::AesECB>,
743        MuxAES128CCM::new(&base_peripherals.ecb,)
744    );
745    kernel::deferred_call::DeferredCallClient::register(aes_mux);
746    base_peripherals.ecb.set_client(aes_mux);
747
748    let device_id = (*addr_of!(nrf52840::ficr::FICR_INSTANCE)).id();
749
750    let device_id_bottom_16 = u16::from_le_bytes([device_id[0], device_id[1]]);
751
752    let (ieee802154_radio, _mux_mac) = components::ieee802154::Ieee802154Component::new(
753        board_kernel,
754        capsules_extra::ieee802154::DRIVER_NUM,
755        &nrf52840_peripherals.ieee802154_radio,
756        aes_mux,
757        PAN_ID,
758        device_id_bottom_16,
759        device_id,
760    )
761    .finalize(components::ieee802154_component_static!(
762        nrf52840::ieee802154_radio::Radio,
763        nrf52840::aes::AesECB<'static>
764    ));
765
766    let process_printer = components::process_printer::ProcessPrinterTextComponent::new()
767        .finalize(components::process_printer_text_component_static!());
768    PANIC_RESOURCES.get().map(|resources| {
769        resources.printer.put(process_printer);
770    });
771
772    let pconsole = components::process_console::ProcessConsoleComponent::new(
773        board_kernel,
774        uart_mux,
775        mux_alarm,
776        process_printer,
777        Some(cortexm4::support::reset),
778    )
779    .finalize(components::process_console_component_static!(
780        nrf52840::rtc::Rtc
781    ));
782    let _ = pconsole.start();
783
784    //--------------------------------------------------------------------------
785    // FINAL SETUP AND BOARD BOOT
786    //--------------------------------------------------------------------------
787
788    // Start all of the clocks. Low power operation will require a better
789    // approach than this.
790    nrf52_components::NrfClockComponent::new(&base_peripherals.clock).finalize(());
791
792    let scheduler = components::sched::round_robin::RoundRobinComponent::new(processes)
793        .finalize(components::round_robin_component_static!(NUM_PROCS));
794
795    let platform = Platform {
796        ble_radio,
797        ieee802154_radio,
798        console,
799        proximity,
800        led,
801        gpio,
802        adc: adc_syscall,
803        screen,
804        button,
805        rng,
806        buzzer,
807        alarm,
808        ipc: kernel::ipc::IPC::new(
809            board_kernel,
810            kernel::ipc::DRIVER_NUM,
811            &memory_allocation_capability,
812        ),
813        temperature,
814        humidity,
815        scheduler,
816        systick: cortexm4::systick::SysTick::new_with_calibration(64000000),
817    };
818
819    let chip = static_init!(
820        nrf52840::chip::NRF52<Nrf52840DefaultPeripherals>,
821        nrf52840::chip::NRF52::new(nrf52840_peripherals)
822    );
823    PANIC_RESOURCES.get().map(|resources| {
824        resources.chip.put(chip);
825    });
826
827    // Need to disable the MPU because the bootloader seems to set it up.
828    chip.mpu().clear_mpu();
829
830    // Configure the USB stack to enable a serial port over CDC-ACM.
831    cdc.enable();
832    cdc.attach();
833
834    debug!("Initialization complete. Entering main loop.");
835
836    //--------------------------------------------------------------------------
837    // PROCESSES AND MAIN LOOP
838    //--------------------------------------------------------------------------
839
840    // These symbols are defined in the linker script.
841    extern "C" {
842        /// Beginning of the ROM region containing app images.
843        static _sapps: u8;
844        /// End of the ROM region containing app images.
845        static _eapps: u8;
846        /// Beginning of the RAM region for app memory.
847        static mut _sappmem: u8;
848        /// End of the RAM region for app memory.
849        static _eappmem: u8;
850    }
851
852    kernel::process::load_processes(
853        board_kernel,
854        chip,
855        core::slice::from_raw_parts(
856            core::ptr::addr_of!(_sapps),
857            core::ptr::addr_of!(_eapps) as usize - core::ptr::addr_of!(_sapps) as usize,
858        ),
859        core::slice::from_raw_parts_mut(
860            core::ptr::addr_of_mut!(_sappmem),
861            core::ptr::addr_of!(_eappmem) as usize - core::ptr::addr_of!(_sappmem) as usize,
862        ),
863        &FAULT_RESPONSE,
864        &process_management_capability,
865    )
866    .unwrap_or_else(|err| {
867        debug!("Error loading processes!");
868        debug!("{:?}", err);
869    });
870
871    (board_kernel, platform, chip)
872}
873
874/// Main function called after RAM initialized.
875#[no_mangle]
876pub unsafe fn main() {
877    let main_loop_capability = create_capability!(capabilities::MainLoopCapability);
878
879    let (board_kernel, board, chip) = start();
880    board_kernel.kernel_loop(&board, chip, Some(&board.ipc), &main_loop_capability);
881}