lora_things_plus/
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//! Board file for SparkFun LoRa Thing Plus - expLoRaBLE
6//!
7//! - <https://www.sparkfun.com/products/17506>
8//!
9//! A Semtech SX1262 is connected as a SPI slave to IOM3
10//! See <https://www.northernmechatronics.com/_files/ugd/3c68cb_764598422c704ed1b32400b047fc7651.pdf>
11//! and <https://www.northernmechatronics.com/nm180100> for details
12//!
13//! See <https://github.com/NorthernMechatronics/nmsdk/blob/master/bsp/nm180100evb/bsp_pins.src>
14//! and <https://cdn.sparkfun.com/assets/4/4/f/7/e/expLoRaBLE_Thing_Plus_schematic.pdf>
15//! for details on the pin break outs
16//!
17//! IOM0: Qwiic I2C
18//! IOM1: Not connected
19//! IOM2: Broken out SPI
20//! IOM3: Semtech SX1262
21//!     Apollo 3 Pin Number | Apollo 3 Name | SX1262 Pin Number | SX1262 Name | SX1262 Description
22//!                      H6 |       GPIO 36 |                19 |  NSS        | SPI slave select
23//!                      J6 |       GPIO 38 |                17 |  MOSI       | SPI slave input
24//!                      J5 |       GPIO 43 |                16 |  MISO       | SPI slave output
25//!                      H5 |       GPIO 42 |                18 |  SCK        | SPI clock input
26//!                      J8 |       GPIO 39 |                14 |  BUSY       | Radio busy indicator
27//!                      J9 |       GPIO 40 |                13 |  DIO1       | Multipurpose digital I/O
28//!                      H9 |       GPIO 47 |                6  |  DIO3       | Multipurpose digital I/O
29//!                      J7 |       GPIO 44 |                15 |  NRESET     | Radio reset signal, active low
30//! IOM4: Not connected
31//! IOM5: Pins used by UART0
32
33#![no_std]
34// Disable this attribute when documenting, as a workaround for
35// https://github.com/rust-lang/rust/issues/62184.
36#![cfg_attr(not(doc), no_main)]
37#![deny(missing_docs)]
38#![feature(custom_test_frameworks)]
39#![test_runner(test_runner)]
40#![reexport_test_harness_main = "test_main"]
41
42use core::ptr::addr_of;
43use core::ptr::addr_of_mut;
44
45use apollo3::chip::Apollo3DefaultPeripherals;
46use capsules_core::virtualizers::virtual_alarm::MuxAlarm;
47use capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm;
48use components::bme280::Bme280Component;
49use components::ccs811::Ccs811Component;
50use kernel::capabilities;
51use kernel::component::Component;
52use kernel::hil::flash::HasClient;
53use kernel::hil::hasher::Hasher;
54use kernel::hil::i2c::I2CMaster;
55use kernel::hil::led::LedHigh;
56use kernel::hil::spi::SpiMaster;
57use kernel::hil::time::Counter;
58use kernel::platform::{KernelResources, SyscallDriverLookup};
59use kernel::scheduler::round_robin::RoundRobinSched;
60use kernel::{create_capability, debug, static_init};
61
62#[cfg(feature = "atecc508a")]
63use {
64    capsules_core::virtualizers::virtual_i2c::MuxI2C,
65    components::atecc508a::Atecc508aComponent,
66    kernel::hil::entropy::Entropy32,
67    kernel::hil::gpio::{Configure, Output},
68    kernel::hil::rng::Rng,
69};
70
71#[cfg(any(feature = "chirp_i2c_moisture", feature = "dfrobot_i2c_rainfall"))]
72use capsules_core::virtualizers::virtual_i2c::MuxI2C;
73
74/// Support routines for debugging I/O.
75pub mod io;
76
77#[cfg(test)]
78mod tests;
79
80// Number of concurrent processes this platform supports.
81const NUM_PROCS: usize = 4;
82
83// Actual memory for holding the active process structures.
84static mut PROCESSES: [Option<&'static dyn kernel::process::Process>; NUM_PROCS] = [None; 4];
85
86// Static reference to chip for panic dumps.
87static mut CHIP: Option<&'static apollo3::chip::Apollo3<Apollo3DefaultPeripherals>> = None;
88// Static reference to process printer for panic dumps.
89static mut PROCESS_PRINTER: Option<&'static capsules_system::process_printer::ProcessPrinterText> =
90    None;
91
92// How should the kernel respond when a process faults.
93const FAULT_RESPONSE: capsules_system::process_policies::PanicFaultPolicy =
94    capsules_system::process_policies::PanicFaultPolicy {};
95
96// Test access to the peripherals
97static mut PERIPHERALS: Option<&'static Apollo3DefaultPeripherals> = None;
98// Test access to board
99#[cfg(test)]
100static mut BOARD: Option<&'static kernel::Kernel> = None;
101// Test access to platform
102#[cfg(test)]
103static mut PLATFORM: Option<&'static LoRaThingsPlus> = None;
104// Test access to main loop capability
105#[cfg(test)]
106static mut MAIN_CAP: Option<&dyn kernel::capabilities::MainLoopCapability> = None;
107// Test access to alarm
108static mut ALARM: Option<&'static MuxAlarm<'static, apollo3::stimer::STimer<'static>>> = None;
109// Test access to sensors
110static mut BME280: Option<
111    &'static capsules_extra::bme280::Bme280<
112        'static,
113        capsules_core::virtualizers::virtual_i2c::I2CDevice<'static, apollo3::iom::Iom<'static>>,
114    >,
115> = None;
116static mut CCS811: Option<&'static capsules_extra::ccs811::Ccs811<'static>> = None;
117#[cfg(feature = "atecc508a")]
118static mut ATECC508A: Option<&'static capsules_extra::atecc508a::Atecc508a<'static>> = None;
119
120/// Dummy buffer that causes the linker to reserve enough space for the stack.
121#[no_mangle]
122#[link_section = ".stack_buffer"]
123pub static mut STACK_MEMORY: [u8; 0x1000] = [0; 0x1000];
124
125const LORA_SPI_DRIVER_NUM: usize = capsules_core::driver::NUM::LoRaPhySPI as usize;
126const LORA_GPIO_DRIVER_NUM: usize = capsules_core::driver::NUM::LoRaPhyGPIO as usize;
127
128type ChirpI2cMoistureType = components::chirp_i2c_moisture::ChirpI2cMoistureComponentType<
129    capsules_core::virtualizers::virtual_i2c::I2CDevice<'static, apollo3::iom::Iom<'static>>,
130>;
131type DFRobotRainFallType = components::dfrobot_rainfall_sensor::DFRobotRainFallSensorComponentType<
132    capsules_core::virtualizers::virtual_alarm::VirtualMuxAlarm<
133        'static,
134        apollo3::stimer::STimer<'static>,
135    >,
136    capsules_core::virtualizers::virtual_i2c::I2CDevice<'static, apollo3::iom::Iom<'static>>,
137>;
138type BME280Sensor = components::bme280::Bme280ComponentType<
139    capsules_core::virtualizers::virtual_i2c::I2CDevice<'static, apollo3::iom::Iom<'static>>,
140>;
141
142type TemperatureDriver = components::temperature::TemperatureComponentType<BME280Sensor>;
143type HumidityDriver = components::humidity::HumidityComponentType<BME280Sensor>;
144
145/// A structure representing this platform that holds references to all
146/// capsules for this platform.
147struct LoRaThingsPlus {
148    alarm: &'static capsules_core::alarm::AlarmDriver<
149        'static,
150        VirtualMuxAlarm<'static, apollo3::stimer::STimer<'static>>,
151    >,
152    led: &'static capsules_core::led::LedDriver<
153        'static,
154        LedHigh<'static, apollo3::gpio::GpioPin<'static>>,
155        1,
156    >,
157    gpio: &'static capsules_core::gpio::GPIO<'static, apollo3::gpio::GpioPin<'static>>,
158    console: &'static capsules_core::console::Console<'static>,
159    i2c_master:
160        &'static capsules_core::i2c_master::I2CMasterDriver<'static, apollo3::iom::Iom<'static>>,
161    external_spi_controller: &'static capsules_core::spi_controller::Spi<
162        'static,
163        capsules_core::virtualizers::virtual_spi::VirtualSpiMasterDevice<
164            'static,
165            apollo3::iom::Iom<'static>,
166        >,
167    >,
168    sx1262_spi_controller: &'static capsules_core::spi_controller::Spi<
169        'static,
170        capsules_core::virtualizers::virtual_spi::VirtualSpiMasterDevice<
171            'static,
172            apollo3::iom::Iom<'static>,
173        >,
174    >,
175    sx1262_gpio: &'static capsules_core::gpio::GPIO<'static, apollo3::gpio::GpioPin<'static>>,
176    temperature: &'static TemperatureDriver,
177    humidity: &'static HumidityDriver,
178    air_quality: &'static capsules_extra::air_quality::AirQualitySensor<'static>,
179    moisture: Option<&'static components::moisture::MoistureComponentType<ChirpI2cMoistureType>>,
180    rainfall: Option<&'static components::rainfall::RainFallComponentType<DFRobotRainFallType>>,
181    rng: Option<
182        &'static capsules_core::rng::RngDriver<
183            'static,
184            capsules_core::rng::Entropy32ToRandom<
185                'static,
186                capsules_extra::atecc508a::Atecc508a<'static>,
187            >,
188        >,
189    >,
190    scheduler: &'static RoundRobinSched<'static>,
191    systick: cortexm4::systick::SysTick,
192    kv_driver: &'static capsules_extra::kv_driver::KVStoreDriver<
193        'static,
194        capsules_extra::virtual_kv::VirtualKVPermissions<
195            'static,
196            capsules_extra::kv_store_permissions::KVStorePermissions<
197                'static,
198                capsules_extra::tickv_kv_store::TicKVKVStore<
199                    'static,
200                    capsules_extra::tickv::TicKVSystem<
201                        'static,
202                        capsules_core::virtualizers::virtual_flash::FlashUser<
203                            'static,
204                            apollo3::flashctrl::FlashCtrl<'static>,
205                        >,
206                        capsules_extra::sip_hash::SipHasher24<'static>,
207                        { apollo3::flashctrl::PAGE_SIZE },
208                    >,
209                    [u8; 8],
210                >,
211            >,
212        >,
213    >,
214}
215
216#[cfg(feature = "atecc508a")]
217fn atecc508a_wakeup() {
218    let peripherals = (unsafe { PERIPHERALS }).unwrap();
219
220    peripherals.gpio_port[6].make_output();
221    peripherals.gpio_port[6].clear();
222
223    // The ATECC508A requires the SDA line to be low for at least 60us
224    // to wake up.
225    for _i in 0..700 {
226        cortexm4::support::nop();
227    }
228
229    // Enable SDA and SCL for I2C (exposed via Qwiic)
230    let _ = &peripherals
231        .gpio_port
232        .enable_i2c(&peripherals.gpio_port[6], &peripherals.gpio_port[5]);
233}
234
235#[cfg(feature = "atecc508a")]
236unsafe fn setup_atecc508a(
237    board_kernel: &'static kernel::Kernel,
238    memory_allocation_cap: &dyn capabilities::MemoryAllocationCapability,
239    mux_i2c: &'static MuxI2C<'static, apollo3::iom::Iom<'static>>,
240) -> &'static capsules_core::rng::RngDriver<
241    'static,
242    capsules_core::rng::Entropy32ToRandom<'static, capsules_extra::atecc508a::Atecc508a<'static>>,
243> {
244    let atecc508a = Atecc508aComponent::new(mux_i2c, 0x60, atecc508a_wakeup).finalize(
245        components::atecc508a_component_static!(apollo3::iom::Iom<'static>),
246    );
247    ATECC508A = Some(atecc508a);
248
249    // Convert hardware RNG to the Random interface.
250    let entropy_to_random = static_init!(
251        capsules_core::rng::Entropy32ToRandom<
252            'static,
253            capsules_extra::atecc508a::Atecc508a<'static>,
254        >,
255        capsules_core::rng::Entropy32ToRandom::new(atecc508a)
256    );
257    atecc508a.set_client(entropy_to_random);
258    // Setup RNG for userspace
259    let rng_local = static_init!(
260        capsules_core::rng::RngDriver<
261            'static,
262            capsules_core::rng::Entropy32ToRandom<
263                'static,
264                capsules_extra::atecc508a::Atecc508a<'static>,
265            >,
266        >,
267        capsules_core::rng::RngDriver::new(
268            entropy_to_random,
269            board_kernel.create_grant(capsules_core::rng::DRIVER_NUM, memory_allocation_cap)
270        )
271    );
272    entropy_to_random.set_client(rng_local);
273
274    rng_local
275}
276
277#[cfg(feature = "chirp_i2c_moisture")]
278unsafe fn setup_chirp_i2c_moisture(
279    board_kernel: &'static kernel::Kernel,
280    _memory_allocation_cap: &dyn capabilities::MemoryAllocationCapability,
281    mux_i2c: &'static MuxI2C<'static, apollo3::iom::Iom<'static>>,
282) -> &'static components::moisture::MoistureComponentType<ChirpI2cMoistureType> {
283    let chirp_moisture =
284        components::chirp_i2c_moisture::ChirpI2cMoistureComponent::new(mux_i2c, 0x20).finalize(
285            components::chirp_i2c_moisture_component_static!(apollo3::iom::Iom<'static>),
286        );
287
288    let moisture = components::moisture::MoistureComponent::new(
289        board_kernel,
290        capsules_extra::moisture::DRIVER_NUM,
291        chirp_moisture,
292    )
293    .finalize(components::moisture_component_static!(ChirpI2cMoistureType));
294
295    moisture
296}
297
298#[cfg(feature = "dfrobot_i2c_rainfall")]
299unsafe fn setup_dfrobot_i2c_rainfall(
300    board_kernel: &'static kernel::Kernel,
301    _memory_allocation_cap: &dyn capabilities::MemoryAllocationCapability,
302    mux_i2c: &'static MuxI2C<'static, apollo3::iom::Iom<'static>>,
303    mux_alarm: &'static MuxAlarm<'static, apollo3::stimer::STimer<'static>>,
304) -> &'static components::rainfall::RainFallComponentType<DFRobotRainFallType> {
305    let dfrobot_rainfall =
306        components::dfrobot_rainfall_sensor::DFRobotRainFallSensorComponent::new(
307            mux_i2c, 0x1D, mux_alarm,
308        )
309        .finalize(components::dfrobot_rainfall_sensor_component_static!(
310            apollo3::stimer::STimer<'static>,
311            apollo3::iom::Iom<'static>
312        ));
313
314    let rainfall = components::rainfall::RainFallComponent::new(
315        board_kernel,
316        capsules_extra::rainfall::DRIVER_NUM,
317        dfrobot_rainfall,
318    )
319    .finalize(components::rainfall_component_static!(DFRobotRainFallType));
320
321    rainfall
322}
323
324/// Mapping of integer syscalls to objects that implement syscalls.
325impl SyscallDriverLookup for LoRaThingsPlus {
326    fn with_driver<F, R>(&self, driver_num: usize, f: F) -> R
327    where
328        F: FnOnce(Option<&dyn kernel::syscall::SyscallDriver>) -> R,
329    {
330        match driver_num {
331            capsules_core::alarm::DRIVER_NUM => f(Some(self.alarm)),
332            capsules_core::led::DRIVER_NUM => f(Some(self.led)),
333            capsules_core::gpio::DRIVER_NUM => f(Some(self.gpio)),
334            capsules_core::console::DRIVER_NUM => f(Some(self.console)),
335            capsules_core::i2c_master::DRIVER_NUM => f(Some(self.i2c_master)),
336            capsules_core::spi_controller::DRIVER_NUM => f(Some(self.external_spi_controller)),
337            LORA_SPI_DRIVER_NUM => f(Some(self.sx1262_spi_controller)),
338            LORA_GPIO_DRIVER_NUM => f(Some(self.sx1262_gpio)),
339            capsules_extra::temperature::DRIVER_NUM => f(Some(self.temperature)),
340            capsules_extra::humidity::DRIVER_NUM => f(Some(self.humidity)),
341            capsules_extra::air_quality::DRIVER_NUM => f(Some(self.air_quality)),
342            capsules_extra::kv_driver::DRIVER_NUM => f(Some(self.kv_driver)),
343            capsules_core::rng::DRIVER_NUM => {
344                if let Some(rng) = self.rng {
345                    f(Some(rng))
346                } else {
347                    f(None)
348                }
349            }
350            capsules_extra::moisture::DRIVER_NUM => {
351                if let Some(moisture) = self.moisture {
352                    f(Some(moisture))
353                } else {
354                    f(None)
355                }
356            }
357            capsules_extra::rainfall::DRIVER_NUM => {
358                if let Some(rainfall) = self.rainfall {
359                    f(Some(rainfall))
360                } else {
361                    f(None)
362                }
363            }
364            _ => f(None),
365        }
366    }
367}
368
369impl KernelResources<apollo3::chip::Apollo3<Apollo3DefaultPeripherals>> for LoRaThingsPlus {
370    type SyscallDriverLookup = Self;
371    type SyscallFilter = ();
372    type ProcessFault = ();
373    type Scheduler = RoundRobinSched<'static>;
374    type SchedulerTimer = cortexm4::systick::SysTick;
375    type WatchDog = ();
376    type ContextSwitchCallback = ();
377
378    fn syscall_driver_lookup(&self) -> &Self::SyscallDriverLookup {
379        self
380    }
381    fn syscall_filter(&self) -> &Self::SyscallFilter {
382        &()
383    }
384    fn process_fault(&self) -> &Self::ProcessFault {
385        &()
386    }
387    fn scheduler(&self) -> &Self::Scheduler {
388        self.scheduler
389    }
390    fn scheduler_timer(&self) -> &Self::SchedulerTimer {
391        &self.systick
392    }
393    fn watchdog(&self) -> &Self::WatchDog {
394        &()
395    }
396    fn context_switch_callback(&self) -> &Self::ContextSwitchCallback {
397        &()
398    }
399}
400
401// Ensure that `setup()` is never inlined
402// This helps reduce the stack frame, see https://github.com/tock/tock/issues/3518
403#[inline(never)]
404unsafe fn setup() -> (
405    &'static kernel::Kernel,
406    &'static LoRaThingsPlus,
407    &'static apollo3::chip::Apollo3<Apollo3DefaultPeripherals>,
408) {
409    let peripherals = static_init!(Apollo3DefaultPeripherals, Apollo3DefaultPeripherals::new());
410    PERIPHERALS = Some(peripherals);
411
412    // No need to statically allocate mcu/pwr/clk_ctrl because they are only used in main!
413    let mcu_ctrl = apollo3::mcuctrl::McuCtrl::new();
414    let pwr_ctrl = apollo3::pwrctrl::PwrCtrl::new();
415    let clkgen = apollo3::clkgen::ClkGen::new();
416
417    clkgen.set_clock_frequency(apollo3::clkgen::ClockFrequency::Freq48MHz);
418
419    // initialize capabilities
420    let memory_allocation_cap = create_capability!(capabilities::MemoryAllocationCapability);
421
422    let board_kernel = static_init!(kernel::Kernel, kernel::Kernel::new(&*addr_of!(PROCESSES)));
423
424    // Power up components
425    pwr_ctrl.enable_uart0();
426    pwr_ctrl.enable_iom0();
427    pwr_ctrl.enable_iom2();
428    pwr_ctrl.enable_iom3();
429
430    peripherals.init();
431
432    // Enable PinCfg
433    peripherals
434        .gpio_port
435        .enable_uart(&peripherals.gpio_port[48], &peripherals.gpio_port[49]);
436    // Enable Main SPI
437    peripherals.gpio_port.enable_spi(
438        &peripherals.gpio_port[27],
439        &peripherals.gpio_port[28],
440        &peripherals.gpio_port[25],
441    );
442    // Enable SPI for SX1262
443    peripherals.gpio_port.enable_spi(
444        &peripherals.gpio_port[42],
445        &peripherals.gpio_port[38],
446        &peripherals.gpio_port[43],
447    );
448    // Enable the radio pins
449    peripherals.gpio_port.enable_sx1262_radio_pins();
450
451    // Configure kernel debug gpios as early as possible
452    kernel::debug::assign_gpios(Some(&peripherals.gpio_port[26]), None, None);
453
454    // Create a shared UART channel for the console and for kernel debug.
455    let uart_mux = components::console::UartMuxComponent::new(&peripherals.uart0, 115200)
456        .finalize(components::uart_mux_component_static!());
457
458    // Setup the console.
459    let console = components::console::ConsoleComponent::new(
460        board_kernel,
461        capsules_core::console::DRIVER_NUM,
462        uart_mux,
463    )
464    .finalize(components::console_component_static!());
465    // Create the debugger object that handles calls to `debug!()`.
466    components::debug_writer::DebugWriterComponent::new(uart_mux)
467        .finalize(components::debug_writer_component_static!());
468
469    // LEDs
470    let led = components::led::LedsComponent::new().finalize(components::led_component_static!(
471        LedHigh<'static, apollo3::gpio::GpioPin>,
472        LedHigh::new(&peripherals.gpio_port[19]),
473    ));
474
475    // GPIOs
476    // Details are at: https://github.com/NorthernMechatronics/nmsdk/blob/master/bsp/nm180100evb/bsp_pins.src
477    let gpio = components::gpio::GpioComponent::new(
478        board_kernel,
479        capsules_core::gpio::DRIVER_NUM,
480        components::gpio_component_helper!(
481            apollo3::gpio::GpioPin,
482            0 => &peripherals.gpio_port[13],  // A0
483            1 => &peripherals.gpio_port[12],  // A1
484            2 => &peripherals.gpio_port[32],  // A2
485            3 => &peripherals.gpio_port[35],  // A3
486            4 => &peripherals.gpio_port[34],  // A4
487        ),
488    )
489    .finalize(components::gpio_component_static!(apollo3::gpio::GpioPin));
490
491    // Create a shared virtualisation mux layer on top of a single hardware
492    // alarm.
493    let _ = peripherals.stimer.start();
494    let mux_alarm = components::alarm::AlarmMuxComponent::new(&peripherals.stimer).finalize(
495        components::alarm_mux_component_static!(apollo3::stimer::STimer),
496    );
497    let alarm = components::alarm::AlarmDriverComponent::new(
498        board_kernel,
499        capsules_core::alarm::DRIVER_NUM,
500        mux_alarm,
501    )
502    .finalize(components::alarm_component_static!(apollo3::stimer::STimer));
503    ALARM = Some(mux_alarm);
504
505    // Create a process printer for panic.
506    let process_printer = components::process_printer::ProcessPrinterTextComponent::new()
507        .finalize(components::process_printer_text_component_static!());
508    PROCESS_PRINTER = Some(process_printer);
509
510    // Enable SDA and SCL for I2C (exposed via Qwiic)
511    peripherals
512        .gpio_port
513        .enable_i2c(&peripherals.gpio_port[6], &peripherals.gpio_port[5]);
514
515    // Init the I2C device attached via Qwiic
516    let i2c_master_buffer = static_init!(
517        [u8; capsules_core::i2c_master::BUFFER_LENGTH],
518        [0; capsules_core::i2c_master::BUFFER_LENGTH]
519    );
520    let i2c_master = static_init!(
521        capsules_core::i2c_master::I2CMasterDriver<'static, apollo3::iom::Iom<'static>>,
522        capsules_core::i2c_master::I2CMasterDriver::new(
523            &peripherals.iom0,
524            i2c_master_buffer,
525            board_kernel.create_grant(
526                capsules_core::i2c_master::DRIVER_NUM,
527                &memory_allocation_cap
528            )
529        )
530    );
531
532    peripherals.iom0.set_master_client(i2c_master);
533    peripherals.iom0.enable();
534
535    let mux_i2c = components::i2c::I2CMuxComponent::new(&peripherals.iom0, None).finalize(
536        components::i2c_mux_component_static!(apollo3::iom::Iom<'static>),
537    );
538
539    let bme280 = Bme280Component::new(mux_i2c, 0x77).finalize(
540        components::bme280_component_static!(apollo3::iom::Iom<'static>),
541    );
542    let temperature = components::temperature::TemperatureComponent::new(
543        board_kernel,
544        capsules_extra::temperature::DRIVER_NUM,
545        bme280,
546    )
547    .finalize(components::temperature_component_static!(BME280Sensor));
548    let humidity = components::humidity::HumidityComponent::new(
549        board_kernel,
550        capsules_extra::humidity::DRIVER_NUM,
551        bme280,
552    )
553    .finalize(components::humidity_component_static!(BME280Sensor));
554    BME280 = Some(bme280);
555
556    let ccs811 = Ccs811Component::new(mux_i2c, 0x5B).finalize(
557        components::ccs811_component_static!(apollo3::iom::Iom<'static>),
558    );
559    let air_quality = components::air_quality::AirQualityComponent::new(
560        board_kernel,
561        capsules_extra::temperature::DRIVER_NUM,
562        ccs811,
563    )
564    .finalize(components::air_quality_component_static!());
565    CCS811 = Some(ccs811);
566
567    #[cfg(feature = "chirp_i2c_moisture")]
568    let moisture = Some(setup_chirp_i2c_moisture(
569        board_kernel,
570        &memory_allocation_cap,
571        mux_i2c,
572    ));
573    #[cfg(not(feature = "chirp_i2c_moisture"))]
574    let moisture = None;
575
576    #[cfg(feature = "dfrobot_i2c_rainfall")]
577    let rainfall = Some(setup_dfrobot_i2c_rainfall(
578        board_kernel,
579        &memory_allocation_cap,
580        mux_i2c,
581        mux_alarm,
582    ));
583    #[cfg(not(feature = "dfrobot_i2c_rainfall"))]
584    let rainfall = None;
585
586    #[cfg(feature = "atecc508a")]
587    let rng = Some(setup_atecc508a(
588        board_kernel,
589        &memory_allocation_cap,
590        mux_i2c,
591    ));
592    #[cfg(not(feature = "atecc508a"))]
593    let rng = None;
594
595    // Init the broken out SPI controller
596    let external_mux_spi = components::spi::SpiMuxComponent::new(&peripherals.iom2).finalize(
597        components::spi_mux_component_static!(apollo3::iom::Iom<'static>),
598    );
599
600    let external_spi_controller = components::spi::SpiSyscallComponent::new(
601        board_kernel,
602        external_mux_spi,
603        kernel::hil::spi::cs::IntoChipSelect::<_, kernel::hil::spi::cs::ActiveLow>::into_cs(
604            &peripherals.gpio_port[11], // A5
605        ),
606        capsules_core::spi_controller::DRIVER_NUM,
607    )
608    .finalize(components::spi_syscall_component_static!(
609        apollo3::iom::Iom<'static>
610    ));
611
612    // Init the internal SX1262 SPI controller
613    let sx1262_mux_spi = components::spi::SpiMuxComponent::new(&peripherals.iom3).finalize(
614        components::spi_mux_component_static!(apollo3::iom::Iom<'static>),
615    );
616
617    let sx1262_spi_controller = components::spi::SpiSyscallComponent::new(
618        board_kernel,
619        sx1262_mux_spi,
620        kernel::hil::spi::cs::IntoChipSelect::<_, kernel::hil::spi::cs::ActiveLow>::into_cs(
621            &peripherals.gpio_port[36], // H6 - SX1262 Slave Select
622        ),
623        LORA_SPI_DRIVER_NUM,
624    )
625    .finalize(components::spi_syscall_component_static!(
626        apollo3::iom::Iom<'static>
627    ));
628    peripherals
629        .iom3
630        .specify_chip_select(kernel::hil::spi::cs::IntoChipSelect::<
631            _,
632            kernel::hil::spi::cs::ActiveLow,
633        >::into_cs(
634            &peripherals.gpio_port[36], // H6 - SX1262 Slave Select
635        ))
636        .unwrap();
637
638    let sx1262_gpio = components::gpio::GpioComponent::new(
639        board_kernel,
640        LORA_GPIO_DRIVER_NUM,
641        components::gpio_component_helper!(
642            apollo3::gpio::GpioPin,
643            0 => &peripherals.gpio_port[36], // H6 - SX1262 Slave Select
644            1 => &peripherals.gpio_port[39], // J8 - SX1262 Radio Busy Indicator
645            2 => &peripherals.gpio_port[40], // J9 - SX1262 Multipurpose digital I/O (DIO1)
646            3 => &peripherals.gpio_port[47], // H9 - SX1262 Multipurpose digital I/O (DIO3)
647            4 => &peripherals.gpio_port[44], // J7 - SX1262 Reset
648        ),
649    )
650    .finalize(components::gpio_component_static!(apollo3::gpio::GpioPin));
651
652    // Setup BLE
653    mcu_ctrl.disable_ble();
654
655    // Flash
656    let flash_ctrl_read_buf = static_init!(
657        [u8; apollo3::flashctrl::PAGE_SIZE],
658        [0; apollo3::flashctrl::PAGE_SIZE]
659    );
660    let page_buffer = static_init!(
661        apollo3::flashctrl::Apollo3Page,
662        apollo3::flashctrl::Apollo3Page::default()
663    );
664
665    let mux_flash = components::flash::FlashMuxComponent::new(&peripherals.flash_ctrl).finalize(
666        components::flash_mux_component_static!(apollo3::flashctrl::FlashCtrl),
667    );
668
669    // SipHash
670    let sip_hash = static_init!(
671        capsules_extra::sip_hash::SipHasher24,
672        capsules_extra::sip_hash::SipHasher24::new()
673    );
674    kernel::deferred_call::DeferredCallClient::register(sip_hash);
675
676    // TicKV
677    let tickv = components::tickv::TicKVComponent::new(
678        sip_hash,
679        mux_flash, // Flash controller
680        core::ptr::addr_of!(_skv_data) as usize / apollo3::flashctrl::PAGE_SIZE, // Region offset (Last 0x28000 bytes of flash)
681        // Region Size, the final page doens't work correctly
682        core::ptr::addr_of!(_lkv_data) as usize - apollo3::flashctrl::PAGE_SIZE,
683        flash_ctrl_read_buf, // Buffer used internally in TicKV
684        page_buffer,         // Buffer used with the flash controller
685    )
686    .finalize(components::tickv_component_static!(
687        apollo3::flashctrl::FlashCtrl,
688        capsules_extra::sip_hash::SipHasher24,
689        { apollo3::flashctrl::PAGE_SIZE }
690    ));
691    HasClient::set_client(&peripherals.flash_ctrl, mux_flash);
692    sip_hash.set_client(tickv);
693
694    let kv_store = components::kv::TicKVKVStoreComponent::new(tickv).finalize(
695        components::tickv_kv_store_component_static!(
696            capsules_extra::tickv::TicKVSystem<
697                capsules_core::virtualizers::virtual_flash::FlashUser<
698                    apollo3::flashctrl::FlashCtrl,
699                >,
700                capsules_extra::sip_hash::SipHasher24<'static>,
701                { apollo3::flashctrl::PAGE_SIZE },
702            >,
703            capsules_extra::tickv::TicKVKeyType,
704        ),
705    );
706
707    let kv_store_permissions = components::kv::KVStorePermissionsComponent::new(kv_store).finalize(
708        components::kv_store_permissions_component_static!(
709            capsules_extra::tickv_kv_store::TicKVKVStore<
710                capsules_extra::tickv::TicKVSystem<
711                    capsules_core::virtualizers::virtual_flash::FlashUser<
712                        apollo3::flashctrl::FlashCtrl,
713                    >,
714                    capsules_extra::sip_hash::SipHasher24<'static>,
715                    { apollo3::flashctrl::PAGE_SIZE },
716                >,
717                capsules_extra::tickv::TicKVKeyType,
718            >
719        ),
720    );
721
722    let mux_kv = components::kv::KVPermissionsMuxComponent::new(kv_store_permissions).finalize(
723        components::kv_permissions_mux_component_static!(
724            capsules_extra::kv_store_permissions::KVStorePermissions<
725                capsules_extra::tickv_kv_store::TicKVKVStore<
726                    capsules_extra::tickv::TicKVSystem<
727                        capsules_core::virtualizers::virtual_flash::FlashUser<
728                            apollo3::flashctrl::FlashCtrl,
729                        >,
730                        capsules_extra::sip_hash::SipHasher24<'static>,
731                        { apollo3::flashctrl::PAGE_SIZE },
732                    >,
733                    capsules_extra::tickv::TicKVKeyType,
734                >,
735            >
736        ),
737    );
738
739    let virtual_kv_driver = components::kv::VirtualKVPermissionsComponent::new(mux_kv).finalize(
740        components::virtual_kv_permissions_component_static!(
741            capsules_extra::kv_store_permissions::KVStorePermissions<
742                capsules_extra::tickv_kv_store::TicKVKVStore<
743                    capsules_extra::tickv::TicKVSystem<
744                        capsules_core::virtualizers::virtual_flash::FlashUser<
745                            apollo3::flashctrl::FlashCtrl,
746                        >,
747                        capsules_extra::sip_hash::SipHasher24<'static>,
748                        { apollo3::flashctrl::PAGE_SIZE },
749                    >,
750                    capsules_extra::tickv::TicKVKeyType,
751                >,
752            >
753        ),
754    );
755
756    let kv_driver = components::kv::KVDriverComponent::new(
757        virtual_kv_driver,
758        board_kernel,
759        capsules_extra::kv_driver::DRIVER_NUM,
760    )
761    .finalize(components::kv_driver_component_static!(
762        capsules_extra::virtual_kv::VirtualKVPermissions<
763            capsules_extra::kv_store_permissions::KVStorePermissions<
764                capsules_extra::tickv_kv_store::TicKVKVStore<
765                    capsules_extra::tickv::TicKVSystem<
766                        capsules_core::virtualizers::virtual_flash::FlashUser<
767                            apollo3::flashctrl::FlashCtrl,
768                        >,
769                        capsules_extra::sip_hash::SipHasher24<'static>,
770                        { apollo3::flashctrl::PAGE_SIZE },
771                    >,
772                    capsules_extra::tickv::TicKVKeyType,
773                >,
774            >,
775        >
776    ));
777
778    mcu_ctrl.print_chip_revision();
779
780    debug!("Initialization complete. Entering main loop");
781
782    // These symbols are defined in the linker script.
783    extern "C" {
784        /// Beginning of the ROM region containing app images.
785        static _sapps: u8;
786        /// End of the ROM region containing app images.
787        static _eapps: u8;
788        /// Beginning of the RAM region for app memory.
789        static mut _sappmem: u8;
790        /// End of the RAM region for app memory.
791        static _eappmem: u8;
792        /// Beginning of the RAM region containing K/V data.
793        static _skv_data: u8;
794        /// Length of the RAM region containing K/V data.
795        static _lkv_data: u8;
796    }
797
798    let scheduler = components::sched::round_robin::RoundRobinComponent::new(&*addr_of!(PROCESSES))
799        .finalize(components::round_robin_component_static!(NUM_PROCS));
800
801    let systick = cortexm4::systick::SysTick::new_with_calibration(48_000_000);
802
803    let artemis_nano = static_init!(
804        LoRaThingsPlus,
805        LoRaThingsPlus {
806            alarm,
807            led,
808            gpio,
809            console,
810            i2c_master,
811            external_spi_controller,
812            sx1262_spi_controller,
813            sx1262_gpio,
814            temperature,
815            humidity,
816            air_quality,
817            moisture,
818            rainfall,
819            rng,
820            scheduler,
821            systick,
822            kv_driver,
823        }
824    );
825
826    let chip = static_init!(
827        apollo3::chip::Apollo3<Apollo3DefaultPeripherals>,
828        apollo3::chip::Apollo3::new(peripherals)
829    );
830    CHIP = Some(chip);
831
832    let checking_policy;
833    #[cfg(feature = "atecc508a")]
834    {
835        // Create the software-based SHA engine.
836        // We could use the ATECC508a for SHA, but writing the entire
837        // application to the device to compute a digtest ends up being
838        // pretty slow and the ATECC508a doesn't support the DigestVerify trait
839        let sha = components::sha::ShaSoftware256Component::new()
840            .finalize(components::sha_software_256_component_static!());
841
842        // These are the generated test keys used below, please do not use them
843        // for anything important!!!!
844        //
845        // These keys are not leaked, they are only used for this test case.
846        //
847        // -----BEGIN PRIVATE KEY-----
848        // MIGHAgEBMBMGByqGSM49AgEGCCqGSM49AwEHBG0wawIBAQQgWClhguWHtAK85Kqc
849        // /BucDBQMGQw6R2PEQkyISHkn5xWhRANCAAQUFMTFoNL9oFpGmg6Cp351hQMq9hol
850        // KpEdQfjP1nYF1jxqz52YjPpFHvudkK/fFsik5Rd0AevNkQqjBdWEqmpW
851        // -----END PRIVATE KEY-----
852        //
853        // -----BEGIN PUBLIC KEY-----
854        // MFkwEwYHKoZIzj0CAQYIKoZIzj0DAQcDQgAEFBTExaDS/aBaRpoOgqd+dYUDKvYa
855        // JSqRHUH4z9Z2BdY8as+dmIz6RR77nZCv3xbIpOUXdAHrzZEKowXVhKpqVg==
856        // -----END PUBLIC KEY-----
857        let public_key = static_init!(
858            [u8; 64],
859            [
860                0x14, 0x14, 0xc4, 0xc5, 0xa0, 0xd2, 0xfd, 0xa0, 0x5a, 0x46, 0x9a, 0x0e, 0x82, 0xa7,
861                0x7e, 0x75, 0x85, 0x03, 0x2a, 0xf6, 0x1a, 0x25, 0x2a, 0x91, 0x1d, 0x41, 0xf8, 0xcf,
862                0xd6, 0x76, 0x05, 0xd6, 0x3c, 0x6a, 0xcf, 0x9d, 0x98, 0x8c, 0xfa, 0x45, 0x1e, 0xfb,
863                0x9d, 0x90, 0xaf, 0xdf, 0x16, 0xc8, 0xa4, 0xe5, 0x17, 0x74, 0x01, 0xeb, 0xcd, 0x91,
864                0x0a, 0xa3, 0x05, 0xd5, 0x84, 0xaa, 0x6a, 0x56
865            ]
866        );
867
868        ATECC508A.unwrap().set_public_key(Some(public_key));
869
870        checking_policy = components::appid::checker_signature::AppCheckerSignatureComponent::new(
871            sha,
872            ATECC508A.unwrap(),
873            tock_tbf::types::TbfFooterV2CredentialsType::EcdsaNistP256,
874        )
875        .finalize(components::app_checker_signature_component_static!(
876            capsules_extra::atecc508a::Atecc508a<'static>,
877            capsules_extra::sha256::Sha256Software<'static>,
878            32,
879            64,
880        ));
881    };
882    #[cfg(not(feature = "atecc508a"))]
883    {
884        checking_policy = components::appid::checker_null::AppCheckerNullComponent::new()
885            .finalize(components::app_checker_null_component_static!());
886    }
887
888    // Create the AppID assigner.
889    let assigner = components::appid::assigner_name::AppIdAssignerNamesComponent::new()
890        .finalize(components::appid_assigner_names_component_static!());
891
892    // Create the process checking machine.
893    let checker = components::appid::checker::ProcessCheckerMachineComponent::new(checking_policy)
894        .finalize(components::process_checker_machine_component_static!());
895
896    let storage_permissions_policy =
897        components::storage_permissions::tbf_header::StoragePermissionsTbfHeaderComponent::new()
898            .finalize(
899                components::storage_permissions_tbf_header_component_static!(
900                    apollo3::chip::Apollo3<Apollo3DefaultPeripherals>,
901                    kernel::process::ProcessStandardDebugFull,
902                ),
903            );
904
905    // Create and start the asynchronous process loader.
906    let _loader = components::loader::sequential::ProcessLoaderSequentialComponent::new(
907        checker,
908        &mut *addr_of_mut!(PROCESSES),
909        board_kernel,
910        chip,
911        &FAULT_RESPONSE,
912        assigner,
913        storage_permissions_policy,
914    )
915    .finalize(components::process_loader_sequential_component_static!(
916        apollo3::chip::Apollo3<Apollo3DefaultPeripherals>,
917        kernel::process::ProcessStandardDebugFull,
918        NUM_PROCS,
919    ));
920
921    (board_kernel, artemis_nano, chip)
922}
923
924/// Main function.
925///
926/// This function is called from the arch crate after some very basic RISC-V
927/// setup and RAM initialization.
928#[no_mangle]
929pub unsafe fn main() {
930    apollo3::init();
931
932    #[cfg(test)]
933    test_main();
934
935    #[cfg(not(test))]
936    {
937        let (board_kernel, sf_lora_thing_plus_board, chip) = setup();
938
939        let main_loop_cap = create_capability!(capabilities::MainLoopCapability);
940
941        board_kernel.kernel_loop(
942            sf_lora_thing_plus_board,
943            chip,
944            None::<&kernel::ipc::IPC<{ NUM_PROCS as u8 }>>,
945            &main_loop_cap,
946        );
947    }
948}
949
950#[cfg(test)]
951use kernel::platform::watchdog::WatchDog;
952
953#[cfg(test)]
954fn test_runner(tests: &[&dyn Fn()]) {
955    unsafe {
956        let (board_kernel, sf_lora_thing_plus_board, _chip) = setup();
957
958        BOARD = Some(board_kernel);
959        PLATFORM = Some(&sf_lora_thing_plus_board);
960        MAIN_CAP = Some(&create_capability!(capabilities::MainLoopCapability));
961
962        PLATFORM.map(|p| {
963            p.watchdog().setup();
964        });
965
966        for test in tests {
967            test();
968        }
969    }
970
971    loop {}
972}