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