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