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