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