1#![no_std]
10#![cfg_attr(not(doc), no_main)]
13#![deny(missing_docs)]
14
15use core::ptr::addr_of;
16use core::ptr::addr_of_mut;
17
18use capsules_core::virtualizers::virtual_aes_ccm::MuxAES128CCM;
19
20use kernel::capabilities;
21use kernel::component::Component;
22use kernel::hil;
23use kernel::hil::buzzer::Buzzer;
24use kernel::hil::i2c::I2CMaster;
25use kernel::hil::led::LedHigh;
26use kernel::hil::symmetric_encryption::AES128;
27use kernel::hil::time::Alarm;
28use kernel::hil::time::Counter;
29use kernel::hil::usb::Client;
30use kernel::platform::chip::Chip;
31use kernel::platform::{KernelResources, SyscallDriverLookup};
32use kernel::scheduler::round_robin::RoundRobinSched;
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
39const 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
45const SPEAKER_PIN: Pin = Pin::P1_00;
47
48const 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
81const I2C_SDA_PIN: Pin = Pin::P0_24;
83const I2C_SCL_PIN: Pin = Pin::P0_25;
84
85const APDS9960_PIN: Pin = Pin::P0_09;
87
88const PAN_ID: u16 = 0xABCD;
90
91const ST7789H2_SCK: Pin = Pin::P0_14;
93const ST7789H2_MOSI: Pin = Pin::P0_15;
94const ST7789H2_MISO: Pin = Pin::P0_26; const ST7789H2_CS: Pin = Pin::P0_12;
96const ST7789H2_DC: Pin = Pin::P0_13;
97const ST7789H2_RESET: Pin = Pin::P1_03;
98
99const _ST7789H2_LITE: Pin = Pin::P1_05;
101
102pub mod io;
104
105const FAULT_RESPONSE: capsules_system::process_policies::StopWithDebugFaultPolicy =
108    capsules_system::process_policies::StopWithDebugFaultPolicy {};
109
110const NUM_PROCS: usize = 8;
112
113static mut PROCESSES: [Option<&'static dyn kernel::process::Process>; NUM_PROCS] =
114    [None; NUM_PROCS];
115
116static mut CHIP: Option<&'static nrf52840::chip::NRF52<Nrf52840DefaultPeripherals>> = None;
117static mut PROCESS_PRINTER: Option<&'static capsules_system::process_printer::ProcessPrinterText> =
118    None;
119static mut CDC_REF_FOR_PANIC: Option<
120    &'static capsules_extra::usb::cdc::CdcAcm<
121        'static,
122        nrf52::usbd::Usbd,
123        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<'static, nrf52::rtc::Rtc>,
124    >,
125> = None;
126static mut NRF52_POWER: Option<&'static nrf52840::power::Power> = None;
127
128#[no_mangle]
130#[link_section = ".stack_buffer"]
131pub static mut STACK_MEMORY: [u8; 0x1000] = [0; 0x1000];
132
133fn baud_rate_reset_bootloader_enter() {
135    unsafe {
136        NRF52_POWER.unwrap().set_gpregret(0x90);
139        cortexm4::scb::reset();
142    }
143}
144
145type SHT3xSensor = components::sht3x::SHT3xComponentType<
146    capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<'static, nrf52::rtc::Rtc<'static>>,
147    capsules_core::virtualizers::virtual_i2c::I2CDevice<'static, nrf52840::i2c::TWI<'static>>,
148>;
149type TemperatureDriver = components::temperature::TemperatureComponentType<SHT3xSensor>;
150type HumidityDriver = components::humidity::HumidityComponentType<SHT3xSensor>;
151type RngDriver = components::rng::RngComponentType<nrf52840::trng::Trng<'static>>;
152
153type Ieee802154Driver = components::ieee802154::Ieee802154ComponentType<
154    nrf52840::ieee802154_radio::Radio<'static>,
155    nrf52840::aes::AesECB<'static>,
156>;
157
158pub struct Platform {
160    ble_radio: &'static capsules_extra::ble_advertising_driver::BLE<
161        'static,
162        nrf52::ble_radio::Radio<'static>,
163        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
164            'static,
165            nrf52::rtc::Rtc<'static>,
166        >,
167    >,
168    ieee802154_radio: &'static Ieee802154Driver,
169    console: &'static capsules_core::console::Console<'static>,
170    proximity: &'static capsules_extra::proximity::ProximitySensor<'static>,
171    gpio: &'static capsules_core::gpio::GPIO<'static, nrf52::gpio::GPIOPin<'static>>,
172    led: &'static capsules_core::led::LedDriver<
173        'static,
174        LedHigh<'static, nrf52::gpio::GPIOPin<'static>>,
175        2,
176    >,
177    button: &'static capsules_core::button::Button<'static, nrf52::gpio::GPIOPin<'static>>,
178    screen: &'static capsules_extra::screen::Screen<'static>,
179    rng: &'static RngDriver,
180    ipc: kernel::ipc::IPC<{ NUM_PROCS as u8 }>,
181    alarm: &'static capsules_core::alarm::AlarmDriver<
182        'static,
183        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
184            'static,
185            nrf52::rtc::Rtc<'static>,
186        >,
187    >,
188    buzzer: &'static capsules_extra::buzzer_driver::Buzzer<
189        'static,
190        capsules_extra::buzzer_pwm::PwmBuzzer<
191            'static,
192            capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
193                'static,
194                nrf52840::rtc::Rtc<'static>,
195            >,
196            capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, nrf52840::pwm::Pwm>,
197        >,
198    >,
199    adc: &'static capsules_core::adc::AdcVirtualized<'static>,
200    temperature: &'static TemperatureDriver,
201    humidity: &'static HumidityDriver,
202    scheduler: &'static RoundRobinSched<'static>,
203    systick: cortexm4::systick::SysTick,
204}
205
206impl SyscallDriverLookup for Platform {
207    fn with_driver<F, R>(&self, driver_num: usize, f: F) -> R
208    where
209        F: FnOnce(Option<&dyn kernel::syscall::SyscallDriver>) -> R,
210    {
211        match driver_num {
212            capsules_core::console::DRIVER_NUM => f(Some(self.console)),
213            capsules_extra::proximity::DRIVER_NUM => f(Some(self.proximity)),
214            capsules_core::gpio::DRIVER_NUM => f(Some(self.gpio)),
215            capsules_core::alarm::DRIVER_NUM => f(Some(self.alarm)),
216            capsules_core::led::DRIVER_NUM => f(Some(self.led)),
217            capsules_core::button::DRIVER_NUM => f(Some(self.button)),
218            capsules_core::adc::DRIVER_NUM => f(Some(self.adc)),
219            capsules_extra::screen::DRIVER_NUM => f(Some(self.screen)),
220            capsules_core::rng::DRIVER_NUM => f(Some(self.rng)),
221            capsules_extra::ble_advertising_driver::DRIVER_NUM => f(Some(self.ble_radio)),
222            capsules_extra::ieee802154::DRIVER_NUM => f(Some(self.ieee802154_radio)),
223            capsules_extra::buzzer_driver::DRIVER_NUM => f(Some(self.buzzer)),
224            kernel::ipc::DRIVER_NUM => f(Some(&self.ipc)),
225            capsules_extra::temperature::DRIVER_NUM => f(Some(self.temperature)),
226            capsules_extra::humidity::DRIVER_NUM => f(Some(self.humidity)),
227            _ => f(None),
228        }
229    }
230}
231
232impl KernelResources<nrf52::chip::NRF52<'static, Nrf52840DefaultPeripherals<'static>>>
233    for Platform
234{
235    type SyscallDriverLookup = Self;
236    type SyscallFilter = ();
237    type ProcessFault = ();
238    type Scheduler = RoundRobinSched<'static>;
239    type SchedulerTimer = cortexm4::systick::SysTick;
240    type WatchDog = ();
241    type ContextSwitchCallback = ();
242
243    fn syscall_driver_lookup(&self) -> &Self::SyscallDriverLookup {
244        self
245    }
246    fn syscall_filter(&self) -> &Self::SyscallFilter {
247        &()
248    }
249    fn process_fault(&self) -> &Self::ProcessFault {
250        &()
251    }
252    fn scheduler(&self) -> &Self::Scheduler {
253        self.scheduler
254    }
255    fn scheduler_timer(&self) -> &Self::SchedulerTimer {
256        &self.systick
257    }
258    fn watchdog(&self) -> &Self::WatchDog {
259        &()
260    }
261    fn context_switch_callback(&self) -> &Self::ContextSwitchCallback {
262        &()
263    }
264}
265
266#[inline(never)]
270unsafe fn start() -> (
271    &'static kernel::Kernel,
272    Platform,
273    &'static nrf52840::chip::NRF52<'static, Nrf52840DefaultPeripherals<'static>>,
274) {
275    nrf52840::init();
276
277    let ieee802154_ack_buf = static_init!(
278        [u8; nrf52840::ieee802154_radio::ACK_BUF_SIZE],
279        [0; nrf52840::ieee802154_radio::ACK_BUF_SIZE]
280    );
281    let nrf52840_peripherals = static_init!(
283        Nrf52840DefaultPeripherals,
284        Nrf52840DefaultPeripherals::new(ieee802154_ack_buf)
285    );
286
287    nrf52840_peripherals.init();
289
290    let base_peripherals = &nrf52840_peripherals.nrf52;
291
292    NRF52_POWER = Some(&base_peripherals.pwr_clk);
295
296    let board_kernel = static_init!(kernel::Kernel, kernel::Kernel::new(&*addr_of!(PROCESSES)));
297
298    let process_management_capability =
305        create_capability!(capabilities::ProcessManagementCapability);
306    let memory_allocation_capability = create_capability!(capabilities::MemoryAllocationCapability);
307
308    kernel::debug::assign_gpios(
316        Some(&nrf52840_peripherals.gpio_port[LED_KERNEL_PIN]),
317        None,
318        None,
319    );
320
321    let gpio = components::gpio::GpioComponent::new(
326        board_kernel,
327        capsules_core::gpio::DRIVER_NUM,
328        components::gpio_component_helper!(
329            nrf52840::gpio::GPIOPin,
330            6 => &nrf52840_peripherals.gpio_port[GPIO_D6],
339            7 => &nrf52840_peripherals.gpio_port[GPIO_D7],
340            8 => &nrf52840_peripherals.gpio_port[GPIO_D8],
341            9 => &nrf52840_peripherals.gpio_port[GPIO_D9],
342
343            13 => &nrf52840_peripherals.gpio_port[GPIO_D13],
350            14 => &nrf52840_peripherals.gpio_port[GPIO_D14],
351            15 => &nrf52840_peripherals.gpio_port[GPIO_D15],
352            16 => &nrf52840_peripherals.gpio_port[GPIO_D16]
353        ),
354    )
355    .finalize(components::gpio_component_static!(nrf52840::gpio::GPIOPin));
356
357    let led = components::led::LedsComponent::new().finalize(components::led_component_static!(
362        LedHigh<'static, nrf52840::gpio::GPIOPin>,
363        LedHigh::new(&nrf52840_peripherals.gpio_port[LED_RED_PIN]),
364        LedHigh::new(&nrf52840_peripherals.gpio_port[LED_WHITE_PIN])
365    ));
366
367    let button = components::button::ButtonComponent::new(
371        board_kernel,
372        capsules_core::button::DRIVER_NUM,
373        components::button_component_helper!(
374            nrf52840::gpio::GPIOPin,
375            (
376                &nrf52840_peripherals.gpio_port[BUTTON_LEFT],
377                kernel::hil::gpio::ActivationMode::ActiveLow,
378                kernel::hil::gpio::FloatingState::PullUp
379            ), (
381                &nrf52840_peripherals.gpio_port[BUTTON_RIGHT],
382                kernel::hil::gpio::ActivationMode::ActiveLow,
383                kernel::hil::gpio::FloatingState::PullUp
384            ) ),
386    )
387    .finalize(components::button_component_static!(
388        nrf52840::gpio::GPIOPin
389    ));
390
391    let rtc = &base_peripherals.rtc;
396    let _ = rtc.start();
397
398    let mux_alarm = components::alarm::AlarmMuxComponent::new(rtc)
399        .finalize(components::alarm_mux_component_static!(nrf52::rtc::Rtc));
400    let alarm = components::alarm::AlarmDriverComponent::new(
401        board_kernel,
402        capsules_core::alarm::DRIVER_NUM,
403        mux_alarm,
404    )
405    .finalize(components::alarm_component_static!(nrf52::rtc::Rtc));
406
407    let mux_pwm = static_init!(
412        capsules_core::virtualizers::virtual_pwm::MuxPwm<'static, nrf52840::pwm::Pwm>,
413        capsules_core::virtualizers::virtual_pwm::MuxPwm::new(&base_peripherals.pwm0)
414    );
415    let virtual_pwm_buzzer = static_init!(
416        capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, nrf52840::pwm::Pwm>,
417        capsules_core::virtualizers::virtual_pwm::PwmPinUser::new(
418            mux_pwm,
419            nrf52840::pinmux::Pinmux::new(SPEAKER_PIN as u32)
420        )
421    );
422    virtual_pwm_buzzer.add_to_mux();
423
424    let virtual_alarm_buzzer = static_init!(
425        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<'static, nrf52840::rtc::Rtc>,
426        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm::new(mux_alarm)
427    );
428    virtual_alarm_buzzer.setup();
429
430    let pwm_buzzer = static_init!(
431        capsules_extra::buzzer_pwm::PwmBuzzer<
432            'static,
433            capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
434                'static,
435                nrf52840::rtc::Rtc,
436            >,
437            capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, nrf52840::pwm::Pwm>,
438        >,
439        capsules_extra::buzzer_pwm::PwmBuzzer::new(
440            virtual_pwm_buzzer,
441            virtual_alarm_buzzer,
442            capsules_extra::buzzer_pwm::DEFAULT_MAX_BUZZ_TIME_MS,
443        )
444    );
445
446    let buzzer = static_init!(
447        capsules_extra::buzzer_driver::Buzzer<
448            'static,
449            capsules_extra::buzzer_pwm::PwmBuzzer<
450                'static,
451                capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
452                    'static,
453                    nrf52840::rtc::Rtc,
454                >,
455                capsules_core::virtualizers::virtual_pwm::PwmPinUser<'static, nrf52840::pwm::Pwm>,
456            >,
457        >,
458        capsules_extra::buzzer_driver::Buzzer::new(
459            pwm_buzzer,
460            capsules_extra::buzzer_driver::DEFAULT_MAX_BUZZ_TIME_MS,
461            board_kernel.create_grant(
462                capsules_extra::buzzer_driver::DRIVER_NUM,
463                &memory_allocation_capability
464            )
465        )
466    );
467
468    pwm_buzzer.set_client(buzzer);
469
470    virtual_alarm_buzzer.set_alarm_client(pwm_buzzer);
471
472    let serial_number_buf = static_init!([u8; 17], [0; 17]);
482    let serial_number_string: &'static str =
483        (*addr_of!(nrf52::ficr::FICR_INSTANCE)).address_str(serial_number_buf);
484    let strings = static_init!(
485        [&str; 3],
486        [
487            "Adafruit",               "CLUE nRF52840 - TockOS", serial_number_string,     ]
491    );
492
493    let cdc = components::cdc::CdcAcmComponent::new(
494        &nrf52840_peripherals.usbd,
495        capsules_extra::usb::cdc::MAX_CTRL_PACKET_SIZE_NRF52840,
496        0x239a,
497        0x8071,
498        strings,
499        mux_alarm,
500        Some(&baud_rate_reset_bootloader_enter),
501    )
502    .finalize(components::cdc_acm_component_static!(
503        nrf52::usbd::Usbd,
504        nrf52::rtc::Rtc
505    ));
506    CDC_REF_FOR_PANIC = Some(cdc); let uart_mux = components::console::UartMuxComponent::new(cdc, 115200)
510        .finalize(components::uart_mux_component_static!());
511
512    let console = components::console::ConsoleComponent::new(
514        board_kernel,
515        capsules_core::console::DRIVER_NUM,
516        uart_mux,
517    )
518    .finalize(components::console_component_static!());
519    components::debug_writer::DebugWriterComponent::new(uart_mux)
521        .finalize(components::debug_writer_component_static!());
522
523    let rng = components::rng::RngComponent::new(
528        board_kernel,
529        capsules_core::rng::DRIVER_NUM,
530        &base_peripherals.trng,
531    )
532    .finalize(components::rng_component_static!(nrf52840::trng::Trng));
533
534    base_peripherals.adc.calibrate();
538
539    let adc_mux = components::adc::AdcMuxComponent::new(&base_peripherals.adc)
540        .finalize(components::adc_mux_component_static!(nrf52840::adc::Adc));
541
542    let adc_syscall =
543        components::adc::AdcVirtualComponent::new(board_kernel, capsules_core::adc::DRIVER_NUM)
544            .finalize(components::adc_syscall_component_helper!(
545                components::adc::AdcComponent::new(
547                    adc_mux,
548                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput7)
549                )
550                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
551                components::adc::AdcComponent::new(
553                    adc_mux,
554                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput5)
555                )
556                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
557                components::adc::AdcComponent::new(
559                    adc_mux,
560                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput2)
561                )
562                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
563                components::adc::AdcComponent::new(
565                    adc_mux,
566                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput3)
567                )
568                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
569                components::adc::AdcComponent::new(
571                    adc_mux,
572                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput1)
573                )
574                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
575                components::adc::AdcComponent::new(
577                    adc_mux,
578                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput4)
579                )
580                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
581                components::adc::AdcComponent::new(
583                    adc_mux,
584                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput0)
585                )
586                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
587            ));
588
589    let sensors_i2c_bus = static_init!(
594        capsules_core::virtualizers::virtual_i2c::MuxI2C<'static, nrf52840::i2c::TWI>,
595        capsules_core::virtualizers::virtual_i2c::MuxI2C::new(&base_peripherals.twi1, None,)
596    );
597    kernel::deferred_call::DeferredCallClient::register(sensors_i2c_bus);
598    base_peripherals.twi1.configure(
599        nrf52840::pinmux::Pinmux::new(I2C_SCL_PIN as u32),
600        nrf52840::pinmux::Pinmux::new(I2C_SDA_PIN as u32),
601    );
602    base_peripherals.twi1.set_master_client(sensors_i2c_bus);
603
604    let apds9960 = components::apds9960::Apds9960Component::new(
605        sensors_i2c_bus,
606        0x39,
607        &nrf52840_peripherals.gpio_port[APDS9960_PIN],
608    )
609    .finalize(components::apds9960_component_static!(nrf52840::i2c::TWI));
610    let proximity = components::proximity::ProximityComponent::new(
611        apds9960,
612        board_kernel,
613        capsules_extra::proximity::DRIVER_NUM,
614    )
615    .finalize(components::proximity_component_static!());
616
617    let sht3x = components::sht3x::SHT3xComponent::new(
618        sensors_i2c_bus,
619        capsules_extra::sht3x::BASE_ADDR,
620        mux_alarm,
621    )
622    .finalize(components::sht3x_component_static!(
623        nrf52::rtc::Rtc<'static>,
624        nrf52840::i2c::TWI
625    ));
626
627    let temperature = components::temperature::TemperatureComponent::new(
628        board_kernel,
629        capsules_extra::temperature::DRIVER_NUM,
630        sht3x,
631    )
632    .finalize(components::temperature_component_static!(SHT3xSensor));
633
634    let humidity = components::humidity::HumidityComponent::new(
635        board_kernel,
636        capsules_extra::humidity::DRIVER_NUM,
637        sht3x,
638    )
639    .finalize(components::humidity_component_static!(SHT3xSensor));
640
641    let spi_mux = components::spi::SpiMuxComponent::new(&base_peripherals.spim0)
646        .finalize(components::spi_mux_component_static!(nrf52840::spi::SPIM));
647
648    base_peripherals.spim0.configure(
649        nrf52840::pinmux::Pinmux::new(ST7789H2_MOSI as u32),
650        nrf52840::pinmux::Pinmux::new(ST7789H2_MISO as u32),
651        nrf52840::pinmux::Pinmux::new(ST7789H2_SCK as u32),
652    );
653
654    let bus = components::bus::SpiMasterBusComponent::new(
655        spi_mux,
656        hil::spi::cs::IntoChipSelect::<_, hil::spi::cs::ActiveLow>::into_cs(
657            &nrf52840_peripherals.gpio_port[ST7789H2_CS],
658        ),
659        20_000_000,
660        kernel::hil::spi::ClockPhase::SampleLeading,
661        kernel::hil::spi::ClockPolarity::IdleLow,
662    )
663    .finalize(components::spi_bus_component_static!(nrf52840::spi::SPIM));
664
665    let tft = components::st77xx::ST77XXComponent::new(
666        mux_alarm,
667        bus,
668        Some(&nrf52840_peripherals.gpio_port[ST7789H2_DC]),
669        Some(&nrf52840_peripherals.gpio_port[ST7789H2_RESET]),
670        &capsules_extra::st77xx::ST7789H2,
671    )
672    .finalize(components::st77xx_component_static!(
673        capsules_extra::bus::SpiMasterBus<
675            'static,
676            capsules_core::virtualizers::virtual_spi::VirtualSpiMasterDevice<
677                'static,
678                nrf52840::spi::SPIM,
679            >,
680        >,
681        nrf52840::rtc::Rtc,
683        nrf52::gpio::GPIOPin<'static>
685    ));
686
687    let _ = tft.init();
688
689    let screen = components::screen::ScreenComponent::new(
690        board_kernel,
691        capsules_extra::screen::DRIVER_NUM,
692        tft,
693        Some(tft),
694    )
695    .finalize(components::screen_component_static!(57600));
696
697    let ble_radio = components::ble::BLEComponent::new(
702        board_kernel,
703        capsules_extra::ble_advertising_driver::DRIVER_NUM,
704        &base_peripherals.ble_radio,
705        mux_alarm,
706    )
707    .finalize(components::ble_component_static!(
708        nrf52840::rtc::Rtc,
709        nrf52840::ble_radio::Radio
710    ));
711
712    let aes_mux = static_init!(
713        MuxAES128CCM<'static, nrf52840::aes::AesECB>,
714        MuxAES128CCM::new(&base_peripherals.ecb,)
715    );
716    kernel::deferred_call::DeferredCallClient::register(aes_mux);
717    base_peripherals.ecb.set_client(aes_mux);
718
719    let device_id = (*addr_of!(nrf52840::ficr::FICR_INSTANCE)).id();
720
721    let device_id_bottom_16 = u16::from_le_bytes([device_id[0], device_id[1]]);
722
723    let (ieee802154_radio, _mux_mac) = components::ieee802154::Ieee802154Component::new(
724        board_kernel,
725        capsules_extra::ieee802154::DRIVER_NUM,
726        &nrf52840_peripherals.ieee802154_radio,
727        aes_mux,
728        PAN_ID,
729        device_id_bottom_16,
730        device_id,
731    )
732    .finalize(components::ieee802154_component_static!(
733        nrf52840::ieee802154_radio::Radio,
734        nrf52840::aes::AesECB<'static>
735    ));
736
737    let process_printer = components::process_printer::ProcessPrinterTextComponent::new()
738        .finalize(components::process_printer_text_component_static!());
739    PROCESS_PRINTER = Some(process_printer);
740
741    let pconsole = components::process_console::ProcessConsoleComponent::new(
742        board_kernel,
743        uart_mux,
744        mux_alarm,
745        process_printer,
746        Some(cortexm4::support::reset),
747    )
748    .finalize(components::process_console_component_static!(
749        nrf52840::rtc::Rtc
750    ));
751    let _ = pconsole.start();
752
753    nrf52_components::NrfClockComponent::new(&base_peripherals.clock).finalize(());
760
761    let scheduler = components::sched::round_robin::RoundRobinComponent::new(&*addr_of!(PROCESSES))
762        .finalize(components::round_robin_component_static!(NUM_PROCS));
763
764    let platform = Platform {
765        ble_radio,
766        ieee802154_radio,
767        console,
768        proximity,
769        led,
770        gpio,
771        adc: adc_syscall,
772        screen,
773        button,
774        rng,
775        buzzer,
776        alarm,
777        ipc: kernel::ipc::IPC::new(
778            board_kernel,
779            kernel::ipc::DRIVER_NUM,
780            &memory_allocation_capability,
781        ),
782        temperature,
783        humidity,
784        scheduler,
785        systick: cortexm4::systick::SysTick::new_with_calibration(64000000),
786    };
787
788    let chip = static_init!(
789        nrf52840::chip::NRF52<Nrf52840DefaultPeripherals>,
790        nrf52840::chip::NRF52::new(nrf52840_peripherals)
791    );
792    CHIP = Some(chip);
793
794    chip.mpu().clear_mpu();
796
797    cdc.enable();
799    cdc.attach();
800
801    debug!("Initialization complete. Entering main loop.");
802
803    extern "C" {
809        static _sapps: u8;
811        static _eapps: u8;
813        static mut _sappmem: u8;
815        static _eappmem: u8;
817    }
818
819    kernel::process::load_processes(
820        board_kernel,
821        chip,
822        core::slice::from_raw_parts(
823            core::ptr::addr_of!(_sapps),
824            core::ptr::addr_of!(_eapps) as usize - core::ptr::addr_of!(_sapps) as usize,
825        ),
826        core::slice::from_raw_parts_mut(
827            core::ptr::addr_of_mut!(_sappmem),
828            core::ptr::addr_of!(_eappmem) as usize - core::ptr::addr_of!(_sappmem) as usize,
829        ),
830        &mut *addr_of_mut!(PROCESSES),
831        &FAULT_RESPONSE,
832        &process_management_capability,
833    )
834    .unwrap_or_else(|err| {
835        debug!("Error loading processes!");
836        debug!("{:?}", err);
837    });
838
839    (board_kernel, platform, chip)
840}
841
842#[no_mangle]
844pub unsafe fn main() {
845    let main_loop_capability = create_capability!(capabilities::MainLoopCapability);
846
847    let (board_kernel, board, chip) = start();
848    board_kernel.kernel_loop(&board, chip, Some(&board.ipc), &main_loop_capability);
849}