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