nano33ble/
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 Arduino Nano 33 BLE.
6//!
7//! It is based on nRF52840 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 kernel::capabilities;
16use kernel::component::Component;
17use kernel::debug::PanicResources;
18use kernel::hil::gpio::Configure;
19use kernel::hil::gpio::Output;
20use kernel::hil::led::LedLow;
21use kernel::hil::time::Counter;
22use kernel::hil::usb::Client;
23use kernel::platform::chip::Chip;
24use kernel::platform::{KernelResources, SyscallDriverLookup};
25use kernel::scheduler::round_robin::RoundRobinSched;
26use kernel::utilities::cells::MapCell;
27use kernel::utilities::single_thread_value::SingleThreadValue;
28#[allow(unused_imports)]
29use kernel::{create_capability, debug, debug_gpio, debug_verbose, static_init};
30
31use nrf52840::gpio::Pin;
32use nrf52840::interrupt_service::Nrf52840DefaultPeripherals;
33
34#[allow(dead_code)]
35mod test;
36
37// Three-color LED.
38const LED_RED_PIN: Pin = Pin::P0_24;
39const LED_GREEN_PIN: Pin = Pin::P0_16;
40const LED_BLUE_PIN: Pin = Pin::P0_06;
41
42const LED_KERNEL_PIN: Pin = Pin::P0_13;
43
44const _BUTTON_RST_PIN: Pin = Pin::P0_18;
45
46const GPIO_D2: Pin = Pin::P1_11;
47const GPIO_D3: Pin = Pin::P1_12;
48const GPIO_D4: Pin = Pin::P1_15;
49const GPIO_D5: Pin = Pin::P1_13;
50const GPIO_D6: Pin = Pin::P1_14;
51const GPIO_D7: Pin = Pin::P0_23;
52const GPIO_D8: Pin = Pin::P0_21;
53const GPIO_D9: Pin = Pin::P0_27;
54const GPIO_D10: Pin = Pin::P1_02;
55
56const _UART_TX_PIN: Pin = Pin::P1_03;
57const _UART_RX_PIN: Pin = Pin::P1_10;
58
59/// I2C pins for all of the sensors.
60const I2C_SDA_PIN: Pin = Pin::P0_14;
61const I2C_SCL_PIN: Pin = Pin::P0_15;
62
63/// GPIO tied to the VCC of the I2C pullup resistors.
64const I2C_PULLUP_PIN: Pin = Pin::P1_00;
65
66/// Interrupt pin for the APDS9960 sensor.
67const APDS9960_PIN: Pin = Pin::P0_19;
68
69// Constants related to the configuration of the 15.4 network stack
70/// Personal Area Network ID for the IEEE 802.15.4 radio
71const PAN_ID: u16 = 0xABCD;
72/// Gateway (or next hop) MAC Address
73const DST_MAC_ADDR: capsules_extra::net::ieee802154::MacAddress =
74    capsules_extra::net::ieee802154::MacAddress::Short(49138);
75const DEFAULT_CTX_PREFIX_LEN: u8 = 8; //Length of context for 6LoWPAN compression
76const DEFAULT_CTX_PREFIX: [u8; 16] = [0x0_u8; 16]; //Context for 6LoWPAN Compression
77
78/// UART Writer for panic!()s.
79pub mod io;
80
81// How should the kernel respond when a process faults. For this board we choose
82// to stop the app and print a notice, but not immediately panic. This allows
83// users to debug their apps, but avoids issues with using the USB/CDC stack
84// synchronously for panic! too early after the board boots.
85const FAULT_RESPONSE: capsules_system::process_policies::StopWithDebugFaultPolicy =
86    capsules_system::process_policies::StopWithDebugFaultPolicy {};
87
88// Number of concurrent processes this platform supports.
89const NUM_PROCS: usize = 8;
90
91type ChipHw = nrf52840::chip::NRF52<'static, Nrf52840DefaultPeripherals<'static>>;
92type ProcessPrinter = capsules_system::process_printer::ProcessPrinterText;
93
94/// Static variables used by io.rs.
95static mut CDC_REF_FOR_PANIC: Option<
96    &'static capsules_extra::usb::cdc::CdcAcm<
97        'static,
98        nrf52::usbd::Usbd,
99        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<'static, nrf52::rtc::Rtc>,
100    >,
101> = None;
102/// Resources for when a board panics used by io.rs.
103static PANIC_RESOURCES: SingleThreadValue<PanicResources<ChipHw, ProcessPrinter>> =
104    SingleThreadValue::new(PanicResources::new());
105static NRF52_POWER: SingleThreadValue<MapCell<&'static nrf52840::power::Power>> =
106    SingleThreadValue::new(MapCell::empty());
107
108kernel::stack_size! {0x1000}
109
110// Function for the CDC/USB stack to use to enter the bootloader.
111fn baud_rate_reset_bootloader_enter() {
112    // 0x90 is the magic value the bootloader expects
113    NRF52_POWER.get().map(|power_cell| {
114        power_cell.map(|power| {
115            power.set_gpregret(0x90);
116        });
117    });
118    unsafe {
119        cortexm4::scb::reset();
120    }
121}
122
123type HTS221Sensor = components::hts221::Hts221ComponentType<
124    capsules_core::virtualizers::virtual_i2c::I2CDevice<'static, nrf52840::i2c::TWI<'static>>,
125>;
126type TemperatureDriver = components::temperature::TemperatureComponentType<HTS221Sensor>;
127type HumidityDriver = components::humidity::HumidityComponentType<HTS221Sensor>;
128type Ieee802154MacDevice = components::ieee802154::Ieee802154ComponentMacDeviceType<
129    nrf52840::ieee802154_radio::Radio<'static>,
130    nrf52840::aes::AesECB<'static>,
131>;
132type Ieee802154Driver = components::ieee802154::Ieee802154ComponentType<
133    nrf52840::ieee802154_radio::Radio<'static>,
134    nrf52840::aes::AesECB<'static>,
135>;
136type RngDriver = components::rng::RngComponentType<nrf52840::trng::Trng<'static>>;
137
138/// Supported drivers by the platform
139pub struct Platform {
140    ble_radio: &'static capsules_extra::ble_advertising_driver::BLE<
141        'static,
142        nrf52::ble_radio::Radio<'static>,
143        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
144            'static,
145            nrf52::rtc::Rtc<'static>,
146        >,
147    >,
148    ieee802154_radio: &'static Ieee802154Driver,
149    console: &'static capsules_core::console::Console<'static>,
150    pconsole: &'static capsules_core::process_console::ProcessConsole<
151        'static,
152        { capsules_core::process_console::DEFAULT_COMMAND_HISTORY_LEN },
153        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
154            'static,
155            nrf52::rtc::Rtc<'static>,
156        >,
157        components::process_console::Capability,
158    >,
159    proximity: &'static capsules_extra::proximity::ProximitySensor<'static>,
160    temperature: &'static TemperatureDriver,
161    humidity: &'static HumidityDriver,
162    gpio: &'static capsules_core::gpio::GPIO<'static, nrf52::gpio::GPIOPin<'static>>,
163    led: &'static capsules_core::led::LedDriver<
164        'static,
165        LedLow<'static, nrf52::gpio::GPIOPin<'static>>,
166        3,
167    >,
168    adc: &'static capsules_core::adc::AdcVirtualized<'static>,
169    rng: &'static RngDriver,
170    ipc: kernel::ipc::IPC<{ NUM_PROCS as u8 }>,
171    alarm: &'static capsules_core::alarm::AlarmDriver<
172        'static,
173        capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
174            'static,
175            nrf52::rtc::Rtc<'static>,
176        >,
177    >,
178    udp_driver: &'static capsules_extra::net::udp::UDPDriver<'static>,
179    scheduler: &'static RoundRobinSched<'static>,
180    systick: cortexm4::systick::SysTick,
181}
182
183impl SyscallDriverLookup for Platform {
184    fn with_driver<F, R>(&self, driver_num: usize, f: F) -> R
185    where
186        F: FnOnce(Option<&dyn kernel::syscall::SyscallDriver>) -> R,
187    {
188        match driver_num {
189            capsules_core::console::DRIVER_NUM => f(Some(self.console)),
190            capsules_extra::proximity::DRIVER_NUM => f(Some(self.proximity)),
191            capsules_extra::temperature::DRIVER_NUM => f(Some(self.temperature)),
192            capsules_extra::humidity::DRIVER_NUM => f(Some(self.humidity)),
193            capsules_core::gpio::DRIVER_NUM => f(Some(self.gpio)),
194            capsules_core::alarm::DRIVER_NUM => f(Some(self.alarm)),
195            capsules_core::led::DRIVER_NUM => f(Some(self.led)),
196            capsules_core::adc::DRIVER_NUM => f(Some(self.adc)),
197            capsules_core::rng::DRIVER_NUM => f(Some(self.rng)),
198            capsules_extra::ble_advertising_driver::DRIVER_NUM => f(Some(self.ble_radio)),
199            capsules_extra::ieee802154::DRIVER_NUM => f(Some(self.ieee802154_radio)),
200            capsules_extra::net::udp::DRIVER_NUM => f(Some(self.udp_driver)),
201            kernel::ipc::DRIVER_NUM => f(Some(&self.ipc)),
202            _ => f(None),
203        }
204    }
205}
206
207impl KernelResources<nrf52::chip::NRF52<'static, Nrf52840DefaultPeripherals<'static>>>
208    for Platform
209{
210    type SyscallDriverLookup = Self;
211    type SyscallFilter = ();
212    type ProcessFault = ();
213    type Scheduler = RoundRobinSched<'static>;
214    type SchedulerTimer = cortexm4::systick::SysTick;
215    type WatchDog = ();
216    type ContextSwitchCallback = ();
217
218    fn syscall_driver_lookup(&self) -> &Self::SyscallDriverLookup {
219        self
220    }
221    fn syscall_filter(&self) -> &Self::SyscallFilter {
222        &()
223    }
224    fn process_fault(&self) -> &Self::ProcessFault {
225        &()
226    }
227    fn scheduler(&self) -> &Self::Scheduler {
228        self.scheduler
229    }
230    fn scheduler_timer(&self) -> &Self::SchedulerTimer {
231        &self.systick
232    }
233    fn watchdog(&self) -> &Self::WatchDog {
234        &()
235    }
236    fn context_switch_callback(&self) -> &Self::ContextSwitchCallback {
237        &()
238    }
239}
240
241/// This is in a separate, inline(never) function so that its stack frame is
242/// removed when this function returns. Otherwise, the stack space used for
243/// these static_inits is wasted.
244#[inline(never)]
245pub unsafe fn start() -> (
246    &'static kernel::Kernel,
247    Platform,
248    &'static nrf52840::chip::NRF52<'static, Nrf52840DefaultPeripherals<'static>>,
249) {
250    nrf52840::init();
251
252    // Initialize deferred calls very early.
253    kernel::deferred_call::initialize_deferred_call_state::<
254        <ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider,
255    >();
256
257    // Bind global variables to this thread.
258    PANIC_RESOURCES.bind_to_thread::<<ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider>();
259
260    let ieee802154_ack_buf = static_init!(
261        [u8; nrf52840::ieee802154_radio::ACK_BUF_SIZE],
262        [0; nrf52840::ieee802154_radio::ACK_BUF_SIZE]
263    );
264
265    // Initialize chip peripheral drivers
266    let nrf52840_peripherals = static_init!(
267        Nrf52840DefaultPeripherals,
268        Nrf52840DefaultPeripherals::new(ieee802154_ack_buf)
269    );
270
271    // set up circular peripheral dependencies
272    nrf52840_peripherals.init();
273    let base_peripherals = &nrf52840_peripherals.nrf52;
274
275    // Save a reference to the power module for resetting the board into the
276    // bootloader.
277    NRF52_POWER.get().map(|power_cell| {
278        power_cell.put(&base_peripherals.pwr_clk);
279    });
280
281    // Create an array to hold process references.
282    let processes = components::process_array::ProcessArrayComponent::new()
283        .finalize(components::process_array_component_static!(NUM_PROCS));
284    PANIC_RESOURCES.get().map(|resources| {
285        resources.processes.put(processes.as_slice());
286    });
287
288    // Setup space to store the core kernel data structure.
289    let board_kernel = static_init!(kernel::Kernel, kernel::Kernel::new(processes.as_slice()));
290
291    //--------------------------------------------------------------------------
292    // CAPABILITIES
293    //--------------------------------------------------------------------------
294
295    // Create capabilities that the board needs to call certain protected kernel
296    // functions.
297    let process_management_capability =
298        create_capability!(capabilities::ProcessManagementCapability);
299    let memory_allocation_capability = create_capability!(capabilities::MemoryAllocationCapability);
300
301    //--------------------------------------------------------------------------
302    // DEBUG GPIO
303    //--------------------------------------------------------------------------
304
305    // Configure kernel debug GPIOs as early as possible. These are used by the
306    // `debug_gpio!(0, toggle)` macro. We configure these early so that the
307    // macro is available during most of the setup code and kernel execution.
308    let debug_gpios = static_init!(
309        [&'static dyn kernel::hil::gpio::Pin; 1],
310        [&nrf52840_peripherals.gpio_port[LED_KERNEL_PIN]]
311    );
312    kernel::debug::initialize_debug_gpio::<
313        <ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider,
314    >();
315    kernel::debug::assign_gpios(debug_gpios);
316
317    //--------------------------------------------------------------------------
318    // GPIO
319    //--------------------------------------------------------------------------
320
321    let gpio = components::gpio::GpioComponent::new(
322        board_kernel,
323        capsules_core::gpio::DRIVER_NUM,
324        components::gpio_component_helper!(
325            nrf52840::gpio::GPIOPin,
326            2 => &nrf52840_peripherals.gpio_port[GPIO_D2],
327            3 => &nrf52840_peripherals.gpio_port[GPIO_D3],
328            4 => &nrf52840_peripherals.gpio_port[GPIO_D4],
329            5 => &nrf52840_peripherals.gpio_port[GPIO_D5],
330            6 => &nrf52840_peripherals.gpio_port[GPIO_D6],
331            7 => &nrf52840_peripherals.gpio_port[GPIO_D7],
332            8 => &nrf52840_peripherals.gpio_port[GPIO_D8],
333            9 => &nrf52840_peripherals.gpio_port[GPIO_D9],
334            10 => &nrf52840_peripherals.gpio_port[GPIO_D10]
335        ),
336    )
337    .finalize(components::gpio_component_static!(nrf52840::gpio::GPIOPin));
338
339    //--------------------------------------------------------------------------
340    // LEDs
341    //--------------------------------------------------------------------------
342
343    let led = components::led::LedsComponent::new().finalize(components::led_component_static!(
344        LedLow<'static, nrf52840::gpio::GPIOPin>,
345        LedLow::new(&nrf52840_peripherals.gpio_port[LED_RED_PIN]),
346        LedLow::new(&nrf52840_peripherals.gpio_port[LED_GREEN_PIN]),
347        LedLow::new(&nrf52840_peripherals.gpio_port[LED_BLUE_PIN]),
348    ));
349
350    //--------------------------------------------------------------------------
351    // ALARM & TIMER
352    //--------------------------------------------------------------------------
353
354    let rtc = &base_peripherals.rtc;
355    let _ = rtc.start();
356
357    let mux_alarm = components::alarm::AlarmMuxComponent::new(rtc)
358        .finalize(components::alarm_mux_component_static!(nrf52::rtc::Rtc));
359    let alarm = components::alarm::AlarmDriverComponent::new(
360        board_kernel,
361        capsules_core::alarm::DRIVER_NUM,
362        mux_alarm,
363    )
364    .finalize(components::alarm_component_static!(nrf52::rtc::Rtc));
365
366    //--------------------------------------------------------------------------
367    // UART & CONSOLE & DEBUG
368    //--------------------------------------------------------------------------
369
370    // Setup the CDC-ACM over USB driver that we will use for UART.
371    // We use the Arduino Vendor ID and Product ID since the device is the same.
372
373    // Create the strings we include in the USB descriptor. We use the hardcoded
374    // DEVICEADDR register on the nRF52 to set the serial number.
375    let serial_number_buf = static_init!([u8; 17], [0; 17]);
376    let serial_number_string: &'static str =
377        (*addr_of!(nrf52::ficr::FICR_INSTANCE)).address_str(serial_number_buf);
378    let strings = static_init!(
379        [&str; 3],
380        [
381            "Arduino",              // Manufacturer
382            "Nano 33 BLE - TockOS", // Product
383            serial_number_string,   // Serial number
384        ]
385    );
386
387    let cdc = components::cdc::CdcAcmComponent::new(
388        &nrf52840_peripherals.usbd,
389        capsules_extra::usb::cdc::MAX_CTRL_PACKET_SIZE_NRF52840,
390        0x2341,
391        0x005a,
392        strings,
393        mux_alarm,
394        Some(&baud_rate_reset_bootloader_enter),
395    )
396    .finalize(components::cdc_acm_component_static!(
397        nrf52::usbd::Usbd,
398        nrf52::rtc::Rtc
399    ));
400    CDC_REF_FOR_PANIC = Some(cdc); //for use by panic handler
401
402    // Process Printer for displaying process information.
403    let process_printer = components::process_printer::ProcessPrinterTextComponent::new()
404        .finalize(components::process_printer_text_component_static!());
405    PANIC_RESOURCES.get().map(|resources| {
406        resources.printer.put(process_printer);
407    });
408
409    // Create a shared UART channel for the console and for kernel debug.
410    let uart_mux = components::console::UartMuxComponent::new(cdc, 115200)
411        .finalize(components::uart_mux_component_static!());
412
413    let pconsole = components::process_console::ProcessConsoleComponent::new(
414        board_kernel,
415        uart_mux,
416        mux_alarm,
417        process_printer,
418        Some(cortexm4::support::reset),
419    )
420    .finalize(components::process_console_component_static!(
421        nrf52::rtc::Rtc<'static>
422    ));
423
424    // Setup the console.
425    let console = components::console::ConsoleComponent::new(
426        board_kernel,
427        capsules_core::console::DRIVER_NUM,
428        uart_mux,
429    )
430    .finalize(components::console_component_static!());
431    // Create the debugger object that handles calls to `debug!()`.
432    components::debug_writer::DebugWriterComponent::new::<
433        <ChipHw as kernel::platform::chip::Chip>::ThreadIdProvider,
434    >(
435        uart_mux,
436        create_capability!(capabilities::SetDebugWriterCapability),
437    )
438    .finalize(components::debug_writer_component_static!());
439
440    //--------------------------------------------------------------------------
441    // RANDOM NUMBERS
442    //--------------------------------------------------------------------------
443
444    let rng = components::rng::RngComponent::new(
445        board_kernel,
446        capsules_core::rng::DRIVER_NUM,
447        &base_peripherals.trng,
448    )
449    .finalize(components::rng_component_static!(nrf52840::trng::Trng));
450
451    //--------------------------------------------------------------------------
452    // ADC
453    //--------------------------------------------------------------------------
454    base_peripherals.adc.calibrate();
455
456    let adc_mux = components::adc::AdcMuxComponent::new(&base_peripherals.adc)
457        .finalize(components::adc_mux_component_static!(nrf52840::adc::Adc));
458
459    let adc_syscall =
460        components::adc::AdcVirtualComponent::new(board_kernel, capsules_core::adc::DRIVER_NUM)
461            .finalize(components::adc_syscall_component_helper!(
462                // A0
463                components::adc::AdcComponent::new(
464                    adc_mux,
465                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput2)
466                )
467                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
468                // A1
469                components::adc::AdcComponent::new(
470                    adc_mux,
471                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput3)
472                )
473                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
474                // A2
475                components::adc::AdcComponent::new(
476                    adc_mux,
477                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput6)
478                )
479                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
480                // A3
481                components::adc::AdcComponent::new(
482                    adc_mux,
483                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput5)
484                )
485                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
486                // A4
487                components::adc::AdcComponent::new(
488                    adc_mux,
489                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput7)
490                )
491                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
492                // A5
493                components::adc::AdcComponent::new(
494                    adc_mux,
495                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput0)
496                )
497                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
498                // A6
499                components::adc::AdcComponent::new(
500                    adc_mux,
501                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput4)
502                )
503                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
504                // A7
505                components::adc::AdcComponent::new(
506                    adc_mux,
507                    nrf52840::adc::AdcChannelSetup::new(nrf52840::adc::AdcChannel::AnalogInput1)
508                )
509                .finalize(components::adc_component_static!(nrf52840::adc::Adc)),
510            ));
511
512    //--------------------------------------------------------------------------
513    // SENSORS
514    //--------------------------------------------------------------------------
515
516    let sensors_i2c_bus = components::i2c::I2CMuxComponent::new(&base_peripherals.twi1, None)
517        .finalize(components::i2c_mux_component_static!(nrf52840::i2c::TWI));
518    base_peripherals.twi1.configure(
519        nrf52840::pinmux::Pinmux::new(I2C_SCL_PIN as u32),
520        nrf52840::pinmux::Pinmux::new(I2C_SDA_PIN as u32),
521    );
522
523    nrf52840_peripherals.gpio_port[I2C_PULLUP_PIN].make_output();
524    nrf52840_peripherals.gpio_port[I2C_PULLUP_PIN].set();
525
526    let apds9960 = components::apds9960::Apds9960Component::new(
527        sensors_i2c_bus,
528        0x39,
529        &nrf52840_peripherals.gpio_port[APDS9960_PIN],
530    )
531    .finalize(components::apds9960_component_static!(nrf52840::i2c::TWI));
532    let proximity = components::proximity::ProximityComponent::new(
533        apds9960,
534        board_kernel,
535        capsules_extra::proximity::DRIVER_NUM,
536    )
537    .finalize(components::proximity_component_static!());
538
539    let hts221 = components::hts221::Hts221Component::new(sensors_i2c_bus, 0x5f)
540        .finalize(components::hts221_component_static!(nrf52840::i2c::TWI));
541    let temperature = components::temperature::TemperatureComponent::new(
542        board_kernel,
543        capsules_extra::temperature::DRIVER_NUM,
544        hts221,
545    )
546    .finalize(components::temperature_component_static!(HTS221Sensor));
547    let humidity = components::humidity::HumidityComponent::new(
548        board_kernel,
549        capsules_extra::humidity::DRIVER_NUM,
550        hts221,
551    )
552    .finalize(components::humidity_component_static!(HTS221Sensor));
553
554    //--------------------------------------------------------------------------
555    // WIRELESS
556    //--------------------------------------------------------------------------
557
558    let ble_radio = components::ble::BLEComponent::new(
559        board_kernel,
560        capsules_extra::ble_advertising_driver::DRIVER_NUM,
561        &base_peripherals.ble_radio,
562        mux_alarm,
563    )
564    .finalize(components::ble_component_static!(
565        nrf52840::rtc::Rtc,
566        nrf52840::ble_radio::Radio
567    ));
568
569    use capsules_extra::net::ieee802154::MacAddress;
570
571    let aes_mux = components::ieee802154::MuxAes128ccmComponent::new(&base_peripherals.ecb)
572        .finalize(components::mux_aes128ccm_component_static!(
573            nrf52840::aes::AesECB
574        ));
575
576    let device_id = (*addr_of!(nrf52840::ficr::FICR_INSTANCE)).id();
577    let device_id_bottom_16 = u16::from_le_bytes([device_id[0], device_id[1]]);
578    let (ieee802154_radio, mux_mac) = components::ieee802154::Ieee802154Component::new(
579        board_kernel,
580        capsules_extra::ieee802154::DRIVER_NUM,
581        &nrf52840_peripherals.ieee802154_radio,
582        aes_mux,
583        PAN_ID,
584        device_id_bottom_16,
585        device_id,
586    )
587    .finalize(components::ieee802154_component_static!(
588        nrf52840::ieee802154_radio::Radio,
589        nrf52840::aes::AesECB<'static>
590    ));
591    use capsules_extra::net::ipv6::ip_utils::IPAddr;
592
593    let local_ip_ifaces = static_init!(
594        [IPAddr; 3],
595        [
596            IPAddr([
597                0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x0a, 0x0b, 0x0c, 0x0d,
598                0x0e, 0x0f,
599            ]),
600            IPAddr([
601                0x10, 0x11, 0x12, 0x13, 0x14, 0x15, 0x16, 0x17, 0x18, 0x19, 0x1a, 0x1b, 0x1c, 0x1d,
602                0x1e, 0x1f,
603            ]),
604            IPAddr::generate_from_mac(capsules_extra::net::ieee802154::MacAddress::Short(
605                device_id_bottom_16
606            )),
607        ]
608    );
609
610    let (udp_send_mux, udp_recv_mux, udp_port_table) = components::udp_mux::UDPMuxComponent::new(
611        mux_mac,
612        DEFAULT_CTX_PREFIX_LEN,
613        DEFAULT_CTX_PREFIX,
614        DST_MAC_ADDR,
615        MacAddress::Short(device_id_bottom_16),
616        local_ip_ifaces,
617        mux_alarm,
618    )
619    .finalize(components::udp_mux_component_static!(
620        nrf52840::rtc::Rtc,
621        Ieee802154MacDevice
622    ));
623
624    // UDP driver initialization happens here
625    let udp_driver = components::udp_driver::UDPDriverComponent::new(
626        board_kernel,
627        capsules_extra::net::udp::DRIVER_NUM,
628        udp_send_mux,
629        udp_recv_mux,
630        udp_port_table,
631        local_ip_ifaces,
632    )
633    .finalize(components::udp_driver_component_static!(nrf52840::rtc::Rtc));
634
635    //--------------------------------------------------------------------------
636    // FINAL SETUP AND BOARD BOOT
637    //--------------------------------------------------------------------------
638
639    // Start all of the clocks. Low power operation will require a better
640    // approach than this.
641    nrf52_components::NrfClockComponent::new(&base_peripherals.clock).finalize(());
642
643    let scheduler = components::sched::round_robin::RoundRobinComponent::new(processes)
644        .finalize(components::round_robin_component_static!(NUM_PROCS));
645
646    let platform = Platform {
647        ble_radio,
648        ieee802154_radio,
649        console,
650        pconsole,
651        proximity,
652        temperature,
653        humidity,
654        adc: adc_syscall,
655        led,
656        gpio,
657        rng,
658        alarm,
659        udp_driver,
660        ipc: kernel::ipc::IPC::new(
661            board_kernel,
662            kernel::ipc::DRIVER_NUM,
663            &memory_allocation_capability,
664        ),
665        scheduler,
666        systick: cortexm4::systick::SysTick::new_with_calibration(64000000),
667    };
668
669    let chip = static_init!(
670        nrf52840::chip::NRF52<Nrf52840DefaultPeripherals>,
671        nrf52840::chip::NRF52::new(nrf52840_peripherals)
672    );
673    PANIC_RESOURCES.get().map(|resources| {
674        resources.chip.put(chip);
675    });
676
677    // Need to disable the MPU because the bootloader seems to set it up.
678    chip.mpu().clear_mpu();
679
680    // Configure the USB stack to enable a serial port over CDC-ACM.
681    cdc.enable();
682    cdc.attach();
683
684    //--------------------------------------------------------------------------
685    // TESTS
686    //--------------------------------------------------------------------------
687    // test::linear_log_test::run(
688    //     mux_alarm,
689    //     &nrf52840_peripherals.nrf52.nvmc,
690    // );
691    // test::log_test::run(
692    //     mux_alarm,
693    //     &nrf52840_peripherals.nrf52.nvmc,
694    // );
695
696    debug!("Initialization complete. Entering main loop.");
697    let _ = platform.pconsole.start();
698
699    //--------------------------------------------------------------------------
700    // PROCESSES AND MAIN LOOP
701    //--------------------------------------------------------------------------
702
703    // These symbols are defined in the linker script.
704    extern "C" {
705        /// Beginning of the ROM region containing app images.
706        static _sapps: u8;
707        /// End of the ROM region containing app images.
708        static _eapps: u8;
709        /// Beginning of the RAM region for app memory.
710        static mut _sappmem: u8;
711        /// End of the RAM region for app memory.
712        static _eappmem: u8;
713    }
714
715    kernel::process::load_processes(
716        board_kernel,
717        chip,
718        core::slice::from_raw_parts(
719            core::ptr::addr_of!(_sapps),
720            core::ptr::addr_of!(_eapps) as usize - core::ptr::addr_of!(_sapps) as usize,
721        ),
722        core::slice::from_raw_parts_mut(
723            core::ptr::addr_of_mut!(_sappmem),
724            core::ptr::addr_of!(_eappmem) as usize - core::ptr::addr_of!(_sappmem) as usize,
725        ),
726        &FAULT_RESPONSE,
727        &process_management_capability,
728    )
729    .unwrap_or_else(|err| {
730        debug!("Error loading processes!");
731        debug!("{:?}", err);
732    });
733
734    (board_kernel, platform, chip)
735}
736
737/// Main function called after RAM initialized.
738#[no_mangle]
739pub unsafe fn main() {
740    let main_loop_capability = create_capability!(capabilities::MainLoopCapability);
741
742    let (board_kernel, platform, chip) = start();
743    board_kernel.kernel_loop(&platform, chip, Some(&platform.ipc), &main_loop_capability);
744}