From 8633b326c1185637bf2a075dc5203ae7304316b8 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sat, 22 Jul 2023 14:25:23 -0400 Subject: [PATCH 01/30] Update lots to update will explain in PR --- .cargo/config | 2 +- boards/communication/src/communication.rs | 8 +- boards/recovery/src/communication.rs | 8 +- boards/recovery/src/data_manager.rs | 52 +++++- boards/recovery/src/main.rs | 28 +-- boards/recovery/src/state_machine/mod.rs | 2 +- .../src/state_machine/states/apogee.rs | 3 +- .../src/state_machine/states/ascent.rs | 2 +- boards/recovery/src/types.rs | 10 +- boards/sensor/src/communication.rs | 166 +++++++++++++++++- boards/sensor/src/main.rs | 75 ++++---- boards/sensor/src/sbg_manager.rs | 19 +- boards/sensor/src/types.rs | 13 +- libraries/common-arm/memory.x | 2 +- libraries/sbg-rs/src/sbg.rs | 34 ++-- 15 files changed, 316 insertions(+), 108 deletions(-) diff --git a/.cargo/config b/.cargo/config index 209886d8..578e04af 100644 --- a/.cargo/config +++ b/.cargo/config @@ -1,5 +1,5 @@ [target.'cfg(all(target_arch = "arm", target_os = "none"))'] -runner = "probe-run --chip ATSAME51J20A --protocol swd" +runner = "probe-run --chip ATSAME51J18A --protocol swd" rustflags = [ "-C", "link-arg=-Tlink.x", "-C", "link-arg=-Tdefmt.x", diff --git a/boards/communication/src/communication.rs b/boards/communication/src/communication.rs index 606cb4b3..7e886b81 100644 --- a/boards/communication/src/communication.rs +++ b/boards/communication/src/communication.rs @@ -120,7 +120,7 @@ impl CanDevice0 { action: Action::StoreFifo0, filter: ecan::StandardId::new(messages::sender::Sender::RecoveryBoard.into()) .unwrap(), - mask: ecan::StandardId::MAX, + mask: ecan::StandardId::ZERO, }) .unwrap_or_else(|_| panic!("Recovery filter")); @@ -129,7 +129,7 @@ impl CanDevice0 { action: Action::StoreFifo1, filter: ecan::StandardId::new(messages::sender::Sender::SensorBoard.into()) .unwrap(), - mask: ecan::StandardId::MAX, + mask: ecan::StandardId::ZERO, }) .unwrap_or_else(|_| panic!("Sensor filter")); @@ -137,7 +137,7 @@ impl CanDevice0 { .push(Filter::Classic { action: Action::StoreFifo0, filter: ecan::StandardId::new(messages::sender::Sender::PowerBoard.into()).unwrap(), - mask: ecan::StandardId::MAX, + mask: ecan::StandardId::ZERO, }) .unwrap_or_else(|_| panic!("Power filter")); @@ -146,7 +146,7 @@ impl CanDevice0 { action: Action::StoreFifo0, filter: ecan::StandardId::new(messages::sender::Sender::GroundStation.into()) .unwrap(), - mask: ecan::StandardId::MAX, + mask: ecan::StandardId::ZERO, }) .unwrap_or_else(|_| panic!("Ground Station filter")); diff --git a/boards/recovery/src/communication.rs b/boards/recovery/src/communication.rs index 8a6f2486..04c22ea9 100644 --- a/boards/recovery/src/communication.rs +++ b/boards/recovery/src/communication.rs @@ -113,7 +113,7 @@ impl CanDevice0 { action: Action::StoreFifo0, filter: ecan::StandardId::new(messages::sender::Sender::SensorBoard.into()) .unwrap(), - mask: ecan::StandardId::MAX, + mask: ecan::StandardId::ZERO, }) .unwrap_or_else(|_| panic!("Sensor Board filter")); @@ -123,7 +123,7 @@ impl CanDevice0 { action: Action::StoreFifo1, filter: ecan::StandardId::new(messages::sender::Sender::CommunicationBoard.into()) .unwrap(), - mask: ecan::StandardId::MAX, + mask: ecan::StandardId::ZERO, }) .unwrap_or_else(|_| panic!("Ground Station filter")); @@ -160,6 +160,8 @@ impl CanDevice0 { for message in &mut self.can.rx_fifo_0 { match from_bytes::(message.data()) { Ok(data) => { + // info!("Received data: {:?}", data); + data_manager.handle_data(data); } Err(e) => { @@ -172,6 +174,8 @@ impl CanDevice0 { for message in &mut self.can.rx_fifo_1 { match from_bytes::(message.data()) { Ok(data) => { + // info!("Received data: {:?}", data) + data_manager.handle_data(data); } Err(e) => { diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index 3fc9c018..3a9f2a15 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -2,6 +2,7 @@ use crate::state_machine::RocketStates; use heapless::HistoryBuffer; use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, UtcTime}; use messages::Message; +use defmt::info; const MAIN_HEIGHT: f32 = 450.0; const VELOCITY_MIN: f32 = 20.0; @@ -14,7 +15,7 @@ pub struct DataManager { pub imu: (Option, Option), pub utc_time: Option, pub gps_vel: Option, - pub historical_pressure: HistoryBuffer, + pub historical_pressure: HistoryBuffer, pub current_state: Option, } @@ -40,23 +41,56 @@ impl DataManager { let ekf_nav1 = self.ekf_nav.0.as_ref(); if let Some(ekf_nav1) = ekf_nav1 { if ekf_nav1.velocity[2] > VELOCITY_MIN { + info!("fail"); return false; } } - match self.historical_pressure.recent() { - Some(mut point_previous) => { + info!("points {}", self.historical_pressure.len()); + if self.historical_pressure.len() < 20 { + info!("fail"); + return false; + } + match self.historical_pressure.last() { + Some(last) => { + let mut avg = 0.0; + let mut prev = last; for i in self.historical_pressure.oldest_ordered() { - let slope = i - point_previous; - if slope > 0.0 { + avg += (i - prev)/0.25; + prev = i; + } + match avg / 20.0 { + x if x < 10.0 => { return false; } - point_previous = i; + _ => { + info!("avg: {}", avg / 20.0); + } } + // if (avg / 20.0 < ) { // 4 is the number of slopes. + // return false; + // } } None => { return false; } } + // match self.historical_pressure.recent() { + // Some(pressure) => { + // match self.historical_pressure.last() { + // Some(last) => { + // if (pressure - last) / 1.25 < 100.0 { + // return false; + // } + // } + // None => { + // return false; + // } + // } + // } + // None => { + // return false; + // } + // } true } pub fn is_launched(&self) -> bool { @@ -71,6 +105,12 @@ impl DataManager { None => false, } } + pub fn get_alt(&self) -> f32 { + match self.air.as_ref() { + Some(air) => air.altitude, + None => 0.0, + } + } pub fn handle_data(&mut self, data: Message) { match data.data { messages::Data::Sensor(sensor) => match sensor.data { diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index df90d922..901598f0 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -15,7 +15,7 @@ use common_arm::mcan; use common_arm::*; use communication::Capacities; use data_manager::DataManager; -use hal::gpio::{Pin, Pins, PushPullOutput, PA14}; +use hal::gpio::{Pin, Pins, PushPullOutput, PB16, PB17}; use hal::prelude::*; use mcan::messageram::SharedMemory; use messages::*; @@ -24,6 +24,7 @@ use state_machine::{StateMachine, StateMachineContext}; use systick_monotonic::*; use types::GPIOController; use types::COM_ID; +use defmt::info; #[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] mod app { @@ -39,7 +40,8 @@ mod app { #[local] struct Local { - led: Pin, + led_green: Pin, + led_red: Pin, state_machine: StateMachine, } @@ -86,10 +88,11 @@ mod app { ); /* GPIO config */ - let led = pins.pa14.into_push_pull_output(); + let led_green = pins.pb16.into_push_pull_output(); + let led_red = pins.pb17.into_push_pull_output(); let gpio = GPIOController::new( - pins.pa18.into_push_pull_output(), - pins.pa19.into_push_pull_output(), + pins.pb14.into_push_pull_output(), + pins.pb15.into_push_pull_output(), ); /* State Machine config */ let state_machine = StateMachine::new(); @@ -109,7 +112,7 @@ mod app { can0, gpio, }, - Local { led, state_machine }, + Local { led_green, led_red, state_machine }, init::Monotonics(mono), ) } @@ -122,15 +125,17 @@ mod app { /// Runs the state machine. /// This takes control of the shared resources. - #[task(priority = 3, local = [state_machine], shared = [can0, gpio, data_manager])] + #[task(local = [state_machine], shared = [can0, gpio, data_manager])] fn run_sm(mut cx: run_sm::Context) { + cx.shared.data_manager.lock(|dm| info!("alt: {}", dm.get_alt())); cx.local.state_machine.run(&mut StateMachineContext { shared_resources: &mut cx.shared, - }) + }); + spawn_after!(run_sm, 2.secs()); } /// Handles the CAN0 interrupt. - #[task(priority = 3, binds = CAN0, shared = [can0, data_manager])] + #[task(binds = CAN0, shared = [can0, data_manager])] fn can0(mut cx: can0::Context) { cx.shared.can0.lock(|can| { cx.shared @@ -175,13 +180,14 @@ mod app { /// Simple blink task to test the system. /// Acts as a heartbeat for the system. - #[task(local = [led], shared = [&em])] + #[task(local = [led_green, led_red], shared = [&em])] fn blink(cx: blink::Context) { cx.shared.em.run(|| { - cx.local.led.toggle()?; if cx.shared.em.has_error() { + cx.local.led_red.toggle()?; spawn_after!(blink, 200.millis())?; } else { + cx.local.led_green.toggle()?; spawn_after!(blink, 1.secs())?; } Ok(()) diff --git a/boards/recovery/src/state_machine/mod.rs b/boards/recovery/src/state_machine/mod.rs index c86f3c7a..aaf8bc84 100644 --- a/boards/recovery/src/state_machine/mod.rs +++ b/boards/recovery/src/state_machine/mod.rs @@ -41,7 +41,7 @@ pub struct StateMachine { // Define some functions to interact with the state machine impl StateMachine { pub fn new() -> Self { - let state = Initializing {}; + let state = Ascent {}; StateMachine { state: state.into(), diff --git a/boards/recovery/src/state_machine/states/apogee.rs b/boards/recovery/src/state_machine/states/apogee.rs index 59d2981d..de906b7b 100644 --- a/boards/recovery/src/state_machine/states/apogee.rs +++ b/boards/recovery/src/state_machine/states/apogee.rs @@ -2,13 +2,14 @@ use super::Ascent; use crate::state_machine::{Landed, RocketStates, State, StateMachineContext, TransitionInto}; use crate::{no_transition, transition}; use rtic::mutex::Mutex; -use defmt::{write, Format, Formatter}; +use defmt::{write, Format, Formatter, info}; #[derive(Debug, Clone)] pub struct Apogee {} impl State for Apogee { fn enter(&self, context: &mut StateMachineContext) { + info!("Apogee"); context.shared_resources.gpio.lock(|gpio| gpio.fire_drogue()); } fn step(&mut self, context: &mut StateMachineContext) -> Option { diff --git a/boards/recovery/src/state_machine/states/ascent.rs b/boards/recovery/src/state_machine/states/ascent.rs index 73138d8c..081cc01c 100644 --- a/boards/recovery/src/state_machine/states/ascent.rs +++ b/boards/recovery/src/state_machine/states/ascent.rs @@ -2,7 +2,7 @@ use crate::state_machine::states::apogee::Apogee; use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; use crate::{no_transition, transition}; -use defmt::{write, Format, Formatter}; +use defmt::{write, Format, Formatter, info}; use rtic::mutex::Mutex; #[derive(Debug, Clone)] diff --git a/boards/recovery/src/types.rs b/boards/recovery/src/types.rs index 7097bcc6..327ca09f 100644 --- a/boards/recovery/src/types.rs +++ b/boards/recovery/src/types.rs @@ -1,4 +1,4 @@ -use atsamd_hal::gpio::{PA18, PA19, Pin, PushPullOutput}; +use atsamd_hal::gpio::{PA18, PA19, PB14, PB15, PB17, Pin, PushPullOutput}; use atsamd_hal::prelude::*; use messages::sender::Sender; use messages::sender::Sender::RecoveryBoard; @@ -10,15 +10,15 @@ pub static COM_ID: Sender = RecoveryBoard; pub struct GPIOController { - drogue_ematch: Pin, - main_ematch: Pin, + drogue_ematch: Pin, + main_ematch: Pin, } impl GPIOController { - pub fn new(drogue_ematch: Pin, main_ematch: Pin) -> Self { + pub fn new(drogue_ematch: Pin, main_ematch: Pin) -> Self { Self { drogue_ematch, - main_ematch, + main_ematch } } pub fn fire_drogue(&mut self) { diff --git a/boards/sensor/src/communication.rs b/boards/sensor/src/communication.rs index f9ebeca6..86d916e8 100644 --- a/boards/sensor/src/communication.rs +++ b/boards/sensor/src/communication.rs @@ -3,10 +3,10 @@ use atsamd_hal::clock::v2::ahb::AhbClk; use atsamd_hal::clock::v2::gclk::Gclk0Id; use atsamd_hal::clock::v2::pclk::Pclk; -use atsamd_hal::clock::v2::types::Can0; +use atsamd_hal::clock::v2::types::{Can0, Can1}; use atsamd_hal::clock::v2::Source; -use atsamd_hal::gpio::{Alternate, AlternateI, Pin, I, PA22, PA23}; -use atsamd_hal::pac::CAN0; +use atsamd_hal::gpio::{Alternate, AlternateI, AlternateH, Pin, I, H, PA22, PA23, PB15, PB14}; +use atsamd_hal::pac::{CAN0, CAN1}; use atsamd_hal::typelevel::Increment; use common_arm::mcan; @@ -107,12 +107,22 @@ impl CanDevice0 { .interrupt_configuration() .enable_line_0(interrupts_to_be_enabled); + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo0, + filter: ecan::StandardId::new(messages::sender::Sender::CommunicationBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Self filter")); + + can.filters_standard() .push(Filter::Classic { action: Action::StoreFifo0, filter: ecan::StandardId::new(messages::sender::Sender::RecoveryBoard.into()) .unwrap(), - mask: ecan::StandardId::MAX, + mask: ecan::StandardId::ZERO, }) .unwrap_or_else(|_| panic!("Recovery filter")); @@ -121,7 +131,7 @@ impl CanDevice0 { action: Action::StoreFifo1, filter: ecan::StandardId::new(messages::sender::Sender::GroundStation.into()) .unwrap(), - mask: ecan::StandardId::MAX, + mask: ecan::StandardId::ZERO, }) .unwrap_or_else(|_| panic!("Ground Station filter")); @@ -183,3 +193,149 @@ impl CanDevice0 { } } } + +pub struct CanDevice1 { + pub can: Can< + 'static, + Can1, + Dependencies>, Pin>, CAN1>, + Capacities, + >, + line_interrupts: OwnedInterruptSet, +} + +impl CanDevice1 { + pub fn new( + can_rx: Pin, + can_tx: Pin, + pclk_can: Pclk, + ahb_clock: AhbClk, + peripheral: CAN1, + gclk0: S, + can_memory: &'static mut SharedMemory, + loopback: bool, + ) -> (Self, S::Inc) + where + S: Source + Increment, + { + let (can_dependencies, gclk0) = + Dependencies::new(gclk0, pclk_can, ahb_clock, can_rx, can_tx, peripheral); + + let mut can = + mcan::bus::CanConfigurable::new(200.kHz(), can_dependencies, can_memory).unwrap(); + can.config().mode = Mode::Fd { + allow_bit_rate_switching: false, + data_phase_timing: BitTiming::new(500.kHz()), + }; + + if loopback { + can.config().loopback = true; + } + + let interrupts_to_be_enabled = can + .interrupts() + .split( + [ + Interrupt::RxFifo0NewMessage, + Interrupt::RxFifo0Full, + Interrupt::RxFifo0MessageLost, + Interrupt::RxFifo1NewMessage, + Interrupt::RxFifo1Full, + Interrupt::RxFifo1MessageLost, + ] + .into_iter() + .collect(), + ) + .unwrap(); + + // Line 0 and 1 are connected to the same interrupt line + let line_interrupts = can + .interrupt_configuration() + .enable_line_0(interrupts_to_be_enabled); + + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo0, + filter: ecan::StandardId::new(messages::sender::Sender::CommunicationBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Self filter")); + + + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo0, + filter: ecan::StandardId::new(messages::sender::Sender::RecoveryBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Recovery filter")); + + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo1, + filter: ecan::StandardId::new(messages::sender::Sender::GroundStation.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Ground Station filter")); + + let can = can.finalize().unwrap(); + ( + CanDevice1 { + can, + line_interrupts, + }, + gclk0, + ) + } + pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { + let payload: Vec = postcard::to_vec(&m)?; + self.can.tx.transmit_queued( + tx::MessageBuilder { + id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), + frame_type: tx::FrameType::FlexibleDatarate { + payload: &payload[..], + bit_rate_switching: false, + force_error_state_indicator: false, + }, + store_tx_event: None, + } + .build()?, + )?; + Ok(()) + } + pub fn process_data(&mut self) { + let line_interrupts = &self.line_interrupts; + for interrupt in line_interrupts.iter_flagged() { + match interrupt { + Interrupt::RxFifo0NewMessage => { + for message in &mut self.can.rx_fifo_0 { + match from_bytes::(message.data()) { + Ok(data) => { + info!("Message: {:?}", data) + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + Interrupt::RxFifo1NewMessage => { + for message in &mut self.can.rx_fifo_1 { + match from_bytes::(message.data()) { + Ok(data) => { + info!("Message: {:?}", data) + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + _ => (), + } + } + } +} diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index 0e719a44..c89faa85 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -17,7 +17,7 @@ use communication::Capacities; use data_manager::DataManager; use hal::dmac; use hal::gpio::Pins; -use hal::gpio::PA14; +use hal::gpio::{PB16, PB17}; use hal::gpio::{Pin, PushPullOutput}; use hal::prelude::*; use mcan::messageram::SharedMemory; @@ -38,13 +38,14 @@ mod app { struct Shared { em: ErrorManager, data_manager: DataManager, - can0: communication::CanDevice0, + can: communication::CanDevice0, } #[local] struct Local { - led: Pin, - sd_manager: SdManager, + led_green: Pin, + led_red: Pin, + // sd_manager: SdManager, sbg_manager: SBGManager, } @@ -60,6 +61,9 @@ mod app { let core = cx.core; let pins = Pins::new(peripherals.PORT); + let mut sbg_pin = pins.pb01.into_push_pull_output(); + sbg_pin.set_high().unwrap(); // turn on sbg + let mut dmac = DmaController::init(peripherals.DMAC, &mut peripherals.PM); let dmaChannels = dmac.split(); @@ -79,7 +83,7 @@ mod app { /* CAN config */ let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0); - let (can0, gclk0) = communication::CanDevice0::new( + let (can, gclk0) = communication::CanDevice0::new( pins.pa23.into_mode(), pins.pa22.into_mode(), pclk_can, @@ -91,32 +95,33 @@ mod app { ); /* SD config */ - let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom1, gclk0); - let sd_manager = SdManager::new( - &mclk, - peripherals.SERCOM1, - pclk_sd.freq(), - pins.pa18.into_push_pull_output(), - pins.pa17.into_push_pull_output(), - pins.pa19.into_push_pull_output(), - pins.pa16.into_push_pull_output(), - ); + // let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom1, gclk0); + // let sd_manager = SdManager::new( + // &mclk, + // peripherals.SERCOM1, + // pclk_sd.freq(), + // pins.pa18.into_push_pull_output(), + // pins.pa17.into_push_pull_output(), + // pins.pa19.into_push_pull_output(), + // pins.pa16.into_push_pull_output(), + // ); /* SBG config */ - let (pclk_sbg, gclk0) = Pclk::enable(tokens.pclks.sercom0, gclk0); + let (pclk_sbg, gclk0) = Pclk::enable(tokens.pclks.sercom5, gclk0); let dmaCh0 = dmaChannels.0.init(dmac::PriorityLevel::LVL3); let sbg_manager = SBGManager::new( - pins.pa09, - pins.pa08, + pins.pb03, + pins.pb02, pclk_sbg, &mut mclk, - peripherals.SERCOM0, + peripherals.SERCOM5, peripherals.RTC, dmaCh0, ); /* Status LED */ - let led = pins.pa14.into_push_pull_output(); + let led_green = pins.pb16.into_push_pull_output(); + let led_red = pins.pb17.into_push_pull_output(); /* Spawn tasks */ sensor_send::spawn().ok(); @@ -129,26 +134,27 @@ mod app { Shared { em: ErrorManager::new(), data_manager: DataManager::new(), - can0, + can, }, Local { - led, - sd_manager, + led_green, + led_red, + // sd_manager, sbg_manager, }, init::Monotonics(mono), ) } - /// Idle task for when no other tasks are running. - #[idle] - fn idle(_: idle::Context) -> ! { - loop {} - } + // /// Idle task for when no other tasks are running. + // #[idle] + // fn idle(_: idle::Context) -> ! { + // loop {} + // } - #[task(priority = 3, binds = CAN0, shared = [can0])] + #[task(priority = 3, binds = CAN0, shared = [can])] fn can0(mut cx: can0::Context) { - cx.shared.can0.lock(|can| { + cx.shared.can.lock(|can| { can.process_data(); }); } @@ -156,10 +162,10 @@ mod app { /** * Sends a message over CAN. */ - #[task(capacity = 10, local = [counter: u16 = 0], shared = [can0, &em])] + #[task(capacity = 10, local = [counter: u16 = 0], shared = [can, &em])] fn send_internal(mut cx: send_internal::Context, m: Message) { cx.shared.em.run(|| { - cx.shared.can0.lock(|can| can.send_message(m))?; + cx.shared.can.lock(|can| can.send_message(m))?; Ok(()) }); } @@ -193,13 +199,14 @@ mod app { * Simple blink task to test the system. * Acts as a heartbeat for the system. */ - #[task(local = [led], shared = [&em])] + #[task(local = [led_green, led_red], shared = [&em])] fn blink(cx: blink::Context) { cx.shared.em.run(|| { - cx.local.led.toggle()?; if cx.shared.em.has_error() { + cx.local.led_red.toggle()?; spawn_after!(blink, 200.millis())?; } else { + cx.local.led_green.toggle()?; spawn_after!(blink, 1.secs())?; } Ok(()) diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index 4cc952c7..b99610d5 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -3,7 +3,8 @@ use atsamd_hal::clock::v2::gclk::Gclk0Id; use atsamd_hal::clock::v2::pclk::Pclk; use atsamd_hal::dmac; use atsamd_hal::dmac::Transfer; -use atsamd_hal::gpio::{Pin, Reset, PA08, PA09}; +use atsamd_hal::sercom::{IoSet1, IoSet6}; +use atsamd_hal::gpio::{Pin, Reset, PA08, PA09, PB03, PB02}; use atsamd_hal::pac::{MCLK, RTC}; use atsamd_hal::prelude::_atsamd21_hal_time_U32Ext; use atsamd_hal::rtc::Rtc; @@ -13,7 +14,7 @@ use core::mem::size_of; use core::ptr; use crate::app::sbg_handle_data; -use atsamd_hal::sercom::{uart, Sercom, Sercom0}; +use atsamd_hal::sercom::{uart, Sercom, Sercom5}; use embedded_alloc::Heap; use rtic::Mutex; use sbg_rs::sbg; @@ -33,11 +34,11 @@ pub struct SBGManager { impl SBGManager { pub fn new( - rx: Pin, - tx: Pin, - pclk_sercom0: Pclk, + rx: Pin, + tx: Pin, + pclk_sercom5: Pclk, mclk: &mut MCLK, - sercom0: Sercom0, + sercom5: Sercom5, rtc: RTC, mut dma_channel: dmac::Channel, ) -> Self { @@ -49,8 +50,8 @@ impl SBGManager { unsafe { HEAP.init(HEAP_MEM.as_ptr() as usize, HEAP_SIZE) } } - let pads_sbg = uart::Pads::::default().rx(rx).tx(tx); - let uart_sbg = ConfigSBG::new(mclk, sercom0, pads_sbg, pclk_sercom0.freq()) + let pads_sbg = uart::Pads::::default().rx(rx).tx(tx); + let uart_sbg = ConfigSBG::new(mclk, sercom5, pads_sbg, pclk_sercom5.freq()) .baud( 115200.hz(), uart::BaudMode::Fractional(uart::Oversampling::Bits8), @@ -65,7 +66,7 @@ impl SBGManager { .enable_interrupts(dmac::InterruptFlags::new().with_tcmpl(true)); let xfer = Transfer::new(dma_channel, sbg_rx, unsafe { &mut *BUF_DST }, false) .expect("DMA err") - .begin(Sercom0::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); + .begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); // There is a bug within the HAL that improperly configures the RTC // in count32 mode. This is circumvented by first using clock mode then diff --git a/boards/sensor/src/types.rs b/boards/sensor/src/types.rs index 644ccdee..c21d1ba2 100644 --- a/boards/sensor/src/types.rs +++ b/boards/sensor/src/types.rs @@ -3,12 +3,11 @@ use atsamd_hal as hal; use atsamd_hal::gpio::*; use atsamd_hal::sercom::uart::EightBit; use atsamd_hal::sercom::uart::Uart; -use atsamd_hal::sercom::{spi, uart, IoSet1, Sercom1}; +use atsamd_hal::sercom::{spi, uart, IoSet1, Sercom5, IoSet6, Sercom1}; use embedded_sdmmc as sd; use hal::dmac; use hal::dmac::BufferPair; -use hal::sercom::Sercom0; -use hal::sercom::Sercom5; +use hal::sercom::Sercom4; use messages::sender::Sender; use messages::sender::Sender::SensorBoard; use sbg_rs::sbg::SBG_BUFFER_SIZE; @@ -18,16 +17,10 @@ use sbg_rs::sbg::SBG_BUFFER_SIZE; // ------- pub static COM_ID: Sender = SensorBoard; -// ------- -// Ground Station -// ------- -pub type GroundStationPads = uart::PadsFromIds; -pub type GroundStationUartConfig = uart::Config; - // ------- // SBG // ------- -pub type PadsSBG = uart::PadsFromIds; +pub type PadsSBG = uart::PadsFromIds; pub type ConfigSBG = uart::Config; pub type SBGTransfer = dmac::Transfer< dmac::Channel, diff --git a/libraries/common-arm/memory.x b/libraries/common-arm/memory.x index 506f899d..59d0511d 100644 --- a/libraries/common-arm/memory.x +++ b/libraries/common-arm/memory.x @@ -1,7 +1,7 @@ MEMORY { /* NOTE K = KiBi = 1024 bytes */ - FLASH : ORIGIN = 0x00000000, LENGTH = 1024K + FLASH : ORIGIN = 0x00000000, LENGTH = 256K CAN : ORIGIN = 0x20000000, LENGTH = 64K RAM : ORIGIN = 0x20010000, LENGTH = 64K } diff --git a/libraries/sbg-rs/src/sbg.rs b/libraries/sbg-rs/src/sbg.rs index b6817e95..fb32fcbf 100644 --- a/libraries/sbg-rs/src/sbg.rs +++ b/libraries/sbg-rs/src/sbg.rs @@ -19,13 +19,13 @@ use core::slice::{from_raw_parts, from_raw_parts_mut}; use core::sync::atomic::AtomicUsize; use defmt::{debug, error, flush, info, warn}; use embedded_hal::serial::Write; -use hal::gpio::{PA08, PA09, PB16, PB17}; +use hal::gpio::{PA08, PA09, PB16, PB17, PB03, PB02}; use hal::sercom::uart::Duplex; use hal::sercom::uart::{self, EightBit, Uart}; -use hal::sercom::{IoSet1, Sercom0, Sercom5}; +use hal::sercom::{IoSet1, IoSet6, Sercom0, Sercom5}; use messages::sensor::*; -type Pads = uart::PadsFromIds; +type Pads = uart::PadsFromIds; type PadsCDC = uart::PadsFromIds; type Config = uart::Config; @@ -481,23 +481,23 @@ pub unsafe extern "C" fn sbgPlatformDebugLogMsg( _errorCode: _SbgErrorCode, pFormat: *const ::core::ffi::c_char, ) { - if pFileName.is_null() || pFunctionName.is_null() || pCategory.is_null() || pFormat.is_null() { - return; - } - // SAFETY: We are converting a raw pointer to a CStr and then to a str. - // This is safe because we check if the pointers are null and - // the pointers can only be accessed during the lifetime of this function. - let file = unsafe { CStr::from_ptr(pFileName).to_str().unwrap() }; - let function = unsafe { CStr::from_ptr(pFunctionName).to_str().unwrap() }; - let _category = unsafe { CStr::from_ptr(pCategory).to_str().unwrap() }; - let _format = unsafe { CStr::from_ptr(pFormat).to_str().unwrap() }; + // if pFileName.is_null() || pFunctionName.is_null() || pCategory.is_null() || pFormat.is_null() { + // return; + // } + // // SAFETY: We are converting a raw pointer to a CStr and then to a str. + // // This is safe because we check if the pointers are null and + // // the pointers can only be accessed during the lifetime of this function. + // let file = unsafe { CStr::from_ptr(pFileName).to_str().unwrap() }; + // let function = unsafe { CStr::from_ptr(pFunctionName).to_str().unwrap() }; + // let _category = unsafe { CStr::from_ptr(pCategory).to_str().unwrap() }; + // let _format = unsafe { CStr::from_ptr(pFormat).to_str().unwrap() }; match logType { // silently handle errors - _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR => error!("SBG Error {} {}", file, function), - _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING => warn!("SBG Warning {} {}", file, function), - _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_INFO => info!("SBG Info {} {}", file, function), - _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_DEBUG => debug!("SBG Debug {} {}", file, function), + // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR => error!("SBG Error {} {}", file, function), + _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING => warn!("SBG Warning"), + // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_INFO => info!("SBG Info {} {}", file, function), + // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_DEBUG => debug!("SBG Debug {} {}", file, function), _ => (), }; flush(); From 859eed159eee16d6fb996a2873842f868f483f5d Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Tue, 1 Aug 2023 19:37:59 -0400 Subject: [PATCH 02/30] Don't know at this point --- Cargo.lock | 1 + boards/communication/Cargo.toml | 3 +- boards/communication/src/main.rs | 2 + boards/communication/src/sd_manager.rs | 145 +++++++++++++++++++++++++ boards/communication/src/types.rs | 23 +++- boards/recovery/src/communication.rs | 4 - boards/recovery/src/data_manager.rs | 28 +---- boards/recovery/src/main.rs | 4 +- boards/recovery/src/types.rs | 8 +- boards/sensor/src/main.rs | 9 +- boards/sensor/src/sbg_manager.rs | 16 ++- boards/sensor/src/sd_manager.rs | 2 +- 12 files changed, 200 insertions(+), 45 deletions(-) create mode 100644 boards/communication/src/sd_manager.rs diff --git a/Cargo.lock b/Cargo.lock index 678522f6..5d4366f9 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -203,6 +203,7 @@ dependencies = [ "cortex-m-rt", "cortex-m-rtic", "defmt", + "embedded-sdmmc", "heapless", "messages", "panic-halt", diff --git a/boards/communication/Cargo.toml b/boards/communication/Cargo.toml index 8a298049..3b880b6e 100644 --- a/boards/communication/Cargo.toml +++ b/boards/communication/Cargo.toml @@ -17,4 +17,5 @@ heapless = "0.7.16" common-arm = { path = "../../libraries/common-arm" } atsamd-hal = { workspace = true } messages = { path = "../../libraries/messages" } -typenum = "1.16.0" \ No newline at end of file +typenum = "1.16.0" +embedded-sdmmc = "0.3.0" diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index ec91c344..c0b35073 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -4,6 +4,7 @@ mod communication; mod data_manager; mod types; +mod sd_manager; use atsamd_hal as hal; use atsamd_hal::clock::v2::pclk::Pclk; @@ -25,6 +26,7 @@ use messages::*; use panic_halt as _; use systick_monotonic::*; use types::*; +use defmt::info; #[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] mod app { diff --git a/boards/communication/src/sd_manager.rs b/boards/communication/src/sd_manager.rs new file mode 100644 index 00000000..6d8c22a5 --- /dev/null +++ b/boards/communication/src/sd_manager.rs @@ -0,0 +1,145 @@ +use crate::types::SdController; +use core::marker::PhantomData; +use atsamd_hal::gpio::{Output, Pin, PushPull, PA16, PA17, PA18, PA19}; +use atsamd_hal::pac; +use atsamd_hal::sercom::{spi, IoSet1, Sercom1}; +use atsamd_hal::time::Hertz; +use defmt::{info, warn}; +use embedded_sdmmc as sd; + +/// Time source for `[SdInterface]`. It doesn't return any useful information for now, and will +/// always return an arbitrary time. +pub struct TimeSink { + _marker: PhantomData<*const ()>, +} + +impl TimeSink { + fn new() -> Self { + TimeSink { + _marker: PhantomData, + } + } +} + +impl sd::TimeSource for TimeSink { + fn get_timestamp(&self) -> sd::Timestamp { + sd::Timestamp { + year_since_1970: 0, + zero_indexed_month: 0, + zero_indexed_day: 0, + hours: 0, + minutes: 0, + seconds: 0, + } + } +} + +/// Wrapper for the SD Card. For now, the pins are hard-coded. +pub struct SdManager { + pub sd_controller: SdController, + pub volume: sd::Volume, + pub root_directory: sd::Directory, + pub file: sd::File, +} + +impl SdManager { + pub fn new( + mclk: &pac::MCLK, + sercom: pac::SERCOM1, + freq: Hertz, + cs: Pin>, + sck: Pin>, + miso: Pin>, + mosi: Pin>, + ) -> Self { + let pads_spi = spi::Pads::::default() + .sclk(sck) + .data_in(miso) + .data_out(mosi); + let sdmmc_spi = spi::Config::new(mclk, sercom, pads_spi, freq) + .length::() + .bit_order(spi::BitOrder::MsbFirst) + .spi_mode(spi::MODE_0) + .enable(); + let time_sink: TimeSink = TimeSink::new(); // Need to give this a DateTime object for actual timing. + let mut sd_cont = sd::Controller::new(sd::SdMmcSpi::new(sdmmc_spi, cs), time_sink); + match sd_cont.device().init() { + Ok(_) => match sd_cont.device().card_size_bytes() { + Ok(size) => info!("Card is {} bytes", size), + Err(_) => warn!("Cannot get card size"), + }, + Err(_) => { + warn!("Cannot get SD card"); + panic!("Cannot get SD card."); + } + } + + let mut volume = match sd_cont.get_volume(sd::VolumeIdx(0)) { + Ok(volume) => volume, + Err(_) => { + warn!("Cannot get volume 0"); + panic!("Cannot get volume 0"); + } + }; + + let root_directory = match sd_cont.open_root_dir(&volume) { + Ok(root_directory) => root_directory, + Err(_) => { + warn!("Cannot get root"); + panic!("Cannot get root"); + } + }; + let file = sd_cont.open_file_in_dir( + &mut volume, + &root_directory, + "test2.txt", + sd::Mode::ReadWriteCreateOrTruncate, + ); + let file = match file { + Ok(file) => file, + Err(_) => { + warn!("Cannot create file."); + panic!("Cannot create file."); + } + }; + + SdManager { + sd_controller: sd_cont, + volume, + root_directory, + file, + } + } + pub fn write( + &mut self, + file: &mut sd::File, + buffer: &[u8], + ) -> Result> { + self.sd_controller.write(&mut self.volume, file, buffer) + } + pub fn write_str( + &mut self, + file: &mut sd::File, + msg: &str, + ) -> Result> { + let buffer: &[u8] = msg.as_bytes(); + self.sd_controller.write(&mut self.volume, file, buffer) + } + pub fn open_file(&mut self, file_name: &str) -> Result> { + self.sd_controller.open_file_in_dir( + &mut self.volume, + &self.root_directory, + file_name, + sd::Mode::ReadWriteCreateOrTruncate, + ) + } + pub fn close_file(&mut self, file: sd::File) -> Result<(), sd::Error> { + self.sd_controller.close_file(&self.volume, file) + } + pub fn close(mut self) { + self.sd_controller + .close_dir(&self.volume, self.root_directory); + } +} + +unsafe impl Send for SdManager {} \ No newline at end of file diff --git a/boards/communication/src/types.rs b/boards/communication/src/types.rs index 1a7b0f0a..380a7370 100644 --- a/boards/communication/src/types.rs +++ b/boards/communication/src/types.rs @@ -1,11 +1,11 @@ -use atsamd_hal as hal; +use crate::sd_manager::TimeSink; use atsamd_hal::gpio::*; use atsamd_hal::sercom::uart::EightBit; - -use atsamd_hal::sercom::{uart, IoSet1}; -use hal::sercom::Sercom5; +use atsamd_hal::sercom::spi; +use atsamd_hal::sercom::{Sercom5, Sercom1, uart, IoSet1}; use messages::sender::Sender; use messages::sender::Sender::CommunicationBoard; +use embedded_sdmmc as sd; // ------- // Sender ID @@ -17,3 +17,18 @@ pub static COM_ID: Sender = CommunicationBoard; // ------- pub type GroundStationPads = uart::PadsFromIds; pub type GroundStationUartConfig = uart::Config; + +// ------- +// SD Card +// ------- +pub type SdPads = spi::Pads< + Sercom1, + IoSet1, + Pin>, + Pin>, + Pin>, +>; +pub type SdController = sd::Controller< + sd::SdMmcSpi, spi::Duplex>, Pin>>, + TimeSink, +>; diff --git a/boards/recovery/src/communication.rs b/boards/recovery/src/communication.rs index 04c22ea9..bd708b84 100644 --- a/boards/recovery/src/communication.rs +++ b/boards/recovery/src/communication.rs @@ -160,8 +160,6 @@ impl CanDevice0 { for message in &mut self.can.rx_fifo_0 { match from_bytes::(message.data()) { Ok(data) => { - // info!("Received data: {:?}", data); - data_manager.handle_data(data); } Err(e) => { @@ -174,8 +172,6 @@ impl CanDevice0 { for message in &mut self.can.rx_fifo_1 { match from_bytes::(message.data()) { Ok(data) => { - // info!("Received data: {:?}", data) - data_manager.handle_data(data); } Err(e) => { diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index 3a9f2a15..a2611daa 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -41,13 +41,10 @@ impl DataManager { let ekf_nav1 = self.ekf_nav.0.as_ref(); if let Some(ekf_nav1) = ekf_nav1 { if ekf_nav1.velocity[2] > VELOCITY_MIN { - info!("fail"); return false; } } - info!("points {}", self.historical_pressure.len()); if self.historical_pressure.len() < 20 { - info!("fail"); return false; } match self.historical_pressure.last() { @@ -58,39 +55,20 @@ impl DataManager { avg += (i - prev)/0.25; prev = i; } - match avg / 20.0 { + // info!("avg {}", avg / 20.0); + match avg / 19.0 { // 19 because we have 19 slopes. x if x < 10.0 => { return false; } _ => { - info!("avg: {}", avg / 20.0); + info!("avg: {}", avg / 19.0); } } - // if (avg / 20.0 < ) { // 4 is the number of slopes. - // return false; - // } } None => { return false; } } - // match self.historical_pressure.recent() { - // Some(pressure) => { - // match self.historical_pressure.last() { - // Some(last) => { - // if (pressure - last) / 1.25 < 100.0 { - // return false; - // } - // } - // None => { - // return false; - // } - // } - // } - // None => { - // return false; - // } - // } true } pub fn is_launched(&self) -> bool { diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 901598f0..4ebf5258 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -15,7 +15,7 @@ use common_arm::mcan; use common_arm::*; use communication::Capacities; use data_manager::DataManager; -use hal::gpio::{Pin, Pins, PushPullOutput, PB16, PB17}; +use hal::gpio::{Pin, Pins, PushPullOutput, PB16, PB17, PB14}; use hal::prelude::*; use mcan::messageram::SharedMemory; use messages::*; @@ -112,7 +112,7 @@ mod app { can0, gpio, }, - Local { led_green, led_red, state_machine }, + Local { led_green, led_red, state_machine}, init::Monotonics(mono), ) } diff --git a/boards/recovery/src/types.rs b/boards/recovery/src/types.rs index 327ca09f..78202fc9 100644 --- a/boards/recovery/src/types.rs +++ b/boards/recovery/src/types.rs @@ -1,4 +1,4 @@ -use atsamd_hal::gpio::{PA18, PA19, PB14, PB15, PB17, Pin, PushPullOutput}; +use atsamd_hal::gpio::{PB14, PB15, Pin, PushPullOutput}; use atsamd_hal::prelude::*; use messages::sender::Sender; use messages::sender::Sender::RecoveryBoard; @@ -27,4 +27,10 @@ impl GPIOController { pub fn fire_main(&mut self) { self.main_ematch.set_high().ok(); } + pub fn close_drouge(&mut self) { + self.drogue_ematch.set_low().ok(); + } + pub fn close_main(&mut self) { + self.main_ematch.set_low().ok(); + } } \ No newline at end of file diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index c89faa85..cf984a01 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -25,7 +25,7 @@ use messages::sensor::Sensor; use messages::*; use panic_halt as _; use sbg_manager::{sbg_dma, sbg_handle_data, SBGManager}; -use sbg_rs::sbg::CallbackData; +use sbg_rs::sbg::{CallbackData, SBG_BUFFER_SIZE}; use sd_manager::SdManager; use systick_monotonic::*; use types::*; @@ -39,13 +39,13 @@ mod app { em: ErrorManager, data_manager: DataManager, can: communication::CanDevice0, + // sd_manager: SdManager, } #[local] struct Local { led_green: Pin, led_red: Pin, - // sd_manager: SdManager, sbg_manager: SBGManager, } @@ -135,11 +135,11 @@ mod app { em: ErrorManager::new(), data_manager: DataManager::new(), can, + // sd_manager, }, Local { led_green, led_red, - // sd_manager, sbg_manager, }, init::Monotonics(mono), @@ -214,6 +214,9 @@ mod app { } extern "Rust" { + // #[task(capacity = 3, shared = [sd_manager])] + // fn sbg_sd_dump(context: sbg_sd_dump::Context, data: [u8; SBG_BUFFER_SIZE]); + #[task(binds = DMAC_0, shared = [&em], local = [sbg_manager])] fn sbg_dma(context: sbg_dma::Context); diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index b99610d5..17c25749 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -13,12 +13,13 @@ use core::ffi::c_void; use core::mem::size_of; use core::ptr; -use crate::app::sbg_handle_data; +use crate::app::{sbg_handle_data}; use atsamd_hal::sercom::{uart, Sercom, Sercom5}; use embedded_alloc::Heap; use rtic::Mutex; use sbg_rs::sbg; use sbg_rs::sbg::{CallbackData, SBG, SBG_BUFFER_SIZE}; +use common_arm::spawn; pub static mut BUF_DST: SBGBuffer = &mut [0; SBG_BUFFER_SIZE]; pub static mut BUF_DST2: SBGBuffer = &mut [0; SBG_BUFFER_SIZE]; @@ -98,10 +99,17 @@ pub fn sbg_handle_data(mut cx: sbg_handle_data::Context, data: CallbackData) { }); } +// pub fn sbg_sd_dump(mut cx: sbg_sd_dump::Context, data: [u8; SBG_BUFFER_SIZE]) { +// cx.shared.sd_manager.lock(|manager| { +// if let Ok(mut file) = manager.open_file("sbg.bin") { +// manager.write(&mut file, &data); // I don't really care if this fails, could add some handling though but resources are limited +// manager.close_file(file); +// } +// }); +// } /** * Handles the DMA interrupt. * Handles the SBG data. - * Logs data to the SD card. */ pub fn sbg_dma(cx: crate::app::sbg_dma::Context) { let sbg = cx.local.sbg_manager; @@ -118,9 +126,9 @@ pub fn sbg_dma(cx: crate::app::sbg_dma::Context) { sbg.xfer.recycle_source(unsafe { &mut *BUF_DST2 })? } }; - + // let buf_clone = buf.clone(); sbg.sbg_device.read_data(buf); - + // spawn!(sbg_sd_dump(buf_clone))?; Ok(()) }); } diff --git a/boards/sensor/src/sd_manager.rs b/boards/sensor/src/sd_manager.rs index ad1793a1..91bb1c85 100644 --- a/boards/sensor/src/sd_manager.rs +++ b/boards/sensor/src/sd_manager.rs @@ -143,4 +143,4 @@ impl SdManager { } } -unsafe impl Send for SdManager {} +unsafe impl Send for SdManager {} \ No newline at end of file From d857b67afd9f9c54b3dc2558fc47411ad29ba24f Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sat, 12 Aug 2023 23:02:49 -0400 Subject: [PATCH 03/30] HMMMMM... --- boards/recovery/src/data_manager.rs | 60 ++++++++++++------- boards/recovery/src/main.rs | 8 +-- .../src/state_machine/states/landed.rs | 3 +- boards/recovery/src/types.rs | 8 +-- boards/sensor/src/main.rs | 28 ++++----- boards/sensor/src/sbg_manager.rs | 21 +++---- 6 files changed, 72 insertions(+), 56 deletions(-) diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index a2611daa..aa915b8c 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -2,11 +2,11 @@ use crate::state_machine::RocketStates; use heapless::HistoryBuffer; use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, UtcTime}; use messages::Message; -use defmt::info; +use defmt::{info, flush}; -const MAIN_HEIGHT: f32 = 450.0; +const MAIN_HEIGHT: f32 = 500.0; const VELOCITY_MIN: f32 = 20.0; -const HEIGHT_MIN: f32 = 300.0; +const HEIGHT_MIN: f32 = 900.0; pub struct DataManager { pub air: Option, @@ -15,13 +15,13 @@ pub struct DataManager { pub imu: (Option, Option), pub utc_time: Option, pub gps_vel: Option, - pub historical_pressure: HistoryBuffer, + pub historical_barometer_altitude: HistoryBuffer<(f32, u32), 8>, pub current_state: Option, } impl DataManager { pub fn new() -> Self { - let historical_pressure = HistoryBuffer::new(); + let historical_barometer_altitude = HistoryBuffer::new(); Self { air: None, ekf_nav: (None, None), @@ -29,7 +29,7 @@ impl DataManager { imu: (None, None), utc_time: None, gps_vel: None, - historical_pressure, + historical_barometer_altitude, current_state: None, } } @@ -38,30 +38,36 @@ impl DataManager { /// Furthermore, we only start checking pressure data when velocity is less than 20m/s /// because we want to avoid the complexities of pressure during transonic flight. pub fn is_falling(&self) -> bool { - let ekf_nav1 = self.ekf_nav.0.as_ref(); - if let Some(ekf_nav1) = ekf_nav1 { - if ekf_nav1.velocity[2] > VELOCITY_MIN { - return false; - } - } - if self.historical_pressure.len() < 20 { + // let ekf_nav1 = self.ekf_nav.0.as_ref(); + // if let Some(ekf_nav1) = ekf_nav1 { + // if ekf_nav1.velocity[2] > VELOCITY_MIN { + // return false; + // } + // } + if self.historical_barometer_altitude.len() < 8 { return false; } - match self.historical_pressure.last() { + let mut buf = self.historical_barometer_altitude.oldest_ordered(); + match buf.next() { Some(last) => { - let mut avg = 0.0; + let mut avg: f32 = 0.0; let mut prev = last; - for i in self.historical_pressure.oldest_ordered() { - avg += (i - prev)/0.25; + for i in buf { + let time_diff: f32 = (i.1 - prev.1) as f32 / 1000000.0; + if time_diff == 0.0 { + info!("diff {} {}", i, prev); + continue; + } + avg += (i.0 - prev.0)/time_diff; prev = i; } - // info!("avg {}", avg / 20.0); - match avg / 19.0 { // 19 because we have 19 slopes. - x if x < 10.0 => { + match avg / 7.0 { // 7 because we have 8 points. + x if x > -10.0 || x < -120.0 => { + info!("avg: {}", avg / 7.0); return false; } _ => { - info!("avg: {}", avg / 19.0); + info!("avg: {}", avg / 7.0); } } } @@ -93,9 +99,17 @@ impl DataManager { match data.data { messages::Data::Sensor(sensor) => match sensor.data { messages::sensor::SensorData::Air(air_data) => { - let pressure = air_data.pressure_abs; + let tup_data = (air_data.altitude, air_data.time_stamp); self.air = Some(air_data); - self.historical_pressure.write(pressure); + if let Some(recent) = self.historical_barometer_altitude.recent() { + if recent.1 != tup_data.1 { + self.historical_barometer_altitude.write(tup_data); + } else { + info!("duplicate data {}", tup_data.1); + } + } else { + self.historical_barometer_altitude.write(tup_data); + } } messages::sensor::SensorData::EkfNav1(nav1_data) => { self.ekf_nav.0 = Some(nav1_data); diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 4ebf5258..481d5d25 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -15,7 +15,7 @@ use common_arm::mcan; use common_arm::*; use communication::Capacities; use data_manager::DataManager; -use hal::gpio::{Pin, Pins, PushPullOutput, PB16, PB17, PB14}; +use hal::gpio::{Pin, Pins, PushPullOutput, PB16, PB17, PA09, PA06}; use hal::prelude::*; use mcan::messageram::SharedMemory; use messages::*; @@ -91,8 +91,8 @@ mod app { let led_green = pins.pb16.into_push_pull_output(); let led_red = pins.pb17.into_push_pull_output(); let gpio = GPIOController::new( - pins.pb14.into_push_pull_output(), - pins.pb15.into_push_pull_output(), + pins.pa09.into_push_pull_output(), + pins.pa06.into_push_pull_output(), ); /* State Machine config */ let state_machine = StateMachine::new(); @@ -112,7 +112,7 @@ mod app { can0, gpio, }, - Local { led_green, led_red, state_machine}, + Local {led_green, led_red, state_machine}, init::Monotonics(mono), ) } diff --git a/boards/recovery/src/state_machine/states/landed.rs b/boards/recovery/src/state_machine/states/landed.rs index d6e756ac..b259963b 100644 --- a/boards/recovery/src/state_machine/states/landed.rs +++ b/boards/recovery/src/state_machine/states/landed.rs @@ -1,4 +1,4 @@ -use defmt::{write, Format, Formatter}; +use defmt::{write, Format, Formatter, info}; use crate::no_transition; use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; @@ -10,6 +10,7 @@ pub struct Landed {} impl State for Landed { fn enter(&self,context: &mut StateMachineContext) { + info!("Landed"); context.shared_resources.gpio.lock(|gpio| gpio.fire_main()); } fn step(&mut self, _context: &mut StateMachineContext) -> Option { diff --git a/boards/recovery/src/types.rs b/boards/recovery/src/types.rs index 78202fc9..fe6c3163 100644 --- a/boards/recovery/src/types.rs +++ b/boards/recovery/src/types.rs @@ -1,4 +1,4 @@ -use atsamd_hal::gpio::{PB14, PB15, Pin, PushPullOutput}; +use atsamd_hal::gpio::{PB14, PB15, Pin, PushPullOutput, PA09, PA06}; use atsamd_hal::prelude::*; use messages::sender::Sender; use messages::sender::Sender::RecoveryBoard; @@ -10,12 +10,12 @@ pub static COM_ID: Sender = RecoveryBoard; pub struct GPIOController { - drogue_ematch: Pin, - main_ematch: Pin, + drogue_ematch: Pin, + main_ematch: Pin, } impl GPIOController { - pub fn new(drogue_ematch: Pin, main_ematch: Pin) -> Self { + pub fn new(drogue_ematch: Pin, main_ematch: Pin) -> Self { Self { drogue_ematch, main_ematch diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index cf984a01..84e6c06a 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -39,7 +39,7 @@ mod app { em: ErrorManager, data_manager: DataManager, can: communication::CanDevice0, - // sd_manager: SdManager, + sd_manager: SdManager, } #[local] @@ -95,16 +95,16 @@ mod app { ); /* SD config */ - // let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom1, gclk0); - // let sd_manager = SdManager::new( - // &mclk, - // peripherals.SERCOM1, - // pclk_sd.freq(), - // pins.pa18.into_push_pull_output(), - // pins.pa17.into_push_pull_output(), - // pins.pa19.into_push_pull_output(), - // pins.pa16.into_push_pull_output(), - // ); + let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom1, gclk0); + let sd_manager = SdManager::new( + &mclk, + peripherals.SERCOM1, + pclk_sd.freq(), + pins.pa18.into_push_pull_output(), + pins.pa17.into_push_pull_output(), + pins.pa19.into_push_pull_output(), + pins.pa16.into_push_pull_output(), + ); /* SBG config */ let (pclk_sbg, gclk0) = Pclk::enable(tokens.pclks.sercom5, gclk0); @@ -135,7 +135,7 @@ mod app { em: ErrorManager::new(), data_manager: DataManager::new(), can, - // sd_manager, + sd_manager, }, Local { led_green, @@ -214,8 +214,8 @@ mod app { } extern "Rust" { - // #[task(capacity = 3, shared = [sd_manager])] - // fn sbg_sd_dump(context: sbg_sd_dump::Context, data: [u8; SBG_BUFFER_SIZE]); + #[task(capacity = 3, shared = [&em, sd_manager])] + fn sbg_sd_task(context: sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]); #[task(binds = DMAC_0, shared = [&em], local = [sbg_manager])] fn sbg_dma(context: sbg_dma::Context); diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index 17c25749..e5411fa4 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -13,6 +13,7 @@ use core::ffi::c_void; use core::mem::size_of; use core::ptr; +use crate::app::sbg_sd_task as sbg_sd; use crate::app::{sbg_handle_data}; use atsamd_hal::sercom::{uart, Sercom, Sercom5}; use embedded_alloc::Heap; @@ -99,14 +100,14 @@ pub fn sbg_handle_data(mut cx: sbg_handle_data::Context, data: CallbackData) { }); } -// pub fn sbg_sd_dump(mut cx: sbg_sd_dump::Context, data: [u8; SBG_BUFFER_SIZE]) { -// cx.shared.sd_manager.lock(|manager| { -// if let Ok(mut file) = manager.open_file("sbg.bin") { -// manager.write(&mut file, &data); // I don't really care if this fails, could add some handling though but resources are limited -// manager.close_file(file); -// } -// }); -// } +pub fn sbg_sd_task(mut cx: crate::app::sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]) { + cx.shared.sd_manager.lock(|manager| { + if let Ok(mut file) = manager.open_file("sbg.bin") { + manager.write(&mut file, &data); + manager.close_file(file); + } + }); +} /** * Handles the DMA interrupt. * Handles the SBG data. @@ -126,9 +127,9 @@ pub fn sbg_dma(cx: crate::app::sbg_dma::Context) { sbg.xfer.recycle_source(unsafe { &mut *BUF_DST2 })? } }; - // let buf_clone = buf.clone(); + let buf_clone = buf.clone(); sbg.sbg_device.read_data(buf); - // spawn!(sbg_sd_dump(buf_clone))?; + spawn!(sbg_sd(buf_clone))?; Ok(()) }); } From 3a8fefec58b5ec03d2355ede5ca0c192424718c0 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sat, 12 Aug 2023 23:09:42 -0400 Subject: [PATCH 04/30] :) --- boards/sensor/src/main.rs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index 84e6c06a..9c9be422 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -24,7 +24,7 @@ use mcan::messageram::SharedMemory; use messages::sensor::Sensor; use messages::*; use panic_halt as _; -use sbg_manager::{sbg_dma, sbg_handle_data, SBGManager}; +use sbg_manager::{sbg_dma, sbg_handle_data, sbg_sd_task, SBGManager}; use sbg_rs::sbg::{CallbackData, SBG_BUFFER_SIZE}; use sd_manager::SdManager; use systick_monotonic::*; From a57213666eea2b438e7be93276b31d02a2f1e820 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sun, 13 Aug 2023 13:32:51 -0400 Subject: [PATCH 05/30] Add Sd to Communication Board --- Cargo.lock | 355 ++++++++-------------- boards/communication/src/communication.rs | 4 +- boards/communication/src/main.rs | 38 ++- boards/communication/src/sd_manager.rs | 16 +- boards/communication/src/types.rs | 12 +- boards/sensor/Cargo.toml | 2 +- boards/sensor/src/main.rs | 20 +- boards/sensor/src/sbg_manager.rs | 11 +- boards/sensor/src/sd_manager.rs | 16 +- boards/sensor/src/types.rs | 15 +- 10 files changed, 217 insertions(+), 272 deletions(-) diff --git a/Cargo.lock b/Cargo.lock index 5d4366f9..3999cfae 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -31,16 +31,17 @@ dependencies = [ [[package]] name = "atsamd-hal" -version = "0.15.1" -source = "git+https://github.com/atsamd-rs/atsamd#52073e88d2940101a161340decfcde527e41d279" +version = "0.16.0" +source = "git+https://github.com/atsamd-rs/atsamd#0820f0df58eb8705ddfa6533ed76953d18e6b992" dependencies = [ "aes", "atsame51j", "bitfield 0.13.2", - "bitflags", + "bitflags 1.3.2", "cipher", "cortex-m", "embedded-hal", + "fugit", "mcan-core", "modular-bitfield", "nb 1.1.0", @@ -57,7 +58,7 @@ dependencies = [ [[package]] name = "atsame51j" version = "0.12.0" -source = "git+https://github.com/atsamd-rs/atsamd#52073e88d2940101a161340decfcde527e41d279" +source = "git+https://github.com/atsamd-rs/atsamd#0820f0df58eb8705ddfa6533ed76953d18e6b992" dependencies = [ "cortex-m", "cortex-m-rt", @@ -118,6 +119,12 @@ version = "1.3.2" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "bef38d45163c2f1dde094a7dfd33ccf595c92905c8f8f4fdc18d06fb1037718a" +[[package]] +name = "bitflags" +version = "2.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b4682ae6287fcf752ecaabbfcc7b6f9b72aa33933dc23a554d853aea8eea8635" + [[package]] name = "byteorder" version = "1.4.3" @@ -126,9 +133,12 @@ checksum = "14c189c53d098945499cdfa7ecc63567cf3886b3332b312a5b4585d8d3a6a610" [[package]] name = "cc" -version = "1.0.79" +version = "1.0.82" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "50d30906286121d95be3d479533b458f87493b30a4b5f79a607db8f5d11aa91f" +checksum = "305fe645edc1442a0fa8b6726ba61d422798d37a52e12eaecf4b022ebbb88f01" +dependencies = [ + "libc", +] [[package]] name = "cfg-if" @@ -246,8 +256,8 @@ version = "0.7.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "f0f6f3e36f203cfedbc78b357fb28730aa2c6dc1ab060ee5c2405e843988d3c7" dependencies = [ - "proc-macro2 1.0.59", - "quote 1.0.28", + "proc-macro2 1.0.66", + "quote 1.0.32", "syn 1.0.109", ] @@ -273,17 +283,17 @@ source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "eefb40b1ca901c759d29526e5c8a0a1b246c20caaa5b4cc5d0f0b94debecd4c7" dependencies = [ "proc-macro-error", - "proc-macro2 1.0.59", - "quote 1.0.28", + "proc-macro2 1.0.66", + "quote 1.0.32", "rtic-syntax", "syn 1.0.109", ] [[package]] name = "cpufeatures" -version = "0.2.7" +version = "0.2.9" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "3e4c1eaa2012c47becbbad2ab175484c2a84d1185b566fb2cc5b8707343dfe58" +checksum = "a17b76ff3a4162b0b27f354a0c87015ddad39d35f9c0c36607a3bdd175dde1f1" dependencies = [ "libc", ] @@ -296,31 +306,31 @@ checksum = "774646b687f63643eb0f4bf13dc263cb581c8c9e57973b6ddf78bda3994d88df" [[package]] name = "critical-section" -version = "1.1.1" +version = "1.1.2" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6548a0ad5d2549e111e1f6a11a6c2e2d00ce6a3dafe22948d67c2b443f775e52" +checksum = "7059fff8937831a9ae6f0fe4d658ffabf58f2ca96aa9dec1c889f936f705f216" [[package]] name = "defmt" -version = "0.3.4" +version = "0.3.5" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "956673bd3cb347512bf988d1e8d89ac9a82b64f6eec54d3c01c3529dac019882" +checksum = "a8a2d011b2fee29fb7d659b83c43fce9a2cb4df453e16d441a51448e448f3f98" dependencies = [ - "bitflags", + "bitflags 1.3.2", "defmt-macros", ] [[package]] name = "defmt-macros" -version = "0.3.5" +version = "0.3.6" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b4abc4821bd84d3d8f49945ddb24d029be9385ed9b77c99bf2f6296847a6a9f0" +checksum = "54f0216f6c5acb5ae1a47050a6645024e6edafc2ee32d421955eccfef12ef92e" dependencies = [ "defmt-parser", "proc-macro-error", - "proc-macro2 1.0.59", - "quote 1.0.28", - "syn 1.0.109", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 2.0.28", ] [[package]] @@ -360,8 +370,8 @@ version = "0.3.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "94a0dfea4063d72e1ba20494dfbc4667f67420869328cf3670b5824a38a22dc1" dependencies = [ - "proc-macro2 1.0.59", - "quote 1.0.28", + "proc-macro2 1.0.66", + "quote 1.0.32", "syn 1.0.109", ] @@ -372,8 +382,8 @@ source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "4fb810d30a7c1953f91334de7244731fc3f3c10d7fe163338a35b9f640960321" dependencies = [ "convert_case", - "proc-macro2 1.0.59", - "quote 1.0.28", + "proc-macro2 1.0.66", + "quote 1.0.32", "rustc_version 0.4.0", "syn 1.0.109", ] @@ -421,25 +431,25 @@ dependencies = [ [[package]] name = "enum_dispatch" -version = "0.3.11" +version = "0.3.12" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "11f36e95862220b211a6e2aa5eca09b4fa391b13cd52ceb8035a24bf65a79de2" +checksum = "8f33313078bb8d4d05a2733a94ac4c2d8a0df9a2b84424ebf4f33bfc224a890e" dependencies = [ "once_cell", - "proc-macro2 1.0.59", - "quote 1.0.28", - "syn 1.0.109", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 2.0.28", ] [[package]] name = "errno" -version = "0.3.1" +version = "0.3.2" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4bcfec3a70f97c962c307b2d2c56e358cf1d00b558d74262b5f929ee8cc7e73a" +checksum = "6b30f669a7961ef1631673d2766cc92f52d64f7ef354d4fe0ddfd30ed52f0f4f" dependencies = [ "errno-dragonfly", "libc", - "windows-sys 0.48.0", + "windows-sys", ] [[package]] @@ -454,12 +464,9 @@ dependencies = [ [[package]] name = "fastrand" -version = "1.9.0" +version = "2.0.0" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e51093e27b0797c359783294ca4f0a911c270184cb10f85783b118614a1501be" -dependencies = [ - "instant", -] +checksum = "6999dc1837253364c2ebb0704ba97994bd874e8f195d665c50b7548f6ea92764" [[package]] name = "fnv" @@ -469,9 +476,9 @@ checksum = "3f9eec918d3f24069decb9af1554cad7c880e2da24a9afd88aca000531ab82c1" [[package]] name = "fugit" -version = "0.3.6" +version = "0.3.7" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "7ab17bb279def6720d058cb6c052249938e7f99260ab534879281a95367a87e5" +checksum = "17186ad64927d5ac8f02c1e77ccefa08ccd9eaa314d5a4772278aa204a22f7e7" dependencies = [ "gcd", ] @@ -494,9 +501,9 @@ dependencies = [ [[package]] name = "getrandom" -version = "0.2.9" +version = "0.2.10" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "c85e1d9ab2eadba7e5040d4e09cbd6d072b76a557ad64e797c2cb9d4da21d7e4" +checksum = "be4136b2a15dd319360be1c07d9933517ccf0be8f16bf62a3bee4f0d618df427" dependencies = [ "cfg-if", "libc", @@ -532,12 +539,6 @@ dependencies = [ "stable_deref_trait", ] -[[package]] -name = "hermit-abi" -version = "0.3.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "fed44880c466736ef9a5c5b5facefb5ed0785676d0c02d612db14e54f0d84286" - [[package]] name = "indexmap" version = "1.9.3" @@ -548,26 +549,6 @@ dependencies = [ "hashbrown", ] -[[package]] -name = "instant" -version = "0.1.12" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "7a5bbe824c507c5da5956355e86a746d82e0e1464f65d862cc5e71da70e94b2c" -dependencies = [ - "cfg-if", -] - -[[package]] -name = "io-lifetimes" -version = "1.0.11" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "eae7b9aee968036d54dce06cebaefd919e4472e753296daccd6d344e3e2df0c2" -dependencies = [ - "hermit-abi", - "libc", - "windows-sys 0.48.0", -] - [[package]] name = "ioctl-rs" version = "0.1.6" @@ -585,9 +566,9 @@ checksum = "e2abad23fbc42b3700f2f279844dc832adb2b2eb069b2df918f455c4e18cc646" [[package]] name = "libc" -version = "0.2.144" +version = "0.2.147" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "2b00cc1c228a6782d0f076e7b232802e0c5689d41bb5df366f2a6b6621cfdfe1" +checksum = "b4668fb0ea861c1df094127ac5f1da3409a82116a4ba74fca2e58ef927159bb3" [[package]] name = "libm" @@ -603,15 +584,15 @@ checksum = "9afa463f5405ee81cdb9cc2baf37e08ec7e4c8209442b5d72c04cfb2cd6e6286" [[package]] name = "linux-raw-sys" -version = "0.3.8" +version = "0.4.5" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "ef53942eb7bf7ff43a617b3e2c1c4a5ecf5944a7c1bc12d7ee39bbb15e5c1519" +checksum = "57bcfdad1b858c2db7c38303a6d2ad4dfaf5eb53dfeb0910128b2c26d6158503" [[package]] name = "lock_api" -version = "0.4.9" +version = "0.4.10" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "435011366fe56583b16cf956f9df0095b405b82d76425bc8981c0e22e60ec4df" +checksum = "c1cc9717a20b1bb222f333e6a92fd32f7d8a18ddc5a3191a11af45dcbf4dcd16" dependencies = [ "autocfg", "scopeguard", @@ -619,19 +600,16 @@ dependencies = [ [[package]] name = "log" -version = "0.4.17" +version = "0.4.20" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "abb12e687cfb44aa40f41fc3978ef76448f9b6038cad6aef4259d3c095a2382e" -dependencies = [ - "cfg-if", -] +checksum = "b5e6163cb8c49088c2c36f57875e58ccd8c87c7427f7fbd50ea6710b2f3f2e8f" [[package]] name = "mavlink" version = "0.11.1" -source = "git+https://github.com/uorocketry/rust-mavlink?branch=hydra_dialect#26623dfbc6b32b2f48f03c1206b815fce0d1f1d3" +source = "git+https://github.com/uorocketry/rust-mavlink?branch=hydra_dialect#0e0bedd0f37ccad490ea693ad80c2ecffb3d6351" dependencies = [ - "bitflags", + "bitflags 1.3.2", "byteorder", "crc-any", "embedded-hal", @@ -640,9 +618,9 @@ dependencies = [ "nb 1.1.0", "num-derive", "num-traits", - "proc-macro2 1.0.59", + "proc-macro2 1.0.66", "quick-xml", - "quote 1.0.28", + "quote 1.0.32", "serde", "serial", ] @@ -709,8 +687,8 @@ version = "0.11.2" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "5a7d5f7076603ebc68de2dc6a650ec331a062a13abaa346975be747bbfa4b789" dependencies = [ - "proc-macro2 1.0.59", - "quote 1.0.28", + "proc-macro2 1.0.66", + "quote 1.0.32", "syn 1.0.109", ] @@ -735,16 +713,16 @@ version = "0.3.3" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "876a53fff98e03a936a674b29568b0e605f06b29372c2489ff4de23f1949743d" dependencies = [ - "proc-macro2 1.0.59", - "quote 1.0.28", + "proc-macro2 1.0.66", + "quote 1.0.32", "syn 1.0.109", ] [[package]] name = "num-traits" -version = "0.2.15" +version = "0.2.16" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "578ede34cf02f8924ab9447f50c28075b4d3e5b269972345e7e0372b38c6cdcd" +checksum = "f30b0abd723be7e2ffca1272140fac1a2f084c77ec3e123c192b66af1ee9e6c2" dependencies = [ "autocfg", "libm", @@ -780,15 +758,15 @@ dependencies = [ [[package]] name = "paste" -version = "1.0.12" +version = "1.0.14" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9f746c4065a8fa3fe23974dd82f15431cc8d40779821001404d10d2e79ca7d79" +checksum = "de3145af08024dea9fa9914f381a17b8fc6034dfb00f3a84013f7ff43f29ed4c" [[package]] name = "postcard" -version = "1.0.4" +version = "1.0.6" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "cfa512cd0d087cc9f99ad30a1bf64795b67871edbead083ffc3a4dfafa59aa00" +checksum = "c9ee729232311d3cd113749948b689627618133b1c5012b77342c1950b25eaeb" dependencies = [ "cobs", "defmt", @@ -809,8 +787,8 @@ source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "da25490ff9892aab3fcf7c36f08cfb902dd3e71ca0f9f9517bea02a73a5ce38c" dependencies = [ "proc-macro-error-attr", - "proc-macro2 1.0.59", - "quote 1.0.28", + "proc-macro2 1.0.66", + "quote 1.0.32", "syn 1.0.109", "version_check", ] @@ -821,8 +799,8 @@ version = "1.0.4" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "a1be40180e52ecc98ad80b184934baf3d0d29f979574e439af5a55274b35f869" dependencies = [ - "proc-macro2 1.0.59", - "quote 1.0.28", + "proc-macro2 1.0.66", + "quote 1.0.32", "version_check", ] @@ -837,9 +815,9 @@ dependencies = [ [[package]] name = "proc-macro2" -version = "1.0.59" +version = "1.0.66" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6aeca18b86b413c660b781aa319e4e2648a3e6f9eadc9b47e9038e6fe9f3451b" +checksum = "18fb31db3f9bddb2ea821cde30a9f70117e3f119938b5ee630b7403aa6e2ead9" dependencies = [ "unicode-ident", ] @@ -851,7 +829,7 @@ source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "4e35c06b98bf36aba164cc17cb25f7e232f5c4aeea73baa14b8a9f0d92dbfa65" dependencies = [ "bit-set", - "bitflags", + "bitflags 1.3.2", "byteorder", "lazy_static", "num-traits", @@ -901,11 +879,11 @@ dependencies = [ [[package]] name = "quote" -version = "1.0.28" +version = "1.0.32" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "1b9ab9c7eadfd8df19006f1cf1a4aed13540ed5cbc047010ece5826e10825488" +checksum = "50f3b39ccfb720540debaa0164757101c08ecb8d326b15358ce76a62c7e85965" dependencies = [ - "proc-macro2 1.0.59", + "proc-macro2 1.0.66", ] [[package]] @@ -972,7 +950,7 @@ version = "0.3.5" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "567664f262709473930a4bf9e51bf2ebf3348f2e748ccc50dea20646858f8f29" dependencies = [ - "bitflags", + "bitflags 1.3.2", ] [[package]] @@ -1000,8 +978,8 @@ source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "5f5e215601dc467752c2bddc6284a622c6f3d2bab569d992adcd5ab7e4cb9478" dependencies = [ "indexmap", - "proc-macro2 1.0.59", - "quote 1.0.28", + "proc-macro2 1.0.66", + "quote 1.0.32", "syn 1.0.109", ] @@ -1040,21 +1018,20 @@ version = "0.4.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "bfa0f585226d2e68097d4f95d113b15b83a82e819ab25717ec0590d9584ef366" dependencies = [ - "semver 1.0.17", + "semver 1.0.18", ] [[package]] name = "rustix" -version = "0.37.19" +version = "0.38.8" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "acf8729d8542766f1b2cf77eb034d52f40d375bb8b615d0b147089946e16613d" +checksum = "19ed4fa021d81c8392ce04db050a3da9a60299050b7ae1cf482d862b54a7218f" dependencies = [ - "bitflags", + "bitflags 2.4.0", "errno", - "io-lifetimes", "libc", "linux-raw-sys", - "windows-sys 0.48.0", + "windows-sys", ] [[package]] @@ -1086,9 +1063,9 @@ dependencies = [ [[package]] name = "scopeguard" -version = "1.1.0" +version = "1.2.0" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d29ab0c6d3fc0ee92fe66e2d99f700eab17a8d57d1c1d3b748380fb20baa78cd" +checksum = "94143f37725109f92c262ed2cf5e59bce7498c01bcc1502d7b9afe439a4e9f49" [[package]] name = "semver" @@ -1101,9 +1078,9 @@ dependencies = [ [[package]] name = "semver" -version = "1.0.17" +version = "1.0.18" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "bebd363326d05ec3e2f532ab7660680f3b02130d780c299bca73469d521bc0ed" +checksum = "b0293b4b29daaf487284529cc2f5675b8e57c61f70167ba415a463651fd6a918" [[package]] name = "semver-parser" @@ -1134,28 +1111,28 @@ dependencies = [ [[package]] name = "seq-macro" -version = "0.3.3" +version = "0.3.5" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e6b44e8fc93a14e66336d230954dda83d18b4605ccace8fe09bc7514a71ad0bc" +checksum = "a3f0bf26fd526d2a95683cd0f87bf103b8539e2ca1ef48ce002d67aad59aa0b4" [[package]] name = "serde" -version = "1.0.163" +version = "1.0.183" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "2113ab51b87a539ae008b5c6c02dc020ffa39afd2d83cffcb3f4eb2722cebec2" +checksum = "32ac8da02677876d532745a130fc9d8e6edfa81a269b107c5b00829b91d8eb3c" dependencies = [ "serde_derive", ] [[package]] name = "serde_derive" -version = "1.0.163" +version = "1.0.183" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8c805777e3930c8883389c602315a24224bcc738b63905ef87cd1420353ea93e" +checksum = "aafe972d60b0b9bee71a91b92fee2d4fb3c9d7e8f6b179aa99f27203d99a4816" dependencies = [ - "proc-macro2 1.0.59", - "quote 1.0.28", - "syn 2.0.18", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 2.0.28", ] [[package]] @@ -1251,19 +1228,19 @@ version = "1.0.109" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "72b64191b275b66ffe2469e8af2c1cfe3bafa67b529ead792a6d0160888b4237" dependencies = [ - "proc-macro2 1.0.59", - "quote 1.0.28", + "proc-macro2 1.0.66", + "quote 1.0.32", "unicode-ident", ] [[package]] name = "syn" -version = "2.0.18" +version = "2.0.28" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "32d41677bcbe24c20c52e7c70b0d8db04134c5d1066bf98662e2871ad200ea3e" +checksum = "04361975b3f5e348b2189d8dc55bc942f278b2d482a6a0365de5bdd62d351567" dependencies = [ - "proc-macro2 1.0.59", - "quote 1.0.28", + "proc-macro2 1.0.66", + "quote 1.0.32", "unicode-ident", ] @@ -1280,15 +1257,15 @@ dependencies = [ [[package]] name = "tempfile" -version = "3.5.0" +version = "3.7.1" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b9fbec84f381d5795b08656e4912bec604d162bff9291d6189a78f4c8ab87998" +checksum = "dc02fddf48964c42031a0b3fe0428320ecf3a73c401040fc0096f97794310651" dependencies = [ "cfg-if", "fastrand", "redox_syscall", "rustix", - "windows-sys 0.45.0", + "windows-sys", ] [[package]] @@ -1311,22 +1288,22 @@ dependencies = [ [[package]] name = "thiserror" -version = "1.0.40" +version = "1.0.44" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "978c9a314bd8dc99be594bc3c175faaa9794be04a5a5e153caba6915336cebac" +checksum = "611040a08a0439f8248d1990b111c95baa9c704c805fa1f62104b39655fd7f90" dependencies = [ "thiserror-impl", ] [[package]] name = "thiserror-impl" -version = "1.0.40" +version = "1.0.44" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f9456a42c5b0d803c8cd86e73dd7cc9edd429499f37a3550d286d5e86720569f" +checksum = "090198534930841fab3a5d1bb637cde49e339654e606195f8d9c76eeb081dc96" dependencies = [ - "proc-macro2 1.0.59", - "quote 1.0.28", - "syn 2.0.18", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 2.0.28", ] [[package]] @@ -1346,8 +1323,8 @@ source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "9f807fdb3151fee75df7485b901a89624358cd07a67a8fb1a5831bf5a07681ff" dependencies = [ "Inflector", - "proc-macro2 1.0.59", - "quote 1.0.28", + "proc-macro2 1.0.66", + "quote 1.0.32", "syn 1.0.109", "termcolor", ] @@ -1366,9 +1343,9 @@ checksum = "eaea85b334db583fe3274d12b4cd1880032beab409c0d774be044d4480ab9a94" [[package]] name = "unicode-ident" -version = "1.0.9" +version = "1.0.11" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b15811caf2415fb889178633e7724bad2509101cde276048e013b9def5e51fa0" +checksum = "301abaae475aa91687eb82514b328ab47a211a533026cb25fc3e519b86adfc3c" [[package]] name = "unicode-xid" @@ -1449,132 +1426,66 @@ version = "0.4.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "712e227841d057c1ee1cd2fb22fa7e5a5461ae8e48fa2ca79ec42cfc1931183f" -[[package]] -name = "windows-sys" -version = "0.45.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "75283be5efb2831d37ea142365f009c02ec203cd29a3ebecbc093d52315b66d0" -dependencies = [ - "windows-targets 0.42.2", -] - [[package]] name = "windows-sys" version = "0.48.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "677d2418bec65e3338edb076e806bc1ec15693c5d0104683f2efe857f61056a9" dependencies = [ - "windows-targets 0.48.0", -] - -[[package]] -name = "windows-targets" -version = "0.42.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8e5180c00cd44c9b1c88adb3693291f1cd93605ded80c250a75d472756b4d071" -dependencies = [ - "windows_aarch64_gnullvm 0.42.2", - "windows_aarch64_msvc 0.42.2", - "windows_i686_gnu 0.42.2", - "windows_i686_msvc 0.42.2", - "windows_x86_64_gnu 0.42.2", - "windows_x86_64_gnullvm 0.42.2", - "windows_x86_64_msvc 0.42.2", + "windows-targets", ] [[package]] name = "windows-targets" -version = "0.48.0" +version = "0.48.1" source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "7b1eb6f0cd7c80c79759c929114ef071b87354ce476d9d94271031c0497adfd5" +checksum = "05d4b17490f70499f20b9e791dcf6a299785ce8af4d709018206dc5b4953e95f" dependencies = [ - "windows_aarch64_gnullvm 0.48.0", - "windows_aarch64_msvc 0.48.0", - "windows_i686_gnu 0.48.0", - "windows_i686_msvc 0.48.0", - "windows_x86_64_gnu 0.48.0", - "windows_x86_64_gnullvm 0.48.0", - "windows_x86_64_msvc 0.48.0", + "windows_aarch64_gnullvm", + "windows_aarch64_msvc", + "windows_i686_gnu", + "windows_i686_msvc", + "windows_x86_64_gnu", + "windows_x86_64_gnullvm", + "windows_x86_64_msvc", ] -[[package]] -name = "windows_aarch64_gnullvm" -version = "0.42.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "597a5118570b68bc08d8d59125332c54f1ba9d9adeedeef5b99b02ba2b0698f8" - [[package]] name = "windows_aarch64_gnullvm" version = "0.48.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "91ae572e1b79dba883e0d315474df7305d12f569b400fcf90581b06062f7e1bc" -[[package]] -name = "windows_aarch64_msvc" -version = "0.42.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e08e8864a60f06ef0d0ff4ba04124db8b0fb3be5776a5cd47641e942e58c4d43" - [[package]] name = "windows_aarch64_msvc" version = "0.48.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "b2ef27e0d7bdfcfc7b868b317c1d32c641a6fe4629c171b8928c7b08d98d7cf3" -[[package]] -name = "windows_i686_gnu" -version = "0.42.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "c61d927d8da41da96a81f029489353e68739737d3beca43145c8afec9a31a84f" - [[package]] name = "windows_i686_gnu" version = "0.48.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "622a1962a7db830d6fd0a69683c80a18fda201879f0f447f065a3b7467daa241" -[[package]] -name = "windows_i686_msvc" -version = "0.42.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "44d840b6ec649f480a41c8d80f9c65108b92d89345dd94027bfe06ac444d1060" - [[package]] name = "windows_i686_msvc" version = "0.48.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "4542c6e364ce21bf45d69fdd2a8e455fa38d316158cfd43b3ac1c5b1b19f8e00" -[[package]] -name = "windows_x86_64_gnu" -version = "0.42.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8de912b8b8feb55c064867cf047dda097f92d51efad5b491dfb98f6bbb70cb36" - [[package]] name = "windows_x86_64_gnu" version = "0.48.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "ca2b8a661f7628cbd23440e50b05d705db3686f894fc9580820623656af974b1" -[[package]] -name = "windows_x86_64_gnullvm" -version = "0.42.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "26d41b46a36d453748aedef1486d5c7a85db22e56aff34643984ea85514e94a3" - [[package]] name = "windows_x86_64_gnullvm" version = "0.48.0" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "7896dbc1f41e08872e9d5e8f8baa8fdd2677f29468c4e156210174edc7f7b953" -[[package]] -name = "windows_x86_64_msvc" -version = "0.42.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9aec5da331524158c6d1a4ac0ab1541149c0b9505fde06423b02f5ef0106b9f0" - [[package]] name = "windows_x86_64_msvc" version = "0.48.0" diff --git a/boards/communication/src/communication.rs b/boards/communication/src/communication.rs index 7e886b81..01643fae 100644 --- a/boards/communication/src/communication.rs +++ b/boards/communication/src/communication.rs @@ -15,7 +15,7 @@ use atsamd_hal::pac::SERCOM5; use atsamd_hal::sercom; use atsamd_hal::sercom::uart; use atsamd_hal::sercom::uart::{Duplex, Uart}; -use atsamd_hal::time::U32Ext; +use atsamd_hal::time::*; use atsamd_hal::typelevel::Increment; use common_arm::mcan; use common_arm::mcan::message::{rx, Raw}; @@ -232,7 +232,7 @@ impl RadioDevice { .tx(tx_pin); let uart = GroundStationUartConfig::new(mclk, sercom, pads, pclk_radio.freq()) .baud( - 57600.hz(), + 57600.Hz(), uart::BaudMode::Fractional(uart::Oversampling::Bits16), ) .enable(); diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index c0b35073..242a0493 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -15,6 +15,7 @@ use common_arm::*; use communication::Capacities; use communication::RadioDevice; use data_manager::DataManager; +use sd_manager::SdManager; use hal::gpio::Pins; use hal::gpio::PA14; @@ -43,6 +44,7 @@ mod app { struct Local { led: Pin, radio: RadioDevice, + sd_manager: SdManager, } #[monotonic(binds = SysTick, default = true)] @@ -100,6 +102,18 @@ mod app { gclk0, ); + /* SD config */ + let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); + let sd_manager = SdManager::new( + &mclk, + peripherals.SERCOM4, + pclk_sd.freq(), + pins.pb14.into_push_pull_output(), + pins.pb13.into_push_pull_output(), + pins.pb15.into_push_pull_output(), + pins.pb12.into_push_pull_output(), + ); + /* Status LED */ let led = pins.pa14.into_push_pull_output(); @@ -108,7 +122,7 @@ mod app { blink::spawn().ok(); /* Monotonic clock */ - let mono = Systick::new(core.SYST, gclk0.freq().0); + let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); ( Shared { @@ -116,7 +130,7 @@ mod app { data_manager: DataManager::new(), can0, }, - Local { led, radio }, + Local { led, radio, sd_manager }, init::Monotonics(mono), ) } @@ -164,6 +178,19 @@ mod app { }); } + #[task(capacity = 3, local = [sd_manager], shared = [&em])] + fn sd_dump(mut cx: sd_dump::Context) { + let mut manager = cx.local.sd_manager; + cx.shared.em.run(|| { + if let Ok(mut file) = manager.open_file("test.txt") { + manager.write(&mut file, "Hello, world!\n".as_bytes()); + manager.close_file(file); + info!("test written to SD card"); + } + Ok(()) + }); + } + /** * Sends information about the sensors. */ @@ -185,7 +212,7 @@ mod app { } Ok(()) }); - spawn_after!(sensor_send, 250.millis()).ok(); + spawn_after!(sensor_send, ExtU64::millis(250)).ok(); } /** @@ -196,10 +223,11 @@ mod app { fn blink(cx: blink::Context) { cx.shared.em.run(|| { cx.local.led.toggle()?; + spawn!(sd_dump)?; if cx.shared.em.has_error() { - spawn_after!(blink, 200.millis())?; + spawn_after!(blink, ExtU64::millis(200))?; } else { - spawn_after!(blink, 1.secs())?; + spawn_after!(blink, ExtU64::secs(1))?; } Ok(()) }); diff --git a/boards/communication/src/sd_manager.rs b/boards/communication/src/sd_manager.rs index 6d8c22a5..682650ba 100644 --- a/boards/communication/src/sd_manager.rs +++ b/boards/communication/src/sd_manager.rs @@ -1,8 +1,8 @@ use crate::types::SdController; use core::marker::PhantomData; -use atsamd_hal::gpio::{Output, Pin, PushPull, PA16, PA17, PA18, PA19}; +use atsamd_hal::gpio::{Output, Pin, PushPull, PA16, PA17, PA18, PA19, PB14, PB13, PB15, PB12}; use atsamd_hal::pac; -use atsamd_hal::sercom::{spi, IoSet1, Sercom1}; +use atsamd_hal::sercom::{spi, IoSet1, Sercom1, Sercom4}; use atsamd_hal::time::Hertz; use defmt::{info, warn}; use embedded_sdmmc as sd; @@ -45,14 +45,14 @@ pub struct SdManager { impl SdManager { pub fn new( mclk: &pac::MCLK, - sercom: pac::SERCOM1, + sercom: pac::SERCOM4, freq: Hertz, - cs: Pin>, - sck: Pin>, - miso: Pin>, - mosi: Pin>, + cs: Pin>, + sck: Pin>, + miso: Pin>, + mosi: Pin>, ) -> Self { - let pads_spi = spi::Pads::::default() + let pads_spi = spi::Pads::::default() .sclk(sck) .data_in(miso) .data_out(mosi); diff --git a/boards/communication/src/types.rs b/boards/communication/src/types.rs index 380a7370..adcc39c7 100644 --- a/boards/communication/src/types.rs +++ b/boards/communication/src/types.rs @@ -1,7 +1,7 @@ use crate::sd_manager::TimeSink; use atsamd_hal::gpio::*; use atsamd_hal::sercom::uart::EightBit; -use atsamd_hal::sercom::spi; +use atsamd_hal::sercom::{spi, Sercom4}; use atsamd_hal::sercom::{Sercom5, Sercom1, uart, IoSet1}; use messages::sender::Sender; use messages::sender::Sender::CommunicationBoard; @@ -22,13 +22,13 @@ pub type GroundStationUartConfig = uart::Config; // SD Card // ------- pub type SdPads = spi::Pads< - Sercom1, + Sercom4, IoSet1, - Pin>, - Pin>, - Pin>, + Pin>, + Pin>, + Pin>, >; pub type SdController = sd::Controller< - sd::SdMmcSpi, spi::Duplex>, Pin>>, + sd::SdMmcSpi, spi::Duplex>, Pin>>, TimeSink, >; diff --git a/boards/sensor/Cargo.toml b/boards/sensor/Cargo.toml index 1948612b..4ecf0024 100644 --- a/boards/sensor/Cargo.toml +++ b/boards/sensor/Cargo.toml @@ -18,6 +18,6 @@ common-arm = { path = "../../libraries/common-arm" } atsamd-hal = { workspace = true } messages = { path = "../../libraries/messages" } sbg-rs = {path = "../../libraries/sbg-rs"} -embedded-sdmmc = "0.3.0" +embedded-sdmmc = "0.3.0" # port to v5 typenum = "1.16.0" embedded-alloc = "0.5.0" \ No newline at end of file diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index 9c9be422..398b334b 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -95,15 +95,15 @@ mod app { ); /* SD config */ - let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom1, gclk0); + let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); let sd_manager = SdManager::new( &mclk, - peripherals.SERCOM1, + peripherals.SERCOM4, pclk_sd.freq(), - pins.pa18.into_push_pull_output(), - pins.pa17.into_push_pull_output(), - pins.pa19.into_push_pull_output(), - pins.pa16.into_push_pull_output(), + pins.pb10.into_push_pull_output(), + pins.pb09.into_push_pull_output(), + pins.pb11.into_push_pull_output(), + pins.pb08.into_push_pull_output(), ); /* SBG config */ @@ -128,7 +128,7 @@ mod app { blink::spawn().ok(); /* Monotonic clock */ - let mono = Systick::new(core.SYST, gclk0.freq().0); + let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); ( Shared { @@ -192,7 +192,7 @@ mod app { Ok(()) }); - spawn_after!(sensor_send, 250.millis()).ok(); + spawn_after!(sensor_send, ExtU64::millis(250)).ok(); } /** @@ -204,10 +204,10 @@ mod app { cx.shared.em.run(|| { if cx.shared.em.has_error() { cx.local.led_red.toggle()?; - spawn_after!(blink, 200.millis())?; + spawn_after!(blink, ExtU64::millis(200))?; } else { cx.local.led_green.toggle()?; - spawn_after!(blink, 1.secs())?; + spawn_after!(blink, ExtU64::secs(1))?; } Ok(()) }); diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index e5411fa4..f47ac9e1 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -6,13 +6,15 @@ use atsamd_hal::dmac::Transfer; use atsamd_hal::sercom::{IoSet1, IoSet6}; use atsamd_hal::gpio::{Pin, Reset, PA08, PA09, PB03, PB02}; use atsamd_hal::pac::{MCLK, RTC}; -use atsamd_hal::prelude::_atsamd21_hal_time_U32Ext; +// use atsamd_hal::prelude::_atsamd21_hal_time_U32Ext; use atsamd_hal::rtc::Rtc; use core::alloc::{GlobalAlloc, Layout}; use core::ffi::c_void; use core::mem::size_of; use core::ptr; - +// use atsamd_hal::time::*; +use atsamd_hal::prelude::*; +use defmt::info; use crate::app::sbg_sd_task as sbg_sd; use crate::app::{sbg_handle_data}; use atsamd_hal::sercom::{uart, Sercom, Sercom5}; @@ -55,7 +57,7 @@ impl SBGManager { let pads_sbg = uart::Pads::::default().rx(rx).tx(tx); let uart_sbg = ConfigSBG::new(mclk, sercom5, pads_sbg, pclk_sercom5.freq()) .baud( - 115200.hz(), + 115200.Hz(), uart::BaudMode::Fractional(uart::Oversampling::Bits8), ) .enable(); @@ -73,7 +75,7 @@ impl SBGManager { // There is a bug within the HAL that improperly configures the RTC // in count32 mode. This is circumvented by first using clock mode then // converting to count32 mode. - let rtc_temp = Rtc::clock_mode(rtc, 1024.hz(), mclk); + let rtc_temp = Rtc::clock_mode(rtc, 1024.Hz(), mclk); let mut rtc = rtc_temp.into_count32_mode(); rtc.set_count32(0); @@ -105,6 +107,7 @@ pub fn sbg_sd_task(mut cx: crate::app::sbg_sd_task::Context, data: [u8; SBG_BUFF if let Ok(mut file) = manager.open_file("sbg.bin") { manager.write(&mut file, &data); manager.close_file(file); + info!("SBG data written to SD card"); } }); } diff --git a/boards/sensor/src/sd_manager.rs b/boards/sensor/src/sd_manager.rs index 91bb1c85..dbbf0145 100644 --- a/boards/sensor/src/sd_manager.rs +++ b/boards/sensor/src/sd_manager.rs @@ -1,9 +1,9 @@ use core::marker::PhantomData; use crate::types::SdController; -use atsamd_hal::gpio::{Output, Pin, PushPull, PA16, PA17, PA18, PA19}; +use atsamd_hal::gpio::{Output, Pin, PushPull, PA16, PA17, PA18, PA19,PA06, PA05, PA07, PA04, PB10, PB09, PB11, PB08}; use atsamd_hal::pac; -use atsamd_hal::sercom::{spi, IoSet1, Sercom1}; +use atsamd_hal::sercom::{spi, IoSet1, Sercom1, Sercom0, IoSet3, Sercom4, IoSet2}; use atsamd_hal::time::Hertz; use defmt::{info, warn}; use embedded_sdmmc as sd; @@ -46,14 +46,14 @@ pub struct SdManager { impl SdManager { pub fn new( mclk: &pac::MCLK, - sercom: pac::SERCOM1, + sercom: pac::SERCOM4, freq: Hertz, - cs: Pin>, - sck: Pin>, - miso: Pin>, - mosi: Pin>, + cs: Pin>, + sck: Pin>, + miso: Pin>, + mosi: Pin>, ) -> Self { - let pads_spi = spi::Pads::::default() + let pads_spi = spi::Pads::::default() .sclk(sck) .data_in(miso) .data_out(mosi); diff --git a/boards/sensor/src/types.rs b/boards/sensor/src/types.rs index c21d1ba2..f02856a0 100644 --- a/boards/sensor/src/types.rs +++ b/boards/sensor/src/types.rs @@ -7,6 +7,9 @@ use atsamd_hal::sercom::{spi, uart, IoSet1, Sercom5, IoSet6, Sercom1}; use embedded_sdmmc as sd; use hal::dmac; use hal::dmac::BufferPair; +use hal::sercom::IoSet2; +use hal::sercom::IoSet3; +use hal::sercom::Sercom0; use hal::sercom::Sercom4; use messages::sender::Sender; use messages::sender::Sender::SensorBoard; @@ -32,13 +35,13 @@ pub type SBGBuffer = &'static mut [u8; SBG_BUFFER_SIZE]; // SD Card // ------- pub type SdPads = spi::Pads< - Sercom1, - IoSet1, - Pin>, - Pin>, - Pin>, + Sercom4, + IoSet2, + Pin>, + Pin>, + Pin>, >; pub type SdController = sd::Controller< - sd::SdMmcSpi, spi::Duplex>, Pin>>, + sd::SdMmcSpi, spi::Duplex>, Pin>>, TimeSink, >; From 8c7b23cd57e333e311830be043d7f879a8001b4d Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sun, 13 Aug 2023 16:57:53 -0400 Subject: [PATCH 06/30] Add sd logging to communication board --- boards/communication/src/data_manager.rs | 1 + boards/communication/src/main.rs | 28 +++++++++++-------- boards/communication/src/sd_manager.rs | 6 ++--- boards/recovery/src/main.rs | 10 +++---- boards/sensor/src/main.rs | 34 +++++++++++++----------- boards/sensor/src/sbg_manager.rs | 24 ++++++++--------- examples/rtic/src/main.rs | 4 +-- libraries/messages/src/lib.rs | 1 - 8 files changed, 58 insertions(+), 50 deletions(-) diff --git a/boards/communication/src/data_manager.rs b/boards/communication/src/data_manager.rs index f95a3e75..cf8b100b 100644 --- a/boards/communication/src/data_manager.rs +++ b/boards/communication/src/data_manager.rs @@ -1,5 +1,6 @@ use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime}; use messages::Message; +use defmt::info; #[derive(Clone)] pub struct DataManager { diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index 242a0493..1825f242 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -18,7 +18,7 @@ use data_manager::DataManager; use sd_manager::SdManager; use hal::gpio::Pins; -use hal::gpio::PA14; +use hal::gpio::PA05; use hal::gpio::{Pin, PushPullOutput}; use hal::prelude::*; use mcan::messageram::SharedMemory; @@ -42,7 +42,7 @@ mod app { #[local] struct Local { - led: Pin, + led: Pin, radio: RadioDevice, sd_manager: SdManager, } @@ -115,7 +115,7 @@ mod app { ); /* Status LED */ - let led = pins.pa14.into_push_pull_output(); + let led = pins.pa05.into_push_pull_output(); /* Spawn tasks */ sensor_send::spawn().ok(); @@ -161,6 +161,9 @@ mod app { }); } + + /// Probably should use this ( ノ^ω^)ノ + /// I see no need for this and this loses the sender information pub fn queue_gs_message(d: impl Into) { let message = Message::new(&monotonics::now(), COM_ID, d.into()); @@ -178,15 +181,18 @@ mod app { }); } - #[task(capacity = 3, local = [sd_manager], shared = [&em])] - fn sd_dump(mut cx: sd_dump::Context) { + #[task(capacity = 10, local = [sd_manager], shared = [&em])] + fn sd_dump(mut cx: sd_dump::Context, m: Message) { let mut manager = cx.local.sd_manager; cx.shared.em.run(|| { - if let Ok(mut file) = manager.open_file("test.txt") { - manager.write(&mut file, "Hello, world!\n".as_bytes()); - manager.close_file(file); - info!("test written to SD card"); - } + let mut buf = [0u8; 256]; + let msg_ser = postcard::to_slice_cobs(&m, &mut buf)?; + info!("{}", msg_ser); + manager.write(msg_ser)?; + // if let Ok(mut file) = manager.open_file("log.txt") { + // manager.write(&mut file, msg_ser)?; + // manager.close_file(file); + // } Ok(()) }); } @@ -209,6 +215,7 @@ mod app { cx.shared.em.run(|| { for msg in messages { spawn!(send_gs, msg.clone())?; + spawn!(sd_dump, msg)?; } Ok(()) }); @@ -223,7 +230,6 @@ mod app { fn blink(cx: blink::Context) { cx.shared.em.run(|| { cx.local.led.toggle()?; - spawn!(sd_dump)?; if cx.shared.em.has_error() { spawn_after!(blink, ExtU64::millis(200))?; } else { diff --git a/boards/communication/src/sd_manager.rs b/boards/communication/src/sd_manager.rs index 682650ba..2eafe666 100644 --- a/boards/communication/src/sd_manager.rs +++ b/boards/communication/src/sd_manager.rs @@ -92,7 +92,7 @@ impl SdManager { let file = sd_cont.open_file_in_dir( &mut volume, &root_directory, - "test2.txt", + "log.txt", sd::Mode::ReadWriteCreateOrTruncate, ); let file = match file { @@ -112,10 +112,10 @@ impl SdManager { } pub fn write( &mut self, - file: &mut sd::File, + // file: &mut sd::File, buffer: &[u8], ) -> Result> { - self.sd_controller.write(&mut self.volume, file, buffer) + self.sd_controller.write(&mut self.volume, &mut self.file, buffer) } pub fn write_str( &mut self, diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 481d5d25..189c7baf 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -103,7 +103,7 @@ mod app { blink::spawn().ok(); /* Monotonic clock */ - let mono = Systick::new(core.SYST, gclk0.freq().0); + let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); ( Shared { @@ -131,7 +131,7 @@ mod app { cx.local.state_machine.run(&mut StateMachineContext { shared_resources: &mut cx.shared, }); - spawn_after!(run_sm, 2.secs()); + spawn_after!(run_sm, ExtU64::secs(2)); } /// Handles the CAN0 interrupt. @@ -173,7 +173,7 @@ mod app { }; let message = Message::new(&monotonics::now(), COM_ID, board_state); spawn!(send_internal, message)?; - spawn_after!(state_send, 5.secs())?; + spawn_after!(state_send, ExtU64::secs(5))?; Ok(()) }) } @@ -185,10 +185,10 @@ mod app { cx.shared.em.run(|| { if cx.shared.em.has_error() { cx.local.led_red.toggle()?; - spawn_after!(blink, 200.millis())?; + spawn_after!(blink, ExtU64::millis(200))?; } else { cx.local.led_green.toggle()?; - spawn_after!(blink, 1.secs())?; + spawn_after!(blink, ExtU64::secs(1))?; } Ok(()) }); diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index 398b334b..4d539b6d 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -24,7 +24,9 @@ use mcan::messageram::SharedMemory; use messages::sensor::Sensor; use messages::*; use panic_halt as _; -use sbg_manager::{sbg_dma, sbg_handle_data, sbg_sd_task, SBGManager}; +// use sbg_manager::{sbg_dma, sbg_handle_data, sbg_sd_task, SBGManager}; +use sbg_manager::{sbg_dma, sbg_handle_data, SBGManager}; + use sbg_rs::sbg::{CallbackData, SBG_BUFFER_SIZE}; use sd_manager::SdManager; use systick_monotonic::*; @@ -39,7 +41,7 @@ mod app { em: ErrorManager, data_manager: DataManager, can: communication::CanDevice0, - sd_manager: SdManager, + // sd_manager: SdManager, } #[local] @@ -94,17 +96,17 @@ mod app { false, ); - /* SD config */ - let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); - let sd_manager = SdManager::new( - &mclk, - peripherals.SERCOM4, - pclk_sd.freq(), - pins.pb10.into_push_pull_output(), - pins.pb09.into_push_pull_output(), - pins.pb11.into_push_pull_output(), - pins.pb08.into_push_pull_output(), - ); + // /* SD config */ + // let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); + // let sd_manager = SdManager::new( + // &mclk, + // peripherals.SERCOM4, + // pclk_sd.freq(), + // pins.pb10.into_push_pull_output(), + // pins.pb09.into_push_pull_output(), + // pins.pb11.into_push_pull_output(), + // pins.pb08.into_push_pull_output(), + // ); /* SBG config */ let (pclk_sbg, gclk0) = Pclk::enable(tokens.pclks.sercom5, gclk0); @@ -135,7 +137,7 @@ mod app { em: ErrorManager::new(), data_manager: DataManager::new(), can, - sd_manager, + // sd_manager, }, Local { led_green, @@ -214,8 +216,8 @@ mod app { } extern "Rust" { - #[task(capacity = 3, shared = [&em, sd_manager])] - fn sbg_sd_task(context: sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]); + // #[task(capacity = 3, shared = [&em, sd_manager])] + // fn sbg_sd_task(context: sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]); #[task(binds = DMAC_0, shared = [&em], local = [sbg_manager])] fn sbg_dma(context: sbg_dma::Context); diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index f47ac9e1..d4352946 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -15,7 +15,7 @@ use core::ptr; // use atsamd_hal::time::*; use atsamd_hal::prelude::*; use defmt::info; -use crate::app::sbg_sd_task as sbg_sd; +// use crate::app::sbg_sd_task as sbg_sd; use crate::app::{sbg_handle_data}; use atsamd_hal::sercom::{uart, Sercom, Sercom5}; use embedded_alloc::Heap; @@ -102,15 +102,15 @@ pub fn sbg_handle_data(mut cx: sbg_handle_data::Context, data: CallbackData) { }); } -pub fn sbg_sd_task(mut cx: crate::app::sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]) { - cx.shared.sd_manager.lock(|manager| { - if let Ok(mut file) = manager.open_file("sbg.bin") { - manager.write(&mut file, &data); - manager.close_file(file); - info!("SBG data written to SD card"); - } - }); -} +// pub fn sbg_sd_task(mut cx: crate::app::sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]) { +// cx.shared.sd_manager.lock(|manager| { +// if let Ok(mut file) = manager.open_file("sbg.bin") { +// manager.write(&mut file, &data); +// manager.close_file(file); +// info!("SBG data written to SD card"); +// } +// }); +// } /** * Handles the DMA interrupt. * Handles the SBG data. @@ -130,9 +130,9 @@ pub fn sbg_dma(cx: crate::app::sbg_dma::Context) { sbg.xfer.recycle_source(unsafe { &mut *BUF_DST2 })? } }; - let buf_clone = buf.clone(); + // let buf_clone = buf.clone(); sbg.sbg_device.read_data(buf); - spawn!(sbg_sd(buf_clone))?; + // spawn!(sbg_sd(buf_clone))?; Ok(()) }); } diff --git a/examples/rtic/src/main.rs b/examples/rtic/src/main.rs index 5a3a9d1c..e4be45fc 100644 --- a/examples/rtic/src/main.rs +++ b/examples/rtic/src/main.rs @@ -53,7 +53,7 @@ mod app { // Use the system's Systick for RTIC to keep track of the time let sysclk: Hertz = clocks.gclk0().into(); - let mono = Systick::new(core.SYST, sysclk.0); + let mono = Systick::new(core.SYST, sysclk.to_Hz()); (Shared {}, Local { led }, init::Monotonics(mono)) } @@ -73,6 +73,6 @@ mod app { let time = monotonics::now().duration_since_epoch().to_secs(); info!("Seconds since epoch: {}", time); - blink::spawn_after(1.secs()).ok(); + blink::spawn_after(ExtU64::secs(1)).ok(); } } diff --git a/libraries/messages/src/lib.rs b/libraries/messages/src/lib.rs index c2000e99..a1d85e68 100644 --- a/libraries/messages/src/lib.rs +++ b/libraries/messages/src/lib.rs @@ -11,7 +11,6 @@ use defmt::Format; use derive_more::From; use fugit::Instant; use serde::{Deserialize, Serialize}; - /// This is to help control versions. pub use mavlink; From c61876c31beabc74ae195f5b0811f2d8c9aff30e Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Thu, 17 Aug 2023 19:58:39 -0400 Subject: [PATCH 07/30] IDK --- boards/communication/src/main.rs | 5 ----- boards/recovery/src/data_manager.rs | 27 ++++++++------------------- 2 files changed, 8 insertions(+), 24 deletions(-) diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index 1825f242..6cd94a51 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -187,12 +187,7 @@ mod app { cx.shared.em.run(|| { let mut buf = [0u8; 256]; let msg_ser = postcard::to_slice_cobs(&m, &mut buf)?; - info!("{}", msg_ser); manager.write(msg_ser)?; - // if let Ok(mut file) = manager.open_file("log.txt") { - // manager.write(&mut file, msg_ser)?; - // manager.close_file(file); - // } Ok(()) }); } diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index aa915b8c..eb470780 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -5,7 +5,6 @@ use messages::Message; use defmt::{info, flush}; const MAIN_HEIGHT: f32 = 500.0; -const VELOCITY_MIN: f32 = 20.0; const HEIGHT_MIN: f32 = 900.0; pub struct DataManager { @@ -33,41 +32,31 @@ impl DataManager { current_state: None, } } - /// Returns true if the rocket has passed apogee. - /// This is determined by looking at the historical pressure data. - /// Furthermore, we only start checking pressure data when velocity is less than 20m/s - /// because we want to avoid the complexities of pressure during transonic flight. + /// Returns true if the rocket is descending pub fn is_falling(&self) -> bool { - // let ekf_nav1 = self.ekf_nav.0.as_ref(); - // if let Some(ekf_nav1) = ekf_nav1 { - // if ekf_nav1.velocity[2] > VELOCITY_MIN { - // return false; - // } - // } if self.historical_barometer_altitude.len() < 8 { return false; } let mut buf = self.historical_barometer_altitude.oldest_ordered(); match buf.next() { Some(last) => { - let mut avg: f32 = 0.0; + let mut avg_sum: f32 = 0.0; let mut prev = last; for i in buf { - let time_diff: f32 = (i.1 - prev.1) as f32 / 1000000.0; + let time_diff: f32 = (i.1 - prev.1) as f32 / 1_000_000.0; if time_diff == 0.0 { - info!("diff {} {}", i, prev); continue; } - avg += (i.0 - prev.0)/time_diff; + avg_sum += (i.0 - prev.0)/time_diff; prev = i; } - match avg / 7.0 { // 7 because we have 8 points. - x if x > -10.0 || x < -120.0 => { - info!("avg: {}", avg / 7.0); + match avg_sum / 7.0 { // 7 because we have 8 points. + x if x > -5.0 || x < -120.0 => { + info!("avg: {}", avg_sum / 7.0); return false; } _ => { - info!("avg: {}", avg / 7.0); + info!("avg: {}", avg_sum / 7.0); } } } From c412cd3f7dbdeeb358b623a45e927cdc550dc2a0 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Fri, 18 Aug 2023 13:06:32 -0400 Subject: [PATCH 08/30] State rename, message seperation of concerns, commands from ground station support --- boards/communication/src/communication.rs | 72 +++++++++++++++++-- boards/communication/src/main.rs | 22 ++++-- boards/communication/src/types.rs | 10 ++- boards/recovery/src/data_manager.rs | 15 +++- boards/recovery/src/main.rs | 36 +++++++--- boards/recovery/src/state_machine/mod.rs | 43 +++++------ .../src/state_machine/states/ascent.rs | 6 +- .../states/{apogee.rs => descent.rs} | 18 ++--- .../recovery/src/state_machine/states/mod.rs | 8 +-- .../states/{landed.rs => terminal_descent.rs} | 18 ++--- boards/recovery/src/types.rs | 2 +- boards/sensor/src/communication.rs | 4 +- boards/sensor/src/main.rs | 8 ++- boards/sensor/src/sbg_manager.rs | 8 +-- boards/sensor/src/sd_manager.rs | 16 ++--- boards/sensor/src/types.rs | 6 +- libraries/messages/src/command.rs | 44 ++++++++++++ libraries/messages/src/lib.rs | 37 ++-------- libraries/messages/src/state.rs | 38 ++++++++++ libraries/sbg-rs/src/sbg.rs | 19 +++-- 20 files changed, 303 insertions(+), 127 deletions(-) rename boards/recovery/src/state_machine/states/{apogee.rs => descent.rs} (70%) rename boards/recovery/src/state_machine/states/{landed.rs => terminal_descent.rs} (61%) create mode 100644 libraries/messages/src/command.rs create mode 100644 libraries/messages/src/state.rs diff --git a/boards/communication/src/communication.rs b/boards/communication/src/communication.rs index 01643fae..4bf7246f 100644 --- a/boards/communication/src/communication.rs +++ b/boards/communication/src/communication.rs @@ -8,12 +8,15 @@ use atsamd_hal::clock::v2::pclk::Pclk; use atsamd_hal::clock::v2::pclk::PclkToken; use atsamd_hal::clock::v2::types::Can0; use atsamd_hal::clock::v2::Source; +use atsamd_hal::dmac; use atsamd_hal::gpio::{Alternate, AlternateI, Disabled, Floating, Pin, I, PA22, PA23, PB16, PB17}; use atsamd_hal::pac::CAN0; use atsamd_hal::pac::MCLK; use atsamd_hal::pac::SERCOM5; +use atsamd_hal::sercom::Sercom; +use atsamd_hal::sercom::{uart, Sercom5}; use atsamd_hal::sercom; -use atsamd_hal::sercom::uart; +use atsamd_hal::sercom::uart::{ TxDuplex, RxDuplex}; use atsamd_hal::sercom::uart::{Duplex, Uart}; use atsamd_hal::time::*; use atsamd_hal::typelevel::Increment; @@ -22,6 +25,8 @@ use common_arm::mcan::message::{rx, Raw}; use common_arm::mcan::tx_buffers::DynTx; use common_arm::HydraError; use defmt::info; +use crate::app::send_internal; +use common_arm::spawn; use heapless::Vec; use mcan::bus::Can; use mcan::embedded_can as ecan; @@ -39,6 +44,7 @@ use postcard::from_bytes; use systick_monotonic::fugit::RateExtU32; use typenum::{U0, U128, U32, U64}; +use atsamd_hal::dmac::Transfer; pub struct Capacities; impl mcan::messageram::Capacities for Capacities { @@ -209,8 +215,11 @@ impl CanDevice0 { } } +pub static mut BUF_DST: RadioBuffer = &mut [0; 255]; +pub static mut BUF_DST2: RadioBuffer = &mut [0; 255]; + pub struct RadioDevice { - uart: Uart, + uart: Uart, mav_sequence: u8, } @@ -222,7 +231,8 @@ impl RadioDevice { rx_pin: Pin>, tx_pin: Pin>, gclk0: S, - ) -> (Self, S::Inc) + mut dma_channel: dmac::Channel, + ) -> (Self, S::Inc, RadioTransfer) where S: Source + Increment, { @@ -236,12 +246,16 @@ impl RadioDevice { uart::BaudMode::Fractional(uart::Oversampling::Bits16), ) .enable(); + let (rx, tx) = uart.split(); // tx sends rx uses dma to receive so we need to setup dma here. + dma_channel.as_mut().enable_interrupts(dmac::InterruptFlags::new().with_tcmpl(true)); + let xfer = Transfer::new(dma_channel, rx, unsafe {&mut *BUF_DST}, false).expect("DMA Radio RX").begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); ( RadioDevice { - uart, + uart: tx, mav_sequence: 0, }, gclk0, + xfer ) } pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { @@ -266,3 +280,53 @@ impl RadioDevice { Ok(()) } } + +pub struct RadioManager { + xfer: RadioTransfer, + buf_select: bool, +} + +impl RadioManager { + pub fn new( + xfer: RadioTransfer, + ) -> Self { + RadioManager { + xfer, + buf_select: false, + } + } + pub fn process_message(&mut self, buf: RadioBuffer) { + info!("Received: {:?}", buf); + match from_bytes::(buf) { + Ok(msg) => { + info!("Radio: {}", msg); + spawn!(send_internal, msg); // dump to the Can Bus + } + Err(_) => { + info!("Radio unknown msg"); + return; + } + } + } +} + +pub fn radio_dma(cx: crate::app::radio_dma::Context) { + let manager = cx.local.radio_manager; + + if manager.xfer.complete() { + cx.shared.em.run(|| { + let buf = match manager.buf_select { + false => { + manager.buf_select = true; + manager.xfer.recycle_source(unsafe{&mut *BUF_DST})? + } + true => { + manager.buf_select = false; + manager.xfer.recycle_source(unsafe{&mut *BUF_DST2})? + } + }; + manager.process_message(buf); + Ok(()) + }) + } +} \ No newline at end of file diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index 6cd94a51..0fbc99dc 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -10,12 +10,14 @@ use atsamd_hal as hal; use atsamd_hal::clock::v2::pclk::Pclk; use atsamd_hal::clock::v2::Source; use atsamd_hal::dmac::DmaController; +use atsamd_hal::dmac; use common_arm::mcan; use common_arm::*; use communication::Capacities; -use communication::RadioDevice; +use communication::{RadioDevice, RadioManager}; use data_manager::DataManager; use sd_manager::SdManager; +use communication::radio_dma; use hal::gpio::Pins; use hal::gpio::PA05; @@ -27,7 +29,7 @@ use messages::*; use panic_halt as _; use systick_monotonic::*; use types::*; -use defmt::info; +use defmt::{info, flush}; #[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] mod app { @@ -45,6 +47,7 @@ mod app { led: Pin, radio: RadioDevice, sd_manager: SdManager, + radio_manager: RadioManager, } #[monotonic(binds = SysTick, default = true)] @@ -60,7 +63,7 @@ mod app { let pins = Pins::new(peripherals.PORT); let mut dmac = DmaController::init(peripherals.DMAC, &mut peripherals.PM); - let _dmaChannels = dmac.split(); + let dmaChannels = dmac.split(); /* Logging Setup */ HydraLogging::set_ground_station_callback(queue_gs_message); @@ -93,15 +96,19 @@ mod app { ); /* Radio config */ - let (radio, gclk0) = RadioDevice::new( + let dmaCh0 = dmaChannels.0.init(dmac::PriorityLevel::LVL3); + let (radio, gclk0, xfer) = RadioDevice::new( tokens.pclks.sercom5, &mclk, peripherals.SERCOM5, pins.pb17, pins.pb16, gclk0, + dmaCh0, ); + let radio_manager = RadioManager::new(xfer); + /* SD config */ let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); let sd_manager = SdManager::new( @@ -130,7 +137,7 @@ mod app { data_manager: DataManager::new(), can0, }, - Local { led, radio, sd_manager }, + Local { led, radio, sd_manager, radio_manager }, init::Monotonics(mono), ) } @@ -233,4 +240,9 @@ mod app { Ok(()) }); } + + extern "Rust" { + #[task(binds = DMAC_0, shared=[&em], local=[radio_manager])] + fn radio_dma(context: radio_dma::Context); + } } diff --git a/boards/communication/src/types.rs b/boards/communication/src/types.rs index adcc39c7..9b2f1b2b 100644 --- a/boards/communication/src/types.rs +++ b/boards/communication/src/types.rs @@ -1,11 +1,13 @@ use crate::sd_manager::TimeSink; -use atsamd_hal::gpio::*; +use atsamd_hal::{gpio::*, dmac}; use atsamd_hal::sercom::uart::EightBit; use atsamd_hal::sercom::{spi, Sercom4}; use atsamd_hal::sercom::{Sercom5, Sercom1, uart, IoSet1}; use messages::sender::Sender; use messages::sender::Sender::CommunicationBoard; use embedded_sdmmc as sd; +use atsamd_hal::dmac::BufferPair; +use atsamd_hal::sercom::uart::Uart; // ------- // Sender ID @@ -32,3 +34,9 @@ pub type SdController = sd::Controller< sd::SdMmcSpi, spi::Duplex>, Pin>>, TimeSink, >; + +pub type RadioTransfer = dmac::Transfer< + dmac::Channel, + BufferPair, RadioBuffer>, +>; +pub type RadioBuffer = &'static mut [u8; 255]; \ No newline at end of file diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index eb470780..52f523fa 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -1,8 +1,10 @@ use crate::state_machine::RocketStates; +use crate::app::{fire_drogue, fire_main}; +use common_arm::spawn; use heapless::HistoryBuffer; use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, UtcTime}; use messages::Message; -use defmt::{info, flush}; +use defmt::{info}; const MAIN_HEIGHT: f32 = 500.0; const HEIGHT_MIN: f32 = 900.0; @@ -84,6 +86,9 @@ impl DataManager { None => 0.0, } } + pub fn set_state(&mut self, state: RocketStates) { + self.current_state = Some(state); + } pub fn handle_data(&mut self, data: Message) { match data.data { messages::Data::Sensor(sensor) => match sensor.data { @@ -122,6 +127,14 @@ impl DataManager { self.utc_time = Some(utc_time_data); } }, + messages::Data::Command(command) => match command.data { + messages::command::CommandData::DeployDrogue(drogue) => { + spawn!(fire_drogue); + }, + messages::command::CommandData::DeployMain(main) => { + spawn!(fire_main); + } + } _ => {} } } diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 189c7baf..4270680b 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -6,7 +6,7 @@ mod data_manager; mod state_machine; mod types; -use crate::state_machine::RocketStates; + use atsamd_hal as hal; use atsamd_hal::clock::v2::pclk::Pclk; use atsamd_hal::clock::v2::Source; @@ -15,7 +15,7 @@ use common_arm::mcan; use common_arm::*; use communication::Capacities; use data_manager::DataManager; -use hal::gpio::{Pin, Pins, PushPullOutput, PB16, PB17, PA09, PA06}; +use hal::gpio::{Pin, Pins, PushPullOutput, PB16, PB17}; use hal::prelude::*; use mcan::messageram::SharedMemory; use messages::*; @@ -123,15 +123,34 @@ mod app { loop {} } + #[task(shared=[gpio])] + fn fire_drogue(mut cx: fire_drogue::Context) { + cx.shared.gpio.lock(|gpio| { + gpio.fire_drogue(); + }); + } + + #[task(shared=[gpio])] + fn fire_main(mut cx: fire_main::Context) { + cx.shared.gpio.lock(|gpio| { + gpio.fire_main(); + }); + } + /// Runs the state machine. /// This takes control of the shared resources. - #[task(local = [state_machine], shared = [can0, gpio, data_manager])] + #[task(local = [state_machine], shared = [can0, gpio, data_manager, &em])] fn run_sm(mut cx: run_sm::Context) { cx.shared.data_manager.lock(|dm| info!("alt: {}", dm.get_alt())); cx.local.state_machine.run(&mut StateMachineContext { shared_resources: &mut cx.shared, }); - spawn_after!(run_sm, ExtU64::secs(2)); + // !! Question, will this error and then never spawn again? Should I just keep trying to spawn it and not care + // to use the error manager. + cx.shared.em.run(|| { + spawn_after!(run_sm, ExtU64::secs(2))?; + Ok(()) + }) } /// Handles the CAN0 interrupt. @@ -165,11 +184,12 @@ mod app { let state = if let Some(rocket_state) = rocket_state { rocket_state } else { - RocketStates::Initializing(state_machine::Initializing {}) + // This isn't really an error, we just don't have data yet. + spawn_after!(state_send, ExtU64::secs(5))?; + return Ok(()) }; - let board_state = messages::State { - status: state.into(), - has_error: em_error, + let board_state = messages::state::State { + data: state.into(), }; let message = Message::new(&monotonics::now(), COM_ID, board_state); spawn!(send_internal, message)?; diff --git a/boards/recovery/src/state_machine/mod.rs b/boards/recovery/src/state_machine/mod.rs index aaf8bc84..34e3689b 100644 --- a/boards/recovery/src/state_machine/mod.rs +++ b/boards/recovery/src/state_machine/mod.rs @@ -1,7 +1,7 @@ mod black_magic; mod states; -use messages::Status; +use messages::state; use crate::communication::CanDevice0; use crate::data_manager::DataManager; use crate::state_machine::states::*; @@ -51,6 +51,9 @@ impl StateMachine { pub fn run(&mut self, context: &mut StateMachineContext) { if let Some(new_state) = self.state.step(context) { self.state.exit(); + context.shared_resources.data_manager.lock(|data| { + data.set_state(new_state.clone()); + }); new_state.enter(context); self.state = new_state; } @@ -71,35 +74,35 @@ pub enum RocketStates { Initializing, WaitForTakeoff, Ascent, - Apogee, - Landed, + Descent, + TerminalDescent, Abort, } // Not ideal, but it works for now. -// Should be able to put this is a shared library, but as of now, I can't figure out how to do that. -impl From for RocketStates { - fn from(state: messages::Status) -> Self { +// Should be able to put this is a shared library. +impl From for RocketStates { + fn from(state: state::StateData) -> Self { match state { - Status::Initializing => RocketStates::Initializing(Initializing {}), - Status::WaitForTakeoff => RocketStates::WaitForTakeoff(WaitForTakeoff {}), - Status::Ascent => RocketStates::Ascent(Ascent {}), - Status::Apogee => RocketStates::Apogee(Apogee {}), - Status::Landed => RocketStates::Landed(Landed {}), - Status::Abort => RocketStates::Abort(Abort {}), + state::StateData::Initializing => RocketStates::Initializing(Initializing {}), + state::StateData::WaitForTakeoff => RocketStates::WaitForTakeoff(WaitForTakeoff {}), + state::StateData::Ascent => RocketStates::Ascent(Ascent {}), + state::StateData::Descent => RocketStates::Descent(Descent {}), + state::StateData::TerminalDescent => RocketStates::TerminalDescent(TerminalDescent { } ), + state::StateData::Abort => RocketStates::Abort(Abort {}), } } } -impl Into for RocketStates { - fn into(self) -> Status { +impl Into for RocketStates { + fn into(self) -> state::StateData { match self { - RocketStates::Initializing(_) => Status::Initializing, - RocketStates::WaitForTakeoff(_) => Status::WaitForTakeoff, - RocketStates::Ascent(_) => Status::Ascent, - RocketStates::Apogee(_) => Status::Apogee, - RocketStates::Landed(_) => Status::Landed, - RocketStates::Abort(_) => Status::Abort, + RocketStates::Initializing(_) => state::StateData::Initializing, + RocketStates::WaitForTakeoff(_) => state::StateData::WaitForTakeoff, + RocketStates::Ascent(_) => state::StateData::Ascent, + RocketStates::Descent(_) => state::StateData::Descent, + RocketStates::TerminalDescent(_) => state::StateData::TerminalDescent, + RocketStates::Abort(_) => state::StateData::Abort, } } } \ No newline at end of file diff --git a/boards/recovery/src/state_machine/states/ascent.rs b/boards/recovery/src/state_machine/states/ascent.rs index 081cc01c..6dd92afe 100644 --- a/boards/recovery/src/state_machine/states/ascent.rs +++ b/boards/recovery/src/state_machine/states/ascent.rs @@ -1,8 +1,8 @@ -use crate::state_machine::states::apogee::Apogee; +use crate::state_machine::states::descent::Descent; use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; use crate::{no_transition, transition}; -use defmt::{write, Format, Formatter, info}; +use defmt::{write, Format, Formatter}; use rtic::mutex::Mutex; #[derive(Debug, Clone)] @@ -15,7 +15,7 @@ impl State for Ascent { .data_manager .lock(|data| { if data.is_falling() { - transition!(self, Apogee) + transition!(self, Descent) } else { no_transition!() } diff --git a/boards/recovery/src/state_machine/states/apogee.rs b/boards/recovery/src/state_machine/states/descent.rs similarity index 70% rename from boards/recovery/src/state_machine/states/apogee.rs rename to boards/recovery/src/state_machine/states/descent.rs index de906b7b..04309087 100644 --- a/boards/recovery/src/state_machine/states/apogee.rs +++ b/boards/recovery/src/state_machine/states/descent.rs @@ -1,13 +1,13 @@ use super::Ascent; -use crate::state_machine::{Landed, RocketStates, State, StateMachineContext, TransitionInto}; +use crate::state_machine::{TerminalDescent, RocketStates, State, StateMachineContext, TransitionInto}; use crate::{no_transition, transition}; use rtic::mutex::Mutex; use defmt::{write, Format, Formatter, info}; #[derive(Debug, Clone)] -pub struct Apogee {} +pub struct Descent {} -impl State for Apogee { +impl State for Descent { fn enter(&self, context: &mut StateMachineContext) { info!("Apogee"); context.shared_resources.gpio.lock(|gpio| gpio.fire_drogue()); @@ -18,7 +18,7 @@ impl State for Apogee { context.shared_resources.data_manager.lock(|data| { // Handle the case where we don't have any data yet if data.is_below_main() { - transition!(self, Landed) + transition!(self, TerminalDescent) } else { no_transition!() } @@ -26,14 +26,14 @@ impl State for Apogee { } } -impl TransitionInto for Ascent { - fn transition(&self) -> Apogee { - Apogee {} +impl TransitionInto for Ascent { + fn transition(&self) -> Descent { + Descent {} } } -impl Format for Apogee { +impl Format for Descent { fn format(&self, f: Formatter) { - write!(f, "Apogee") + write!(f, "Descent") } } diff --git a/boards/recovery/src/state_machine/states/mod.rs b/boards/recovery/src/state_machine/states/mod.rs index 14cf4411..fd24eb7c 100644 --- a/boards/recovery/src/state_machine/states/mod.rs +++ b/boards/recovery/src/state_machine/states/mod.rs @@ -1,13 +1,13 @@ mod initializing; -mod landed; +mod terminal_descent; mod ascent; -mod apogee; +mod descent; mod wait_for_takeoff; mod abort; -pub use crate::state_machine::states::apogee::Apogee; +pub use crate::state_machine::states::descent::Descent; pub use crate::state_machine::states::ascent::Ascent; pub use crate::state_machine::states::initializing::Initializing; pub use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; -pub use crate::state_machine::states::landed::Landed; +pub use crate::state_machine::states::terminal_descent::TerminalDescent; pub use crate::state_machine::states::abort::Abort; \ No newline at end of file diff --git a/boards/recovery/src/state_machine/states/landed.rs b/boards/recovery/src/state_machine/states/terminal_descent.rs similarity index 61% rename from boards/recovery/src/state_machine/states/landed.rs rename to boards/recovery/src/state_machine/states/terminal_descent.rs index b259963b..1e5dcc76 100644 --- a/boards/recovery/src/state_machine/states/landed.rs +++ b/boards/recovery/src/state_machine/states/terminal_descent.rs @@ -3,14 +3,14 @@ use defmt::{write, Format, Formatter, info}; use crate::no_transition; use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; use rtic::mutex::Mutex; -use super::Apogee; +use super::Descent; #[derive(Debug, Clone)] -pub struct Landed {} +pub struct TerminalDescent {} -impl State for Landed { +impl State for TerminalDescent { fn enter(&self,context: &mut StateMachineContext) { - info!("Landed"); + info!("Terminal Descent"); context.shared_resources.gpio.lock(|gpio| gpio.fire_main()); } fn step(&mut self, _context: &mut StateMachineContext) -> Option { @@ -18,14 +18,14 @@ impl State for Landed { } } -impl TransitionInto for Apogee { - fn transition(&self) -> Landed { - Landed {} +impl TransitionInto for Descent { + fn transition(&self) -> TerminalDescent { + TerminalDescent {} } } -impl Format for Landed { +impl Format for TerminalDescent { fn format(&self, f: Formatter) { - write!(f, "Landed") + write!(f, "Terminal Descent") } } diff --git a/boards/recovery/src/types.rs b/boards/recovery/src/types.rs index fe6c3163..7b2456ae 100644 --- a/boards/recovery/src/types.rs +++ b/boards/recovery/src/types.rs @@ -1,4 +1,4 @@ -use atsamd_hal::gpio::{PB14, PB15, Pin, PushPullOutput, PA09, PA06}; +use atsamd_hal::gpio::{Pin, PushPullOutput, PA09, PA06}; use atsamd_hal::prelude::*; use messages::sender::Sender; use messages::sender::Sender::RecoveryBoard; diff --git a/boards/sensor/src/communication.rs b/boards/sensor/src/communication.rs index 86d916e8..2987e8e6 100644 --- a/boards/sensor/src/communication.rs +++ b/boards/sensor/src/communication.rs @@ -290,7 +290,7 @@ impl CanDevice1 { gclk0, ) } - pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { + pub fn _send_message(&mut self, m: Message) -> Result<(), HydraError> { let payload: Vec = postcard::to_vec(&m)?; self.can.tx.transmit_queued( tx::MessageBuilder { @@ -306,7 +306,7 @@ impl CanDevice1 { )?; Ok(()) } - pub fn process_data(&mut self) { + pub fn _process_data(&mut self) { let line_interrupts = &self.line_interrupts; for interrupt in line_interrupts.iter_flagged() { match interrupt { diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index 4d539b6d..16207d07 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -16,6 +16,7 @@ use common_arm::*; use communication::Capacities; use data_manager::DataManager; use hal::dmac; + use hal::gpio::Pins; use hal::gpio::{PB16, PB17}; use hal::gpio::{Pin, PushPullOutput}; @@ -27,8 +28,8 @@ use panic_halt as _; // use sbg_manager::{sbg_dma, sbg_handle_data, sbg_sd_task, SBGManager}; use sbg_manager::{sbg_dma, sbg_handle_data, SBGManager}; -use sbg_rs::sbg::{CallbackData, SBG_BUFFER_SIZE}; -use sd_manager::SdManager; +use sbg_rs::sbg::{CallbackData}; + use systick_monotonic::*; use types::*; @@ -121,6 +122,8 @@ mod app { dmaCh0, ); + // Buzzer should go here. There is complexity using the new clock system with the atsamdhal pwm implementation. + /* Status LED */ let led_green = pins.pb16.into_push_pull_output(); let led_red = pins.pb17.into_push_pull_output(); @@ -191,7 +194,6 @@ mod app { for msg in messages { spawn!(send_internal, msg)?; } - Ok(()) }); spawn_after!(sensor_send, ExtU64::millis(250)).ok(); diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index d4352946..e8f787d5 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -3,8 +3,8 @@ use atsamd_hal::clock::v2::gclk::Gclk0Id; use atsamd_hal::clock::v2::pclk::Pclk; use atsamd_hal::dmac; use atsamd_hal::dmac::Transfer; -use atsamd_hal::sercom::{IoSet1, IoSet6}; -use atsamd_hal::gpio::{Pin, Reset, PA08, PA09, PB03, PB02}; +use atsamd_hal::sercom::{IoSet6}; +use atsamd_hal::gpio::{Pin, Reset, PB03, PB02}; use atsamd_hal::pac::{MCLK, RTC}; // use atsamd_hal::prelude::_atsamd21_hal_time_U32Ext; use atsamd_hal::rtc::Rtc; @@ -14,7 +14,7 @@ use core::mem::size_of; use core::ptr; // use atsamd_hal::time::*; use atsamd_hal::prelude::*; -use defmt::info; + // use crate::app::sbg_sd_task as sbg_sd; use crate::app::{sbg_handle_data}; use atsamd_hal::sercom::{uart, Sercom, Sercom5}; @@ -22,7 +22,7 @@ use embedded_alloc::Heap; use rtic::Mutex; use sbg_rs::sbg; use sbg_rs::sbg::{CallbackData, SBG, SBG_BUFFER_SIZE}; -use common_arm::spawn; + pub static mut BUF_DST: SBGBuffer = &mut [0; SBG_BUFFER_SIZE]; pub static mut BUF_DST2: SBGBuffer = &mut [0; SBG_BUFFER_SIZE]; diff --git a/boards/sensor/src/sd_manager.rs b/boards/sensor/src/sd_manager.rs index dbbf0145..9905659f 100644 --- a/boards/sensor/src/sd_manager.rs +++ b/boards/sensor/src/sd_manager.rs @@ -1,9 +1,9 @@ use core::marker::PhantomData; use crate::types::SdController; -use atsamd_hal::gpio::{Output, Pin, PushPull, PA16, PA17, PA18, PA19,PA06, PA05, PA07, PA04, PB10, PB09, PB11, PB08}; +use atsamd_hal::gpio::{Output, Pin, PushPull, PB10, PB09, PB11, PB08}; use atsamd_hal::pac; -use atsamd_hal::sercom::{spi, IoSet1, Sercom1, Sercom0, IoSet3, Sercom4, IoSet2}; +use atsamd_hal::sercom::{spi, Sercom4, IoSet2}; use atsamd_hal::time::Hertz; use defmt::{info, warn}; use embedded_sdmmc as sd; @@ -44,7 +44,7 @@ pub struct SdManager { } impl SdManager { - pub fn new( + pub fn _new( mclk: &pac::MCLK, sercom: pac::SERCOM4, freq: Hertz, @@ -111,14 +111,14 @@ impl SdManager { file, } } - pub fn write( + pub fn _write( &mut self, file: &mut sd::File, buffer: &[u8], ) -> Result> { self.sd_controller.write(&mut self.volume, file, buffer) } - pub fn write_str( + pub fn _write_str( &mut self, file: &mut sd::File, msg: &str, @@ -126,7 +126,7 @@ impl SdManager { let buffer: &[u8] = msg.as_bytes(); self.sd_controller.write(&mut self.volume, file, buffer) } - pub fn open_file(&mut self, file_name: &str) -> Result> { + pub fn _open_file(&mut self, file_name: &str) -> Result> { self.sd_controller.open_file_in_dir( &mut self.volume, &self.root_directory, @@ -134,10 +134,10 @@ impl SdManager { sd::Mode::ReadWriteCreateOrTruncate, ) } - pub fn close_file(&mut self, file: sd::File) -> Result<(), sd::Error> { + pub fn _close_file(&mut self, file: sd::File) -> Result<(), sd::Error> { self.sd_controller.close_file(&self.volume, file) } - pub fn close(mut self) { + pub fn _close(mut self) { self.sd_controller .close_dir(&self.volume, self.root_directory); } diff --git a/boards/sensor/src/types.rs b/boards/sensor/src/types.rs index f02856a0..ad7c2b76 100644 --- a/boards/sensor/src/types.rs +++ b/boards/sensor/src/types.rs @@ -3,13 +3,13 @@ use atsamd_hal as hal; use atsamd_hal::gpio::*; use atsamd_hal::sercom::uart::EightBit; use atsamd_hal::sercom::uart::Uart; -use atsamd_hal::sercom::{spi, uart, IoSet1, Sercom5, IoSet6, Sercom1}; +use atsamd_hal::sercom::{spi, uart, Sercom5, IoSet6}; use embedded_sdmmc as sd; use hal::dmac; use hal::dmac::BufferPair; use hal::sercom::IoSet2; -use hal::sercom::IoSet3; -use hal::sercom::Sercom0; + + use hal::sercom::Sercom4; use messages::sender::Sender; use messages::sender::Sender::SensorBoard; diff --git a/libraries/messages/src/command.rs b/libraries/messages/src/command.rs new file mode 100644 index 00000000..e98e317e --- /dev/null +++ b/libraries/messages/src/command.rs @@ -0,0 +1,44 @@ +use derive_more::From; +use defmt::Format; +use serde::{Deserialize, Serialize}; + +#[cfg(feature = "ts")] +use ts_rs::TS; + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Command { + pub data: CommandData, +} + +#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub enum CommandData { + DeployDrogue(DeployDrogue), + DeployMain(DeployMain), +} + +#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct DeployDrogue { + pub val: bool, +} + +#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct DeployMain { + pub val: bool, + // Auth? +} + +impl Command { + pub fn new(data: impl Into) -> Self { + Command { + data: data.into(), + } + } +} \ No newline at end of file diff --git a/libraries/messages/src/lib.rs b/libraries/messages/src/lib.rs index a1d85e68..0fb9febb 100644 --- a/libraries/messages/src/lib.rs +++ b/libraries/messages/src/lib.rs @@ -7,6 +7,8 @@ use crate::sender::Sender; use crate::sensor::Sensor; +use crate::state::State; +use crate::command::Command; use defmt::Format; use derive_more::From; use fugit::Instant; @@ -23,6 +25,8 @@ use ts_rs::TS; mod logging; pub mod sender; pub mod sensor; +pub mod command; +pub mod state; pub const MAX_SIZE: usize = 64; @@ -55,38 +59,7 @@ pub enum Data { State(State), Sensor(Sensor), Log(Log), -} - -// #[derive(Serialize, Deserialize, Clone, Debug, Format)] -// #[cfg_attr(test, derive(Arbitrary))] -// #[cfg_attr(feature = "ts", derive(TS))] -// #[cfg_attr(feature = "ts", ts(export))] -// pub enum Status { -// Uninitialized, -// Initializing, -// Running, -// } - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub enum Status { - Initializing, - WaitForTakeoff, - Ascent, - Apogee, - Landed, - Abort, -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct State { - pub status: Status, - pub has_error: bool, + Command(Command), } impl Message { diff --git a/libraries/messages/src/state.rs b/libraries/messages/src/state.rs new file mode 100644 index 00000000..2704906c --- /dev/null +++ b/libraries/messages/src/state.rs @@ -0,0 +1,38 @@ +use derive_more::From; +use defmt::Format; +use serde::{Deserialize, Serialize}; + +#[cfg(test)] +use proptest_derive::Arbitrary; + +#[cfg(feature = "ts")] +use ts_rs::TS; + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct State { + pub data: StateData, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub enum StateData { + Initializing, + WaitForTakeoff, + Ascent, + Descent, + TerminalDescent, + Abort, +} + +impl State { + pub fn new(data: impl Into) -> Self { + State { + data: data.into(), + } + } +} \ No newline at end of file diff --git a/libraries/sbg-rs/src/sbg.rs b/libraries/sbg-rs/src/sbg.rs index fb32fcbf..aabb65c4 100644 --- a/libraries/sbg-rs/src/sbg.rs +++ b/libraries/sbg-rs/src/sbg.rs @@ -1,6 +1,5 @@ use crate::bindings::{ - self, _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_DEBUG, _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR, - _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_INFO, _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING, + self, _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING, _SbgEComLog_SBG_ECOM_LOG_AIR_DATA, _SbgEComLog_SBG_ECOM_LOG_EKF_NAV, _SbgEComLog_SBG_ECOM_LOG_GPS1_VEL, _SbgEComLog_SBG_ECOM_LOG_UTC_TIME, _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, _SbgErrorCode_SBG_NO_ERROR, @@ -13,16 +12,16 @@ use crate::bindings::{ _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, _SbgEComProtocol, _SbgErrorCode, _SbgInterface, }; use atsamd_hal as hal; -use core::ffi::{c_void, CStr}; +use core::ffi::{c_void}; use core::ptr::null_mut; use core::slice::{from_raw_parts, from_raw_parts_mut}; use core::sync::atomic::AtomicUsize; -use defmt::{debug, error, flush, info, warn}; +use defmt::{flush, warn}; use embedded_hal::serial::Write; -use hal::gpio::{PA08, PA09, PB16, PB17, PB03, PB02}; +use hal::gpio::{PB16, PB17, PB03, PB02}; use hal::sercom::uart::Duplex; use hal::sercom::uart::{self, EightBit, Uart}; -use hal::sercom::{IoSet1, IoSet6, Sercom0, Sercom5}; +use hal::sercom::{IoSet1, IoSet6, Sercom5}; use messages::sensor::*; type Pads = uart::PadsFromIds; @@ -473,13 +472,13 @@ unsafe impl Send for SBG {} */ #[no_mangle] pub unsafe extern "C" fn sbgPlatformDebugLogMsg( - pFileName: *const ::core::ffi::c_char, - pFunctionName: *const ::core::ffi::c_char, + _pFileName: *const ::core::ffi::c_char, + _pFunctionName: *const ::core::ffi::c_char, _line: u32, - pCategory: *const ::core::ffi::c_char, + _pCategory: *const ::core::ffi::c_char, logType: _SbgDebugLogType, _errorCode: _SbgErrorCode, - pFormat: *const ::core::ffi::c_char, + _pFormat: *const ::core::ffi::c_char, ) { // if pFileName.is_null() || pFunctionName.is_null() || pCategory.is_null() || pFormat.is_null() { // return; From 8ff2cfae34053e2c23c62a3cd67cca5cff912dbe Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Fri, 18 Aug 2023 21:08:30 -0400 Subject: [PATCH 09/30] Fix DMA --- boards/communication/src/communication.rs | 97 ++++++++++++++++++----- boards/communication/src/main.rs | 49 ++++++------ boards/communication/src/types.rs | 2 +- boards/sensor/src/main.rs | 5 +- boards/sensor/src/sbg_manager.rs | 55 ++++++++----- libraries/sbg-rs/src/sbg.rs | 4 +- 6 files changed, 142 insertions(+), 70 deletions(-) diff --git a/boards/communication/src/communication.rs b/boards/communication/src/communication.rs index 4bf7246f..8fa83d5e 100644 --- a/boards/communication/src/communication.rs +++ b/boards/communication/src/communication.rs @@ -45,6 +45,10 @@ use systick_monotonic::fugit::RateExtU32; use typenum::{U0, U128, U32, U64}; use atsamd_hal::dmac::Transfer; +// use embedded_alloc::Heap; + + + pub struct Capacities; impl mcan::messageram::Capacities for Capacities { @@ -215,8 +219,8 @@ impl CanDevice0 { } } -pub static mut BUF_DST: RadioBuffer = &mut [0; 255]; -pub static mut BUF_DST2: RadioBuffer = &mut [0; 255]; +pub static mut BUF_DST: RadioBuffer = &mut [0; 5]; +pub static mut BUF_DST2: RadioBuffer = &mut [0; 5]; pub struct RadioDevice { uart: Uart, @@ -255,7 +259,7 @@ impl RadioDevice { mav_sequence: 0, }, gclk0, - xfer + xfer, ) } pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { @@ -282,7 +286,9 @@ impl RadioDevice { } pub struct RadioManager { - xfer: RadioTransfer, + xfer: Option, + // chan0: Option>, + // source: Option>, buf_select: bool, } @@ -291,7 +297,10 @@ impl RadioManager { xfer: RadioTransfer, ) -> Self { RadioManager { - xfer, + xfer: Some(xfer), + // xfer: Some(xfer), + // chan0: None, + // source: None, buf_select: false, } } @@ -312,21 +321,65 @@ impl RadioManager { pub fn radio_dma(cx: crate::app::radio_dma::Context) { let manager = cx.local.radio_manager; + // match manager.xfer { + // Some(xfer) => { + // if xfer.complete() { + // let (chan0, source, payload) = xfer.stop(); + // manager.chan0 = Some(chan0); + // manager.source = Some(source); + // manager.process_message(payload) + // } + // } + // None => { + // if let Some(chan0) = manager.chan0.take() { + // let source = manager.source.take().unwrap(); + // // static mut dest: RadioBuffer = &mut [0; 5]; + // let xfer = manager.xfer.get_or_insert( + // dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).unwrap() + // ); + // manager.xfer = Some(*xfer); + // } + // } + // } + // let mut xfer = manager.xfer.take().unwrap(); + match &mut manager.xfer { + Some(xfer) => { + if xfer.complete() { + let (chan0, source, buf) = manager.xfer.take().unwrap().stop(); + let mut xfer = dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).expect("f").begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); + manager.process_message(buf); + unsafe{BUF_DST.copy_from_slice(&[0;5])}; + xfer.block_transfer_interrupt(); + manager.xfer = Some(xfer); + } + } + None => { + info!("none"); + } + } - if manager.xfer.complete() { - cx.shared.em.run(|| { - let buf = match manager.buf_select { - false => { - manager.buf_select = true; - manager.xfer.recycle_source(unsafe{&mut *BUF_DST})? - } - true => { - manager.buf_select = false; - manager.xfer.recycle_source(unsafe{&mut *BUF_DST2})? - } - }; - manager.process_message(buf); - Ok(()) - }) - } -} \ No newline at end of file + // if manager.xfer.complete() { + // cx.shared.em.run(|| { + + // let buf = match manager.buf_select { + // false => { + // manager.buf_select = true; + // unsafe{BUF_DST.copy_from_slice(&[0; 5])}; + // manager.xfer.recycle_source(unsafe{&mut *BUF_DST})? + // } + // true => { + // manager.buf_select = false; + // unsafe{BUF_DST2.copy_from_slice(&[0; 5])}; + // manager.xfer.recycle_source(unsafe{&mut *BUF_DST2})? + // } + // }; + // manager.process_message(buf); + // Ok(()) + // }) + // } +} + +// pub fn produce_dest() -> RadioBuffer { +// let mut dest: RadioBuffer = &mut [0; 5]; +// dest +// } \ No newline at end of file diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index 0fbc99dc..a91360d7 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -46,7 +46,7 @@ mod app { struct Local { led: Pin, radio: RadioDevice, - sd_manager: SdManager, + // sd_manager: SdManager, radio_manager: RadioManager, } @@ -110,16 +110,16 @@ mod app { let radio_manager = RadioManager::new(xfer); /* SD config */ - let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); - let sd_manager = SdManager::new( - &mclk, - peripherals.SERCOM4, - pclk_sd.freq(), - pins.pb14.into_push_pull_output(), - pins.pb13.into_push_pull_output(), - pins.pb15.into_push_pull_output(), - pins.pb12.into_push_pull_output(), - ); + // let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); + // let sd_manager = SdManager::new( + // &mclk, + // peripherals.SERCOM4, + // pclk_sd.freq(), + // pins.pb14.into_push_pull_output(), + // pins.pb13.into_push_pull_output(), + // pins.pb15.into_push_pull_output(), + // pins.pb12.into_push_pull_output(), + // ); /* Status LED */ let led = pins.pa05.into_push_pull_output(); @@ -137,7 +137,8 @@ mod app { data_manager: DataManager::new(), can0, }, - Local { led, radio, sd_manager, radio_manager }, + Local { led, radio, radio_manager }, + // Local { led, radio, sd_manager, radio_manager }, init::Monotonics(mono), ) } @@ -188,16 +189,16 @@ mod app { }); } - #[task(capacity = 10, local = [sd_manager], shared = [&em])] - fn sd_dump(mut cx: sd_dump::Context, m: Message) { - let mut manager = cx.local.sd_manager; - cx.shared.em.run(|| { - let mut buf = [0u8; 256]; - let msg_ser = postcard::to_slice_cobs(&m, &mut buf)?; - manager.write(msg_ser)?; - Ok(()) - }); - } + // #[task(capacity = 10, local = [sd_manager], shared = [&em])] + // fn sd_dump(mut cx: sd_dump::Context, m: Message) { + // let mut manager = cx.local.sd_manager; + // cx.shared.em.run(|| { + // let mut buf = [0u8; 256]; + // let msg_ser = postcard::to_slice_cobs(&m, &mut buf)?; + // manager.write(msg_ser)?; + // Ok(()) + // }); + // } /** * Sends information about the sensors. @@ -217,7 +218,7 @@ mod app { cx.shared.em.run(|| { for msg in messages { spawn!(send_gs, msg.clone())?; - spawn!(sd_dump, msg)?; + // spawn!(sd_dump, msg)?; } Ok(()) }); @@ -242,7 +243,7 @@ mod app { } extern "Rust" { - #[task(binds = DMAC_0, shared=[&em], local=[radio_manager])] + #[task(priority = 3, binds = DMAC_0, shared=[&em], local=[radio_manager])] fn radio_dma(context: radio_dma::Context); } } diff --git a/boards/communication/src/types.rs b/boards/communication/src/types.rs index 9b2f1b2b..412b7270 100644 --- a/boards/communication/src/types.rs +++ b/boards/communication/src/types.rs @@ -39,4 +39,4 @@ pub type RadioTransfer = dmac::Transfer< dmac::Channel, BufferPair, RadioBuffer>, >; -pub type RadioBuffer = &'static mut [u8; 255]; \ No newline at end of file +pub type RadioBuffer = &'static mut [u8; 5]; \ No newline at end of file diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index 16207d07..10a7cb7e 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -16,7 +16,7 @@ use common_arm::*; use communication::Capacities; use data_manager::DataManager; use hal::dmac; - +use defmt::info; use hal::gpio::Pins; use hal::gpio::{PB16, PB17}; use hal::gpio::{Pin, PushPullOutput}; @@ -192,7 +192,8 @@ mod app { cx.shared.em.run(|| { for msg in messages { - spawn!(send_internal, msg)?; + // spawn!(send_internal, msg)?; + info!("{}", msg); } Ok(()) }); diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index e8f787d5..63f8249d 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -14,6 +14,7 @@ use core::mem::size_of; use core::ptr; // use atsamd_hal::time::*; use atsamd_hal::prelude::*; +use defmt::info; // use crate::app::sbg_sd_task as sbg_sd; use crate::app::{sbg_handle_data}; @@ -32,7 +33,7 @@ static HEAP: Heap = Heap::empty(); pub struct SBGManager { sbg_device: SBG, - xfer: SBGTransfer, + xfer: Option, buf_select: bool, } @@ -86,7 +87,7 @@ impl SBGManager { SBGManager { sbg_device: sbg, buf_select: false, - xfer, + xfer: Some(xfer), } } } @@ -118,24 +119,40 @@ pub fn sbg_handle_data(mut cx: sbg_handle_data::Context, data: CallbackData) { pub fn sbg_dma(cx: crate::app::sbg_dma::Context) { let sbg = cx.local.sbg_manager; - if sbg.xfer.complete() { - cx.shared.em.run(|| { - let buf = match sbg.buf_select { - false => { - sbg.buf_select = true; - sbg.xfer.recycle_source(unsafe { &mut *BUF_DST })? - } - true => { - sbg.buf_select = false; - sbg.xfer.recycle_source(unsafe { &mut *BUF_DST2 })? - } - }; - // let buf_clone = buf.clone(); - sbg.sbg_device.read_data(buf); - // spawn!(sbg_sd(buf_clone))?; - Ok(()) - }); + match &mut sbg.xfer { + Some(xfer) => { + if xfer.complete() { + let (chan0, source, buf) = sbg.xfer.take().unwrap().stop(); + let mut xfer = dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).unwrap().begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); + sbg.sbg_device.read_data(buf); + // unsafe{BUF_DST.copy_from_slice(&[0;SBG_BUFFER_SIZE])}; + xfer.block_transfer_interrupt(); + sbg.xfer = Some(xfer); + } + } + None => { + info!("None"); + } } + + // if sbg.xfer.complete() { + // cx.shared.em.run(|| { + // let buf = match sbg.buf_select { + // false => { + // sbg.buf_select = true; + // sbg.xfer.recycle_source(unsafe { &mut *BUF_DST })? + // } + // true => { + // sbg.buf_select = false; + // sbg.xfer.recycle_source(unsafe { &mut *BUF_DST2 })? + // } + // }; + // // let buf_clone = buf.clone(); + // sbg.sbg_device.read_data(buf); + // // spawn!(sbg_sd(buf_clone))?; + // Ok(()) + // }); + // } } /// Stored right before an allocation. Stores information that is needed to deallocate memory. diff --git a/libraries/sbg-rs/src/sbg.rs b/libraries/sbg-rs/src/sbg.rs index aabb65c4..9902c7e3 100644 --- a/libraries/sbg-rs/src/sbg.rs +++ b/libraries/sbg-rs/src/sbg.rs @@ -16,7 +16,7 @@ use core::ffi::{c_void}; use core::ptr::null_mut; use core::slice::{from_raw_parts, from_raw_parts_mut}; use core::sync::atomic::AtomicUsize; -use defmt::{flush, warn}; +use defmt::{flush, warn, error}; use embedded_hal::serial::Write; use hal::gpio::{PB16, PB17, PB03, PB02}; use hal::sercom::uart::Duplex; @@ -493,7 +493,7 @@ pub unsafe extern "C" fn sbgPlatformDebugLogMsg( match logType { // silently handle errors - // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR => error!("SBG Error {} {}", file, function), + _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR => error!("SBG Error"), _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING => warn!("SBG Warning"), // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_INFO => info!("SBG Info {} {}", file, function), // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_DEBUG => debug!("SBG Debug {} {}", file, function), From 56a20306b66ef32238ff80ffa5b5dbbe78f6dfb1 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sat, 19 Aug 2023 10:42:17 -0400 Subject: [PATCH 10/30] IDK --- Cargo.lock | 1 + boards/sensor/src/main.rs | 4 ++-- boards/sensor/src/sbg_manager.rs | 2 +- libraries/sbg-rs/Cargo.toml | 1 + libraries/sbg-rs/src/sbg.rs | 3 ++- 5 files changed, 7 insertions(+), 4 deletions(-) diff --git a/Cargo.lock b/Cargo.lock index 3999cfae..a3fa55e1 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -1057,6 +1057,7 @@ dependencies = [ "cortex-m-rt", "defmt", "embedded-hal", + "heapless", "messages", "nb 1.1.0", ] diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index 10a7cb7e..c86a1570 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -192,8 +192,8 @@ mod app { cx.shared.em.run(|| { for msg in messages { - // spawn!(send_internal, msg)?; - info!("{}", msg); + spawn!(send_internal, msg)?; + // info!("{}", msg); } Ok(()) }); diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index 63f8249d..9b591446 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -125,7 +125,7 @@ pub fn sbg_dma(cx: crate::app::sbg_dma::Context) { let (chan0, source, buf) = sbg.xfer.take().unwrap().stop(); let mut xfer = dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).unwrap().begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); sbg.sbg_device.read_data(buf); - // unsafe{BUF_DST.copy_from_slice(&[0;SBG_BUFFER_SIZE])}; + unsafe{BUF_DST.copy_from_slice(&[0;SBG_BUFFER_SIZE])}; xfer.block_transfer_interrupt(); sbg.xfer = Some(xfer); } diff --git a/libraries/sbg-rs/Cargo.toml b/libraries/sbg-rs/Cargo.toml index efd546bc..2e049b76 100644 --- a/libraries/sbg-rs/Cargo.toml +++ b/libraries/sbg-rs/Cargo.toml @@ -14,6 +14,7 @@ cortex-m = { workspace = true } cortex-m-rt = "^0.7.0" messages = { path = "../../libraries/messages" } common-arm = { path = "../../libraries/common-arm" } +heapless = "0.7.16" [build-dependencies] cmake = "0.1" \ No newline at end of file diff --git a/libraries/sbg-rs/src/sbg.rs b/libraries/sbg-rs/src/sbg.rs index 9902c7e3..7faa4857 100644 --- a/libraries/sbg-rs/src/sbg.rs +++ b/libraries/sbg-rs/src/sbg.rs @@ -23,6 +23,7 @@ use hal::sercom::uart::Duplex; use hal::sercom::uart::{self, EightBit, Uart}; use hal::sercom::{IoSet1, IoSet6, Sercom5}; use messages::sensor::*; +use heapless::Deque; type Pads = uart::PadsFromIds; type PadsCDC = uart::PadsFromIds; @@ -493,7 +494,7 @@ pub unsafe extern "C" fn sbgPlatformDebugLogMsg( match logType { // silently handle errors - _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR => error!("SBG Error"), + // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR => error!("SBG Error"), _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING => warn!("SBG Warning"), // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_INFO => info!("SBG Info {} {}", file, function), // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_DEBUG => debug!("SBG Debug {} {}", file, function), From 7326942e4322a0004ce8124c51597227d8d61841 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sat, 19 Aug 2023 13:13:42 -0400 Subject: [PATCH 11/30] Final Recovery algo --- boards/recovery/src/data_manager.rs | 11 ++- boards/recovery/src/main.rs | 2 +- boards/recovery/src/state_machine/mod.rs | 2 +- boards/sensor/src/main.rs | 2 +- libraries/sbg-rs/src/sbg.rs | 100 +++++++++++++---------- 5 files changed, 71 insertions(+), 46 deletions(-) diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index 52f523fa..e2b29818 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -7,7 +7,7 @@ use messages::Message; use defmt::{info}; const MAIN_HEIGHT: f32 = 500.0; -const HEIGHT_MIN: f32 = 900.0; +const HEIGHT_MIN: f32 = 300.0; pub struct DataManager { pub air: Option, @@ -36,6 +36,13 @@ impl DataManager { } /// Returns true if the rocket is descending pub fn is_falling(&self) -> bool { + // if let Some(air) = &self.air { + // if air.altitude < HEIGHT_MIN { + // return false + // } + // } else { + // return false; + // } if self.historical_barometer_altitude.len() < 8 { return false; } @@ -53,7 +60,7 @@ impl DataManager { prev = i; } match avg_sum / 7.0 { // 7 because we have 8 points. - x if x > -5.0 || x < -120.0 => { + x if x > -2.0 || x < -100.0 => { info!("avg: {}", avg_sum / 7.0); return false; } diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 4270680b..4cdbcc27 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -148,7 +148,7 @@ mod app { // !! Question, will this error and then never spawn again? Should I just keep trying to spawn it and not care // to use the error manager. cx.shared.em.run(|| { - spawn_after!(run_sm, ExtU64::secs(2))?; + spawn_after!(run_sm, ExtU64::millis(500))?; Ok(()) }) } diff --git a/boards/recovery/src/state_machine/mod.rs b/boards/recovery/src/state_machine/mod.rs index 34e3689b..6dd6fdc7 100644 --- a/boards/recovery/src/state_machine/mod.rs +++ b/boards/recovery/src/state_machine/mod.rs @@ -41,7 +41,7 @@ pub struct StateMachine { // Define some functions to interact with the state machine impl StateMachine { pub fn new() -> Self { - let state = Ascent {}; + let state = Initializing {}; StateMachine { state: state.into(), diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index c86a1570..413ba4aa 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -197,7 +197,7 @@ mod app { } Ok(()) }); - spawn_after!(sensor_send, ExtU64::millis(250)).ok(); + spawn_after!(sensor_send, ExtU64::millis(100)).ok(); } /** diff --git a/libraries/sbg-rs/src/sbg.rs b/libraries/sbg-rs/src/sbg.rs index 7faa4857..1944bcaf 100644 --- a/libraries/sbg-rs/src/sbg.rs +++ b/libraries/sbg-rs/src/sbg.rs @@ -16,7 +16,7 @@ use core::ffi::{c_void}; use core::ptr::null_mut; use core::slice::{from_raw_parts, from_raw_parts_mut}; use core::sync::atomic::AtomicUsize; -use defmt::{flush, warn, error}; +use defmt::{flush, warn, error, info}; use embedded_hal::serial::Write; use hal::gpio::{PB16, PB17, PB03, PB02}; use hal::sercom::uart::Duplex; @@ -43,6 +43,8 @@ static mut BUF_INDEX: AtomicUsize = AtomicUsize::new(0); */ static mut BUF: &[u8; SBG_BUFFER_SIZE] = &[0; SBG_BUFFER_SIZE]; +static mut DEQ: Deque = Deque::new(); + /** * Holds the RTC instance. This is used to get the current time. */ @@ -150,7 +152,10 @@ impl SBG { pub fn read_data(&mut self, buffer: &'static [u8; SBG_BUFFER_SIZE]) { // SAFETY: We are assigning a static mut variable. // Buf can only be accessed from functions called by sbgEComHandle after this assignment. - unsafe { BUF = buffer }; + // unsafe { BUF = buffer }; + for i in buffer { + unsafe{DEQ.push_back(*i)}; + } // SAFETY: We are assigning a static variable. // This is safe because are the only thread reading since SBG is locked. unsafe { @@ -286,46 +291,59 @@ impl SBG { // SAFETY: We are accessing a static mut variable. // This is safe because we ensure that the variable is only accessed in this function. let index = unsafe { *BUF_INDEX.get_mut() }; - - if index + bytesToRead > SBG_BUFFER_SIZE { - // Read what we can. - bytesToRead = SBG_BUFFER_SIZE - index; - if bytesToRead == 0 { - // SAFETY: We are accessing a mutable pointer. - // This is safe because the pointer cannot be null - // and the SBGECom library ensures that the pointer - // is not accessed during the lifetime of this function. - unsafe { *pBytesRead = 0 }; - return _SbgErrorCode_SBG_READ_ERROR; // no data + let mut readBytes = 0; + for i in 0..(bytesToRead) { + if let Some(front) = DEQ.pop_front() { + readBytes += 1; + array[i] = front; + } else { + // info!("No item in dequeue"); + break; } - let end = bytesToRead + index; - // SAFETY: We are accessing a static mut variable. - // This is safe because we ensure that the variable is only accessed in this function. - array[0..bytesToRead - 1].copy_from_slice(unsafe { &BUF[index..end - 1] }); - // SAFETY: We are accessing a static mut variable. - // This is safe because we ensure that the variable is only accessed in this function. - unsafe { *BUF_INDEX.get_mut() = index + bytesToRead }; - // SAFETY: We are accessing a mutable pointer. - // This is safe because the pointer cannot be null - // and the SBGECom library ensures that the pointer - // is not accessed during the lifetime of this function. - unsafe { *pBytesRead = bytesToRead }; - return _SbgErrorCode_SBG_NO_ERROR; } - let end = bytesToRead + index; - // SAFETY: We are accessing a static mut variable. - // This is safe because we ensure that the variable is only accessed in this function. - array[0..bytesToRead - 1].copy_from_slice(unsafe { &BUF[index..end - 1] }); - // SAFETY: We are accessing a static mut variable. - // This is safe because we ensure that the variable is only accessed in this function. - unsafe { *BUF_INDEX.get_mut() = index + bytesToRead }; - // SAFETY: We are accessing a mutable pointer. - // This is safe because the pointer cannot be null - // and the SBGECom library ensures that the pointer - // is not accessed during the lifetime of this function. - unsafe { *pBytesRead = bytesToRead }; - - _SbgErrorCode_SBG_NO_ERROR + // info!("Bytes Read {}", readBytes); + unsafe {*pBytesRead = readBytes}; + return _SbgErrorCode_SBG_NO_ERROR; + + // if index + bytesToRead > SBG_BUFFER_SIZE { + // // Read what we can. + // bytesToRead = SBG_BUFFER_SIZE - index; + // if bytesToRead == 0 { + // // SAFETY: We are accessing a mutable pointer. + // // This is safe because the pointer cannot be null + // // and the SBGECom library ensures that the pointer + // // is not accessed during the lifetime of this function. + // unsafe { *pBytesRead = 0 }; + // return _SbgErrorCode_SBG_READ_ERROR; // no data + // } + // let end = bytesToRead + index; + // // SAFETY: We are accessing a static mut variable. + // // This is safe because we ensure that the variable is only accessed in this function. + // array[0..bytesToRead - 1].copy_from_slice(unsafe { &BUF[index..end - 1] }); + // // SAFETY: We are accessing a static mut variable. + // // This is safe because we ensure that the variable is only accessed in this function. + // unsafe { *BUF_INDEX.get_mut() = index + bytesToRead }; + // // SAFETY: We are accessing a mutable pointer. + // // This is safe because the pointer cannot be null + // // and the SBGECom library ensures that the pointer + // // is not accessed during the lifetime of this function. + // unsafe { *pBytesRead = bytesToRead }; + // return _SbgErrorCode_SBG_NO_ERROR; + // } + // let end = bytesToRead + index; + // // SAFETY: We are accessing a static mut variable. + // // This is safe because we ensure that the variable is only accessed in this function. + // array[0..bytesToRead - 1].copy_from_slice(unsafe { &BUF[index..end - 1] }); + // // SAFETY: We are accessing a static mut variable. + // // This is safe because we ensure that the variable is only accessed in this function. + // unsafe { *BUF_INDEX.get_mut() = index + bytesToRead }; + // // SAFETY: We are accessing a mutable pointer. + // // This is safe because the pointer cannot be null + // // and the SBGECom library ensures that the pointer + // // is not accessed during the lifetime of this function. + // unsafe { *pBytesRead = bytesToRead }; + + // _SbgErrorCode_SBG_NO_ERROR } /** @@ -494,7 +512,7 @@ pub unsafe extern "C" fn sbgPlatformDebugLogMsg( match logType { // silently handle errors - // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR => error!("SBG Error"), + _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR => error!("SBG Error"), _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING => warn!("SBG Warning"), // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_INFO => info!("SBG Info {} {}", file, function), // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_DEBUG => debug!("SBG Debug {} {}", file, function), From 652815a5de45c8a2ba9b0b5d503343bac7ae4fc9 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sat, 19 Aug 2023 14:37:55 -0400 Subject: [PATCH 12/30] Update --- boards/communication/src/communication.rs | 20 ++++++++++----- boards/communication/src/data_manager.rs | 31 +++++++++++++++++++++++ boards/communication/src/main.rs | 19 ++++++++++++++ boards/communication/src/types.rs | 2 +- boards/recovery/src/data_manager.rs | 4 ++- boards/recovery/src/main.rs | 5 +++- boards/recovery/src/state_machine/mod.rs | 10 +++++--- libraries/messages/src/command.rs | 7 +++++ 8 files changed, 85 insertions(+), 13 deletions(-) diff --git a/boards/communication/src/communication.rs b/boards/communication/src/communication.rs index 8fa83d5e..070944c2 100644 --- a/boards/communication/src/communication.rs +++ b/boards/communication/src/communication.rs @@ -219,8 +219,8 @@ impl CanDevice0 { } } -pub static mut BUF_DST: RadioBuffer = &mut [0; 5]; -pub static mut BUF_DST2: RadioBuffer = &mut [0; 5]; +pub static mut BUF_DST: RadioBuffer = &mut [0; 255]; +pub static mut BUF_DST2: RadioBuffer = &mut [0; 255]; pub struct RadioDevice { uart: Uart, @@ -268,13 +268,12 @@ impl RadioDevice { let mav_header = mavlink::MavHeader { system_id: 1, component_id: 1, - sequence: self.mav_sequence.wrapping_add(1), + sequence: self.increment_mav_sequence(), }; let mav_message = mavlink::uorocketry::MavMessage::POSTCARD_MESSAGE( mavlink::uorocketry::POSTCARD_MESSAGE_DATA { message: payload }, ); - mavlink::write_versioned_msg( &mut self.uart, mavlink::MavlinkVersion::V2, @@ -283,6 +282,10 @@ impl RadioDevice { )?; Ok(()) } + pub fn increment_mav_sequence(&mut self) -> u8 { + self.mav_sequence = self.mav_sequence.wrapping_add(1); + self.mav_sequence + } } pub struct RadioManager { @@ -305,14 +308,17 @@ impl RadioManager { } } pub fn process_message(&mut self, buf: RadioBuffer) { - info!("Received: {:?}", buf); + // info!("Received: {:?}", buf); + // mavlink::read_versioned_msg(buf, + // mavlink::MavlinkVersion::V2, + // ); match from_bytes::(buf) { Ok(msg) => { info!("Radio: {}", msg); spawn!(send_internal, msg); // dump to the Can Bus } Err(_) => { - info!("Radio unknown msg"); + // info!("Radio unknown msg"); return; } } @@ -348,7 +354,7 @@ pub fn radio_dma(cx: crate::app::radio_dma::Context) { let (chan0, source, buf) = manager.xfer.take().unwrap().stop(); let mut xfer = dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).expect("f").begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); manager.process_message(buf); - unsafe{BUF_DST.copy_from_slice(&[0;5])}; + unsafe{BUF_DST.copy_from_slice(&[0;255])}; xfer.block_transfer_interrupt(); manager.xfer = Some(xfer); } diff --git a/boards/communication/src/data_manager.rs b/boards/communication/src/data_manager.rs index cf8b100b..39c1ad1a 100644 --- a/boards/communication/src/data_manager.rs +++ b/boards/communication/src/data_manager.rs @@ -1,5 +1,6 @@ use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime}; use messages::Message; +use messages::state::{State, StateData}; use defmt::info; #[derive(Clone)] @@ -10,6 +11,7 @@ pub struct DataManager { pub imu: (Option, Option), pub utc_time: Option, pub gps_vel: Option, + pub state: Option, } impl DataManager { @@ -21,6 +23,7 @@ impl DataManager { imu: (None, None), utc_time: None, gps_vel: None, + state: None, } } @@ -36,6 +39,11 @@ impl DataManager { self.gps_vel.clone().map(|x| x.into()), ] } + pub fn clone_states(&self) -> [Option; 1] { + [ + self.state.clone().map(|x| x.into()), + ] + } pub fn handle_data(&mut self, data: Message) { match data.data { messages::Data::Sensor(sensor) => match sensor.data { @@ -64,6 +72,29 @@ impl DataManager { self.utc_time = Some(utc_time_data); } }, + messages::Data::State(state) => match state.data { + _ => { + self.state = Some(state.data); + } + // messages::state::StateData::Abort => { + // self.state = Some(state.data); + // } + // messages::state::StateData::Ascent(ascent) => { + // self.state = Some(ascent); + // } + // messages::state::StateData::Descent(descent) => { + // self.state = Some(descent); + // } + // messages::state::StateData::Initializing(init) => { + // self.state = Some(init); + // } + // messages::state::StateData::TerminalDescent(term) => { + // self.state = Some(term); + // } + // messages::state::StateData::WaitForTakeoff(wait) => { + // self.state = Some(wait); + // } + } _ => {} } } diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index a91360d7..65a16565 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -25,6 +25,7 @@ use hal::gpio::{Pin, PushPullOutput}; use hal::prelude::*; use mcan::messageram::SharedMemory; use messages::sensor::Sensor; +use messages::state::State; use messages::*; use panic_halt as _; use systick_monotonic::*; @@ -225,6 +226,24 @@ mod app { spawn_after!(sensor_send, ExtU64::millis(250)).ok(); } + #[task(shared = [data_manager, &em])] + fn state_send(mut cx: state_send::Context) { + let state_data = cx.shared.data_manager.lock(|data_manager| data_manager.clone_states()); + + let messages = state_data + .into_iter() + .flatten() + .map(|x| Message::new(&monotonics::now(), COM_ID, State::new(x))); + + cx.shared.em.run(|| { + for msg in messages { + spawn!(send_gs, msg.clone())?; + } + Ok(()) + }); + spawn_after!(state_send, ExtU64::secs(5)).ok(); + } + /** * Simple blink task to test the system. * Acts as a heartbeat for the system. diff --git a/boards/communication/src/types.rs b/boards/communication/src/types.rs index 412b7270..9b2f1b2b 100644 --- a/boards/communication/src/types.rs +++ b/boards/communication/src/types.rs @@ -39,4 +39,4 @@ pub type RadioTransfer = dmac::Transfer< dmac::Channel, BufferPair, RadioBuffer>, >; -pub type RadioBuffer = &'static mut [u8; 5]; \ No newline at end of file +pub type RadioBuffer = &'static mut [u8; 255]; \ No newline at end of file diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index e2b29818..0393b84b 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -142,7 +142,9 @@ impl DataManager { spawn!(fire_main); } } - _ => {} + _ => { + info!("unkown"); + } } } } diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 4cdbcc27..c8d834e7 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -145,6 +145,9 @@ mod app { cx.local.state_machine.run(&mut StateMachineContext { shared_resources: &mut cx.shared, }); + cx.shared.data_manager.lock(|data| { + data.set_state(cx.local.state_machine.get_state()); + }); // !! Question, will this error and then never spawn again? Should I just keep trying to spawn it and not care // to use the error manager. cx.shared.em.run(|| { @@ -185,7 +188,7 @@ mod app { rocket_state } else { // This isn't really an error, we just don't have data yet. - spawn_after!(state_send, ExtU64::secs(5))?; + // spawn_after!(state_send, ExtU64::secs(5))?; return Ok(()) }; let board_state = messages::state::State { diff --git a/boards/recovery/src/state_machine/mod.rs b/boards/recovery/src/state_machine/mod.rs index 6dd6fdc7..e6236701 100644 --- a/boards/recovery/src/state_machine/mod.rs +++ b/boards/recovery/src/state_machine/mod.rs @@ -51,13 +51,17 @@ impl StateMachine { pub fn run(&mut self, context: &mut StateMachineContext) { if let Some(new_state) = self.state.step(context) { self.state.exit(); - context.shared_resources.data_manager.lock(|data| { - data.set_state(new_state.clone()); - }); + // context.shared_resources.data_manager.lock(|data| { + // data.set_state(new_state.clone()); + // }); new_state.enter(context); self.state = new_state; } } + + pub fn get_state(&self) -> RocketStates { + self.state.clone() + } } // All events are found here diff --git a/libraries/messages/src/command.rs b/libraries/messages/src/command.rs index e98e317e..4cd33576 100644 --- a/libraries/messages/src/command.rs +++ b/libraries/messages/src/command.rs @@ -2,10 +2,14 @@ use derive_more::From; use defmt::Format; use serde::{Deserialize, Serialize}; +#[cfg(test)] +use proptest_derive::Arbitrary; + #[cfg(feature = "ts")] use ts_rs::TS; #[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] #[cfg_attr(feature = "ts", derive(TS))] #[cfg_attr(feature = "ts", ts(export))] pub struct Command { @@ -13,6 +17,7 @@ pub struct Command { } #[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(test, derive(Arbitrary))] #[cfg_attr(feature = "ts", derive(TS))] #[cfg_attr(feature = "ts", ts(export))] pub enum CommandData { @@ -21,6 +26,7 @@ pub enum CommandData { } #[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(test, derive(Arbitrary))] #[cfg_attr(feature = "ts", derive(TS))] #[cfg_attr(feature = "ts", ts(export))] pub struct DeployDrogue { @@ -28,6 +34,7 @@ pub struct DeployDrogue { } #[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(test, derive(Arbitrary))] #[cfg_attr(feature = "ts", derive(TS))] #[cfg_attr(feature = "ts", ts(export))] pub struct DeployMain { From 06335e343e1eeacbd712f61ece049be1d340e2fa Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sun, 20 Aug 2023 13:56:21 -0400 Subject: [PATCH 13/30] Sensor SD support --- boards/communication/src/communication.rs | 8 +++-- boards/communication/src/data_manager.rs | 23 +++----------- boards/communication/src/main.rs | 29 +++++++++++------ boards/recovery/src/data_manager.rs | 2 +- boards/recovery/src/main.rs | 13 +++----- boards/sensor/src/main.rs | 38 +++++++++++------------ boards/sensor/src/sbg_manager.rs | 23 +++++++------- boards/sensor/src/sd_manager.rs | 12 +++---- libraries/sbg-rs/src/sbg.rs | 2 +- 9 files changed, 71 insertions(+), 79 deletions(-) diff --git a/boards/communication/src/communication.rs b/boards/communication/src/communication.rs index 070944c2..9d49fd45 100644 --- a/boards/communication/src/communication.rs +++ b/boards/communication/src/communication.rs @@ -24,6 +24,7 @@ use common_arm::mcan; use common_arm::mcan::message::{rx, Raw}; use common_arm::mcan::tx_buffers::DynTx; use common_arm::HydraError; +use defmt::flush; use defmt::info; use crate::app::send_internal; use common_arm::spawn; @@ -205,7 +206,8 @@ impl CanDevice0 { for message in &mut self.can.rx_fifo_1 { match from_bytes::(message.data()) { Ok(data) => { - data_manager.handle_data(data); + // data_manager.handle_data(data); + info!("{}", data); } Err(e) => { info!("Error: {:?}", e) @@ -315,10 +317,10 @@ impl RadioManager { match from_bytes::(buf) { Ok(msg) => { info!("Radio: {}", msg); - spawn!(send_internal, msg); // dump to the Can Bus + // spawn!(send_internal, msg); // dump to the Can Bus } Err(_) => { - // info!("Radio unknown msg"); + info!("Radio unknown msg"); return; } } diff --git a/boards/communication/src/data_manager.rs b/boards/communication/src/data_manager.rs index 39c1ad1a..2aad5269 100644 --- a/boards/communication/src/data_manager.rs +++ b/boards/communication/src/data_manager.rs @@ -74,28 +74,13 @@ impl DataManager { }, messages::Data::State(state) => match state.data { _ => { + info!("state: {}", state.data.clone()); self.state = Some(state.data); } - // messages::state::StateData::Abort => { - // self.state = Some(state.data); - // } - // messages::state::StateData::Ascent(ascent) => { - // self.state = Some(ascent); - // } - // messages::state::StateData::Descent(descent) => { - // self.state = Some(descent); - // } - // messages::state::StateData::Initializing(init) => { - // self.state = Some(init); - // } - // messages::state::StateData::TerminalDescent(term) => { - // self.state = Some(term); - // } - // messages::state::StateData::WaitForTakeoff(wait) => { - // self.state = Some(wait); - // } } - _ => {} + _ => { + info!("unkown"); + } } } } diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index 65a16565..fee11451 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -127,6 +127,7 @@ mod app { /* Spawn tasks */ sensor_send::spawn().ok(); + state_send::spawn().ok(); blink::spawn().ok(); /* Monotonic clock */ @@ -228,17 +229,25 @@ mod app { #[task(shared = [data_manager, &em])] fn state_send(mut cx: state_send::Context) { - let state_data = cx.shared.data_manager.lock(|data_manager| data_manager.clone_states()); - - let messages = state_data - .into_iter() - .flatten() - .map(|x| Message::new(&monotonics::now(), COM_ID, State::new(x))); + let state_data = cx.shared.data_manager.lock(|data_manager| { + if let Some(state) = &data_manager.state { + state.clone() + } else { + messages::state::StateData::Abort + } + }); + let message = Message::new(&monotonics::now(), COM_ID, State::new(state_data)); + // let messages = state_data + // .into_iter() + // .flatten() + // .map(|x| Message::new(&monotonics::now(), COM_ID, State::new(x))); cx.shared.em.run(|| { - for msg in messages { - spawn!(send_gs, msg.clone())?; - } + spawn!(send_gs, message.clone())?; + // for msg in messages { + // // spawn!(send_gs, msg.clone())?; + // info!("state: {}", msg); + // } Ok(()) }); spawn_after!(state_send, ExtU64::secs(5)).ok(); @@ -262,7 +271,7 @@ mod app { } extern "Rust" { - #[task(priority = 3, binds = DMAC_0, shared=[&em], local=[radio_manager])] + #[task(binds = DMAC_0, shared=[&em], local=[radio_manager])] fn radio_dma(context: radio_dma::Context); } } diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index 0393b84b..2ccc94bb 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -60,7 +60,7 @@ impl DataManager { prev = i; } match avg_sum / 7.0 { // 7 because we have 8 points. - x if x > -2.0 || x < -100.0 => { + x if !(-100.0..=-2.0).contains(&x) => { info!("avg: {}", avg_sum / 7.0); return false; } diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index c8d834e7..6cc8f4c6 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -139,7 +139,7 @@ mod app { /// Runs the state machine. /// This takes control of the shared resources. - #[task(local = [state_machine], shared = [can0, gpio, data_manager, &em])] + #[task(priority = 3, local = [state_machine], shared = [can0, gpio, data_manager, &em])] fn run_sm(mut cx: run_sm::Context) { cx.shared.data_manager.lock(|dm| info!("alt: {}", dm.get_alt())); cx.local.state_machine.run(&mut StateMachineContext { @@ -150,10 +150,7 @@ mod app { }); // !! Question, will this error and then never spawn again? Should I just keep trying to spawn it and not care // to use the error manager. - cx.shared.em.run(|| { - spawn_after!(run_sm, ExtU64::millis(500))?; - Ok(()) - }) + spawn_after!(run_sm, ExtU64::millis(500)).ok(); } /// Handles the CAN0 interrupt. @@ -178,7 +175,6 @@ mod app { /// Sends info about the current state of the system. #[task(shared = [data_manager, &em])] fn state_send(mut cx: state_send::Context) { - let em_error = cx.shared.em.has_error(); cx.shared.em.run(|| { let rocket_state = cx .shared @@ -188,7 +184,6 @@ mod app { rocket_state } else { // This isn't really an error, we just don't have data yet. - // spawn_after!(state_send, ExtU64::secs(5))?; return Ok(()) }; let board_state = messages::state::State { @@ -196,9 +191,9 @@ mod app { }; let message = Message::new(&monotonics::now(), COM_ID, board_state); spawn!(send_internal, message)?; - spawn_after!(state_send, ExtU64::secs(5))?; Ok(()) - }) + }); + spawn_after!(state_send, ExtU64::secs(2)); } /// Simple blink task to test the system. diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index 413ba4aa..7c59aca6 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -25,10 +25,11 @@ use mcan::messageram::SharedMemory; use messages::sensor::Sensor; use messages::*; use panic_halt as _; -// use sbg_manager::{sbg_dma, sbg_handle_data, sbg_sd_task, SBGManager}; -use sbg_manager::{sbg_dma, sbg_handle_data, SBGManager}; +use sd_manager::SdManager; +use sbg_manager::{sbg_dma, sbg_handle_data, sbg_sd_task, SBGManager}; +//use sbg_manager::{sbg_dma, sbg_handle_data, SBGManager}; -use sbg_rs::sbg::{CallbackData}; +use sbg_rs::sbg::{CallbackData, SBG_BUFFER_SIZE}; use systick_monotonic::*; use types::*; @@ -42,7 +43,7 @@ mod app { em: ErrorManager, data_manager: DataManager, can: communication::CanDevice0, - // sd_manager: SdManager, + sd_manager: SdManager, } #[local] @@ -98,16 +99,16 @@ mod app { ); // /* SD config */ - // let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); - // let sd_manager = SdManager::new( - // &mclk, - // peripherals.SERCOM4, - // pclk_sd.freq(), - // pins.pb10.into_push_pull_output(), - // pins.pb09.into_push_pull_output(), - // pins.pb11.into_push_pull_output(), - // pins.pb08.into_push_pull_output(), - // ); + let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); + let sd_manager = SdManager::new( + &mclk, + peripherals.SERCOM4, + pclk_sd.freq(), + pins.pb10.into_push_pull_output(), + pins.pb09.into_push_pull_output(), + pins.pb11.into_push_pull_output(), + pins.pb08.into_push_pull_output(), + ); /* SBG config */ let (pclk_sbg, gclk0) = Pclk::enable(tokens.pclks.sercom5, gclk0); @@ -140,7 +141,7 @@ mod app { em: ErrorManager::new(), data_manager: DataManager::new(), can, - // sd_manager, + sd_manager, }, Local { led_green, @@ -157,7 +158,7 @@ mod app { // loop {} // } - #[task(priority = 3, binds = CAN0, shared = [can])] + #[task(binds = CAN0, shared = [can])] fn can0(mut cx: can0::Context) { cx.shared.can.lock(|can| { can.process_data(); @@ -193,7 +194,6 @@ mod app { cx.shared.em.run(|| { for msg in messages { spawn!(send_internal, msg)?; - // info!("{}", msg); } Ok(()) }); @@ -219,8 +219,8 @@ mod app { } extern "Rust" { - // #[task(capacity = 3, shared = [&em, sd_manager])] - // fn sbg_sd_task(context: sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]); + #[task(capacity = 3, shared = [&em, sd_manager])] + fn sbg_sd_task(context: sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]); #[task(binds = DMAC_0, shared = [&em], local = [sbg_manager])] fn sbg_dma(context: sbg_dma::Context); diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index 9b591446..d41b477f 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -15,8 +15,8 @@ use core::ptr; // use atsamd_hal::time::*; use atsamd_hal::prelude::*; use defmt::info; - -// use crate::app::sbg_sd_task as sbg_sd; +use common_arm::spawn; +use crate::app::sbg_sd_task as sbg_sd; use crate::app::{sbg_handle_data}; use atsamd_hal::sercom::{uart, Sercom, Sercom5}; use embedded_alloc::Heap; @@ -103,15 +103,14 @@ pub fn sbg_handle_data(mut cx: sbg_handle_data::Context, data: CallbackData) { }); } -// pub fn sbg_sd_task(mut cx: crate::app::sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]) { -// cx.shared.sd_manager.lock(|manager| { -// if let Ok(mut file) = manager.open_file("sbg.bin") { -// manager.write(&mut file, &data); -// manager.close_file(file); -// info!("SBG data written to SD card"); -// } -// }); -// } +pub fn sbg_sd_task(mut cx: crate::app::sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]) { + cx.shared.sd_manager.lock(|manager| { + if let Ok(mut file) = manager.open_file("sbg.txt") { + manager.write(&mut file, &data); + manager.close_file(file); + } + }); +} /** * Handles the DMA interrupt. * Handles the SBG data. @@ -124,9 +123,11 @@ pub fn sbg_dma(cx: crate::app::sbg_dma::Context) { if xfer.complete() { let (chan0, source, buf) = sbg.xfer.take().unwrap().stop(); let mut xfer = dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).unwrap().begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); + let buf_clone = buf.clone(); sbg.sbg_device.read_data(buf); unsafe{BUF_DST.copy_from_slice(&[0;SBG_BUFFER_SIZE])}; xfer.block_transfer_interrupt(); + spawn!(sbg_sd(buf_clone)); sbg.xfer = Some(xfer); } } diff --git a/boards/sensor/src/sd_manager.rs b/boards/sensor/src/sd_manager.rs index 9905659f..f062e1d7 100644 --- a/boards/sensor/src/sd_manager.rs +++ b/boards/sensor/src/sd_manager.rs @@ -44,7 +44,7 @@ pub struct SdManager { } impl SdManager { - pub fn _new( + pub fn new( mclk: &pac::MCLK, sercom: pac::SERCOM4, freq: Hertz, @@ -111,14 +111,14 @@ impl SdManager { file, } } - pub fn _write( + pub fn write( &mut self, file: &mut sd::File, buffer: &[u8], ) -> Result> { self.sd_controller.write(&mut self.volume, file, buffer) } - pub fn _write_str( + pub fn write_str( &mut self, file: &mut sd::File, msg: &str, @@ -126,7 +126,7 @@ impl SdManager { let buffer: &[u8] = msg.as_bytes(); self.sd_controller.write(&mut self.volume, file, buffer) } - pub fn _open_file(&mut self, file_name: &str) -> Result> { + pub fn open_file(&mut self, file_name: &str) -> Result> { self.sd_controller.open_file_in_dir( &mut self.volume, &self.root_directory, @@ -134,10 +134,10 @@ impl SdManager { sd::Mode::ReadWriteCreateOrTruncate, ) } - pub fn _close_file(&mut self, file: sd::File) -> Result<(), sd::Error> { + pub fn close_file(&mut self, file: sd::File) -> Result<(), sd::Error> { self.sd_controller.close_file(&self.volume, file) } - pub fn _close(mut self) { + pub fn close(mut self) { self.sd_controller .close_dir(&self.volume, self.root_directory); } diff --git a/libraries/sbg-rs/src/sbg.rs b/libraries/sbg-rs/src/sbg.rs index 1944bcaf..2d4a66c4 100644 --- a/libraries/sbg-rs/src/sbg.rs +++ b/libraries/sbg-rs/src/sbg.rs @@ -512,7 +512,7 @@ pub unsafe extern "C" fn sbgPlatformDebugLogMsg( match logType { // silently handle errors - _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR => error!("SBG Error"), + // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR => error!("SBG Error"), _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING => warn!("SBG Warning"), // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_INFO => info!("SBG Info {} {}", file, function), // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_DEBUG => debug!("SBG Debug {} {}", file, function), From 3122ac158700aa3a9c67f4301b6613a4f2ea556c Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sun, 20 Aug 2023 16:33:06 -0400 Subject: [PATCH 14/30] Add Power Board --- boards/communication/src/data_manager.rs | 3 + boards/power/Cargo.toml | 21 +++ boards/power/src/communication.rs | 185 +++++++++++++++++++++++ boards/power/src/data_manager.rs | 47 ++++++ boards/power/src/main.rs | 158 +++++++++++++++++++ boards/power/src/types.rs | 5 + boards/recovery/src/data_manager.rs | 3 + 7 files changed, 422 insertions(+) create mode 100644 boards/power/Cargo.toml create mode 100644 boards/power/src/communication.rs create mode 100644 boards/power/src/data_manager.rs create mode 100644 boards/power/src/main.rs create mode 100644 boards/power/src/types.rs diff --git a/boards/communication/src/data_manager.rs b/boards/communication/src/data_manager.rs index 2aad5269..794c4a0b 100644 --- a/boards/communication/src/data_manager.rs +++ b/boards/communication/src/data_manager.rs @@ -70,6 +70,9 @@ impl DataManager { } messages::sensor::SensorData::UtcTime(utc_time_data) => { self.utc_time = Some(utc_time_data); + }, + _ => { + info!("impl power related"); } }, messages::Data::State(state) => match state.data { diff --git a/boards/power/Cargo.toml b/boards/power/Cargo.toml new file mode 100644 index 00000000..37dfe3bd --- /dev/null +++ b/boards/power/Cargo.toml @@ -0,0 +1,21 @@ +[package] +name = "power" +version = "0.1.0" +edition = "2021" + +# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html + +[dependencies] +cortex-m = { workspace = true } +cortex-m-rt = "^0.7.0" +cortex-m-rtic = "1.1.3" +panic-halt = "0.2.0" +systick-monotonic = "1.0.1" +defmt = "0.3.2" +postcard = "1.0.2" +heapless = "0.7.16" +common-arm = { path = "../../libraries/common-arm" } +atsamd-hal = { workspace = true } +messages = { path = "../../libraries/messages" } +typenum = "1.16.0" +enum_dispatch = "0.3.11" \ No newline at end of file diff --git a/boards/power/src/communication.rs b/boards/power/src/communication.rs new file mode 100644 index 00000000..20229f15 --- /dev/null +++ b/boards/power/src/communication.rs @@ -0,0 +1,185 @@ +use atsamd_hal as hal; +use hal::can::Dependencies; +use hal::pac::CAN0; +use hal::clock::v2::ahb::AhbClk; +use hal::clock::v2::gclk::Gclk0Id; +use hal::clock::v2::pclk::Pclk; +use hal::clock::v2::types::Can0; +use hal::clock::v2::Source; +use hal::gpio::{Alternate, AlternateI, Pin, I, PA22, PA23}; +use hal::typelevel::Increment; +use common_arm::mcan; +use mcan::message::{rx, Raw}; +use mcan::tx_buffers::DynTx; +use mcan::bus::Can; +use mcan::embedded_can as ecan; +use mcan::interrupt::state::EnabledLine0; // line 0 and 1 are connected +use mcan::interrupt::{Interrupt, OwnedInterruptSet}; +use mcan::message::tx; +use mcan::messageram::SharedMemory; +use mcan::{ + config::{BitTiming, Mode}, + filter::{Action, Filter}, +}; +use common_arm::HydraError; +use messages::Message; +use heapless::Vec; +use defmt::info; +use crate::data_manager::DataManager; +use systick_monotonic::fugit::RateExtU32; +use typenum::{U0, U128, U32, U64}; +use postcard::from_bytes; +pub struct Capacities; + +impl mcan::messageram::Capacities for Capacities { + type StandardFilters = U128; + type ExtendedFilters = U64; + type RxBufferMessage = rx::Message<64>; + type DedicatedRxBuffers = U64; + type RxFifo0Message = rx::Message<64>; + type RxFifo0 = U64; + type RxFifo1Message = rx::Message<64>; + type RxFifo1 = U64; + type TxMessage = tx::Message<64>; + type TxBuffers = U32; + type DedicatedTxBuffers = U0; + type TxEventFifo = U32; +} + +pub struct CanDevice0 { + pub can: Can< + 'static, + Can0, + Dependencies>, Pin>, CAN0>, + Capacities, + >, + line_interrupts: OwnedInterruptSet, +} + +impl CanDevice0 { + pub fn new( + can_rx: Pin, + can_tx: Pin, + pclk_can: Pclk, + ahb_clock: AhbClk, + peripheral: CAN0, + gclk0: S, + can_memory: &'static mut SharedMemory, + loopback: bool, + ) -> (Self, S::Inc) + where + S: Source + Increment, + { + let (can_dependencies, gclk0) = + Dependencies::new(gclk0, pclk_can, ahb_clock, can_rx, can_tx, peripheral); + + let mut can = + mcan::bus::CanConfigurable::new(200.kHz(), can_dependencies, can_memory).unwrap(); + can.config().mode = Mode::Fd { + allow_bit_rate_switching: false, + data_phase_timing: BitTiming::new(500.kHz()), + }; + + if loopback { + can.config().loopback = true; + } + + let interrupts_to_be_enabled = can + .interrupts() + .split( + [ + Interrupt::RxFifo0NewMessage, + Interrupt::RxFifo0Full, + Interrupt::RxFifo0MessageLost, + Interrupt::RxFifo1NewMessage, + Interrupt::RxFifo1Full, + Interrupt::RxFifo1MessageLost, + ] + .into_iter() + .collect(), + ) + .unwrap(); + + // Line 0 and 1 are connected to the same interrupt line + let line_interrupts = can + .interrupt_configuration() + .enable_line_0(interrupts_to_be_enabled); + + // We accept messages from the sensor board as we need data from the sensors. + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo0, + filter: ecan::StandardId::new(messages::sender::Sender::SensorBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Sensor Board filter")); + + // We accept messages from the communication board as we may need to force the deployment of the parachute. + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo1, + filter: ecan::StandardId::new(messages::sender::Sender::CommunicationBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Ground Station filter")); + + let can = can.finalize().unwrap(); + ( + CanDevice0 { + can, + line_interrupts, + }, + gclk0, + ) + } + pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { + let payload: Vec = postcard::to_vec(&m)?; + self.can.tx.transmit_queued( + tx::MessageBuilder { + id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), + frame_type: tx::FrameType::FlexibleDatarate { + payload: &payload[..], + bit_rate_switching: false, + force_error_state_indicator: false, + }, + store_tx_event: None, + } + .build()?, + )?; + Ok(()) + } + pub fn process_data(&mut self, data_manager: &mut DataManager) { + let line_interrupts = &self.line_interrupts; + for interrupt in line_interrupts.iter_flagged() { + match interrupt { + Interrupt::RxFifo0NewMessage => { + for message in &mut self.can.rx_fifo_0 { + match from_bytes::(message.data()) { + Ok(data) => { + data_manager.handle_data(data); + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + Interrupt::RxFifo1NewMessage => { + for message in &mut self.can.rx_fifo_1 { + match from_bytes::(message.data()) { + Ok(data) => { + data_manager.handle_data(data); + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + _ => (), + } + } + } +} \ No newline at end of file diff --git a/boards/power/src/data_manager.rs b/boards/power/src/data_manager.rs new file mode 100644 index 00000000..1a149386 --- /dev/null +++ b/boards/power/src/data_manager.rs @@ -0,0 +1,47 @@ +// import messages +use messages::sensor::{Current, Voltage, Regulator, Temperature, SensorData}; +use messages::Message; + +pub struct DataManager { + pub regulator: [Option; 4], + pub voltage: [Option; 4], + pub current: Option, + pub temperature: [Option; 4], +} + +impl DataManager { + pub fn new() -> Self { + Self { + regulator: [None, None, None, None], + voltage: [None, None, None, None], + current: None, + temperature: [None, None, None, None], + } + } + pub fn clone_power(&self) -> [Option; 13] { + [ + self.regulator[0].clone().map(|x| x.into()), + self.regulator[1].clone().map(|x| x.into()), + self.regulator[2].clone().map(|x| x.into()), + self.regulator[3].clone().map(|x| x.into()), + self.voltage[0].clone().map(|x| x.into()), + self.voltage[1].clone().map(|x| x.into()), + self.voltage[2].clone().map(|x| x.into()), + self.voltage[3].clone().map(|x| x.into()), + self.current.clone().map(|x| x.into()), + self.temperature[0].clone().map(|x| x.into()), + self.temperature[1].clone().map(|x| x.into()), + self.temperature[2].clone().map(|x| x.into()), + self.temperature[3].clone().map(|x| x.into()), + ] + } + pub fn handle_data(&mut self, data: Message) { + // to do + } +} + +impl Default for DataManager { + fn default() -> Self { + Self::new() + } +} \ No newline at end of file diff --git a/boards/power/src/main.rs b/boards/power/src/main.rs new file mode 100644 index 00000000..c3cbd2cf --- /dev/null +++ b/boards/power/src/main.rs @@ -0,0 +1,158 @@ +#![no_std] +#![no_main] + +mod communication; +mod data_manager; +mod types; + +use atsamd_hal as hal; +use hal::clock::v2::pclk::Pclk; +use hal::clock::v2::Source; +use hal::prelude::*; +use hal::gpio::{PB16, PushPullOutput, Pin, PB17, Pins}; +use common_arm::*; +use common_arm::mcan; +use mcan::messageram::SharedMemory; +use communication::Capacities; +use communication::CanDevice0; +use systick_monotonic::*; +use panic_halt as _; +use defmt::info; + +#[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] +mod app { + use hal::gpio::{PA10, Input, Floating, Alternate, B, PA08, C, PA09, PA02, AlternateB}; + + use crate::data_manager::DataManager; + + use super::*; + + #[shared] + struct Shared { + em: ErrorManager, + data_manager: DataManager, + can0: CanDevice0, + } + + #[local] + struct Local { + led_green: Pin, + led_red: Pin, + adc_test: hal::adc::Adc, + adc_pin: Pin, + } + + #[monotonic(binds = SysTick, default = true)] + type SysMono = Systick<100>; // 100 Hz / 10 ms granularity + + #[init(local = [ + #[link_section = ".can"] + can_memory: SharedMemory = SharedMemory::new() + ])] + fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { + let mut peripherals = cx.device; + let core = cx.core; + let pins = Pins::new(peripherals.PORT); + + /* Clock setup */ + let (_, clocks, tokens) = hal::clock::v2::clock_system_at_reset( + peripherals.OSCCTRL, + peripherals.OSC32KCTRL, + peripherals.GCLK, + peripherals.MCLK, + &mut peripherals.NVMCTRL, + ); + let gclk0 = clocks.gclk0; + + /* CAN config */ + let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0); + let (can0, gclk0) = communication::CanDevice0::new( + pins.pa23.into_mode(), + pins.pa22.into_mode(), + pclk_can, + clocks.ahbs.can0, + peripherals.CAN0, + gclk0, + cx.local.can_memory, + false, + ); + + + + let (pclk_adc0, gclk0) = Pclk::enable(tokens.pclks.adc0, gclk0); + + + // SAFETY: Misusing the PAC API can break the system. + // This is safe because we only steal the MCLK. + let (_, _, gclk, mut mclk) = unsafe { clocks.pac.steal() }; + + + // setup ADC + let mut adc_test = hal::adc::Adc::adc0(peripherals.ADC0, &mut mclk); + + + // LEDs + let led_green = pins.pb16.into_push_pull_output(); + let led_red = pins.pb17.into_push_pull_output(); + + blink::spawn().ok(); + adc::spawn().ok(); + + /* Monotonic clock */ + let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); + + ( + Shared { + em: ErrorManager::new(), + data_manager: DataManager::new(), + can0, + }, + Local { + led_green, led_red, adc_test, adc_pin: pins.pa10.into_alternate() + }, + init::Monotonics(mono), + ) + } + + /// Idle task for when no other tasks are running. + #[idle] + fn idle(_: idle::Context) -> ! { + loop {} + } + + #[task(local = [adc_test, adc_pin], shared = [&em])] + fn adc(cx: adc::Context) { + // test adc for 5v PWR sense + info!("try adc"); + cx.shared.em.run(||{ + let val = cx.local.adc_test.read(cx.local.adc_pin); + let x: u16 = match val { + Ok(v) => { + v + } + Err(_) => { + 0 + } + }; + info!("{}", x); + Ok(()) + }); + spawn_after!(adc, ExtU64::millis(500)).ok(); + } + + /// Simple blink task to test the system. + /// Acts as a heartbeat for the system. + #[task(local = [led_green, led_red], shared = [&em])] + fn blink(cx: blink::Context) { + cx.shared.em.run(|| { + if cx.shared.em.has_error() { + cx.local.led_red.toggle()?; + spawn_after!(blink, ExtU64::millis(200))?; + } else { + cx.local.led_green.toggle()?; + spawn_after!(blink, ExtU64::secs(1))?; + } + Ok(()) + }); + } +} \ No newline at end of file diff --git a/boards/power/src/types.rs b/boards/power/src/types.rs new file mode 100644 index 00000000..58d2ab49 --- /dev/null +++ b/boards/power/src/types.rs @@ -0,0 +1,5 @@ +use messages::sender::{Sender, Sender::PowerBoard}; +// ------- +// Sender ID +// ------- +pub static COM_ID: Sender = PowerBoard; \ No newline at end of file diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index 2ccc94bb..5b2b86c2 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -132,6 +132,9 @@ impl DataManager { } messages::sensor::SensorData::UtcTime(utc_time_data) => { self.utc_time = Some(utc_time_data); + }, + _ => { + info!("impl power"); } }, messages::Data::Command(command) => match command.data { From 61de13f256804f8c9f2e5727b91d4e907b69cb68 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Tue, 22 Aug 2023 02:07:38 +0000 Subject: [PATCH 15/30] Sleep commands, cleanup, wait for recovery state, etc --- .cargo/config | 24 +- Cargo.lock | 19 + Cargo.toml | 114 +- boards/communication/Cargo.toml | 42 +- boards/communication/src/communication.rs | 723 +++++------ boards/communication/src/data_manager.rs | 190 +-- boards/communication/src/main.rs | 551 +++++---- boards/communication/src/sd_manager.rs | 290 ++--- boards/communication/src/types.rs | 82 +- boards/power/Cargo.toml | 40 +- boards/power/src/communication.rs | 357 +++--- boards/power/src/data_manager.rs | 92 +- boards/power/src/main.rs | 308 +++-- boards/power/src/types.rs | 8 +- boards/recovery/src/communication.rs | 374 +++--- boards/recovery/src/data_manager.rs | 342 ++--- boards/recovery/src/main.rs | 425 ++++--- boards/recovery/src/state_machine/mod.rs | 221 ++-- .../src/state_machine/states/ascent.rs | 72 +- .../src/state_machine/states/descent.rs | 74 +- .../src/state_machine/states/initializing.rs | 1 - .../recovery/src/state_machine/states/mod.rs | 26 +- .../state_machine/states/terminal_descent.rs | 70 +- .../state_machine/states/wait_for_recovery.rs | 39 + boards/recovery/src/types.rs | 70 +- boards/sensor/Cargo.toml | 44 +- boards/sensor/src/communication.rs | 538 +++----- boards/sensor/src/data_manager.rs | 28 + boards/sensor/src/main.rs | 473 +++---- boards/sensor/src/sbg_manager.rs | 416 +++---- boards/sensor/src/sd_manager.rs | 292 ++--- boards/sensor/src/types.rs | 94 +- examples/rtic/src/main.rs | 156 +-- libraries/common-arm/memory.x | 28 +- libraries/messages/src/command.rs | 110 +- libraries/messages/src/lib.rs | 186 +-- libraries/messages/src/sender.rs | 1 + libraries/messages/src/sensor.rs | 39 + libraries/messages/src/state.rs | 74 +- libraries/sbg-rs/Cargo.toml | 38 +- libraries/sbg-rs/src/sbg.rs | 1096 ++++++++--------- 41 files changed, 4053 insertions(+), 4114 deletions(-) create mode 100644 boards/recovery/src/state_machine/states/wait_for_recovery.rs diff --git a/.cargo/config b/.cargo/config index 578e04af..a8dbc043 100644 --- a/.cargo/config +++ b/.cargo/config @@ -1,12 +1,12 @@ -[target.'cfg(all(target_arch = "arm", target_os = "none"))'] -runner = "probe-run --chip ATSAME51J18A --protocol swd" -rustflags = [ - "-C", "link-arg=-Tlink.x", - "-C", "link-arg=-Tdefmt.x", -] - -[env] -DEFMT_LOG="info" - -[build] -target = "thumbv7em-none-eabihf" # Cortex-M4F and Cortex-M7F (with FPU) +[target.'cfg(all(target_arch = "arm", target_os = "none"))'] +runner = "probe-run --chip ATSAME51J18A --protocol swd" +rustflags = [ + "-C", "link-arg=-Tlink.x", + "-C", "link-arg=-Tdefmt.x", +] + +[env] +DEFMT_LOG="info" + +[build] +target = "thumbv7em-none-eabihf" # Cortex-M4F and Cortex-M7F (with FPU) diff --git a/Cargo.lock b/Cargo.lock index a3fa55e1..b1e19754 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -774,6 +774,25 @@ dependencies = [ "serde", ] +[[package]] +name = "power" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "cortex-m-rtic", + "defmt", + "enum_dispatch", + "heapless", + "messages", + "panic-halt", + "postcard", + "systick-monotonic", + "typenum", +] + [[package]] name = "ppv-lite86" version = "0.2.17" diff --git a/Cargo.toml b/Cargo.toml index fcc1f27c..7ccf1783 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -1,57 +1,57 @@ -[workspace] - -members = [ - "boards/*", - "examples/*", - "libraries/*" -] - -# Specify which members to build by default. Some libraries, such as messages, contain dev-dependencies that will give -# compile errors if built directly. -default-members = [ - "boards/*", - "examples/*" -] - -[workspace.dependencies.atsamd-hal] -git = "https://github.com/atsamd-rs/atsamd" -features = ["same51j", "same51j-rt", "dma", "can"] - -[workspace.dependencies.serde] -version = "1.0.150" -default-features = false -features = ["derive"] - -[workspace.dependencies.cortex-m] -version = "0.7.6" -features = ["critical-section-single-core"] - -[profile.dev] -# Using LTO causes issues with GDB. -lto = false - -# Only optimize dependencies for size in debug, keeping the top crate debug friendly -[profile.dev.package."*"] -opt-level = "s" - -[profile.dev.package.sbg-rs] -opt-level = 0 -debug = true - -[profile.dev.build-override] -opt-level = 0 -debug = true - -[profile.release] -# symbols are nice and they don't increase the size on Flash -debug = true -lto = true -opt-level = 1 - -[profile.release.package.sbg-rs] -debug = true -opt-level = 0 - -[profile.release.build-override] -opt-level = 0 -debug = true +[workspace] + +members = [ + "boards/*", + "examples/*", + "libraries/*" +] + +# Specify which members to build by default. Some libraries, such as messages, contain dev-dependencies that will give +# compile errors if built directly. +default-members = [ + "boards/*", + "examples/*" +] + +[workspace.dependencies.atsamd-hal] +git = "https://github.com/atsamd-rs/atsamd" +features = ["same51j", "same51j-rt", "dma", "can"] + +[workspace.dependencies.serde] +version = "1.0.150" +default-features = false +features = ["derive"] + +[workspace.dependencies.cortex-m] +version = "0.7.6" +features = ["critical-section-single-core"] + +[profile.dev] +# Using LTO causes issues with GDB. +lto = false + +# Only optimize dependencies for size in debug, keeping the top crate debug friendly +[profile.dev.package."*"] +opt-level = "s" + +[profile.dev.package.sbg-rs] +opt-level = 0 +debug = true + +[profile.dev.build-override] +opt-level = 0 +debug = true + +[profile.release] +# symbols are nice and they don't increase the size on Flash +debug = true +lto = true +opt-level = 1 + +[profile.release.package.sbg-rs] +debug = true +opt-level = 0 + +[profile.release.build-override] +opt-level = 0 +debug = true diff --git a/boards/communication/Cargo.toml b/boards/communication/Cargo.toml index 3b880b6e..85829983 100644 --- a/boards/communication/Cargo.toml +++ b/boards/communication/Cargo.toml @@ -1,21 +1,21 @@ -[package] -name = "communication" -version = "0.1.0" -edition = "2021" - -# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html - -[dependencies] -cortex-m = { workspace = true } -cortex-m-rt = "^0.7.0" -cortex-m-rtic = "1.1.3" -panic-halt = "0.2.0" -systick-monotonic = "1.0.1" -defmt = "0.3.2" -postcard = "1.0.2" -heapless = "0.7.16" -common-arm = { path = "../../libraries/common-arm" } -atsamd-hal = { workspace = true } -messages = { path = "../../libraries/messages" } -typenum = "1.16.0" -embedded-sdmmc = "0.3.0" +[package] +name = "communication" +version = "0.1.0" +edition = "2021" + +# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html + +[dependencies] +cortex-m = { workspace = true } +cortex-m-rt = "^0.7.0" +cortex-m-rtic = "1.1.3" +panic-halt = "0.2.0" +systick-monotonic = "1.0.1" +defmt = "0.3.2" +postcard = "1.0.2" +heapless = "0.7.16" +common-arm = { path = "../../libraries/common-arm" } +atsamd-hal = { workspace = true } +messages = { path = "../../libraries/messages" } +typenum = "1.16.0" +embedded-sdmmc = "0.3.0" diff --git a/boards/communication/src/communication.rs b/boards/communication/src/communication.rs index 9d49fd45..684ee8ca 100644 --- a/boards/communication/src/communication.rs +++ b/boards/communication/src/communication.rs @@ -1,393 +1,332 @@ -/// Encapsulates all communication logic. -use crate::data_manager::DataManager; -use crate::types::*; -use atsamd_hal::can::Dependencies; -use atsamd_hal::clock::v2::ahb::AhbClk; -use atsamd_hal::clock::v2::gclk::Gclk0Id; -use atsamd_hal::clock::v2::pclk::Pclk; -use atsamd_hal::clock::v2::pclk::PclkToken; -use atsamd_hal::clock::v2::types::Can0; -use atsamd_hal::clock::v2::Source; -use atsamd_hal::dmac; -use atsamd_hal::gpio::{Alternate, AlternateI, Disabled, Floating, Pin, I, PA22, PA23, PB16, PB17}; -use atsamd_hal::pac::CAN0; -use atsamd_hal::pac::MCLK; -use atsamd_hal::pac::SERCOM5; -use atsamd_hal::sercom::Sercom; -use atsamd_hal::sercom::{uart, Sercom5}; -use atsamd_hal::sercom; -use atsamd_hal::sercom::uart::{ TxDuplex, RxDuplex}; -use atsamd_hal::sercom::uart::{Duplex, Uart}; -use atsamd_hal::time::*; -use atsamd_hal::typelevel::Increment; -use common_arm::mcan; -use common_arm::mcan::message::{rx, Raw}; -use common_arm::mcan::tx_buffers::DynTx; -use common_arm::HydraError; -use defmt::flush; -use defmt::info; -use crate::app::send_internal; -use common_arm::spawn; -use heapless::Vec; -use mcan::bus::Can; -use mcan::embedded_can as ecan; -use mcan::interrupt::state::EnabledLine0; -use mcan::interrupt::{Interrupt, OwnedInterruptSet}; -use mcan::message::tx; -use mcan::messageram::SharedMemory; -use mcan::{ - config::{BitTiming, Mode}, - filter::{Action, Filter}, -}; -use messages::mavlink; -use messages::Message; -use postcard::from_bytes; -use systick_monotonic::fugit::RateExtU32; -use typenum::{U0, U128, U32, U64}; - -use atsamd_hal::dmac::Transfer; -// use embedded_alloc::Heap; - - - -pub struct Capacities; - -impl mcan::messageram::Capacities for Capacities { - type StandardFilters = U128; - type ExtendedFilters = U64; - type RxBufferMessage = rx::Message<64>; - type DedicatedRxBuffers = U64; - type RxFifo0Message = rx::Message<64>; - type RxFifo0 = U64; - type RxFifo1Message = rx::Message<64>; - type RxFifo1 = U64; - type TxMessage = tx::Message<64>; - type TxBuffers = U32; - type DedicatedTxBuffers = U0; - type TxEventFifo = U32; -} - -pub struct CanDevice0 { - pub can: Can< - 'static, - Can0, - Dependencies>, Pin>, CAN0>, - Capacities, - >, - line_interrupts: OwnedInterruptSet, -} - -impl CanDevice0 { - pub fn new( - can_rx: Pin, - can_tx: Pin, - pclk_can: Pclk, - ahb_clock: AhbClk, - peripheral: CAN0, - gclk0: S, - can_memory: &'static mut SharedMemory, - loopback: bool, - ) -> (Self, S::Inc) - where - S: Source + Increment, - { - let (can_dependencies, gclk0) = - Dependencies::new(gclk0, pclk_can, ahb_clock, can_rx, can_tx, peripheral); - - let mut can = - mcan::bus::CanConfigurable::new(200.kHz(), can_dependencies, can_memory).unwrap(); - can.config().mode = Mode::Fd { - allow_bit_rate_switching: false, - data_phase_timing: BitTiming::new(500.kHz()), - }; - - if loopback { - can.config().loopback = true; - } - - let interrupts_to_be_enabled = can - .interrupts() - .split( - [ - Interrupt::RxFifo0NewMessage, - Interrupt::RxFifo0Full, - Interrupt::RxFifo0MessageLost, - Interrupt::RxFifo1NewMessage, - Interrupt::RxFifo1Full, - Interrupt::RxFifo1MessageLost, - ] - .into_iter() - .collect(), - ) - .unwrap(); - - // Line 0 and 1 are connected to the same interrupt line - let line_interrupts = can - .interrupt_configuration() - .enable_line_0(interrupts_to_be_enabled); - - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo0, - filter: ecan::StandardId::new(messages::sender::Sender::RecoveryBoard.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Recovery filter")); - - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo1, - filter: ecan::StandardId::new(messages::sender::Sender::SensorBoard.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Sensor filter")); - - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo0, - filter: ecan::StandardId::new(messages::sender::Sender::PowerBoard.into()).unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Power filter")); - - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo0, - filter: ecan::StandardId::new(messages::sender::Sender::GroundStation.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Ground Station filter")); - - let can = can.finalize().unwrap(); - ( - CanDevice0 { - can, - line_interrupts, - }, - gclk0, - ) - } - pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { - let payload: Vec = postcard::to_vec(&m)?; - self.can.tx.transmit_queued( - tx::MessageBuilder { - id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), - frame_type: tx::FrameType::FlexibleDatarate { - payload: &payload[..], - bit_rate_switching: false, - force_error_state_indicator: false, - }, - store_tx_event: None, - } - .build()?, - )?; - Ok(()) - } - pub fn process_data(&mut self, data_manager: &mut DataManager) { - let line_interrupts = &self.line_interrupts; - for interrupt in line_interrupts.iter_flagged() { - match interrupt { - Interrupt::RxFifo0NewMessage => { - for message in &mut self.can.rx_fifo_0 { - match from_bytes::(message.data()) { - Ok(data) => { - data_manager.handle_data(data); - } - Err(e) => { - info!("Error: {:?}", e) - } - } - } - } - Interrupt::RxFifo1NewMessage => { - for message in &mut self.can.rx_fifo_1 { - match from_bytes::(message.data()) { - Ok(data) => { - // data_manager.handle_data(data); - info!("{}", data); - } - Err(e) => { - info!("Error: {:?}", e) - } - } - } - } - _ => (), - } - } - } -} - -pub static mut BUF_DST: RadioBuffer = &mut [0; 255]; -pub static mut BUF_DST2: RadioBuffer = &mut [0; 255]; - -pub struct RadioDevice { - uart: Uart, - mav_sequence: u8, -} - -impl RadioDevice { - pub fn new( - radio_token: PclkToken, - mclk: &MCLK, - sercom: SERCOM5, - rx_pin: Pin>, - tx_pin: Pin>, - gclk0: S, - mut dma_channel: dmac::Channel, - ) -> (Self, S::Inc, RadioTransfer) - where - S: Source + Increment, - { - let (pclk_radio, gclk0) = Pclk::enable(radio_token, gclk0); - let pads = uart::Pads::::default() - .rx(rx_pin) - .tx(tx_pin); - let uart = GroundStationUartConfig::new(mclk, sercom, pads, pclk_radio.freq()) - .baud( - 57600.Hz(), - uart::BaudMode::Fractional(uart::Oversampling::Bits16), - ) - .enable(); - let (rx, tx) = uart.split(); // tx sends rx uses dma to receive so we need to setup dma here. - dma_channel.as_mut().enable_interrupts(dmac::InterruptFlags::new().with_tcmpl(true)); - let xfer = Transfer::new(dma_channel, rx, unsafe {&mut *BUF_DST}, false).expect("DMA Radio RX").begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); - ( - RadioDevice { - uart: tx, - mav_sequence: 0, - }, - gclk0, - xfer, - ) - } - pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { - let payload: Vec = postcard::to_vec(&m)?; - - let mav_header = mavlink::MavHeader { - system_id: 1, - component_id: 1, - sequence: self.increment_mav_sequence(), - }; - - let mav_message = mavlink::uorocketry::MavMessage::POSTCARD_MESSAGE( - mavlink::uorocketry::POSTCARD_MESSAGE_DATA { message: payload }, - ); - mavlink::write_versioned_msg( - &mut self.uart, - mavlink::MavlinkVersion::V2, - mav_header, - &mav_message, - )?; - Ok(()) - } - pub fn increment_mav_sequence(&mut self) -> u8 { - self.mav_sequence = self.mav_sequence.wrapping_add(1); - self.mav_sequence - } -} - -pub struct RadioManager { - xfer: Option, - // chan0: Option>, - // source: Option>, - buf_select: bool, -} - -impl RadioManager { - pub fn new( - xfer: RadioTransfer, - ) -> Self { - RadioManager { - xfer: Some(xfer), - // xfer: Some(xfer), - // chan0: None, - // source: None, - buf_select: false, - } - } - pub fn process_message(&mut self, buf: RadioBuffer) { - // info!("Received: {:?}", buf); - // mavlink::read_versioned_msg(buf, - // mavlink::MavlinkVersion::V2, - // ); - match from_bytes::(buf) { - Ok(msg) => { - info!("Radio: {}", msg); - // spawn!(send_internal, msg); // dump to the Can Bus - } - Err(_) => { - info!("Radio unknown msg"); - return; - } - } - } -} - -pub fn radio_dma(cx: crate::app::radio_dma::Context) { - let manager = cx.local.radio_manager; - // match manager.xfer { - // Some(xfer) => { - // if xfer.complete() { - // let (chan0, source, payload) = xfer.stop(); - // manager.chan0 = Some(chan0); - // manager.source = Some(source); - // manager.process_message(payload) - // } - // } - // None => { - // if let Some(chan0) = manager.chan0.take() { - // let source = manager.source.take().unwrap(); - // // static mut dest: RadioBuffer = &mut [0; 5]; - // let xfer = manager.xfer.get_or_insert( - // dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).unwrap() - // ); - // manager.xfer = Some(*xfer); - // } - // } - // } - // let mut xfer = manager.xfer.take().unwrap(); - match &mut manager.xfer { - Some(xfer) => { - if xfer.complete() { - let (chan0, source, buf) = manager.xfer.take().unwrap().stop(); - let mut xfer = dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).expect("f").begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); - manager.process_message(buf); - unsafe{BUF_DST.copy_from_slice(&[0;255])}; - xfer.block_transfer_interrupt(); - manager.xfer = Some(xfer); - } - } - None => { - info!("none"); - } - } - - // if manager.xfer.complete() { - // cx.shared.em.run(|| { - - // let buf = match manager.buf_select { - // false => { - // manager.buf_select = true; - // unsafe{BUF_DST.copy_from_slice(&[0; 5])}; - // manager.xfer.recycle_source(unsafe{&mut *BUF_DST})? - // } - // true => { - // manager.buf_select = false; - // unsafe{BUF_DST2.copy_from_slice(&[0; 5])}; - // manager.xfer.recycle_source(unsafe{&mut *BUF_DST2})? - // } - // }; - // manager.process_message(buf); - // Ok(()) - // }) - // } -} - -// pub fn produce_dest() -> RadioBuffer { -// let mut dest: RadioBuffer = &mut [0; 5]; -// dest +use crate::data_manager::DataManager; +use crate::types::*; +use atsamd_hal::can::Dependencies; +use atsamd_hal::clock::v2::ahb::AhbClk; +use atsamd_hal::clock::v2::gclk::Gclk0Id; +use atsamd_hal::clock::v2::pclk::Pclk; +use atsamd_hal::clock::v2::pclk::PclkToken; +use atsamd_hal::clock::v2::types::Can0; +use atsamd_hal::clock::v2::Source; +use atsamd_hal::dmac; +use atsamd_hal::gpio::{Alternate, AlternateI, Disabled, Floating, Pin, I, PA22, PA23, PB16, PB17}; +use atsamd_hal::pac::CAN0; +use atsamd_hal::pac::MCLK; +use atsamd_hal::pac::SERCOM5; +use atsamd_hal::sercom::Sercom; +use atsamd_hal::sercom::{uart, Sercom5}; +use atsamd_hal::sercom; +use atsamd_hal::sercom::uart::{ TxDuplex, RxDuplex}; +use atsamd_hal::sercom::uart::{Duplex, Uart}; +use atsamd_hal::time::*; +use atsamd_hal::typelevel::Increment; +use common_arm::mcan; +use common_arm::mcan::message::{rx, Raw}; +use common_arm::mcan::tx_buffers::DynTx; +use common_arm::HydraError; +use defmt::flush; +use defmt::info; +use crate::app::send_internal; +use common_arm::spawn; +use heapless::Vec; +use mcan::bus::Can; +use mcan::embedded_can as ecan; +use mcan::interrupt::state::EnabledLine0; +use mcan::interrupt::{Interrupt, OwnedInterruptSet}; +use mcan::message::tx; +use mcan::messageram::SharedMemory; +use mcan::{ + config::{BitTiming, Mode}, + filter::{Action, Filter}, +}; +use messages::mavlink; +use messages::Message; +use postcard::from_bytes; +use systick_monotonic::fugit::RateExtU32; +use typenum::{U0, U128, U32, U64}; + +use atsamd_hal::dmac::Transfer; + +pub struct Capacities; + +impl mcan::messageram::Capacities for Capacities { + type StandardFilters = U128; + type ExtendedFilters = U64; + type RxBufferMessage = rx::Message<64>; + type DedicatedRxBuffers = U64; + type RxFifo0Message = rx::Message<64>; + type RxFifo0 = U64; + type RxFifo1Message = rx::Message<64>; + type RxFifo1 = U64; + type TxMessage = tx::Message<64>; + type TxBuffers = U32; + type DedicatedTxBuffers = U0; + type TxEventFifo = U32; +} + +pub struct CanDevice0 { + pub can: Can< + 'static, + Can0, + Dependencies>, Pin>, CAN0>, + Capacities, + >, + line_interrupts: OwnedInterruptSet, +} + +impl CanDevice0 { + pub fn new( + can_rx: Pin, + can_tx: Pin, + pclk_can: Pclk, + ahb_clock: AhbClk, + peripheral: CAN0, + gclk0: S, + can_memory: &'static mut SharedMemory, + loopback: bool, + ) -> (Self, S::Inc) + where + S: Source + Increment, + { + let (can_dependencies, gclk0) = + Dependencies::new(gclk0, pclk_can, ahb_clock, can_rx, can_tx, peripheral); + + let mut can = + mcan::bus::CanConfigurable::new(200.kHz(), can_dependencies, can_memory).unwrap(); + can.config().mode = Mode::Fd { + allow_bit_rate_switching: false, + data_phase_timing: BitTiming::new(500.kHz()), + }; + + if loopback { + can.config().loopback = true; + } + + let interrupts_to_be_enabled = can + .interrupts() + .split( + [ + Interrupt::RxFifo0NewMessage, + Interrupt::RxFifo0Full, + Interrupt::RxFifo0MessageLost, + Interrupt::RxFifo1NewMessage, + Interrupt::RxFifo1Full, + Interrupt::RxFifo1MessageLost, + ] + .into_iter() + .collect(), + ) + .unwrap(); + + // Line 0 and 1 are connected to the same interrupt line + let line_interrupts = can + .interrupt_configuration() + .enable_line_0(interrupts_to_be_enabled); + + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo0, + filter: ecan::StandardId::new(messages::sender::Sender::RecoveryBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Recovery filter")); + + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo1, + filter: ecan::StandardId::new(messages::sender::Sender::SensorBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Sensor filter")); + + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo0, + filter: ecan::StandardId::new(messages::sender::Sender::PowerBoard.into()).unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Power filter")); + + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo0, + filter: ecan::StandardId::new(messages::sender::Sender::GroundStation.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Ground Station filter")); + + let can = can.finalize().unwrap(); + ( + CanDevice0 { + can, + line_interrupts, + }, + gclk0, + ) + } + pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { + let payload: Vec = postcard::to_vec(&m)?; + self.can.tx.transmit_queued( + tx::MessageBuilder { + id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), + frame_type: tx::FrameType::FlexibleDatarate { + payload: &payload[..], + bit_rate_switching: false, + force_error_state_indicator: false, + }, + store_tx_event: None, + } + .build()?, + )?; + Ok(()) + } + pub fn process_data(&mut self, data_manager: &mut DataManager) { + let line_interrupts = &self.line_interrupts; + for interrupt in line_interrupts.iter_flagged() { + match interrupt { + Interrupt::RxFifo0NewMessage => { + for message in &mut self.can.rx_fifo_0 { + match from_bytes::(message.data()) { + Ok(data) => { + data_manager.handle_data(data); + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + Interrupt::RxFifo1NewMessage => { + for message in &mut self.can.rx_fifo_1 { + match from_bytes::(message.data()) { + Ok(data) => { + data_manager.handle_data(data); + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + _ => (), + } + } + } +} + +pub static mut BUF_DST: RadioBuffer = &mut [0; 255]; + +pub struct RadioDevice { + uart: Uart, + mav_sequence: u8, +} + +impl RadioDevice { + pub fn new( + radio_token: PclkToken, + mclk: &MCLK, + sercom: SERCOM5, + rx_pin: Pin>, + tx_pin: Pin>, + gclk0: S, + mut dma_channel: dmac::Channel, + ) -> (Self, S::Inc, RadioTransfer) + where + S: Source + Increment, + { + let (pclk_radio, gclk0) = Pclk::enable(radio_token, gclk0); + let pads = uart::Pads::::default() + .rx(rx_pin) + .tx(tx_pin); + let uart = GroundStationUartConfig::new(mclk, sercom, pads, pclk_radio.freq()) + .baud( + 57600.Hz(), + uart::BaudMode::Fractional(uart::Oversampling::Bits16), + ) + .enable(); + let (rx, tx) = uart.split(); // tx sends rx uses dma to receive so we need to setup dma here. + dma_channel.as_mut().enable_interrupts(dmac::InterruptFlags::new().with_tcmpl(true)); + let xfer = Transfer::new(dma_channel, rx, unsafe {&mut *BUF_DST}, false).expect("DMA Radio RX").begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); + ( + RadioDevice { + uart: tx, + mav_sequence: 0, + }, + gclk0, + xfer, + ) + } + pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { + let payload: Vec = postcard::to_vec(&m)?; + + let mav_header = mavlink::MavHeader { + system_id: 1, + component_id: 1, + sequence: self.increment_mav_sequence(), + }; + + let mav_message = mavlink::uorocketry::MavMessage::POSTCARD_MESSAGE( + mavlink::uorocketry::POSTCARD_MESSAGE_DATA { message: payload }, + ); + mavlink::write_versioned_msg( + &mut self.uart, + mavlink::MavlinkVersion::V2, + mav_header, + &mav_message, + )?; + Ok(()) + } + pub fn increment_mav_sequence(&mut self) -> u8 { + self.mav_sequence = self.mav_sequence.wrapping_add(1); + self.mav_sequence + } +} + +pub struct RadioManager { + xfer: Option, + buf_select: bool, +} + +impl RadioManager { + pub fn new( + xfer: RadioTransfer, + ) -> Self { + RadioManager { + xfer: Some(xfer), + buf_select: false, + } + } + pub fn process_message(&mut self, buf: RadioBuffer) { + match from_bytes::(buf) { + Ok(msg) => { + info!("Radio: {}", msg); + // spawn!(send_internal, msg); // dump to the Can Bus + } + Err(_) => { + info!("Radio unknown msg"); + return; + } + } + } +} + +// pub fn radio_dma(cx: crate::app::radio_dma::Context) { +// let manager = cx.local.radio_manager; +// match &mut manager.xfer { +// Some(xfer) => { +// if xfer.complete() { +// let (chan0, source, buf) = manager.xfer.take().unwrap().stop(); +// let mut xfer = dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).expect("f").begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); +// manager.process_message(buf); +// unsafe{BUF_DST.copy_from_slice(&[0;255])}; +// xfer.block_transfer_interrupt(); +// manager.xfer = Some(xfer); +// } +// } +// None => { +// info!("none"); +// } +// } // } \ No newline at end of file diff --git a/boards/communication/src/data_manager.rs b/boards/communication/src/data_manager.rs index 794c4a0b..05b94670 100644 --- a/boards/communication/src/data_manager.rs +++ b/boards/communication/src/data_manager.rs @@ -1,95 +1,95 @@ -use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime}; -use messages::Message; -use messages::state::{State, StateData}; -use defmt::info; - -#[derive(Clone)] -pub struct DataManager { - pub air: Option, - pub ekf_nav: (Option, Option), - pub ekf_quat: Option, - pub imu: (Option, Option), - pub utc_time: Option, - pub gps_vel: Option, - pub state: Option, -} - -impl DataManager { - pub fn new() -> Self { - Self { - air: None, - ekf_nav: (None, None), - ekf_quat: None, - imu: (None, None), - utc_time: None, - gps_vel: None, - state: None, - } - } - - pub fn clone_sensors(&self) -> [Option; 8] { - [ - self.air.clone().map(|x| x.into()), - self.ekf_nav.0.clone().map(|x| x.into()), - self.ekf_nav.1.clone().map(|x| x.into()), - self.ekf_quat.clone().map(|x| x.into()), - self.imu.0.clone().map(|x| x.into()), - self.imu.1.clone().map(|x| x.into()), - self.utc_time.clone().map(|x| x.into()), - self.gps_vel.clone().map(|x| x.into()), - ] - } - pub fn clone_states(&self) -> [Option; 1] { - [ - self.state.clone().map(|x| x.into()), - ] - } - pub fn handle_data(&mut self, data: Message) { - match data.data { - messages::Data::Sensor(sensor) => match sensor.data { - messages::sensor::SensorData::Air(air_data) => { - self.air = Some(air_data); - } - messages::sensor::SensorData::EkfNav1(nav1_data) => { - self.ekf_nav.0 = Some(nav1_data); - } - messages::sensor::SensorData::EkfNav2(nav2_data) => { - self.ekf_nav.1 = Some(nav2_data); - } - messages::sensor::SensorData::EkfQuat(quat_data) => { - self.ekf_quat = Some(quat_data); - } - messages::sensor::SensorData::GpsVel(gps_vel_data) => { - self.gps_vel = Some(gps_vel_data); - } - messages::sensor::SensorData::Imu1(imu1_data) => { - self.imu.0 = Some(imu1_data); - } - messages::sensor::SensorData::Imu2(imu2_data) => { - self.imu.1 = Some(imu2_data); - } - messages::sensor::SensorData::UtcTime(utc_time_data) => { - self.utc_time = Some(utc_time_data); - }, - _ => { - info!("impl power related"); - } - }, - messages::Data::State(state) => match state.data { - _ => { - info!("state: {}", state.data.clone()); - self.state = Some(state.data); - } - } - _ => { - info!("unkown"); - } - } - } -} - -impl Default for DataManager { - fn default() -> Self { - Self::new() - } -} +use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime}; +use messages::Message; +use messages::state::{State, StateData}; +use defmt::info; + +#[derive(Clone)] +pub struct DataManager { + pub air: Option, + pub ekf_nav: (Option, Option), + pub ekf_quat: Option, + pub imu: (Option, Option), + pub utc_time: Option, + pub gps_vel: Option, + pub state: Option, +} + +impl DataManager { + pub fn new() -> Self { + Self { + air: None, + ekf_nav: (None, None), + ekf_quat: None, + imu: (None, None), + utc_time: None, + gps_vel: None, + state: None, + } + } + + pub fn clone_sensors(&self) -> [Option; 8] { + [ + self.air.clone().map(|x| x.into()), + self.ekf_nav.0.clone().map(|x| x.into()), + self.ekf_nav.1.clone().map(|x| x.into()), + self.ekf_quat.clone().map(|x| x.into()), + self.imu.0.clone().map(|x| x.into()), + self.imu.1.clone().map(|x| x.into()), + self.utc_time.clone().map(|x| x.into()), + self.gps_vel.clone().map(|x| x.into()), + ] + } + pub fn clone_states(&self) -> [Option; 1] { + [ + self.state.clone().map(|x| x.into()), + ] + } + pub fn handle_data(&mut self, data: Message) { + match data.data { + messages::Data::Sensor(sensor) => match sensor.data { + messages::sensor::SensorData::Air(air_data) => { + self.air = Some(air_data); + } + messages::sensor::SensorData::EkfNav1(nav1_data) => { + self.ekf_nav.0 = Some(nav1_data); + } + messages::sensor::SensorData::EkfNav2(nav2_data) => { + self.ekf_nav.1 = Some(nav2_data); + } + messages::sensor::SensorData::EkfQuat(quat_data) => { + self.ekf_quat = Some(quat_data); + } + messages::sensor::SensorData::GpsVel(gps_vel_data) => { + self.gps_vel = Some(gps_vel_data); + } + messages::sensor::SensorData::Imu1(imu1_data) => { + self.imu.0 = Some(imu1_data); + } + messages::sensor::SensorData::Imu2(imu2_data) => { + self.imu.1 = Some(imu2_data); + } + messages::sensor::SensorData::UtcTime(utc_time_data) => { + self.utc_time = Some(utc_time_data); + }, + _ => { + info!("impl power related"); + } + }, + messages::Data::State(state) => match state.data { + _ => { + info!("state: {}", state.data.clone()); + self.state = Some(state.data); + } + } + _ => { + info!("unkown"); + } + } + } +} + +impl Default for DataManager { + fn default() -> Self { + Self::new() + } +} diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index fee11451..d7a2bfe3 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -1,277 +1,274 @@ -#![no_std] -#![no_main] - -mod communication; -mod data_manager; -mod types; -mod sd_manager; - -use atsamd_hal as hal; -use atsamd_hal::clock::v2::pclk::Pclk; -use atsamd_hal::clock::v2::Source; -use atsamd_hal::dmac::DmaController; -use atsamd_hal::dmac; -use common_arm::mcan; -use common_arm::*; -use communication::Capacities; -use communication::{RadioDevice, RadioManager}; -use data_manager::DataManager; -use sd_manager::SdManager; -use communication::radio_dma; - -use hal::gpio::Pins; -use hal::gpio::PA05; -use hal::gpio::{Pin, PushPullOutput}; -use hal::prelude::*; -use mcan::messageram::SharedMemory; -use messages::sensor::Sensor; -use messages::state::State; -use messages::*; -use panic_halt as _; -use systick_monotonic::*; -use types::*; -use defmt::{info, flush}; - -#[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] -mod app { - use super::*; - - #[shared] - struct Shared { - em: ErrorManager, - data_manager: DataManager, - can0: communication::CanDevice0, - } - - #[local] - struct Local { - led: Pin, - radio: RadioDevice, - // sd_manager: SdManager, - radio_manager: RadioManager, - } - - #[monotonic(binds = SysTick, default = true)] - type SysMono = Systick<100>; // 100 Hz / 10 ms granularity - - #[init(local = [ - #[link_section = ".can"] - can_memory: SharedMemory = SharedMemory::new() - ])] - fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { - let mut peripherals = cx.device; - let core = cx.core; - let pins = Pins::new(peripherals.PORT); - - let mut dmac = DmaController::init(peripherals.DMAC, &mut peripherals.PM); - let dmaChannels = dmac.split(); - - /* Logging Setup */ - HydraLogging::set_ground_station_callback(queue_gs_message); - - /* Clock setup */ - let (_, clocks, tokens) = atsamd_hal::clock::v2::clock_system_at_reset( - peripherals.OSCCTRL, - peripherals.OSC32KCTRL, - peripherals.GCLK, - peripherals.MCLK, - &mut peripherals.NVMCTRL, - ); - let gclk0 = clocks.gclk0; - - // SAFETY: Misusing the PAC API can break the system. - // This is safe because we only steal the MCLK. - let (_, _, _, mclk) = unsafe { clocks.pac.steal() }; - - /* CAN config */ - let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0); - let (can0, gclk0) = communication::CanDevice0::new( - pins.pa23.into_mode(), - pins.pa22.into_mode(), - pclk_can, - clocks.ahbs.can0, - peripherals.CAN0, - gclk0, - cx.local.can_memory, - false, - ); - - /* Radio config */ - let dmaCh0 = dmaChannels.0.init(dmac::PriorityLevel::LVL3); - let (radio, gclk0, xfer) = RadioDevice::new( - tokens.pclks.sercom5, - &mclk, - peripherals.SERCOM5, - pins.pb17, - pins.pb16, - gclk0, - dmaCh0, - ); - - let radio_manager = RadioManager::new(xfer); - - /* SD config */ - // let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); - // let sd_manager = SdManager::new( - // &mclk, - // peripherals.SERCOM4, - // pclk_sd.freq(), - // pins.pb14.into_push_pull_output(), - // pins.pb13.into_push_pull_output(), - // pins.pb15.into_push_pull_output(), - // pins.pb12.into_push_pull_output(), - // ); - - /* Status LED */ - let led = pins.pa05.into_push_pull_output(); - - /* Spawn tasks */ - sensor_send::spawn().ok(); - state_send::spawn().ok(); - blink::spawn().ok(); - - /* Monotonic clock */ - let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); - - ( - Shared { - em: ErrorManager::new(), - data_manager: DataManager::new(), - can0, - }, - Local { led, radio, radio_manager }, - // Local { led, radio, sd_manager, radio_manager }, - init::Monotonics(mono), - ) - } - - /// Idle task for when no other tasks are running. - #[idle] - fn idle(_: idle::Context) -> ! { - loop {} - } - - /// Handles the CAN0 interrupt. - #[task(priority = 3, binds = CAN0, shared = [can0, data_manager])] - fn can0(mut cx: can0::Context) { - cx.shared.can0.lock(|can| { - cx.shared - .data_manager - .lock(|data_manager| can.process_data(data_manager)); - }); - } - /** - * Sends a message over CAN. - */ - #[task(capacity = 10, local = [counter: u16 = 0], shared = [can0, &em])] - fn send_internal(mut cx: send_internal::Context, m: Message) { - cx.shared.em.run(|| { - cx.shared.can0.lock(|can| can.send_message(m))?; - Ok(()) - }); - } - - - /// Probably should use this ( ノ^ω^)ノ - /// I see no need for this and this loses the sender information - pub fn queue_gs_message(d: impl Into) { - let message = Message::new(&monotonics::now(), COM_ID, d.into()); - - send_gs::spawn(message).ok(); - } - - /** - * Sends a message to the radio over UART. - */ - #[task(capacity = 10, local = [radio], shared = [&em])] - fn send_gs(cx: send_gs::Context, m: Message) { - cx.shared.em.run(|| { - cx.local.radio.send_message(m)?; - Ok(()) - }); - } - - // #[task(capacity = 10, local = [sd_manager], shared = [&em])] - // fn sd_dump(mut cx: sd_dump::Context, m: Message) { - // let mut manager = cx.local.sd_manager; - // cx.shared.em.run(|| { - // let mut buf = [0u8; 256]; - // let msg_ser = postcard::to_slice_cobs(&m, &mut buf)?; - // manager.write(msg_ser)?; - // Ok(()) - // }); - // } - - /** - * Sends information about the sensors. - */ - #[task(shared = [data_manager, &em])] - fn sensor_send(mut cx: sensor_send::Context) { - let sensor_data = cx - .shared - .data_manager - .lock(|data_manager| data_manager.clone_sensors()); - - let messages = sensor_data - .into_iter() - .flatten() - .map(|x| Message::new(&monotonics::now(), COM_ID, Sensor::new(x))); - - cx.shared.em.run(|| { - for msg in messages { - spawn!(send_gs, msg.clone())?; - // spawn!(sd_dump, msg)?; - } - Ok(()) - }); - spawn_after!(sensor_send, ExtU64::millis(250)).ok(); - } - - #[task(shared = [data_manager, &em])] - fn state_send(mut cx: state_send::Context) { - let state_data = cx.shared.data_manager.lock(|data_manager| { - if let Some(state) = &data_manager.state { - state.clone() - } else { - messages::state::StateData::Abort - } - }); - let message = Message::new(&monotonics::now(), COM_ID, State::new(state_data)); - // let messages = state_data - // .into_iter() - // .flatten() - // .map(|x| Message::new(&monotonics::now(), COM_ID, State::new(x))); - - cx.shared.em.run(|| { - spawn!(send_gs, message.clone())?; - // for msg in messages { - // // spawn!(send_gs, msg.clone())?; - // info!("state: {}", msg); - // } - Ok(()) - }); - spawn_after!(state_send, ExtU64::secs(5)).ok(); - } - - /** - * Simple blink task to test the system. - * Acts as a heartbeat for the system. - */ - #[task(local = [led], shared = [&em])] - fn blink(cx: blink::Context) { - cx.shared.em.run(|| { - cx.local.led.toggle()?; - if cx.shared.em.has_error() { - spawn_after!(blink, ExtU64::millis(200))?; - } else { - spawn_after!(blink, ExtU64::secs(1))?; - } - Ok(()) - }); - } - - extern "Rust" { - #[task(binds = DMAC_0, shared=[&em], local=[radio_manager])] - fn radio_dma(context: radio_dma::Context); - } -} +#![no_std] +#![no_main] + +mod communication; +mod data_manager; +mod types; +mod sd_manager; + +use atsamd_hal as hal; +use atsamd_hal::clock::v2::pclk::Pclk; +use atsamd_hal::clock::v2::Source; +use atsamd_hal::dmac::DmaController; +use atsamd_hal::dmac; +use common_arm::mcan; +use common_arm::*; +use communication::Capacities; +use communication::{RadioDevice, RadioManager}; +use data_manager::DataManager; +use sd_manager::SdManager; +// use communication::radio_dma; + +use heapless::Vec; +use hal::gpio::Pins; +use hal::gpio::PA05; +use hal::gpio::{Pin, PushPullOutput}; +use hal::prelude::*; +use mcan::messageram::SharedMemory; +use messages::sensor::Sensor; +use messages::state::State; +use messages::*; +use panic_halt as _; +use systick_monotonic::*; +use types::*; +use defmt::{info, flush}; + +#[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] +mod app { + use super::*; + + #[shared] + struct Shared { + em: ErrorManager, + data_manager: DataManager, + can0: communication::CanDevice0, + } + + #[local] + struct Local { + led: Pin, + radio: RadioDevice, + sd_manager: SdManager, + radio_manager: RadioManager, + } + + #[monotonic(binds = SysTick, default = true)] + type SysMono = Systick<100>; // 100 Hz / 10 ms granularity + + #[init(local = [ + #[link_section = ".can"] + can_memory: SharedMemory = SharedMemory::new() + ])] + fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { + let mut peripherals = cx.device; + let core = cx.core; + let pins = Pins::new(peripherals.PORT); + + let mut dmac = DmaController::init(peripherals.DMAC, &mut peripherals.PM); + let dmaChannels = dmac.split(); + + /* Logging Setup */ + HydraLogging::set_ground_station_callback(queue_gs_message); + + /* Clock setup */ + let (_, clocks, tokens) = atsamd_hal::clock::v2::clock_system_at_reset( + peripherals.OSCCTRL, + peripherals.OSC32KCTRL, + peripherals.GCLK, + peripherals.MCLK, + &mut peripherals.NVMCTRL, + ); + let gclk0 = clocks.gclk0; + + // SAFETY: Misusing the PAC API can break the system. + // This is safe because we only steal the MCLK. + let (_, _, _, mclk) = unsafe { clocks.pac.steal() }; + + /* CAN config */ + let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0); + let (can0, gclk0) = communication::CanDevice0::new( + pins.pa23.into_mode(), + pins.pa22.into_mode(), + pclk_can, + clocks.ahbs.can0, + peripherals.CAN0, + gclk0, + cx.local.can_memory, + false, + ); + + /* Radio config */ + let dmaCh0 = dmaChannels.0.init(dmac::PriorityLevel::LVL3); + let (radio, gclk0, xfer) = RadioDevice::new( + tokens.pclks.sercom5, + &mclk, + peripherals.SERCOM5, + pins.pb17, + pins.pb16, + gclk0, + dmaCh0, + ); + + let radio_manager = RadioManager::new(xfer); + + /* SD config */ + let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); + let sd_manager = SdManager::new( + &mclk, + peripherals.SERCOM4, + pclk_sd.freq(), + pins.pb14.into_push_pull_output(), + pins.pb13.into_push_pull_output(), + pins.pb15.into_push_pull_output(), + pins.pb12.into_push_pull_output(), + ); + + /* Status LED */ + let led = pins.pa05.into_push_pull_output(); + + /* Spawn tasks */ + sensor_send::spawn().ok(); + state_send::spawn().ok(); + blink::spawn().ok(); + + /* Monotonic clock */ + let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); + + ( + Shared { + em: ErrorManager::new(), + data_manager: DataManager::new(), + can0, + }, + Local { led, radio, sd_manager, radio_manager }, + init::Monotonics(mono), + ) + } + + /// Idle task for when no other tasks are running. + #[idle] + fn idle(_: idle::Context) -> ! { + loop {} + } + + /// Handles the CAN0 interrupt. + #[task(priority = 3, binds = CAN0, shared = [can0, data_manager])] + fn can0(mut cx: can0::Context) { + cx.shared.can0.lock(|can| { + cx.shared + .data_manager + .lock(|data_manager| can.process_data(data_manager)); + }); + } + /** + * Sends a message over CAN. + */ + #[task(capacity = 10, local = [counter: u16 = 0], shared = [can0, &em])] + fn send_internal(mut cx: send_internal::Context, m: Message) { + cx.shared.em.run(|| { + cx.shared.can0.lock(|can| can.send_message(m))?; + Ok(()) + }); + } + + + /// Probably should use this ( ノ^ω^)ノ + /// I see no need for this and this loses the sender information + pub fn queue_gs_message(d: impl Into) { + let message = Message::new(&monotonics::now(), COM_ID, d.into()); + + send_gs::spawn(message).ok(); + } + + /** + * Sends a message to the radio over UART. + */ + #[task(capacity = 10, local = [radio], shared = [&em])] + fn send_gs(cx: send_gs::Context, m: Message) { + cx.shared.em.run(|| { + cx.local.radio.send_message(m)?; + Ok(()) + }); + } + + #[task(capacity = 10, local = [sd_manager], shared = [&em])] + fn sd_dump(mut cx: sd_dump::Context, m: Message) { + let mut manager = cx.local.sd_manager; + cx.shared.em.run(|| { + let mut buf: [u8; 255] = [0; 255]; + let msg_ser = postcard::to_slice_cobs(&m, &mut buf)?; + if let Some(mut file) = manager.file.take() { + manager.write(&mut file, &msg_ser)?; + manager.file = Some(file); + } else { + if let Ok(mut file) = manager.open_file("log.txt") { + manager.write(&mut file, &msg_ser)?; + manager.file = Some(file); + } + } + Ok(()) + }); + } + + /** + * Sends information about the sensors. + */ + #[task(shared = [data_manager, &em])] + fn sensor_send(mut cx: sensor_send::Context) { + let sensor_data = cx + .shared + .data_manager + .lock(|data_manager| data_manager.clone_sensors()); + + let messages = sensor_data + .into_iter() + .flatten() + .map(|x| Message::new(&monotonics::now(), COM_ID, Sensor::new(x))); + + cx.shared.em.run(|| { + for msg in messages { + spawn!(send_gs, msg.clone())?; + spawn!(sd_dump, msg)?; + } + Ok(()) + }); + spawn_after!(sensor_send, ExtU64::millis(250)).ok(); + } + + #[task(shared = [data_manager, &em])] + fn state_send(mut cx: state_send::Context) { + let state_data = cx.shared.data_manager.lock(|data_manager| { + data_manager.state.clone() + }); + cx.shared.em.run(|| { + if let Some(x) = state_data { + let message = Message::new(&monotonics::now(), COM_ID, State::new(x)); + spawn!(send_gs, message)?; + } // if there is none we still return since we simply don't have data yet. + Ok(()) + }); + spawn_after!(state_send, ExtU64::secs(5)).ok(); + } + + /** + * Simple blink task to test the system. + * Acts as a heartbeat for the system. + */ + #[task(local = [led], shared = [&em])] + fn blink(cx: blink::Context) { + cx.shared.em.run(|| { + cx.local.led.toggle()?; + if cx.shared.em.has_error() { + spawn_after!(blink, ExtU64::millis(200))?; + } else { + spawn_after!(blink, ExtU64::secs(1))?; + } + Ok(()) + }); + } + + // extern "Rust" { + // #[task(binds = DMAC_0, shared=[&em], local=[radio_manager])] + // fn radio_dma(context: radio_dma::Context); + // } +} diff --git a/boards/communication/src/sd_manager.rs b/boards/communication/src/sd_manager.rs index 2eafe666..e32fb4fc 100644 --- a/boards/communication/src/sd_manager.rs +++ b/boards/communication/src/sd_manager.rs @@ -1,145 +1,147 @@ -use crate::types::SdController; -use core::marker::PhantomData; -use atsamd_hal::gpio::{Output, Pin, PushPull, PA16, PA17, PA18, PA19, PB14, PB13, PB15, PB12}; -use atsamd_hal::pac; -use atsamd_hal::sercom::{spi, IoSet1, Sercom1, Sercom4}; -use atsamd_hal::time::Hertz; -use defmt::{info, warn}; -use embedded_sdmmc as sd; - -/// Time source for `[SdInterface]`. It doesn't return any useful information for now, and will -/// always return an arbitrary time. -pub struct TimeSink { - _marker: PhantomData<*const ()>, -} - -impl TimeSink { - fn new() -> Self { - TimeSink { - _marker: PhantomData, - } - } -} - -impl sd::TimeSource for TimeSink { - fn get_timestamp(&self) -> sd::Timestamp { - sd::Timestamp { - year_since_1970: 0, - zero_indexed_month: 0, - zero_indexed_day: 0, - hours: 0, - minutes: 0, - seconds: 0, - } - } -} - -/// Wrapper for the SD Card. For now, the pins are hard-coded. -pub struct SdManager { - pub sd_controller: SdController, - pub volume: sd::Volume, - pub root_directory: sd::Directory, - pub file: sd::File, -} - -impl SdManager { - pub fn new( - mclk: &pac::MCLK, - sercom: pac::SERCOM4, - freq: Hertz, - cs: Pin>, - sck: Pin>, - miso: Pin>, - mosi: Pin>, - ) -> Self { - let pads_spi = spi::Pads::::default() - .sclk(sck) - .data_in(miso) - .data_out(mosi); - let sdmmc_spi = spi::Config::new(mclk, sercom, pads_spi, freq) - .length::() - .bit_order(spi::BitOrder::MsbFirst) - .spi_mode(spi::MODE_0) - .enable(); - let time_sink: TimeSink = TimeSink::new(); // Need to give this a DateTime object for actual timing. - let mut sd_cont = sd::Controller::new(sd::SdMmcSpi::new(sdmmc_spi, cs), time_sink); - match sd_cont.device().init() { - Ok(_) => match sd_cont.device().card_size_bytes() { - Ok(size) => info!("Card is {} bytes", size), - Err(_) => warn!("Cannot get card size"), - }, - Err(_) => { - warn!("Cannot get SD card"); - panic!("Cannot get SD card."); - } - } - - let mut volume = match sd_cont.get_volume(sd::VolumeIdx(0)) { - Ok(volume) => volume, - Err(_) => { - warn!("Cannot get volume 0"); - panic!("Cannot get volume 0"); - } - }; - - let root_directory = match sd_cont.open_root_dir(&volume) { - Ok(root_directory) => root_directory, - Err(_) => { - warn!("Cannot get root"); - panic!("Cannot get root"); - } - }; - let file = sd_cont.open_file_in_dir( - &mut volume, - &root_directory, - "log.txt", - sd::Mode::ReadWriteCreateOrTruncate, - ); - let file = match file { - Ok(file) => file, - Err(_) => { - warn!("Cannot create file."); - panic!("Cannot create file."); - } - }; - - SdManager { - sd_controller: sd_cont, - volume, - root_directory, - file, - } - } - pub fn write( - &mut self, - // file: &mut sd::File, - buffer: &[u8], - ) -> Result> { - self.sd_controller.write(&mut self.volume, &mut self.file, buffer) - } - pub fn write_str( - &mut self, - file: &mut sd::File, - msg: &str, - ) -> Result> { - let buffer: &[u8] = msg.as_bytes(); - self.sd_controller.write(&mut self.volume, file, buffer) - } - pub fn open_file(&mut self, file_name: &str) -> Result> { - self.sd_controller.open_file_in_dir( - &mut self.volume, - &self.root_directory, - file_name, - sd::Mode::ReadWriteCreateOrTruncate, - ) - } - pub fn close_file(&mut self, file: sd::File) -> Result<(), sd::Error> { - self.sd_controller.close_file(&self.volume, file) - } - pub fn close(mut self) { - self.sd_controller - .close_dir(&self.volume, self.root_directory); - } -} - +use crate::types::SdController; +use core::marker::PhantomData; +use atsamd_hal::gpio::{Output, Pin, PushPull, PA16, PA17, PA18, PA19, PB14, PB13, PB15, PB12}; +use atsamd_hal::pac; +use atsamd_hal::sercom::{spi, IoSet1, Sercom1, Sercom4}; +use atsamd_hal::time::Hertz; +use defmt::{info, warn}; +use embedded_sdmmc as sd; + +/// Time source for `[SdInterface]`. It doesn't return any useful information for now, and will +/// always return an arbitrary time. +pub struct TimeSink { + _marker: PhantomData<*const ()>, +} + +impl TimeSink { + fn new() -> Self { + TimeSink { + _marker: PhantomData, + } + } +} + +impl sd::TimeSource for TimeSink { + fn get_timestamp(&self) -> sd::Timestamp { + sd::Timestamp { + year_since_1970: 0, + zero_indexed_month: 0, + zero_indexed_day: 0, + hours: 0, + minutes: 0, + seconds: 0, + } + } +} + +/// Wrapper for the SD Card. For now, the pins are hard-coded. +pub struct SdManager { + pub sd_controller: SdController, + pub volume: sd::Volume, + pub root_directory: sd::Directory, + pub file: Option, +} + +impl SdManager { + pub fn new( + mclk: &pac::MCLK, + sercom: pac::SERCOM4, + freq: Hertz, + cs: Pin>, + sck: Pin>, + miso: Pin>, + mosi: Pin>, + ) -> Self { + let pads_spi = spi::Pads::::default() + .sclk(sck) + .data_in(miso) + .data_out(mosi); + let sdmmc_spi = spi::Config::new(mclk, sercom, pads_spi, freq) + .length::() + .bit_order(spi::BitOrder::MsbFirst) + .spi_mode(spi::MODE_0) + .enable(); + let time_sink: TimeSink = TimeSink::new(); // Need to give this a DateTime object for actual timing. + let mut sd_cont = sd::Controller::new(sd::SdMmcSpi::new(sdmmc_spi, cs), time_sink); + match sd_cont.device().init() { + Ok(_) => match sd_cont.device().card_size_bytes() { + Ok(size) => info!("Card is {} bytes", size), + Err(_) => panic!("Cannot get card size"), + }, + Err(_) => { + panic!("Cannot get SD card."); + } + } + + let mut volume = match sd_cont.get_volume(sd::VolumeIdx(0)) { + Ok(volume) => volume, + Err(_) => { + panic!("Cannot get volume 0"); + } + }; + + let root_directory = match sd_cont.open_root_dir(&volume) { + Ok(root_directory) => root_directory, + Err(_) => { + panic!("Cannot get root"); + } + }; + let file = sd_cont.open_file_in_dir( + &mut volume, + &root_directory, + "log.txt", + sd::Mode::ReadWriteCreateOrTruncate, + ); + let file = match file { + Ok(file) => file, + Err(_) => { + panic!("Cannot create file."); + } + }; + + SdManager { + sd_controller: sd_cont, + volume, + root_directory, + file: Some(file), + } + } + pub fn write( + &mut self, + file: &mut sd::File, + buffer: &[u8], + ) -> Result> { + self.sd_controller.write(&mut self.volume, file, buffer) + } + pub fn write_str( + &mut self, + file: &mut sd::File, + msg: &str, + ) -> Result> { + let buffer: &[u8] = msg.as_bytes(); + self.sd_controller.write(&mut self.volume, file, buffer) + } + pub fn open_file(&mut self, file_name: &str) -> Result> { + self.sd_controller.open_file_in_dir( + &mut self.volume, + &self.root_directory, + file_name, + sd::Mode::ReadWriteCreateOrTruncate, + ) + } + pub fn close_current_file(&mut self) -> Result<(), sd::Error> { + if let Some(file) = self.file.take() { + return self.close_file(file); + } + Ok(()) + } + pub fn close_file(&mut self, file: sd::File) -> Result<(), sd::Error> { + self.sd_controller.close_file(&self.volume, file) + } + pub fn close(mut self) { + self.sd_controller + .close_dir(&self.volume, self.root_directory); + } +} + unsafe impl Send for SdManager {} \ No newline at end of file diff --git a/boards/communication/src/types.rs b/boards/communication/src/types.rs index 9b2f1b2b..83d216a9 100644 --- a/boards/communication/src/types.rs +++ b/boards/communication/src/types.rs @@ -1,42 +1,42 @@ -use crate::sd_manager::TimeSink; -use atsamd_hal::{gpio::*, dmac}; -use atsamd_hal::sercom::uart::EightBit; -use atsamd_hal::sercom::{spi, Sercom4}; -use atsamd_hal::sercom::{Sercom5, Sercom1, uart, IoSet1}; -use messages::sender::Sender; -use messages::sender::Sender::CommunicationBoard; -use embedded_sdmmc as sd; -use atsamd_hal::dmac::BufferPair; -use atsamd_hal::sercom::uart::Uart; - -// ------- -// Sender ID -// ------- -pub static COM_ID: Sender = CommunicationBoard; - -// ------- -// Ground Station -// ------- -pub type GroundStationPads = uart::PadsFromIds; -pub type GroundStationUartConfig = uart::Config; - -// ------- -// SD Card -// ------- -pub type SdPads = spi::Pads< - Sercom4, - IoSet1, - Pin>, - Pin>, - Pin>, ->; -pub type SdController = sd::Controller< - sd::SdMmcSpi, spi::Duplex>, Pin>>, - TimeSink, ->; - -pub type RadioTransfer = dmac::Transfer< - dmac::Channel, - BufferPair, RadioBuffer>, ->; +use crate::sd_manager::TimeSink; +use atsamd_hal::{gpio::*, dmac}; +use atsamd_hal::sercom::uart::EightBit; +use atsamd_hal::sercom::{spi, Sercom4}; +use atsamd_hal::sercom::{Sercom5, Sercom1, uart, IoSet1}; +use messages::sender::Sender; +use messages::sender::Sender::CommunicationBoard; +use embedded_sdmmc as sd; +use atsamd_hal::dmac::BufferPair; +use atsamd_hal::sercom::uart::Uart; + +// ------- +// Sender ID +// ------- +pub static COM_ID: Sender = CommunicationBoard; + +// ------- +// Ground Station +// ------- +pub type GroundStationPads = uart::PadsFromIds; +pub type GroundStationUartConfig = uart::Config; + +// ------- +// SD Card +// ------- +pub type SdPads = spi::Pads< + Sercom4, + IoSet1, + Pin>, + Pin>, + Pin>, +>; +pub type SdController = sd::Controller< + sd::SdMmcSpi, spi::Duplex>, Pin>>, + TimeSink, +>; + +pub type RadioTransfer = dmac::Transfer< + dmac::Channel, + BufferPair, RadioBuffer>, +>; pub type RadioBuffer = &'static mut [u8; 255]; \ No newline at end of file diff --git a/boards/power/Cargo.toml b/boards/power/Cargo.toml index 37dfe3bd..73764080 100644 --- a/boards/power/Cargo.toml +++ b/boards/power/Cargo.toml @@ -1,21 +1,21 @@ -[package] -name = "power" -version = "0.1.0" -edition = "2021" - -# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html - -[dependencies] -cortex-m = { workspace = true } -cortex-m-rt = "^0.7.0" -cortex-m-rtic = "1.1.3" -panic-halt = "0.2.0" -systick-monotonic = "1.0.1" -defmt = "0.3.2" -postcard = "1.0.2" -heapless = "0.7.16" -common-arm = { path = "../../libraries/common-arm" } -atsamd-hal = { workspace = true } -messages = { path = "../../libraries/messages" } -typenum = "1.16.0" +[package] +name = "power" +version = "0.1.0" +edition = "2021" + +# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html + +[dependencies] +cortex-m = { workspace = true } +cortex-m-rt = "^0.7.0" +cortex-m-rtic = "1.1.3" +panic-halt = "0.2.0" +systick-monotonic = "1.0.1" +defmt = "0.3.2" +postcard = "1.0.2" +heapless = "0.7.16" +common-arm = { path = "../../libraries/common-arm" } +atsamd-hal = { workspace = true } +messages = { path = "../../libraries/messages" } +typenum = "1.16.0" enum_dispatch = "0.3.11" \ No newline at end of file diff --git a/boards/power/src/communication.rs b/boards/power/src/communication.rs index 20229f15..3e11ed29 100644 --- a/boards/power/src/communication.rs +++ b/boards/power/src/communication.rs @@ -1,185 +1,174 @@ -use atsamd_hal as hal; -use hal::can::Dependencies; -use hal::pac::CAN0; -use hal::clock::v2::ahb::AhbClk; -use hal::clock::v2::gclk::Gclk0Id; -use hal::clock::v2::pclk::Pclk; -use hal::clock::v2::types::Can0; -use hal::clock::v2::Source; -use hal::gpio::{Alternate, AlternateI, Pin, I, PA22, PA23}; -use hal::typelevel::Increment; -use common_arm::mcan; -use mcan::message::{rx, Raw}; -use mcan::tx_buffers::DynTx; -use mcan::bus::Can; -use mcan::embedded_can as ecan; -use mcan::interrupt::state::EnabledLine0; // line 0 and 1 are connected -use mcan::interrupt::{Interrupt, OwnedInterruptSet}; -use mcan::message::tx; -use mcan::messageram::SharedMemory; -use mcan::{ - config::{BitTiming, Mode}, - filter::{Action, Filter}, -}; -use common_arm::HydraError; -use messages::Message; -use heapless::Vec; -use defmt::info; -use crate::data_manager::DataManager; -use systick_monotonic::fugit::RateExtU32; -use typenum::{U0, U128, U32, U64}; -use postcard::from_bytes; -pub struct Capacities; - -impl mcan::messageram::Capacities for Capacities { - type StandardFilters = U128; - type ExtendedFilters = U64; - type RxBufferMessage = rx::Message<64>; - type DedicatedRxBuffers = U64; - type RxFifo0Message = rx::Message<64>; - type RxFifo0 = U64; - type RxFifo1Message = rx::Message<64>; - type RxFifo1 = U64; - type TxMessage = tx::Message<64>; - type TxBuffers = U32; - type DedicatedTxBuffers = U0; - type TxEventFifo = U32; -} - -pub struct CanDevice0 { - pub can: Can< - 'static, - Can0, - Dependencies>, Pin>, CAN0>, - Capacities, - >, - line_interrupts: OwnedInterruptSet, -} - -impl CanDevice0 { - pub fn new( - can_rx: Pin, - can_tx: Pin, - pclk_can: Pclk, - ahb_clock: AhbClk, - peripheral: CAN0, - gclk0: S, - can_memory: &'static mut SharedMemory, - loopback: bool, - ) -> (Self, S::Inc) - where - S: Source + Increment, - { - let (can_dependencies, gclk0) = - Dependencies::new(gclk0, pclk_can, ahb_clock, can_rx, can_tx, peripheral); - - let mut can = - mcan::bus::CanConfigurable::new(200.kHz(), can_dependencies, can_memory).unwrap(); - can.config().mode = Mode::Fd { - allow_bit_rate_switching: false, - data_phase_timing: BitTiming::new(500.kHz()), - }; - - if loopback { - can.config().loopback = true; - } - - let interrupts_to_be_enabled = can - .interrupts() - .split( - [ - Interrupt::RxFifo0NewMessage, - Interrupt::RxFifo0Full, - Interrupt::RxFifo0MessageLost, - Interrupt::RxFifo1NewMessage, - Interrupt::RxFifo1Full, - Interrupt::RxFifo1MessageLost, - ] - .into_iter() - .collect(), - ) - .unwrap(); - - // Line 0 and 1 are connected to the same interrupt line - let line_interrupts = can - .interrupt_configuration() - .enable_line_0(interrupts_to_be_enabled); - - // We accept messages from the sensor board as we need data from the sensors. - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo0, - filter: ecan::StandardId::new(messages::sender::Sender::SensorBoard.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Sensor Board filter")); - - // We accept messages from the communication board as we may need to force the deployment of the parachute. - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo1, - filter: ecan::StandardId::new(messages::sender::Sender::CommunicationBoard.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Ground Station filter")); - - let can = can.finalize().unwrap(); - ( - CanDevice0 { - can, - line_interrupts, - }, - gclk0, - ) - } - pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { - let payload: Vec = postcard::to_vec(&m)?; - self.can.tx.transmit_queued( - tx::MessageBuilder { - id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), - frame_type: tx::FrameType::FlexibleDatarate { - payload: &payload[..], - bit_rate_switching: false, - force_error_state_indicator: false, - }, - store_tx_event: None, - } - .build()?, - )?; - Ok(()) - } - pub fn process_data(&mut self, data_manager: &mut DataManager) { - let line_interrupts = &self.line_interrupts; - for interrupt in line_interrupts.iter_flagged() { - match interrupt { - Interrupt::RxFifo0NewMessage => { - for message in &mut self.can.rx_fifo_0 { - match from_bytes::(message.data()) { - Ok(data) => { - data_manager.handle_data(data); - } - Err(e) => { - info!("Error: {:?}", e) - } - } - } - } - Interrupt::RxFifo1NewMessage => { - for message in &mut self.can.rx_fifo_1 { - match from_bytes::(message.data()) { - Ok(data) => { - data_manager.handle_data(data); - } - Err(e) => { - info!("Error: {:?}", e) - } - } - } - } - _ => (), - } - } - } +use atsamd_hal as hal; +use hal::can::Dependencies; +use hal::pac::CAN0; +use hal::clock::v2::ahb::AhbClk; +use hal::clock::v2::gclk::Gclk0Id; +use hal::clock::v2::pclk::Pclk; +use hal::clock::v2::types::Can0; +use hal::clock::v2::Source; +use hal::gpio::{Alternate, AlternateI, Pin, I, PA22, PA23}; +use hal::typelevel::Increment; +use common_arm::mcan; +use mcan::message::{rx, Raw}; +use mcan::tx_buffers::DynTx; +use mcan::bus::Can; +use mcan::embedded_can as ecan; +use mcan::interrupt::state::EnabledLine0; // line 0 and 1 are connected +use mcan::interrupt::{Interrupt, OwnedInterruptSet}; +use mcan::message::tx; +use mcan::messageram::SharedMemory; +use mcan::{ + config::{BitTiming, Mode}, + filter::{Action, Filter}, +}; +use common_arm::HydraError; +use messages::Message; +use heapless::Vec; +use defmt::info; +use crate::data_manager::DataManager; +use systick_monotonic::fugit::RateExtU32; +use typenum::{U0, U128, U32, U64}; +use postcard::from_bytes; +pub struct Capacities; + +impl mcan::messageram::Capacities for Capacities { + type StandardFilters = U128; + type ExtendedFilters = U64; + type RxBufferMessage = rx::Message<64>; + type DedicatedRxBuffers = U64; + type RxFifo0Message = rx::Message<64>; + type RxFifo0 = U64; + type RxFifo1Message = rx::Message<64>; + type RxFifo1 = U64; + type TxMessage = tx::Message<64>; + type TxBuffers = U32; + type DedicatedTxBuffers = U0; + type TxEventFifo = U32; +} + +pub struct CanDevice0 { + pub can: Can< + 'static, + Can0, + Dependencies>, Pin>, CAN0>, + Capacities, + >, + line_interrupts: OwnedInterruptSet, +} + +impl CanDevice0 { + pub fn new( + can_rx: Pin, + can_tx: Pin, + pclk_can: Pclk, + ahb_clock: AhbClk, + peripheral: CAN0, + gclk0: S, + can_memory: &'static mut SharedMemory, + loopback: bool, + ) -> (Self, S::Inc) + where + S: Source + Increment, + { + let (can_dependencies, gclk0) = + Dependencies::new(gclk0, pclk_can, ahb_clock, can_rx, can_tx, peripheral); + + let mut can = + mcan::bus::CanConfigurable::new(200.kHz(), can_dependencies, can_memory).unwrap(); + can.config().mode = Mode::Fd { + allow_bit_rate_switching: false, + data_phase_timing: BitTiming::new(500.kHz()), + }; + + if loopback { + can.config().loopback = true; + } + + let interrupts_to_be_enabled = can + .interrupts() + .split( + [ + Interrupt::RxFifo0NewMessage, + Interrupt::RxFifo0Full, + Interrupt::RxFifo0MessageLost, + Interrupt::RxFifo1NewMessage, + Interrupt::RxFifo1Full, + Interrupt::RxFifo1MessageLost, + ] + .into_iter() + .collect(), + ) + .unwrap(); + + // Line 0 and 1 are connected to the same interrupt line + let line_interrupts = can + .interrupt_configuration() + .enable_line_0(interrupts_to_be_enabled); + + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo1, + filter: ecan::StandardId::new(messages::sender::Sender::CommunicationBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Ground Station filter")); + + let can = can.finalize().unwrap(); + ( + CanDevice0 { + can, + line_interrupts, + }, + gclk0, + ) + } + pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { + let payload: Vec = postcard::to_vec(&m)?; + self.can.tx.transmit_queued( + tx::MessageBuilder { + id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), + frame_type: tx::FrameType::FlexibleDatarate { + payload: &payload[..], + bit_rate_switching: false, + force_error_state_indicator: false, + }, + store_tx_event: None, + } + .build()?, + )?; + Ok(()) + } + pub fn process_data(&mut self, data_manager: &mut DataManager) { + let line_interrupts = &self.line_interrupts; + for interrupt in line_interrupts.iter_flagged() { + match interrupt { + Interrupt::RxFifo0NewMessage => { + for message in &mut self.can.rx_fifo_0 { + match from_bytes::(message.data()) { + Ok(data) => { + data_manager.handle_data(data); + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + Interrupt::RxFifo1NewMessage => { + for message in &mut self.can.rx_fifo_1 { + match from_bytes::(message.data()) { + Ok(data) => { + data_manager.handle_data(data); + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + _ => (), + } + } + } } \ No newline at end of file diff --git a/boards/power/src/data_manager.rs b/boards/power/src/data_manager.rs index 1a149386..b7cdb6d3 100644 --- a/boards/power/src/data_manager.rs +++ b/boards/power/src/data_manager.rs @@ -1,47 +1,47 @@ -// import messages -use messages::sensor::{Current, Voltage, Regulator, Temperature, SensorData}; -use messages::Message; - -pub struct DataManager { - pub regulator: [Option; 4], - pub voltage: [Option; 4], - pub current: Option, - pub temperature: [Option; 4], -} - -impl DataManager { - pub fn new() -> Self { - Self { - regulator: [None, None, None, None], - voltage: [None, None, None, None], - current: None, - temperature: [None, None, None, None], - } - } - pub fn clone_power(&self) -> [Option; 13] { - [ - self.regulator[0].clone().map(|x| x.into()), - self.regulator[1].clone().map(|x| x.into()), - self.regulator[2].clone().map(|x| x.into()), - self.regulator[3].clone().map(|x| x.into()), - self.voltage[0].clone().map(|x| x.into()), - self.voltage[1].clone().map(|x| x.into()), - self.voltage[2].clone().map(|x| x.into()), - self.voltage[3].clone().map(|x| x.into()), - self.current.clone().map(|x| x.into()), - self.temperature[0].clone().map(|x| x.into()), - self.temperature[1].clone().map(|x| x.into()), - self.temperature[2].clone().map(|x| x.into()), - self.temperature[3].clone().map(|x| x.into()), - ] - } - pub fn handle_data(&mut self, data: Message) { - // to do - } -} - -impl Default for DataManager { - fn default() -> Self { - Self::new() - } +// import messages +use messages::sensor::{Current, Voltage, Regulator, Temperature, SensorData}; +use messages::Message; + +pub struct DataManager { + pub regulator: [Option; 4], + pub voltage: [Option; 4], + pub current: Option, + pub temperature: [Option; 4], +} + +impl DataManager { + pub fn new() -> Self { + Self { + regulator: [None, None, None, None], + voltage: [None, None, None, None], + current: None, + temperature: [None, None, None, None], + } + } + pub fn clone_power(&self) -> [Option; 13] { + [ + self.regulator[0].clone().map(|x| x.into()), + self.regulator[1].clone().map(|x| x.into()), + self.regulator[2].clone().map(|x| x.into()), + self.regulator[3].clone().map(|x| x.into()), + self.voltage[0].clone().map(|x| x.into()), + self.voltage[1].clone().map(|x| x.into()), + self.voltage[2].clone().map(|x| x.into()), + self.voltage[3].clone().map(|x| x.into()), + self.current.clone().map(|x| x.into()), + self.temperature[0].clone().map(|x| x.into()), + self.temperature[1].clone().map(|x| x.into()), + self.temperature[2].clone().map(|x| x.into()), + self.temperature[3].clone().map(|x| x.into()), + ] + } + pub fn handle_data(&mut self, data: Message) { + // to do + } +} + +impl Default for DataManager { + fn default() -> Self { + Self::new() + } } \ No newline at end of file diff --git a/boards/power/src/main.rs b/boards/power/src/main.rs index c3cbd2cf..c2573639 100644 --- a/boards/power/src/main.rs +++ b/boards/power/src/main.rs @@ -1,158 +1,152 @@ -#![no_std] -#![no_main] - -mod communication; -mod data_manager; -mod types; - -use atsamd_hal as hal; -use hal::clock::v2::pclk::Pclk; -use hal::clock::v2::Source; -use hal::prelude::*; -use hal::gpio::{PB16, PushPullOutput, Pin, PB17, Pins}; -use common_arm::*; -use common_arm::mcan; -use mcan::messageram::SharedMemory; -use communication::Capacities; -use communication::CanDevice0; -use systick_monotonic::*; -use panic_halt as _; -use defmt::info; - -#[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] -mod app { - use hal::gpio::{PA10, Input, Floating, Alternate, B, PA08, C, PA09, PA02, AlternateB}; - - use crate::data_manager::DataManager; - - use super::*; - - #[shared] - struct Shared { - em: ErrorManager, - data_manager: DataManager, - can0: CanDevice0, - } - - #[local] - struct Local { - led_green: Pin, - led_red: Pin, - adc_test: hal::adc::Adc, - adc_pin: Pin, - } - - #[monotonic(binds = SysTick, default = true)] - type SysMono = Systick<100>; // 100 Hz / 10 ms granularity - - #[init(local = [ - #[link_section = ".can"] - can_memory: SharedMemory = SharedMemory::new() - ])] - fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { - let mut peripherals = cx.device; - let core = cx.core; - let pins = Pins::new(peripherals.PORT); - - /* Clock setup */ - let (_, clocks, tokens) = hal::clock::v2::clock_system_at_reset( - peripherals.OSCCTRL, - peripherals.OSC32KCTRL, - peripherals.GCLK, - peripherals.MCLK, - &mut peripherals.NVMCTRL, - ); - let gclk0 = clocks.gclk0; - - /* CAN config */ - let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0); - let (can0, gclk0) = communication::CanDevice0::new( - pins.pa23.into_mode(), - pins.pa22.into_mode(), - pclk_can, - clocks.ahbs.can0, - peripherals.CAN0, - gclk0, - cx.local.can_memory, - false, - ); - - - - let (pclk_adc0, gclk0) = Pclk::enable(tokens.pclks.adc0, gclk0); - - - // SAFETY: Misusing the PAC API can break the system. - // This is safe because we only steal the MCLK. - let (_, _, gclk, mut mclk) = unsafe { clocks.pac.steal() }; - - - // setup ADC - let mut adc_test = hal::adc::Adc::adc0(peripherals.ADC0, &mut mclk); - - - // LEDs - let led_green = pins.pb16.into_push_pull_output(); - let led_red = pins.pb17.into_push_pull_output(); - - blink::spawn().ok(); - adc::spawn().ok(); - - /* Monotonic clock */ - let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); - - ( - Shared { - em: ErrorManager::new(), - data_manager: DataManager::new(), - can0, - }, - Local { - led_green, led_red, adc_test, adc_pin: pins.pa10.into_alternate() - }, - init::Monotonics(mono), - ) - } - - /// Idle task for when no other tasks are running. - #[idle] - fn idle(_: idle::Context) -> ! { - loop {} - } - - #[task(local = [adc_test, adc_pin], shared = [&em])] - fn adc(cx: adc::Context) { - // test adc for 5v PWR sense - info!("try adc"); - cx.shared.em.run(||{ - let val = cx.local.adc_test.read(cx.local.adc_pin); - let x: u16 = match val { - Ok(v) => { - v - } - Err(_) => { - 0 - } - }; - info!("{}", x); - Ok(()) - }); - spawn_after!(adc, ExtU64::millis(500)).ok(); - } - - /// Simple blink task to test the system. - /// Acts as a heartbeat for the system. - #[task(local = [led_green, led_red], shared = [&em])] - fn blink(cx: blink::Context) { - cx.shared.em.run(|| { - if cx.shared.em.has_error() { - cx.local.led_red.toggle()?; - spawn_after!(blink, ExtU64::millis(200))?; - } else { - cx.local.led_green.toggle()?; - spawn_after!(blink, ExtU64::secs(1))?; - } - Ok(()) - }); - } +#![no_std] +#![no_main] + +mod communication; +mod data_manager; +mod types; + +use atsamd_hal as hal; +use hal::clock::v2::pclk::Pclk; +use hal::clock::v2::Source; +use hal::prelude::*; +use hal::gpio::{PB16, PushPullOutput, Pin, PB17, Pins}; +use common_arm::*; +use common_arm::mcan; +use mcan::messageram::SharedMemory; +use communication::Capacities; +use communication::CanDevice0; +use systick_monotonic::*; +use panic_halt as _; +use crate::data_manager::DataManager; + +#[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] +mod app { + use super::*; + + #[shared] + struct Shared { + em: ErrorManager, + data_manager: DataManager, + can0: CanDevice0, + } + + #[local] + struct Local { + led_green: Pin, + led_red: Pin, + } + + #[monotonic(binds = SysTick, default = true)] + type SysMono = Systick<100>; // 100 Hz / 10 ms granularity + + #[init(local = [ + #[link_section = ".can"] + can_memory: SharedMemory = SharedMemory::new() + ])] + fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { + let mut peripherals = cx.device; + let core = cx.core; + let pins = Pins::new(peripherals.PORT); + + /* Clock setup */ + let (_, clocks, tokens) = hal::clock::v2::clock_system_at_reset( + peripherals.OSCCTRL, + peripherals.OSC32KCTRL, + peripherals.GCLK, + peripherals.MCLK, + &mut peripherals.NVMCTRL, + ); + let gclk0 = clocks.gclk0; + + /* CAN config */ + let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0); + let (can0, gclk0) = communication::CanDevice0::new( + pins.pa23.into_mode(), + pins.pa22.into_mode(), + pclk_can, + clocks.ahbs.can0, + peripherals.CAN0, + gclk0, + cx.local.can_memory, + false, + ); + + + + // let (pclk_adc0, gclk0) = Pclk::enable(tokens.pclks.adc0, gclk0); + + + // // SAFETY: Misusing the PAC API can break the system. + // // This is safe because we only steal the MCLK. + // let (_, _, gclk, mut mclk) = unsafe { clocks.pac.steal() }; + + + // // setup ADC + // let mut adc_test = hal::adc::Adc::adc0(peripherals.ADC0, &mut mclk); + + + // LEDs + let led_green = pins.pb16.into_push_pull_output(); + let led_red = pins.pb17.into_push_pull_output(); + + blink::spawn().ok(); + // adc::spawn().ok(); + + /* Monotonic clock */ + let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); + + ( + Shared { + em: ErrorManager::new(), + data_manager: DataManager::new(), + can0, + }, + Local { + led_green, led_red, + }, + init::Monotonics(mono), + ) + } + + /// Idle task for when no other tasks are running. + #[idle] + fn idle(_: idle::Context) -> ! { + loop {} + } + + // #[task(local = [adc_test, adc_pin], shared = [&em])] + // fn adc(cx: adc::Context) { + // // test adc for 5v PWR sense + // info!("try adc"); + // cx.shared.em.run(||{ + // let val = cx.local.adc_test.read(cx.local.adc_pin); + // let x: u16 = match val { + // Ok(v) => { + // v + // } + // Err(_) => { + // 0 + // } + // }; + // info!("{}", x); + // Ok(()) + // }); + // spawn_after!(adc, ExtU64::millis(500)).ok(); + // } + + /// Simple blink task to test the system. + /// Acts as a heartbeat for the system. + #[task(local = [led_green, led_red], shared = [&em])] + fn blink(cx: blink::Context) { + cx.shared.em.run(|| { + if cx.shared.em.has_error() { + cx.local.led_red.toggle()?; + spawn_after!(blink, ExtU64::millis(200))?; + } else { + cx.local.led_green.toggle()?; + spawn_after!(blink, ExtU64::secs(1))?; + } + Ok(()) + }); + } } \ No newline at end of file diff --git a/boards/power/src/types.rs b/boards/power/src/types.rs index 58d2ab49..cf6f8db0 100644 --- a/boards/power/src/types.rs +++ b/boards/power/src/types.rs @@ -1,5 +1,5 @@ -use messages::sender::{Sender, Sender::PowerBoard}; -// ------- -// Sender ID -// ------- +use messages::sender::{Sender, Sender::PowerBoard}; +// ------- +// Sender ID +// ------- pub static COM_ID: Sender = PowerBoard; \ No newline at end of file diff --git a/boards/recovery/src/communication.rs b/boards/recovery/src/communication.rs index bd708b84..e30867da 100644 --- a/boards/recovery/src/communication.rs +++ b/boards/recovery/src/communication.rs @@ -1,187 +1,187 @@ -/// Encapsulates all communication logic. -use atsamd_hal::can::Dependencies; -use atsamd_hal::clock::v2::ahb::AhbClk; -use atsamd_hal::clock::v2::gclk::Gclk0Id; -use atsamd_hal::clock::v2::pclk::Pclk; -use atsamd_hal::clock::v2::types::Can0; -use atsamd_hal::clock::v2::Source; -use atsamd_hal::gpio::{Alternate, AlternateI, Pin, I, PA22, PA23}; -use atsamd_hal::pac::CAN0; -use atsamd_hal::typelevel::Increment; -use common_arm::mcan; -use common_arm::mcan::message::{rx, Raw}; -use common_arm::mcan::tx_buffers::DynTx; -use common_arm::HydraError; -use defmt::info; -use heapless::Vec; -use mcan::bus::Can; -use mcan::embedded_can as ecan; -use mcan::interrupt::state::EnabledLine0; -use mcan::interrupt::{Interrupt, OwnedInterruptSet}; -use mcan::message::tx; -use mcan::messageram::SharedMemory; -use mcan::{ - config::{BitTiming, Mode}, - filter::{Action, Filter}, -}; - -use crate::data_manager::DataManager; -use messages::Message; -use postcard::from_bytes; -use systick_monotonic::fugit::RateExtU32; -use typenum::{U0, U128, U32, U64}; - -pub struct Capacities; - -impl mcan::messageram::Capacities for Capacities { - type StandardFilters = U128; - type ExtendedFilters = U64; - type RxBufferMessage = rx::Message<64>; - type DedicatedRxBuffers = U64; - type RxFifo0Message = rx::Message<64>; - type RxFifo0 = U64; - type RxFifo1Message = rx::Message<64>; - type RxFifo1 = U64; - type TxMessage = tx::Message<64>; - type TxBuffers = U32; - type DedicatedTxBuffers = U0; - type TxEventFifo = U32; -} - -pub struct CanDevice0 { - pub can: Can< - 'static, - Can0, - Dependencies>, Pin>, CAN0>, - Capacities, - >, - line_interrupts: OwnedInterruptSet, -} - -impl CanDevice0 { - pub fn new( - can_rx: Pin, - can_tx: Pin, - pclk_can: Pclk, - ahb_clock: AhbClk, - peripheral: CAN0, - gclk0: S, - can_memory: &'static mut SharedMemory, - loopback: bool, - ) -> (Self, S::Inc) - where - S: Source + Increment, - { - let (can_dependencies, gclk0) = - Dependencies::new(gclk0, pclk_can, ahb_clock, can_rx, can_tx, peripheral); - - let mut can = - mcan::bus::CanConfigurable::new(200.kHz(), can_dependencies, can_memory).unwrap(); - can.config().mode = Mode::Fd { - allow_bit_rate_switching: false, - data_phase_timing: BitTiming::new(500.kHz()), - }; - - if loopback { - can.config().loopback = true; - } - - let interrupts_to_be_enabled = can - .interrupts() - .split( - [ - Interrupt::RxFifo0NewMessage, - Interrupt::RxFifo0Full, - Interrupt::RxFifo0MessageLost, - Interrupt::RxFifo1NewMessage, - Interrupt::RxFifo1Full, - Interrupt::RxFifo1MessageLost, - ] - .into_iter() - .collect(), - ) - .unwrap(); - - // Line 0 and 1 are connected to the same interrupt line - let line_interrupts = can - .interrupt_configuration() - .enable_line_0(interrupts_to_be_enabled); - - // We accept messages from the sensor board as we need data from the sensors. - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo0, - filter: ecan::StandardId::new(messages::sender::Sender::SensorBoard.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Sensor Board filter")); - - // We accept messages from the communication board as we may need to force the deployment of the parachute. - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo1, - filter: ecan::StandardId::new(messages::sender::Sender::CommunicationBoard.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Ground Station filter")); - - let can = can.finalize().unwrap(); - ( - CanDevice0 { - can, - line_interrupts, - }, - gclk0, - ) - } - pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { - let payload: Vec = postcard::to_vec(&m)?; - self.can.tx.transmit_queued( - tx::MessageBuilder { - id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), - frame_type: tx::FrameType::FlexibleDatarate { - payload: &payload[..], - bit_rate_switching: false, - force_error_state_indicator: false, - }, - store_tx_event: None, - } - .build()?, - )?; - Ok(()) - } - pub fn process_data(&mut self, data_manager: &mut DataManager) { - let line_interrupts = &self.line_interrupts; - for interrupt in line_interrupts.iter_flagged() { - match interrupt { - Interrupt::RxFifo0NewMessage => { - for message in &mut self.can.rx_fifo_0 { - match from_bytes::(message.data()) { - Ok(data) => { - data_manager.handle_data(data); - } - Err(e) => { - info!("Error: {:?}", e) - } - } - } - } - Interrupt::RxFifo1NewMessage => { - for message in &mut self.can.rx_fifo_1 { - match from_bytes::(message.data()) { - Ok(data) => { - data_manager.handle_data(data); - } - Err(e) => { - info!("Error: {:?}", e) - } - } - } - } - _ => (), - } - } - } -} +/// Encapsulates all communication logic. +use atsamd_hal::can::Dependencies; +use atsamd_hal::clock::v2::ahb::AhbClk; +use atsamd_hal::clock::v2::gclk::Gclk0Id; +use atsamd_hal::clock::v2::pclk::Pclk; +use atsamd_hal::clock::v2::types::Can0; +use atsamd_hal::clock::v2::Source; +use atsamd_hal::gpio::{Alternate, AlternateI, Pin, I, PA22, PA23}; +use atsamd_hal::pac::CAN0; +use atsamd_hal::typelevel::Increment; +use common_arm::mcan; +use common_arm::mcan::message::{rx, Raw}; +use common_arm::mcan::tx_buffers::DynTx; +use common_arm::HydraError; +use defmt::info; +use heapless::Vec; +use mcan::bus::Can; +use mcan::embedded_can as ecan; +use mcan::interrupt::state::EnabledLine0; +use mcan::interrupt::{Interrupt, OwnedInterruptSet}; +use mcan::message::tx; +use mcan::messageram::SharedMemory; +use mcan::{ + config::{BitTiming, Mode}, + filter::{Action, Filter}, +}; + +use crate::data_manager::DataManager; +use messages::Message; +use postcard::from_bytes; +use systick_monotonic::fugit::RateExtU32; +use typenum::{U0, U128, U32, U64}; + +pub struct Capacities; + +impl mcan::messageram::Capacities for Capacities { + type StandardFilters = U128; + type ExtendedFilters = U64; + type RxBufferMessage = rx::Message<64>; + type DedicatedRxBuffers = U64; + type RxFifo0Message = rx::Message<64>; + type RxFifo0 = U64; + type RxFifo1Message = rx::Message<64>; + type RxFifo1 = U64; + type TxMessage = tx::Message<64>; + type TxBuffers = U32; + type DedicatedTxBuffers = U0; + type TxEventFifo = U32; +} + +pub struct CanDevice0 { + pub can: Can< + 'static, + Can0, + Dependencies>, Pin>, CAN0>, + Capacities, + >, + line_interrupts: OwnedInterruptSet, +} + +impl CanDevice0 { + pub fn new( + can_rx: Pin, + can_tx: Pin, + pclk_can: Pclk, + ahb_clock: AhbClk, + peripheral: CAN0, + gclk0: S, + can_memory: &'static mut SharedMemory, + loopback: bool, + ) -> (Self, S::Inc) + where + S: Source + Increment, + { + let (can_dependencies, gclk0) = + Dependencies::new(gclk0, pclk_can, ahb_clock, can_rx, can_tx, peripheral); + + let mut can = + mcan::bus::CanConfigurable::new(200.kHz(), can_dependencies, can_memory).unwrap(); + can.config().mode = Mode::Fd { + allow_bit_rate_switching: false, + data_phase_timing: BitTiming::new(500.kHz()), + }; + + if loopback { + can.config().loopback = true; + } + + let interrupts_to_be_enabled = can + .interrupts() + .split( + [ + Interrupt::RxFifo0NewMessage, + Interrupt::RxFifo0Full, + Interrupt::RxFifo0MessageLost, + Interrupt::RxFifo1NewMessage, + Interrupt::RxFifo1Full, + Interrupt::RxFifo1MessageLost, + ] + .into_iter() + .collect(), + ) + .unwrap(); + + // Line 0 and 1 are connected to the same interrupt line + let line_interrupts = can + .interrupt_configuration() + .enable_line_0(interrupts_to_be_enabled); + + // We accept messages from the sensor board as we need data from the sensors. + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo0, + filter: ecan::StandardId::new(messages::sender::Sender::SensorBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Sensor Board filter")); + + // We accept messages from the communication board as we may need to force the deployment of the parachute. + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo1, + filter: ecan::StandardId::new(messages::sender::Sender::CommunicationBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Ground Station filter")); + + let can = can.finalize().unwrap(); + ( + CanDevice0 { + can, + line_interrupts, + }, + gclk0, + ) + } + pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { + let payload: Vec = postcard::to_vec(&m)?; + self.can.tx.transmit_queued( + tx::MessageBuilder { + id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), + frame_type: tx::FrameType::FlexibleDatarate { + payload: &payload[..], + bit_rate_switching: false, + force_error_state_indicator: false, + }, + store_tx_event: None, + } + .build()?, + )?; + Ok(()) + } + pub fn process_data(&mut self, data_manager: &mut DataManager) { + let line_interrupts = &self.line_interrupts; + for interrupt in line_interrupts.iter_flagged() { + match interrupt { + Interrupt::RxFifo0NewMessage => { + for message in &mut self.can.rx_fifo_0 { + match from_bytes::(message.data()) { + Ok(data) => { + data_manager.handle_data(data); + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + Interrupt::RxFifo1NewMessage => { + for message in &mut self.can.rx_fifo_1 { + match from_bytes::(message.data()) { + Ok(data) => { + data_manager.handle_data(data); + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + _ => (), + } + } + } +} diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index 5b2b86c2..4956ba43 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -1,159 +1,183 @@ -use crate::state_machine::RocketStates; -use crate::app::{fire_drogue, fire_main}; -use common_arm::spawn; -use heapless::HistoryBuffer; -use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, UtcTime}; -use messages::Message; -use defmt::{info}; - -const MAIN_HEIGHT: f32 = 500.0; -const HEIGHT_MIN: f32 = 300.0; - -pub struct DataManager { - pub air: Option, - pub ekf_nav: (Option, Option), - pub ekf_quat: Option, - pub imu: (Option, Option), - pub utc_time: Option, - pub gps_vel: Option, - pub historical_barometer_altitude: HistoryBuffer<(f32, u32), 8>, - pub current_state: Option, -} - -impl DataManager { - pub fn new() -> Self { - let historical_barometer_altitude = HistoryBuffer::new(); - Self { - air: None, - ekf_nav: (None, None), - ekf_quat: None, - imu: (None, None), - utc_time: None, - gps_vel: None, - historical_barometer_altitude, - current_state: None, - } - } - /// Returns true if the rocket is descending - pub fn is_falling(&self) -> bool { - // if let Some(air) = &self.air { - // if air.altitude < HEIGHT_MIN { - // return false - // } - // } else { - // return false; - // } - if self.historical_barometer_altitude.len() < 8 { - return false; - } - let mut buf = self.historical_barometer_altitude.oldest_ordered(); - match buf.next() { - Some(last) => { - let mut avg_sum: f32 = 0.0; - let mut prev = last; - for i in buf { - let time_diff: f32 = (i.1 - prev.1) as f32 / 1_000_000.0; - if time_diff == 0.0 { - continue; - } - avg_sum += (i.0 - prev.0)/time_diff; - prev = i; - } - match avg_sum / 7.0 { // 7 because we have 8 points. - x if !(-100.0..=-2.0).contains(&x) => { - info!("avg: {}", avg_sum / 7.0); - return false; - } - _ => { - info!("avg: {}", avg_sum / 7.0); - } - } - } - None => { - return false; - } - } - true - } - pub fn is_launched(&self) -> bool { - match self.air.as_ref() { - Some(air) => air.altitude > HEIGHT_MIN, - None => false, - } - } - pub fn is_below_main(&self) -> bool { - match self.air.as_ref() { - Some(air) => air.altitude < MAIN_HEIGHT, - None => false, - } - } - pub fn get_alt(&self) -> f32 { - match self.air.as_ref() { - Some(air) => air.altitude, - None => 0.0, - } - } - pub fn set_state(&mut self, state: RocketStates) { - self.current_state = Some(state); - } - pub fn handle_data(&mut self, data: Message) { - match data.data { - messages::Data::Sensor(sensor) => match sensor.data { - messages::sensor::SensorData::Air(air_data) => { - let tup_data = (air_data.altitude, air_data.time_stamp); - self.air = Some(air_data); - if let Some(recent) = self.historical_barometer_altitude.recent() { - if recent.1 != tup_data.1 { - self.historical_barometer_altitude.write(tup_data); - } else { - info!("duplicate data {}", tup_data.1); - } - } else { - self.historical_barometer_altitude.write(tup_data); - } - } - messages::sensor::SensorData::EkfNav1(nav1_data) => { - self.ekf_nav.0 = Some(nav1_data); - } - messages::sensor::SensorData::EkfNav2(nav2_data) => { - self.ekf_nav.1 = Some(nav2_data); - } - messages::sensor::SensorData::EkfQuat(quat_data) => { - self.ekf_quat = Some(quat_data); - } - messages::sensor::SensorData::GpsVel(gps_vel_data) => { - self.gps_vel = Some(gps_vel_data); - } - messages::sensor::SensorData::Imu1(imu1_data) => { - self.imu.0 = Some(imu1_data); - } - messages::sensor::SensorData::Imu2(imu2_data) => { - self.imu.1 = Some(imu2_data); - } - messages::sensor::SensorData::UtcTime(utc_time_data) => { - self.utc_time = Some(utc_time_data); - }, - _ => { - info!("impl power"); - } - }, - messages::Data::Command(command) => match command.data { - messages::command::CommandData::DeployDrogue(drogue) => { - spawn!(fire_drogue); - }, - messages::command::CommandData::DeployMain(main) => { - spawn!(fire_main); - } - } - _ => { - info!("unkown"); - } - } - } -} - -impl Default for DataManager { - fn default() -> Self { - Self::new() - } -} +use crate::state_machine::RocketStates; +use crate::app::{fire_drogue, fire_main}; +use common_arm::spawn; +use heapless::HistoryBuffer; +use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, UtcTime}; +use messages::Message; +use defmt::{info}; + +const MAIN_HEIGHT: f32 = 500.0; // meters +const HEIGHT_MIN: f32 = 300.0; // meters + +pub struct DataManager { + pub air: Option, + pub ekf_nav: (Option, Option), + pub ekf_quat: Option, + pub imu: (Option, Option), + pub utc_time: Option, + pub gps_vel: Option, + pub historical_barometer_altitude: HistoryBuffer<(f32, u32), 8>, + pub current_state: Option, +} + +impl DataManager { + pub fn new() -> Self { + let historical_barometer_altitude = HistoryBuffer::new(); + Self { + air: None, + ekf_nav: (None, None), + ekf_quat: None, + imu: (None, None), + utc_time: None, + gps_vel: None, + historical_barometer_altitude, + current_state: None, + } + } + /// Returns true if the rocket is descending + pub fn is_falling(&self) -> bool { + if self.historical_barometer_altitude.len() < 8 { + return false; + } + let mut buf = self.historical_barometer_altitude.oldest_ordered(); + match buf.next() { + Some(last) => { + let mut avg_sum: f32 = 0.0; + let mut prev = last; + for i in buf { + let time_diff: f32 = (i.1 - prev.1) as f32 / 1_000_000.0; + if time_diff == 0.0 { + continue; + } + avg_sum += (i.0 - prev.0)/time_diff; + prev = i; + } + match avg_sum / 7.0 { // 7 because we have 8 points. + x if !(-100.0..=-2.0).contains(&x) => { + info!("avg: {}", avg_sum / 7.0); + return false; + } + _ => { + info!("avg: {}", avg_sum / 7.0); + } + } + } + None => { + return false; + } + } + true + } + pub fn is_launched(&self) -> bool { + match self.air.as_ref() { + Some(air) => air.altitude > HEIGHT_MIN, + None => false, + } + } + pub fn is_landed(&self) -> bool { + if self.historical_barometer_altitude.len() < 8 { + return false; + } + let mut buf = self.historical_barometer_altitude.oldest_ordered(); + match buf.next() { + Some(last) => { + let mut avg_sum: f32 = 0.0; + let mut prev = last; + for i in buf { + let time_diff: f32 = (i.1 - prev.1) as f32 / 1_000_000.0; + if time_diff == 0.0 { + continue; + } + avg_sum += (i.0 - prev.0)/time_diff; + prev = i; + } + match avg_sum / 7.0 { + // if we aren't going faster than +- 1 m/s it is safe to assume we have landed. + x if (1.0..=-1.0).contains(&x) => { + info!("avg: {}", avg_sum / 7.0); + return true; + } + _ => { + info!("avg: {}", avg_sum / 7.0); + } + } + } + None => { + return false; + } + } + false + } + pub fn is_below_main(&self) -> bool { + match self.air.as_ref() { + Some(air) => air.altitude < MAIN_HEIGHT, + None => false, + } + } + pub fn set_state(&mut self, state: RocketStates) { + self.current_state = Some(state); + } + pub fn handle_data(&mut self, data: Message) { + match data.data { + messages::Data::Sensor(sensor) => match sensor.data { + messages::sensor::SensorData::Air(air_data) => { + let tup_data = (air_data.altitude, air_data.time_stamp); + self.air = Some(air_data); + if let Some(recent) = self.historical_barometer_altitude.recent() { + if recent.1 != tup_data.1 { + self.historical_barometer_altitude.write(tup_data); + } else { + info!("duplicate data {}", tup_data.1); + } + } else { + self.historical_barometer_altitude.write(tup_data); + } + } + messages::sensor::SensorData::EkfNav1(nav1_data) => { + self.ekf_nav.0 = Some(nav1_data); + } + messages::sensor::SensorData::EkfNav2(nav2_data) => { + self.ekf_nav.1 = Some(nav2_data); + } + messages::sensor::SensorData::EkfQuat(quat_data) => { + self.ekf_quat = Some(quat_data); + } + messages::sensor::SensorData::GpsVel(gps_vel_data) => { + self.gps_vel = Some(gps_vel_data); + } + messages::sensor::SensorData::Imu1(imu1_data) => { + self.imu.0 = Some(imu1_data); + } + messages::sensor::SensorData::Imu2(imu2_data) => { + self.imu.1 = Some(imu2_data); + } + messages::sensor::SensorData::UtcTime(utc_time_data) => { + self.utc_time = Some(utc_time_data); + }, + _ => { + info!("impl power"); + } + }, + messages::Data::Command(command) => match command.data { + messages::command::CommandData::DeployDrogue(drogue) => { + spawn!(fire_drogue); + }, + messages::command::CommandData::DeployMain(main) => { + spawn!(fire_main); + }, + messages::command::CommandData::PowerDown(_) => { + // don't handle for now. + } + } + _ => { + info!("unkown"); + } + } + } +} + +impl Default for DataManager { + fn default() -> Self { + Self::new() + } +} diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 6cc8f4c6..77718502 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -1,214 +1,211 @@ -#![no_std] -#![no_main] - -mod communication; -mod data_manager; -mod state_machine; -mod types; - - -use atsamd_hal as hal; -use atsamd_hal::clock::v2::pclk::Pclk; -use atsamd_hal::clock::v2::Source; -use atsamd_hal::dmac::DmaController; -use common_arm::mcan; -use common_arm::*; -use communication::Capacities; -use data_manager::DataManager; -use hal::gpio::{Pin, Pins, PushPullOutput, PB16, PB17}; -use hal::prelude::*; -use mcan::messageram::SharedMemory; -use messages::*; -use panic_halt as _; -use state_machine::{StateMachine, StateMachineContext}; -use systick_monotonic::*; -use types::GPIOController; -use types::COM_ID; -use defmt::info; - -#[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] -mod app { - use super::*; - - #[shared] - struct Shared { - em: ErrorManager, - data_manager: DataManager, - can0: communication::CanDevice0, - gpio: GPIOController, - } - - #[local] - struct Local { - led_green: Pin, - led_red: Pin, - state_machine: StateMachine, - } - - #[monotonic(binds = SysTick, default = true)] - type SysMono = Systick<100>; // 100 Hz / 10 ms granularity - - #[init(local = [ - #[link_section = ".can"] - can_memory: SharedMemory = SharedMemory::new() - ])] - fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { - let mut peripherals = cx.device; - let core = cx.core; - let pins = Pins::new(peripherals.PORT); - - let mut dmac = DmaController::init(peripherals.DMAC, &mut peripherals.PM); - let _dmaChannels = dmac.split(); - - /* Clock setup */ - let (_, clocks, tokens) = atsamd_hal::clock::v2::clock_system_at_reset( - peripherals.OSCCTRL, - peripherals.OSC32KCTRL, - peripherals.GCLK, - peripherals.MCLK, - &mut peripherals.NVMCTRL, - ); - let gclk0 = clocks.gclk0; - - // SAFETY: Misusing the PAC API can break the system. - // This is safe because we only steal the MCLK. - let (_, _, _, _mclk) = unsafe { clocks.pac.steal() }; - - /* CAN config */ - let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0); - let (can0, gclk0) = communication::CanDevice0::new( - pins.pa23.into_mode(), - pins.pa22.into_mode(), - pclk_can, - clocks.ahbs.can0, - peripherals.CAN0, - gclk0, - cx.local.can_memory, - false, - ); - - /* GPIO config */ - let led_green = pins.pb16.into_push_pull_output(); - let led_red = pins.pb17.into_push_pull_output(); - let gpio = GPIOController::new( - pins.pa09.into_push_pull_output(), - pins.pa06.into_push_pull_output(), - ); - /* State Machine config */ - let state_machine = StateMachine::new(); - - /* Spawn tasks */ - run_sm::spawn().ok(); - state_send::spawn().ok(); - blink::spawn().ok(); - - /* Monotonic clock */ - let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); - - ( - Shared { - em: ErrorManager::new(), - data_manager: DataManager::new(), - can0, - gpio, - }, - Local {led_green, led_red, state_machine}, - init::Monotonics(mono), - ) - } - - /// Idle task for when no other tasks are running. - #[idle] - fn idle(_: idle::Context) -> ! { - loop {} - } - - #[task(shared=[gpio])] - fn fire_drogue(mut cx: fire_drogue::Context) { - cx.shared.gpio.lock(|gpio| { - gpio.fire_drogue(); - }); - } - - #[task(shared=[gpio])] - fn fire_main(mut cx: fire_main::Context) { - cx.shared.gpio.lock(|gpio| { - gpio.fire_main(); - }); - } - - /// Runs the state machine. - /// This takes control of the shared resources. - #[task(priority = 3, local = [state_machine], shared = [can0, gpio, data_manager, &em])] - fn run_sm(mut cx: run_sm::Context) { - cx.shared.data_manager.lock(|dm| info!("alt: {}", dm.get_alt())); - cx.local.state_machine.run(&mut StateMachineContext { - shared_resources: &mut cx.shared, - }); - cx.shared.data_manager.lock(|data| { - data.set_state(cx.local.state_machine.get_state()); - }); - // !! Question, will this error and then never spawn again? Should I just keep trying to spawn it and not care - // to use the error manager. - spawn_after!(run_sm, ExtU64::millis(500)).ok(); - } - - /// Handles the CAN0 interrupt. - #[task(binds = CAN0, shared = [can0, data_manager])] - fn can0(mut cx: can0::Context) { - cx.shared.can0.lock(|can| { - cx.shared - .data_manager - .lock(|data_manager| can.process_data(data_manager)); - }); - } - - /// Sends a message over CAN. - #[task(capacity = 10, shared = [can0, &em])] - fn send_internal(mut cx: send_internal::Context, m: Message) { - cx.shared.em.run(|| { - cx.shared.can0.lock(|can| can.send_message(m))?; - Ok(()) - }); - } - - /// Sends info about the current state of the system. - #[task(shared = [data_manager, &em])] - fn state_send(mut cx: state_send::Context) { - cx.shared.em.run(|| { - let rocket_state = cx - .shared - .data_manager - .lock(|data| data.current_state.clone()); - let state = if let Some(rocket_state) = rocket_state { - rocket_state - } else { - // This isn't really an error, we just don't have data yet. - return Ok(()) - }; - let board_state = messages::state::State { - data: state.into(), - }; - let message = Message::new(&monotonics::now(), COM_ID, board_state); - spawn!(send_internal, message)?; - Ok(()) - }); - spawn_after!(state_send, ExtU64::secs(2)); - } - - /// Simple blink task to test the system. - /// Acts as a heartbeat for the system. - #[task(local = [led_green, led_red], shared = [&em])] - fn blink(cx: blink::Context) { - cx.shared.em.run(|| { - if cx.shared.em.has_error() { - cx.local.led_red.toggle()?; - spawn_after!(blink, ExtU64::millis(200))?; - } else { - cx.local.led_green.toggle()?; - spawn_after!(blink, ExtU64::secs(1))?; - } - Ok(()) - }); - } -} +#![no_std] +#![no_main] + +mod communication; +mod data_manager; +mod state_machine; +mod types; + + +use atsamd_hal as hal; +use atsamd_hal::clock::v2::pclk::Pclk; +use atsamd_hal::clock::v2::Source; +use atsamd_hal::dmac::DmaController; +use common_arm::mcan; +use common_arm::*; +use communication::Capacities; +use data_manager::DataManager; +use hal::gpio::{Pin, Pins, PushPullOutput, PB16, PB17}; +use hal::prelude::*; +use mcan::messageram::SharedMemory; +use messages::*; +use panic_halt as _; +use state_machine::{StateMachine, StateMachineContext}; +use systick_monotonic::*; +use types::GPIOController; +use types::COM_ID; +use defmt::info; + +#[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] +mod app { + use super::*; + + #[shared] + struct Shared { + em: ErrorManager, + data_manager: DataManager, + can0: communication::CanDevice0, + gpio: GPIOController, + } + + #[local] + struct Local { + led_green: Pin, + led_red: Pin, + state_machine: StateMachine, + } + + #[monotonic(binds = SysTick, default = true)] + type SysMono = Systick<100>; // 100 Hz / 10 ms granularity + + #[init(local = [ + #[link_section = ".can"] + can_memory: SharedMemory = SharedMemory::new() + ])] + fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { + let mut peripherals = cx.device; + let core = cx.core; + let pins = Pins::new(peripherals.PORT); + + let mut dmac = DmaController::init(peripherals.DMAC, &mut peripherals.PM); + let _dmaChannels = dmac.split(); + + /* Clock setup */ + let (_, clocks, tokens) = atsamd_hal::clock::v2::clock_system_at_reset( + peripherals.OSCCTRL, + peripherals.OSC32KCTRL, + peripherals.GCLK, + peripherals.MCLK, + &mut peripherals.NVMCTRL, + ); + let gclk0 = clocks.gclk0; + + // SAFETY: Misusing the PAC API can break the system. + // This is safe because we only steal the MCLK. + let (_, _, _, _mclk) = unsafe { clocks.pac.steal() }; + + /* CAN config */ + let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0); + let (can0, gclk0) = communication::CanDevice0::new( + pins.pa23.into_mode(), + pins.pa22.into_mode(), + pclk_can, + clocks.ahbs.can0, + peripherals.CAN0, + gclk0, + cx.local.can_memory, + false, + ); + + /* GPIO config */ + let led_green = pins.pb16.into_push_pull_output(); + let led_red = pins.pb17.into_push_pull_output(); + let gpio = GPIOController::new( + pins.pa09.into_push_pull_output(), + pins.pa06.into_push_pull_output(), + ); + /* State Machine config */ + let state_machine = StateMachine::new(); + + /* Spawn tasks */ + run_sm::spawn().ok(); + state_send::spawn().ok(); + blink::spawn().ok(); + + /* Monotonic clock */ + let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); + + ( + Shared { + em: ErrorManager::new(), + data_manager: DataManager::new(), + can0, + gpio, + }, + Local {led_green, led_red, state_machine}, + init::Monotonics(mono), + ) + } + + /// Idle task for when no other tasks are running. + #[idle] + fn idle(_: idle::Context) -> ! { + loop {} + } + + #[task(shared=[gpio])] + fn fire_drogue(mut cx: fire_drogue::Context) { + cx.shared.gpio.lock(|gpio| { + gpio.fire_drogue(); + }); + } + + #[task(shared=[gpio])] + fn fire_main(mut cx: fire_main::Context) { + cx.shared.gpio.lock(|gpio| { + gpio.fire_main(); + }); + } + + /// Runs the state machine. + /// This takes control of the shared resources. + #[task(priority = 3, local = [state_machine], shared = [can0, gpio, data_manager, &em])] + fn run_sm(mut cx: run_sm::Context) { + cx.local.state_machine.run(&mut StateMachineContext { + shared_resources: &mut cx.shared, + }); + cx.shared.data_manager.lock(|data| { + data.set_state(cx.local.state_machine.get_state()); + }); + spawn_after!(run_sm, ExtU64::millis(500)).ok(); + } + + /// Handles the CAN0 interrupt. + #[task(binds = CAN0, shared = [can0, data_manager])] + fn can0(mut cx: can0::Context) { + cx.shared.can0.lock(|can| { + cx.shared + .data_manager + .lock(|data_manager| can.process_data(data_manager)); + }); + } + + /// Sends a message over CAN. + #[task(capacity = 10, shared = [can0, &em])] + fn send_internal(mut cx: send_internal::Context, m: Message) { + cx.shared.em.run(|| { + cx.shared.can0.lock(|can| can.send_message(m))?; + Ok(()) + }); + } + + /// Sends info about the current state of the system. + #[task(shared = [data_manager, &em])] + fn state_send(mut cx: state_send::Context) { + cx.shared.em.run(|| { + let rocket_state = cx + .shared + .data_manager + .lock(|data| data.current_state.clone()); + let state = if let Some(rocket_state) = rocket_state { + rocket_state + } else { + // This isn't really an error, we just don't have data yet. + return Ok(()) + }; + let board_state = messages::state::State { + data: state.into(), + }; + let message = Message::new(&monotonics::now(), COM_ID, board_state); + spawn!(send_internal, message)?; + Ok(()) + }); + spawn_after!(state_send, ExtU64::secs(2)); + } + + /// Simple blink task to test the system. + /// Acts as a heartbeat for the system. + #[task(local = [led_green, led_red], shared = [&em])] + fn blink(cx: blink::Context) { + cx.shared.em.run(|| { + if cx.shared.em.has_error() { + cx.local.led_red.toggle()?; + spawn_after!(blink, ExtU64::millis(200))?; + } else { + cx.local.led_green.toggle()?; + spawn_after!(blink, ExtU64::secs(1))?; + } + Ok(()) + }); + } +} diff --git a/boards/recovery/src/state_machine/mod.rs b/boards/recovery/src/state_machine/mod.rs index e6236701..30aac831 100644 --- a/boards/recovery/src/state_machine/mod.rs +++ b/boards/recovery/src/state_machine/mod.rs @@ -1,112 +1,111 @@ -mod black_magic; -mod states; - -use messages::state; -use crate::communication::CanDevice0; -use crate::data_manager::DataManager; -use crate::state_machine::states::*; -use crate::GPIOController; -pub use black_magic::*; -pub use states::Initializing; -use core::fmt::Debug; -use defmt::Format; -use enum_dispatch::enum_dispatch; -use rtic::Mutex; - -pub trait StateMachineSharedResources { - fn lock_can(&mut self, f: &dyn Fn(&mut CanDevice0)); - fn lock_data_manager(&mut self, f: &dyn Fn(&mut DataManager)); - fn lock_gpio(&mut self, f: &dyn Fn(&mut GPIOController)); -} - -impl<'a> StateMachineSharedResources for crate::app::__rtic_internal_run_smSharedResources<'a> { - fn lock_can(&mut self, fun: &dyn Fn(&mut CanDevice0)) { - self.can0.lock(fun) - } - fn lock_data_manager(&mut self, fun: &dyn Fn(&mut DataManager)) { - self.data_manager.lock(fun) - } - fn lock_gpio(&mut self, fun: &dyn Fn(&mut GPIOController)) { - self.gpio.lock(fun) - } -} - -pub struct StateMachineContext<'a, 'b> { - pub shared_resources: &'b mut crate::app::__rtic_internal_run_smSharedResources<'a> -} -pub struct StateMachine { - state: RocketStates, -} - -// Define some functions to interact with the state machine -impl StateMachine { - pub fn new() -> Self { - let state = Initializing {}; - - StateMachine { - state: state.into(), - } - } - - pub fn run(&mut self, context: &mut StateMachineContext) { - if let Some(new_state) = self.state.step(context) { - self.state.exit(); - // context.shared_resources.data_manager.lock(|data| { - // data.set_state(new_state.clone()); - // }); - new_state.enter(context); - self.state = new_state; - } - } - - pub fn get_state(&self) -> RocketStates { - self.state.clone() - } -} - -// All events are found here -pub enum RocketEvents { - DeployDrogue, - DeployMain, -} - -// All states are defined here. Another struct must be defined for the actual state, and that struct -// must implement the State trait -#[enum_dispatch(State)] -#[derive(Debug, Format, Clone)] -pub enum RocketStates { - Initializing, - WaitForTakeoff, - Ascent, - Descent, - TerminalDescent, - Abort, -} - -// Not ideal, but it works for now. -// Should be able to put this is a shared library. -impl From for RocketStates { - fn from(state: state::StateData) -> Self { - match state { - state::StateData::Initializing => RocketStates::Initializing(Initializing {}), - state::StateData::WaitForTakeoff => RocketStates::WaitForTakeoff(WaitForTakeoff {}), - state::StateData::Ascent => RocketStates::Ascent(Ascent {}), - state::StateData::Descent => RocketStates::Descent(Descent {}), - state::StateData::TerminalDescent => RocketStates::TerminalDescent(TerminalDescent { } ), - state::StateData::Abort => RocketStates::Abort(Abort {}), - } - } -} - -impl Into for RocketStates { - fn into(self) -> state::StateData { - match self { - RocketStates::Initializing(_) => state::StateData::Initializing, - RocketStates::WaitForTakeoff(_) => state::StateData::WaitForTakeoff, - RocketStates::Ascent(_) => state::StateData::Ascent, - RocketStates::Descent(_) => state::StateData::Descent, - RocketStates::TerminalDescent(_) => state::StateData::TerminalDescent, - RocketStates::Abort(_) => state::StateData::Abort, - } - } +mod black_magic; +mod states; + +use messages::state; +use crate::communication::CanDevice0; +use crate::data_manager::DataManager; +use crate::state_machine::states::*; +use crate::GPIOController; +pub use black_magic::*; +pub use states::Initializing; +use core::fmt::Debug; +use defmt::Format; +use enum_dispatch::enum_dispatch; +use rtic::Mutex; + +pub trait StateMachineSharedResources { + fn lock_can(&mut self, f: &dyn Fn(&mut CanDevice0)); + fn lock_data_manager(&mut self, f: &dyn Fn(&mut DataManager)); + fn lock_gpio(&mut self, f: &dyn Fn(&mut GPIOController)); +} + +impl<'a> StateMachineSharedResources for crate::app::__rtic_internal_run_smSharedResources<'a> { + fn lock_can(&mut self, fun: &dyn Fn(&mut CanDevice0)) { + self.can0.lock(fun) + } + fn lock_data_manager(&mut self, fun: &dyn Fn(&mut DataManager)) { + self.data_manager.lock(fun) + } + fn lock_gpio(&mut self, fun: &dyn Fn(&mut GPIOController)) { + self.gpio.lock(fun) + } +} + +pub struct StateMachineContext<'a, 'b> { + pub shared_resources: &'b mut crate::app::__rtic_internal_run_smSharedResources<'a> +} +pub struct StateMachine { + state: RocketStates, +} + +// Define some functions to interact with the state machine +impl StateMachine { + pub fn new() -> Self { + let state = Initializing {}; + + StateMachine { + state: state.into(), + } + } + + pub fn run(&mut self, context: &mut StateMachineContext) { + if let Some(new_state) = self.state.step(context) { + self.state.exit(); + new_state.enter(context); + self.state = new_state; + } + } + + pub fn get_state(&self) -> RocketStates { + self.state.clone() + } +} + +// All events are found here +pub enum RocketEvents { + DeployDrogue, + DeployMain, +} + +// All states are defined here. Another struct must be defined for the actual state, and that struct +// must implement the State trait +#[enum_dispatch(State)] +#[derive(Debug, Format, Clone)] +pub enum RocketStates { + Initializing, + WaitForTakeoff, + Ascent, + Descent, + TerminalDescent, + WaitForRecovery, + Abort, +} + +// Not a fan of this. +// Should be able to put this is a shared library. +impl From for RocketStates { + fn from(state: state::StateData) -> Self { + match state { + state::StateData::Initializing => RocketStates::Initializing(Initializing {}), + state::StateData::WaitForTakeoff => RocketStates::WaitForTakeoff(WaitForTakeoff {}), + state::StateData::Ascent => RocketStates::Ascent(Ascent {}), + state::StateData::Descent => RocketStates::Descent(Descent {}), + state::StateData::TerminalDescent => RocketStates::TerminalDescent(TerminalDescent { } ), + state::StateData::WaitForRecovery => RocketStates::WaitForTakeoff(WaitForTakeoff { }), + state::StateData::Abort => RocketStates::Abort(Abort {}), + } + } +} +impl Into for RocketStates { + fn into(self) -> state::StateData { + match self { + RocketStates::Initializing(_) => state::StateData::Initializing, + RocketStates::WaitForTakeoff(_) => state::StateData::WaitForTakeoff, + RocketStates::Ascent(_) => state::StateData::Ascent, + RocketStates::Descent(_) => state::StateData::Descent, + RocketStates::TerminalDescent(_) => state::StateData::TerminalDescent, + RocketStates::WaitForRecovery(_) => state::StateData::WaitForRecovery, + RocketStates::Abort(_) => state::StateData::Abort, + } + } } \ No newline at end of file diff --git a/boards/recovery/src/state_machine/states/ascent.rs b/boards/recovery/src/state_machine/states/ascent.rs index 6dd92afe..b3efa120 100644 --- a/boards/recovery/src/state_machine/states/ascent.rs +++ b/boards/recovery/src/state_machine/states/ascent.rs @@ -1,36 +1,36 @@ -use crate::state_machine::states::descent::Descent; -use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; -use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; -use crate::{no_transition, transition}; -use defmt::{write, Format, Formatter}; -use rtic::mutex::Mutex; - -#[derive(Debug, Clone)] -pub struct Ascent {} - -impl State for Ascent { - fn step(&mut self, context: &mut StateMachineContext) -> Option { - context - .shared_resources - .data_manager - .lock(|data| { - if data.is_falling() { - transition!(self, Descent) - } else { - no_transition!() - } - }) - } -} - -impl TransitionInto for WaitForTakeoff { - fn transition(&self) -> Ascent { - Ascent {} - } -} - -impl Format for Ascent { - fn format(&self, f: Formatter) { - write!(f, "Ascent") - } -} +use crate::state_machine::states::descent::Descent; +use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; +use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; +use crate::{no_transition, transition}; +use defmt::{write, Format, Formatter}; +use rtic::mutex::Mutex; + +#[derive(Debug, Clone)] +pub struct Ascent {} + +impl State for Ascent { + fn step(&mut self, context: &mut StateMachineContext) -> Option { + context + .shared_resources + .data_manager + .lock(|data| { + if data.is_falling() { + transition!(self, Descent) + } else { + no_transition!() + } + }) + } +} + +impl TransitionInto for WaitForTakeoff { + fn transition(&self) -> Ascent { + Ascent {} + } +} + +impl Format for Ascent { + fn format(&self, f: Formatter) { + write!(f, "Ascent") + } +} diff --git a/boards/recovery/src/state_machine/states/descent.rs b/boards/recovery/src/state_machine/states/descent.rs index 04309087..09ac9436 100644 --- a/boards/recovery/src/state_machine/states/descent.rs +++ b/boards/recovery/src/state_machine/states/descent.rs @@ -1,39 +1,35 @@ -use super::Ascent; -use crate::state_machine::{TerminalDescent, RocketStates, State, StateMachineContext, TransitionInto}; -use crate::{no_transition, transition}; -use rtic::mutex::Mutex; -use defmt::{write, Format, Formatter, info}; - -#[derive(Debug, Clone)] -pub struct Descent {} - -impl State for Descent { - fn enter(&self, context: &mut StateMachineContext) { - info!("Apogee"); - context.shared_resources.gpio.lock(|gpio| gpio.fire_drogue()); - } - fn step(&mut self, context: &mut StateMachineContext) -> Option { - // is this 450 AGL? I could put these types of values in a top file like - // types.rs to make it easier to change. - context.shared_resources.data_manager.lock(|data| { - // Handle the case where we don't have any data yet - if data.is_below_main() { - transition!(self, TerminalDescent) - } else { - no_transition!() - } - }) - } -} - -impl TransitionInto for Ascent { - fn transition(&self) -> Descent { - Descent {} - } -} - -impl Format for Descent { - fn format(&self, f: Formatter) { - write!(f, "Descent") - } -} +use super::Ascent; +use crate::state_machine::{TerminalDescent, RocketStates, State, StateMachineContext, TransitionInto}; +use crate::{no_transition, transition}; +use rtic::mutex::Mutex; +use defmt::{write, Format, Formatter, info}; + +#[derive(Debug, Clone)] +pub struct Descent {} + +impl State for Descent { + fn enter(&self, context: &mut StateMachineContext) { + context.shared_resources.gpio.lock(|gpio| gpio.fire_drogue()); + } + fn step(&mut self, context: &mut StateMachineContext) -> Option { + context.shared_resources.data_manager.lock(|data| { + if data.is_below_main() { + transition!(self, TerminalDescent) + } else { + no_transition!() + } + }) + } +} + +impl TransitionInto for Ascent { + fn transition(&self) -> Descent { + Descent {} + } +} + +impl Format for Descent { + fn format(&self, f: Formatter) { + write!(f, "Descent") + } +} diff --git a/boards/recovery/src/state_machine/states/initializing.rs b/boards/recovery/src/state_machine/states/initializing.rs index ce88f32a..51d98b62 100644 --- a/boards/recovery/src/state_machine/states/initializing.rs +++ b/boards/recovery/src/state_machine/states/initializing.rs @@ -9,7 +9,6 @@ pub struct Initializing {} impl State for Initializing { fn step(&mut self, _context: &mut StateMachineContext) -> Option { - // Check that all systems are ok, then transition transition!(self, WaitForTakeoff) } } diff --git a/boards/recovery/src/state_machine/states/mod.rs b/boards/recovery/src/state_machine/states/mod.rs index fd24eb7c..f4d4c3fe 100644 --- a/boards/recovery/src/state_machine/states/mod.rs +++ b/boards/recovery/src/state_machine/states/mod.rs @@ -1,13 +1,15 @@ -mod initializing; -mod terminal_descent; -mod ascent; -mod descent; -mod wait_for_takeoff; -mod abort; - -pub use crate::state_machine::states::descent::Descent; -pub use crate::state_machine::states::ascent::Ascent; -pub use crate::state_machine::states::initializing::Initializing; -pub use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; -pub use crate::state_machine::states::terminal_descent::TerminalDescent; +mod initializing; +mod terminal_descent; +mod ascent; +mod descent; +mod wait_for_takeoff; +mod wait_for_recovery; +mod abort; + +pub use crate::state_machine::states::descent::Descent; +pub use crate::state_machine::states::ascent::Ascent; +pub use crate::state_machine::states::initializing::Initializing; +pub use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; +pub use crate::state_machine::states::terminal_descent::TerminalDescent; +pub use crate::state_machine::states::wait_for_recovery::WaitForRecovery; pub use crate::state_machine::states::abort::Abort; \ No newline at end of file diff --git a/boards/recovery/src/state_machine/states/terminal_descent.rs b/boards/recovery/src/state_machine/states/terminal_descent.rs index 1e5dcc76..a307ff13 100644 --- a/boards/recovery/src/state_machine/states/terminal_descent.rs +++ b/boards/recovery/src/state_machine/states/terminal_descent.rs @@ -1,31 +1,39 @@ -use defmt::{write, Format, Formatter, info}; - -use crate::no_transition; -use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; -use rtic::mutex::Mutex; -use super::Descent; - -#[derive(Debug, Clone)] -pub struct TerminalDescent {} - -impl State for TerminalDescent { - fn enter(&self,context: &mut StateMachineContext) { - info!("Terminal Descent"); - context.shared_resources.gpio.lock(|gpio| gpio.fire_main()); - } - fn step(&mut self, _context: &mut StateMachineContext) -> Option { - no_transition!() - } -} - -impl TransitionInto for Descent { - fn transition(&self) -> TerminalDescent { - TerminalDescent {} - } -} - -impl Format for TerminalDescent { - fn format(&self, f: Formatter) { - write!(f, "Terminal Descent") - } -} +use defmt::{write, Format, Formatter, info}; + +use crate::{no_transition, transition}; +use crate::state_machine::{WaitForRecovery, RocketStates, State, StateMachineContext, TransitionInto}; +use rtic::mutex::Mutex; +use super::Descent; + +#[derive(Debug, Clone)] +pub struct TerminalDescent {} + +impl State for TerminalDescent { + fn enter(&self,context: &mut StateMachineContext) { + context.shared_resources.gpio.lock(|gpio| gpio.fire_main()); + } + fn step(&mut self, context: &mut StateMachineContext) -> Option { + context + .shared_resources + .data_manager + .lock(|data| { + if data.is_landed() { + transition!(self, WaitForRecovery) + } else { + no_transition!() + } + }) + } +} + +impl TransitionInto for Descent { + fn transition(&self) -> TerminalDescent { + TerminalDescent {} + } +} + +impl Format for TerminalDescent { + fn format(&self, f: Formatter) { + write!(f, "Terminal Descent") + } +} diff --git a/boards/recovery/src/state_machine/states/wait_for_recovery.rs b/boards/recovery/src/state_machine/states/wait_for_recovery.rs new file mode 100644 index 00000000..e8f36d12 --- /dev/null +++ b/boards/recovery/src/state_machine/states/wait_for_recovery.rs @@ -0,0 +1,39 @@ +use super::TerminalDescent; +use crate::app::monotonics; +use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; +use crate::types::COM_ID; +use crate::{no_transition, transition}; +use rtic::mutex::Mutex; +use defmt::{write, Format, Formatter, info}; +use messages::command::{Command, CommandData, PowerDown}; +use messages::Message; +use messages::sender::Sender::SensorBoard; + +#[derive(Debug, Clone)] +pub struct WaitForRecovery {} + +impl State for WaitForRecovery { + fn enter(&self, context: &mut StateMachineContext) { + // send a command over CAN to shut down non-critical systems for recovery. + let sensor_power_down = PowerDown { + board: SensorBoard + }; + let message = Message::new(&monotonics::now(), COM_ID, Command::new(sensor_power_down)); + context.shared_resources.can0.lock(|can| can.send_message(message)); // unhandled result + } + fn step(&mut self, context: &mut StateMachineContext) -> Option { + no_transition!() // this is our final resting place. We should also powerdown this board. + } +} + +impl TransitionInto for TerminalDescent { + fn transition(&self) -> WaitForRecovery { + WaitForRecovery {} + } +} + +impl Format for WaitForRecovery { + fn format(&self, f: Formatter) { + write!(f, "Descent") + } +} diff --git a/boards/recovery/src/types.rs b/boards/recovery/src/types.rs index 7b2456ae..7cae5fc6 100644 --- a/boards/recovery/src/types.rs +++ b/boards/recovery/src/types.rs @@ -1,36 +1,36 @@ -use atsamd_hal::gpio::{Pin, PushPullOutput, PA09, PA06}; -use atsamd_hal::prelude::*; -use messages::sender::Sender; -use messages::sender::Sender::RecoveryBoard; - -// ------- -// Sender ID -// ------- -pub static COM_ID: Sender = RecoveryBoard; - - -pub struct GPIOController { - drogue_ematch: Pin, - main_ematch: Pin, -} - -impl GPIOController { - pub fn new(drogue_ematch: Pin, main_ematch: Pin) -> Self { - Self { - drogue_ematch, - main_ematch - } - } - pub fn fire_drogue(&mut self) { - self.drogue_ematch.set_high().ok(); - } - pub fn fire_main(&mut self) { - self.main_ematch.set_high().ok(); - } - pub fn close_drouge(&mut self) { - self.drogue_ematch.set_low().ok(); - } - pub fn close_main(&mut self) { - self.main_ematch.set_low().ok(); - } +use atsamd_hal::gpio::{Pin, PushPullOutput, PA09, PA06}; +use atsamd_hal::prelude::*; +use messages::sender::Sender; +use messages::sender::Sender::RecoveryBoard; + +// ------- +// Sender ID +// ------- +pub static COM_ID: Sender = RecoveryBoard; + + +pub struct GPIOController { + drogue_ematch: Pin, + main_ematch: Pin, +} + +impl GPIOController { + pub fn new(drogue_ematch: Pin, main_ematch: Pin) -> Self { + Self { + drogue_ematch, + main_ematch + } + } + pub fn fire_drogue(&mut self) { + self.drogue_ematch.set_high().ok(); + } + pub fn fire_main(&mut self) { + self.main_ematch.set_high().ok(); + } + pub fn close_drouge(&mut self) { + self.drogue_ematch.set_low().ok(); + } + pub fn close_main(&mut self) { + self.main_ematch.set_low().ok(); + } } \ No newline at end of file diff --git a/boards/sensor/Cargo.toml b/boards/sensor/Cargo.toml index 4ecf0024..943de5c5 100644 --- a/boards/sensor/Cargo.toml +++ b/boards/sensor/Cargo.toml @@ -1,23 +1,23 @@ -[package] -name = "sensor" -version = "0.1.0" -edition = "2021" - -# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html - -[dependencies] -cortex-m = { workspace = true } -cortex-m-rt = "^0.7.0" -cortex-m-rtic = "1.1.3" -panic-halt = "0.2.0" -systick-monotonic = "1.0.1" -defmt = "0.3.2" -postcard = "1.0.2" -heapless = "0.7.16" -common-arm = { path = "../../libraries/common-arm" } -atsamd-hal = { workspace = true } -messages = { path = "../../libraries/messages" } -sbg-rs = {path = "../../libraries/sbg-rs"} -embedded-sdmmc = "0.3.0" # port to v5 -typenum = "1.16.0" +[package] +name = "sensor" +version = "0.1.0" +edition = "2021" + +# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html + +[dependencies] +cortex-m = { workspace = true } +cortex-m-rt = "^0.7.0" +cortex-m-rtic = "1.1.3" +panic-halt = "0.2.0" +systick-monotonic = "1.0.1" +defmt = "0.3.2" +postcard = "1.0.2" +heapless = "0.7.16" +common-arm = { path = "../../libraries/common-arm" } +atsamd-hal = { workspace = true } +messages = { path = "../../libraries/messages" } +sbg-rs = {path = "../../libraries/sbg-rs"} +embedded-sdmmc = "0.3.0" # port to v5 +typenum = "1.16.0" embedded-alloc = "0.5.0" \ No newline at end of file diff --git a/boards/sensor/src/communication.rs b/boards/sensor/src/communication.rs index 2987e8e6..59af1120 100644 --- a/boards/sensor/src/communication.rs +++ b/boards/sensor/src/communication.rs @@ -1,341 +1,197 @@ -use atsamd_hal::can::Dependencies; -use atsamd_hal::clock::v2::ahb::AhbClk; -use atsamd_hal::clock::v2::gclk::Gclk0Id; -use atsamd_hal::clock::v2::pclk::Pclk; - -use atsamd_hal::clock::v2::types::{Can0, Can1}; -use atsamd_hal::clock::v2::Source; -use atsamd_hal::gpio::{Alternate, AlternateI, AlternateH, Pin, I, H, PA22, PA23, PB15, PB14}; -use atsamd_hal::pac::{CAN0, CAN1}; - -use atsamd_hal::typelevel::Increment; -use common_arm::mcan; -use common_arm::mcan::message::{rx, Raw}; -use common_arm::mcan::tx_buffers::DynTx; -use common_arm::HydraError; -use defmt::info; -use heapless::Vec; -use mcan::bus::Can; -use mcan::embedded_can as ecan; -use mcan::interrupt::state::EnabledLine0; -use mcan::interrupt::{Interrupt, OwnedInterruptSet}; -use mcan::message::tx; -use mcan::messageram::SharedMemory; -use mcan::{ - config::{BitTiming, Mode}, - filter::{Action, Filter}, -}; - -use messages::Message; -use postcard::from_bytes; -use systick_monotonic::fugit::RateExtU32; -use typenum::{U0, U128, U32, U64}; - -pub struct Capacities; - -impl mcan::messageram::Capacities for Capacities { - type StandardFilters = U128; - type ExtendedFilters = U64; - type RxBufferMessage = rx::Message<64>; - type DedicatedRxBuffers = U64; - type RxFifo0Message = rx::Message<64>; - type RxFifo0 = U64; - type RxFifo1Message = rx::Message<64>; - type RxFifo1 = U64; - type TxMessage = tx::Message<64>; - type TxBuffers = U32; - type DedicatedTxBuffers = U0; - type TxEventFifo = U32; -} - -pub struct CanDevice0 { - pub can: Can< - 'static, - Can0, - Dependencies>, Pin>, CAN0>, - Capacities, - >, - line_interrupts: OwnedInterruptSet, -} - -impl CanDevice0 { - pub fn new( - can_rx: Pin, - can_tx: Pin, - pclk_can: Pclk, - ahb_clock: AhbClk, - peripheral: CAN0, - gclk0: S, - can_memory: &'static mut SharedMemory, - loopback: bool, - ) -> (Self, S::Inc) - where - S: Source + Increment, - { - let (can_dependencies, gclk0) = - Dependencies::new(gclk0, pclk_can, ahb_clock, can_rx, can_tx, peripheral); - - let mut can = - mcan::bus::CanConfigurable::new(200.kHz(), can_dependencies, can_memory).unwrap(); - can.config().mode = Mode::Fd { - allow_bit_rate_switching: false, - data_phase_timing: BitTiming::new(500.kHz()), - }; - - if loopback { - can.config().loopback = true; - } - - let interrupts_to_be_enabled = can - .interrupts() - .split( - [ - Interrupt::RxFifo0NewMessage, - Interrupt::RxFifo0Full, - Interrupt::RxFifo0MessageLost, - Interrupt::RxFifo1NewMessage, - Interrupt::RxFifo1Full, - Interrupt::RxFifo1MessageLost, - ] - .into_iter() - .collect(), - ) - .unwrap(); - - // Line 0 and 1 are connected to the same interrupt line - let line_interrupts = can - .interrupt_configuration() - .enable_line_0(interrupts_to_be_enabled); - - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo0, - filter: ecan::StandardId::new(messages::sender::Sender::CommunicationBoard.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Self filter")); - - - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo0, - filter: ecan::StandardId::new(messages::sender::Sender::RecoveryBoard.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Recovery filter")); - - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo1, - filter: ecan::StandardId::new(messages::sender::Sender::GroundStation.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Ground Station filter")); - - let can = can.finalize().unwrap(); - ( - CanDevice0 { - can, - line_interrupts, - }, - gclk0, - ) - } - pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { - let payload: Vec = postcard::to_vec(&m)?; - self.can.tx.transmit_queued( - tx::MessageBuilder { - id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), - frame_type: tx::FrameType::FlexibleDatarate { - payload: &payload[..], - bit_rate_switching: false, - force_error_state_indicator: false, - }, - store_tx_event: None, - } - .build()?, - )?; - Ok(()) - } - pub fn process_data(&mut self) { - let line_interrupts = &self.line_interrupts; - for interrupt in line_interrupts.iter_flagged() { - match interrupt { - Interrupt::RxFifo0NewMessage => { - for message in &mut self.can.rx_fifo_0 { - match from_bytes::(message.data()) { - Ok(data) => { - info!("Message: {:?}", data) - } - Err(e) => { - info!("Error: {:?}", e) - } - } - } - } - Interrupt::RxFifo1NewMessage => { - for message in &mut self.can.rx_fifo_1 { - match from_bytes::(message.data()) { - Ok(data) => { - info!("Message: {:?}", data) - } - Err(e) => { - info!("Error: {:?}", e) - } - } - } - } - _ => (), - } - } - } -} - -pub struct CanDevice1 { - pub can: Can< - 'static, - Can1, - Dependencies>, Pin>, CAN1>, - Capacities, - >, - line_interrupts: OwnedInterruptSet, -} - -impl CanDevice1 { - pub fn new( - can_rx: Pin, - can_tx: Pin, - pclk_can: Pclk, - ahb_clock: AhbClk, - peripheral: CAN1, - gclk0: S, - can_memory: &'static mut SharedMemory, - loopback: bool, - ) -> (Self, S::Inc) - where - S: Source + Increment, - { - let (can_dependencies, gclk0) = - Dependencies::new(gclk0, pclk_can, ahb_clock, can_rx, can_tx, peripheral); - - let mut can = - mcan::bus::CanConfigurable::new(200.kHz(), can_dependencies, can_memory).unwrap(); - can.config().mode = Mode::Fd { - allow_bit_rate_switching: false, - data_phase_timing: BitTiming::new(500.kHz()), - }; - - if loopback { - can.config().loopback = true; - } - - let interrupts_to_be_enabled = can - .interrupts() - .split( - [ - Interrupt::RxFifo0NewMessage, - Interrupt::RxFifo0Full, - Interrupt::RxFifo0MessageLost, - Interrupt::RxFifo1NewMessage, - Interrupt::RxFifo1Full, - Interrupt::RxFifo1MessageLost, - ] - .into_iter() - .collect(), - ) - .unwrap(); - - // Line 0 and 1 are connected to the same interrupt line - let line_interrupts = can - .interrupt_configuration() - .enable_line_0(interrupts_to_be_enabled); - - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo0, - filter: ecan::StandardId::new(messages::sender::Sender::CommunicationBoard.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Self filter")); - - - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo0, - filter: ecan::StandardId::new(messages::sender::Sender::RecoveryBoard.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Recovery filter")); - - can.filters_standard() - .push(Filter::Classic { - action: Action::StoreFifo1, - filter: ecan::StandardId::new(messages::sender::Sender::GroundStation.into()) - .unwrap(), - mask: ecan::StandardId::ZERO, - }) - .unwrap_or_else(|_| panic!("Ground Station filter")); - - let can = can.finalize().unwrap(); - ( - CanDevice1 { - can, - line_interrupts, - }, - gclk0, - ) - } - pub fn _send_message(&mut self, m: Message) -> Result<(), HydraError> { - let payload: Vec = postcard::to_vec(&m)?; - self.can.tx.transmit_queued( - tx::MessageBuilder { - id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), - frame_type: tx::FrameType::FlexibleDatarate { - payload: &payload[..], - bit_rate_switching: false, - force_error_state_indicator: false, - }, - store_tx_event: None, - } - .build()?, - )?; - Ok(()) - } - pub fn _process_data(&mut self) { - let line_interrupts = &self.line_interrupts; - for interrupt in line_interrupts.iter_flagged() { - match interrupt { - Interrupt::RxFifo0NewMessage => { - for message in &mut self.can.rx_fifo_0 { - match from_bytes::(message.data()) { - Ok(data) => { - info!("Message: {:?}", data) - } - Err(e) => { - info!("Error: {:?}", e) - } - } - } - } - Interrupt::RxFifo1NewMessage => { - for message in &mut self.can.rx_fifo_1 { - match from_bytes::(message.data()) { - Ok(data) => { - info!("Message: {:?}", data) - } - Err(e) => { - info!("Error: {:?}", e) - } - } - } - } - _ => (), - } - } - } -} +use atsamd_hal::can::Dependencies; +use atsamd_hal::clock::v2::ahb::AhbClk; +use atsamd_hal::clock::v2::gclk::Gclk0Id; +use atsamd_hal::clock::v2::pclk::Pclk; + +use atsamd_hal::clock::v2::types::{Can0, Can1}; +use atsamd_hal::clock::v2::Source; +use atsamd_hal::gpio::{Alternate, AlternateI, AlternateH, Pin, I, H, PA22, PA23, PB15, PB14}; +use atsamd_hal::pac::{CAN0, CAN1}; + +use atsamd_hal::typelevel::Increment; +use common_arm::mcan; +use common_arm::mcan::message::{rx, Raw}; +use common_arm::mcan::tx_buffers::DynTx; +use common_arm::HydraError; +use defmt::info; +use heapless::Vec; +use mcan::bus::Can; +use mcan::embedded_can as ecan; +use mcan::interrupt::state::EnabledLine0; +use mcan::interrupt::{Interrupt, OwnedInterruptSet}; +use mcan::message::tx; +use mcan::messageram::SharedMemory; +use mcan::{ + config::{BitTiming, Mode}, + filter::{Action, Filter}, +}; + +use messages::Message; +use postcard::from_bytes; +use systick_monotonic::fugit::RateExtU32; +use typenum::{U0, U128, U32, U64}; + +use crate::data_manager::{DataManager, self}; + +pub struct Capacities; + +impl mcan::messageram::Capacities for Capacities { + type StandardFilters = U128; + type ExtendedFilters = U64; + type RxBufferMessage = rx::Message<64>; + type DedicatedRxBuffers = U64; + type RxFifo0Message = rx::Message<64>; + type RxFifo0 = U64; + type RxFifo1Message = rx::Message<64>; + type RxFifo1 = U64; + type TxMessage = tx::Message<64>; + type TxBuffers = U32; + type DedicatedTxBuffers = U0; + type TxEventFifo = U32; +} + +pub struct CanDevice0 { + pub can: Can< + 'static, + Can0, + Dependencies>, Pin>, CAN0>, + Capacities, + >, + line_interrupts: OwnedInterruptSet, +} + +impl CanDevice0 { + pub fn new( + can_rx: Pin, + can_tx: Pin, + pclk_can: Pclk, + ahb_clock: AhbClk, + peripheral: CAN0, + gclk0: S, + can_memory: &'static mut SharedMemory, + loopback: bool, + ) -> (Self, S::Inc) + where + S: Source + Increment, + { + let (can_dependencies, gclk0) = + Dependencies::new(gclk0, pclk_can, ahb_clock, can_rx, can_tx, peripheral); + + let mut can = + mcan::bus::CanConfigurable::new(200.kHz(), can_dependencies, can_memory).unwrap(); + can.config().mode = Mode::Fd { + allow_bit_rate_switching: false, + data_phase_timing: BitTiming::new(500.kHz()), + }; + + if loopback { + can.config().loopback = true; + } + + let interrupts_to_be_enabled = can + .interrupts() + .split( + [ + Interrupt::RxFifo0NewMessage, + Interrupt::RxFifo0Full, + Interrupt::RxFifo0MessageLost, + Interrupt::RxFifo1NewMessage, + Interrupt::RxFifo1Full, + Interrupt::RxFifo1MessageLost, + ] + .into_iter() + .collect(), + ) + .unwrap(); + + // Line 0 and 1 are connected to the same interrupt line + let line_interrupts = can + .interrupt_configuration() + .enable_line_0(interrupts_to_be_enabled); + + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo0, + filter: ecan::StandardId::new(messages::sender::Sender::CommunicationBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Communication filter")); + + + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo0, + filter: ecan::StandardId::new(messages::sender::Sender::RecoveryBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Recovery filter")); + + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo1, + filter: ecan::StandardId::new(messages::sender::Sender::GroundStation.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Ground Station filter")); + + let can = can.finalize().unwrap(); + ( + CanDevice0 { + can, + line_interrupts, + }, + gclk0, + ) + } + pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { + let payload: Vec = postcard::to_vec(&m)?; + self.can.tx.transmit_queued( + tx::MessageBuilder { + id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), + frame_type: tx::FrameType::FlexibleDatarate { + payload: &payload[..], + bit_rate_switching: false, + force_error_state_indicator: false, + }, + store_tx_event: None, + } + .build()?, + )?; + Ok(()) + } + pub fn process_data(&mut self, data_manager: &mut DataManager) { + let line_interrupts = &self.line_interrupts; + for interrupt in line_interrupts.iter_flagged() { + match interrupt { + Interrupt::RxFifo0NewMessage => { + for message in &mut self.can.rx_fifo_0 { + match from_bytes::(message.data()) { + Ok(data) => { + data_manager.handle_data(data); + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + Interrupt::RxFifo1NewMessage => { + for message in &mut self.can.rx_fifo_1 { + match from_bytes::(message.data()) { + Ok(data) => { + data_manager.handle_data(data); + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + _ => (), + } + } + } +} \ No newline at end of file diff --git a/boards/sensor/src/data_manager.rs b/boards/sensor/src/data_manager.rs index 61c9977f..b50982a6 100644 --- a/boards/sensor/src/data_manager.rs +++ b/boards/sensor/src/data_manager.rs @@ -1,4 +1,8 @@ +use common_arm::spawn; +use messages::sender::Sender; use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime}; +use messages::Message; +use crate::app::sleep_system; #[derive(Clone)] pub struct DataManager { @@ -34,6 +38,30 @@ impl DataManager { self.gps_vel.clone().map(|x| x.into()), ] } + + pub fn handle_data(&mut self, data: Message) { + match data.data { + messages::Data::Command(command) => match command.data { + messages::command::CommandData::PowerDown(info) => { + match info.board { + Sender::SensorBoard => { + // sleep the system. + spawn!(sleep_system); + } + _ => { + // don't care + } + } + } + _ => { + // We don't care atm about these other commands. + } + } + _ => { + // we can disregard all other messages for now. + } + } + } } impl Default for DataManager { diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index 7c59aca6..dde16fe2 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -1,231 +1,242 @@ -#![no_std] -#![no_main] - -mod communication; -mod data_manager; -mod sbg_manager; -mod sd_manager; -mod types; - -use atsamd_hal as hal; -use atsamd_hal::clock::v2::pclk::Pclk; -use atsamd_hal::clock::v2::Source; -use atsamd_hal::dmac::DmaController; -use common_arm::mcan; -use common_arm::*; -use communication::Capacities; -use data_manager::DataManager; -use hal::dmac; -use defmt::info; -use hal::gpio::Pins; -use hal::gpio::{PB16, PB17}; -use hal::gpio::{Pin, PushPullOutput}; -use hal::prelude::*; -use mcan::messageram::SharedMemory; -use messages::sensor::Sensor; -use messages::*; -use panic_halt as _; -use sd_manager::SdManager; -use sbg_manager::{sbg_dma, sbg_handle_data, sbg_sd_task, SBGManager}; -//use sbg_manager::{sbg_dma, sbg_handle_data, SBGManager}; - -use sbg_rs::sbg::{CallbackData, SBG_BUFFER_SIZE}; - -use systick_monotonic::*; -use types::*; - -#[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] -mod app { - use super::*; - - #[shared] - struct Shared { - em: ErrorManager, - data_manager: DataManager, - can: communication::CanDevice0, - sd_manager: SdManager, - } - - #[local] - struct Local { - led_green: Pin, - led_red: Pin, - sbg_manager: SBGManager, - } - - #[monotonic(binds = SysTick, default = true)] - type SysMono = Systick<100>; // 100 Hz / 10 ms granularity - - #[init(local = [ - #[link_section = ".can"] - can_memory: SharedMemory = SharedMemory::new() - ])] - fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { - let mut peripherals = cx.device; - let core = cx.core; - let pins = Pins::new(peripherals.PORT); - - let mut sbg_pin = pins.pb01.into_push_pull_output(); - sbg_pin.set_high().unwrap(); // turn on sbg - - let mut dmac = DmaController::init(peripherals.DMAC, &mut peripherals.PM); - let dmaChannels = dmac.split(); - - /* Clock setup */ - let (_, clocks, tokens) = atsamd_hal::clock::v2::clock_system_at_reset( - peripherals.OSCCTRL, - peripherals.OSC32KCTRL, - peripherals.GCLK, - peripherals.MCLK, - &mut peripherals.NVMCTRL, - ); - let gclk0 = clocks.gclk0; - - // SAFETY: Misusing the PAC API can break the system. - // This is safe because we only steal the MCLK. - let (_, _, _, mut mclk) = unsafe { clocks.pac.steal() }; - - /* CAN config */ - let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0); - let (can, gclk0) = communication::CanDevice0::new( - pins.pa23.into_mode(), - pins.pa22.into_mode(), - pclk_can, - clocks.ahbs.can0, - peripherals.CAN0, - gclk0, - cx.local.can_memory, - false, - ); - - // /* SD config */ - let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); - let sd_manager = SdManager::new( - &mclk, - peripherals.SERCOM4, - pclk_sd.freq(), - pins.pb10.into_push_pull_output(), - pins.pb09.into_push_pull_output(), - pins.pb11.into_push_pull_output(), - pins.pb08.into_push_pull_output(), - ); - - /* SBG config */ - let (pclk_sbg, gclk0) = Pclk::enable(tokens.pclks.sercom5, gclk0); - let dmaCh0 = dmaChannels.0.init(dmac::PriorityLevel::LVL3); - let sbg_manager = SBGManager::new( - pins.pb03, - pins.pb02, - pclk_sbg, - &mut mclk, - peripherals.SERCOM5, - peripherals.RTC, - dmaCh0, - ); - - // Buzzer should go here. There is complexity using the new clock system with the atsamdhal pwm implementation. - - /* Status LED */ - let led_green = pins.pb16.into_push_pull_output(); - let led_red = pins.pb17.into_push_pull_output(); - - /* Spawn tasks */ - sensor_send::spawn().ok(); - blink::spawn().ok(); - - /* Monotonic clock */ - let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); - - ( - Shared { - em: ErrorManager::new(), - data_manager: DataManager::new(), - can, - sd_manager, - }, - Local { - led_green, - led_red, - sbg_manager, - }, - init::Monotonics(mono), - ) - } - - // /// Idle task for when no other tasks are running. - // #[idle] - // fn idle(_: idle::Context) -> ! { - // loop {} - // } - - #[task(binds = CAN0, shared = [can])] - fn can0(mut cx: can0::Context) { - cx.shared.can.lock(|can| { - can.process_data(); - }); - } - - /** - * Sends a message over CAN. - */ - #[task(capacity = 10, local = [counter: u16 = 0], shared = [can, &em])] - fn send_internal(mut cx: send_internal::Context, m: Message) { - cx.shared.em.run(|| { - cx.shared.can.lock(|can| can.send_message(m))?; - Ok(()) - }); - } - - /** - * Sends information about the sensors. - */ - #[task(shared = [data_manager, &em])] - fn sensor_send(mut cx: sensor_send::Context) { - let sensor_data = cx - .shared - .data_manager - .lock(|data_manager| data_manager.clone_sensors()); - - let messages = sensor_data - .into_iter() - .flatten() - .map(|x| Message::new(&monotonics::now(), COM_ID, Sensor::new(x))); - - cx.shared.em.run(|| { - for msg in messages { - spawn!(send_internal, msg)?; - } - Ok(()) - }); - spawn_after!(sensor_send, ExtU64::millis(100)).ok(); - } - - /** - * Simple blink task to test the system. - * Acts as a heartbeat for the system. - */ - #[task(local = [led_green, led_red], shared = [&em])] - fn blink(cx: blink::Context) { - cx.shared.em.run(|| { - if cx.shared.em.has_error() { - cx.local.led_red.toggle()?; - spawn_after!(blink, ExtU64::millis(200))?; - } else { - cx.local.led_green.toggle()?; - spawn_after!(blink, ExtU64::secs(1))?; - } - Ok(()) - }); - } - - extern "Rust" { - #[task(capacity = 3, shared = [&em, sd_manager])] - fn sbg_sd_task(context: sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]); - - #[task(binds = DMAC_0, shared = [&em], local = [sbg_manager])] - fn sbg_dma(context: sbg_dma::Context); - - #[task(capacity = 20, shared = [data_manager])] - fn sbg_handle_data(context: sbg_handle_data::Context, data: CallbackData); - } -} +#![no_std] +#![no_main] + +mod communication; +mod data_manager; +mod sbg_manager; +mod sd_manager; +mod types; + +use atsamd_hal as hal; +use atsamd_hal::clock::v2::pclk::Pclk; +use atsamd_hal::clock::v2::Source; +use atsamd_hal::dmac::DmaController; +use common_arm::mcan; +use common_arm::*; +use communication::Capacities; +use data_manager::DataManager; +use hal::dmac; +use defmt::info; +use hal::gpio::Pins; +use hal::gpio::{PB16, PB17, PB01}; +use hal::gpio::{Pin, PushPullOutput}; +use hal::prelude::*; +use mcan::messageram::SharedMemory; +use messages::sensor::Sensor; +use messages::*; +use panic_halt as _; +use sd_manager::SdManager; +use sbg_manager::{sbg_dma, sbg_handle_data, sbg_sd_task, SBGManager}; +//use sbg_manager::{sbg_dma, sbg_handle_data, SBGManager}; + +use sbg_rs::sbg::{CallbackData, SBG_BUFFER_SIZE}; + +use systick_monotonic::*; +use types::*; + +#[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] +mod app { + use super::*; + + #[shared] + struct Shared { + em: ErrorManager, + data_manager: DataManager, + can: communication::CanDevice0, + sd_manager: SdManager, + } + + #[local] + struct Local { + led_green: Pin, + led_red: Pin, + sbg_manager: SBGManager, + sbg_power_pin: Pin, // this is here so we do not need to lock sbg_manager.! put into a gpio controller with leds. + } + + #[monotonic(binds = SysTick, default = true)] + type SysMono = Systick<100>; // 100 Hz / 10 ms granularity + + #[init(local = [ + #[link_section = ".can"] + can_memory: SharedMemory = SharedMemory::new() + ])] + fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { + let mut peripherals = cx.device; + let core = cx.core; + let pins = Pins::new(peripherals.PORT); + + let mut sbg_power_pin = pins.pb01.into_push_pull_output(); + sbg_power_pin.set_high().unwrap(); + + let mut dmac = DmaController::init(peripherals.DMAC, &mut peripherals.PM); + let dmaChannels = dmac.split(); + + /* Clock setup */ + let (_, clocks, tokens) = atsamd_hal::clock::v2::clock_system_at_reset( + peripherals.OSCCTRL, + peripherals.OSC32KCTRL, + peripherals.GCLK, + peripherals.MCLK, + &mut peripherals.NVMCTRL, + ); + let gclk0 = clocks.gclk0; + + // SAFETY: Misusing the PAC API can break the system. + // This is safe because we only steal the MCLK. + let (_, _, _, mut mclk) = unsafe { clocks.pac.steal() }; + + /* CAN config */ + let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0); + let (can, gclk0) = communication::CanDevice0::new( + pins.pa23.into_mode(), + pins.pa22.into_mode(), + pclk_can, + clocks.ahbs.can0, + peripherals.CAN0, + gclk0, + cx.local.can_memory, + false, + ); + + // /* SD config */ + let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); + let sd_manager = SdManager::new( + &mclk, + peripherals.SERCOM4, + pclk_sd.freq(), + pins.pb10.into_push_pull_output(), + pins.pb09.into_push_pull_output(), + pins.pb11.into_push_pull_output(), + pins.pb08.into_push_pull_output(), + ); + + /* SBG config */ + let (pclk_sbg, gclk0) = Pclk::enable(tokens.pclks.sercom5, gclk0); + let dmaCh0 = dmaChannels.0.init(dmac::PriorityLevel::LVL3); + let sbg_manager = SBGManager::new( + pins.pb03, + pins.pb02, + pclk_sbg, + &mut mclk, + peripherals.SERCOM5, + peripherals.RTC, + dmaCh0, + ); + + // Buzzer should go here. There is complexity using the new clock system with the atsamdhal pwm implementation. + + /* Status LED */ + let led_green = pins.pb16.into_push_pull_output(); + let led_red = pins.pb17.into_push_pull_output(); + + /* Spawn tasks */ + sensor_send::spawn().ok(); + blink::spawn().ok(); + + /* Monotonic clock */ + let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); + + ( + Shared { + em: ErrorManager::new(), + data_manager: DataManager::new(), + can, + sd_manager, + }, + Local { + led_green, + led_red, + sbg_manager, + sbg_power_pin, + }, + init::Monotonics(mono), + ) + } + + /// Idle task for when no other tasks are running. + #[idle] + fn idle(_: idle::Context) -> ! { + loop {} + } + + #[task(local = [sbg_power_pin], shared = [sd_manager])] + fn sleep_system(mut cx: sleep_system::Context) { + // close out sd files. + cx.shared.sd_manager.lock(|sd| sd.close_current_file()); + // power down sbg + cx.local.sbg_power_pin.set_low(); + // Call core.SCB.set_deepsleep for even less power consumption. + } + + #[task(binds = CAN0, shared = [can, data_manager])] + fn can0(mut cx: can0::Context) { + cx.shared.can.lock(|can| { + cx.shared.data_manager.lock(|manager| can.process_data(manager)) + }); + } + + /** + * Sends a message over CAN. + */ + #[task(capacity = 10, local = [counter: u16 = 0], shared = [can, &em])] + fn send_internal(mut cx: send_internal::Context, m: Message) { + cx.shared.em.run(|| { + cx.shared.can.lock(|can| can.send_message(m))?; + Ok(()) + }); + } + + /** + * Sends information about the sensors. + */ + #[task(shared = [data_manager, &em])] + fn sensor_send(mut cx: sensor_send::Context) { + let sensor_data = cx + .shared + .data_manager + .lock(|data_manager| data_manager.clone_sensors()); + + let messages = sensor_data + .into_iter() + .flatten() + .map(|x| Message::new(&monotonics::now(), COM_ID, Sensor::new(x))); + + cx.shared.em.run(|| { + for msg in messages { + spawn!(send_internal, msg)?; + } + Ok(()) + }); + spawn_after!(sensor_send, ExtU64::millis(100)).ok(); + } + + /** + * Simple blink task to test the system. + * Acts as a heartbeat for the system. + */ + #[task(local = [led_green, led_red], shared = [&em])] + fn blink(cx: blink::Context) { + cx.shared.em.run(|| { + if cx.shared.em.has_error() { + cx.local.led_red.toggle()?; + spawn_after!(blink, ExtU64::millis(200))?; + } else { + cx.local.led_green.toggle()?; + spawn_after!(blink, ExtU64::secs(1))?; + } + Ok(()) + }); + } + + extern "Rust" { + #[task(capacity = 3, shared = [&em, sd_manager])] + fn sbg_sd_task(context: sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]); + + #[task(binds = DMAC_0, shared = [&em], local = [sbg_manager])] + fn sbg_dma(context: sbg_dma::Context); + + #[task(capacity = 20, shared = [data_manager])] + fn sbg_handle_data(context: sbg_handle_data::Context, data: CallbackData); + } +} diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index d41b477f..5251c525 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -1,214 +1,202 @@ -use crate::types::{ConfigSBG, SBGBuffer, SBGTransfer}; -use atsamd_hal::clock::v2::gclk::Gclk0Id; -use atsamd_hal::clock::v2::pclk::Pclk; -use atsamd_hal::dmac; -use atsamd_hal::dmac::Transfer; -use atsamd_hal::sercom::{IoSet6}; -use atsamd_hal::gpio::{Pin, Reset, PB03, PB02}; -use atsamd_hal::pac::{MCLK, RTC}; -// use atsamd_hal::prelude::_atsamd21_hal_time_U32Ext; -use atsamd_hal::rtc::Rtc; -use core::alloc::{GlobalAlloc, Layout}; -use core::ffi::c_void; -use core::mem::size_of; -use core::ptr; -// use atsamd_hal::time::*; -use atsamd_hal::prelude::*; -use defmt::info; -use common_arm::spawn; -use crate::app::sbg_sd_task as sbg_sd; -use crate::app::{sbg_handle_data}; -use atsamd_hal::sercom::{uart, Sercom, Sercom5}; -use embedded_alloc::Heap; -use rtic::Mutex; -use sbg_rs::sbg; -use sbg_rs::sbg::{CallbackData, SBG, SBG_BUFFER_SIZE}; - - -pub static mut BUF_DST: SBGBuffer = &mut [0; SBG_BUFFER_SIZE]; -pub static mut BUF_DST2: SBGBuffer = &mut [0; SBG_BUFFER_SIZE]; - -// Simple heap required by the SBG library -static HEAP: Heap = Heap::empty(); - -pub struct SBGManager { - sbg_device: SBG, - xfer: Option, - buf_select: bool, -} - -impl SBGManager { - pub fn new( - rx: Pin, - tx: Pin, - pclk_sercom5: Pclk, - mclk: &mut MCLK, - sercom5: Sercom5, - rtc: RTC, - mut dma_channel: dmac::Channel, - ) -> Self { - /* Initialize the Heap */ - { - use core::mem::MaybeUninit; - const HEAP_SIZE: usize = 1024; - static mut HEAP_MEM: [MaybeUninit; HEAP_SIZE] = [MaybeUninit::uninit(); HEAP_SIZE]; - unsafe { HEAP.init(HEAP_MEM.as_ptr() as usize, HEAP_SIZE) } - } - - let pads_sbg = uart::Pads::::default().rx(rx).tx(tx); - let uart_sbg = ConfigSBG::new(mclk, sercom5, pads_sbg, pclk_sercom5.freq()) - .baud( - 115200.Hz(), - uart::BaudMode::Fractional(uart::Oversampling::Bits8), - ) - .enable(); - - let (sbg_rx, sbg_tx) = uart_sbg.split(); - - /* DMAC config */ - dma_channel - .as_mut() - .enable_interrupts(dmac::InterruptFlags::new().with_tcmpl(true)); - let xfer = Transfer::new(dma_channel, sbg_rx, unsafe { &mut *BUF_DST }, false) - .expect("DMA err") - .begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); - - // There is a bug within the HAL that improperly configures the RTC - // in count32 mode. This is circumvented by first using clock mode then - // converting to count32 mode. - let rtc_temp = Rtc::clock_mode(rtc, 1024.Hz(), mclk); - let mut rtc = rtc_temp.into_count32_mode(); - rtc.set_count32(0); - - let sbg: sbg::SBG = sbg::SBG::new(sbg_tx, rtc, |data| { - sbg_handle_data::spawn(data).ok(); - }); - - SBGManager { - sbg_device: sbg, - buf_select: false, - xfer: Some(xfer), - } - } -} - -pub fn sbg_handle_data(mut cx: sbg_handle_data::Context, data: CallbackData) { - cx.shared.data_manager.lock(|manager| match data { - CallbackData::UtcTime(x) => manager.utc_time = Some(x), - CallbackData::Air(x) => manager.air = Some(x), - CallbackData::EkfQuat(x) => manager.ekf_quat = Some(x), - CallbackData::EkfNav(x) => manager.ekf_nav = Some(x), - CallbackData::Imu(x) => manager.imu = Some(x), - CallbackData::GpsVel(x) => manager.gps_vel = Some(x), - }); -} - -pub fn sbg_sd_task(mut cx: crate::app::sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]) { - cx.shared.sd_manager.lock(|manager| { - if let Ok(mut file) = manager.open_file("sbg.txt") { - manager.write(&mut file, &data); - manager.close_file(file); - } - }); -} -/** - * Handles the DMA interrupt. - * Handles the SBG data. - */ -pub fn sbg_dma(cx: crate::app::sbg_dma::Context) { - let sbg = cx.local.sbg_manager; - - match &mut sbg.xfer { - Some(xfer) => { - if xfer.complete() { - let (chan0, source, buf) = sbg.xfer.take().unwrap().stop(); - let mut xfer = dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).unwrap().begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); - let buf_clone = buf.clone(); - sbg.sbg_device.read_data(buf); - unsafe{BUF_DST.copy_from_slice(&[0;SBG_BUFFER_SIZE])}; - xfer.block_transfer_interrupt(); - spawn!(sbg_sd(buf_clone)); - sbg.xfer = Some(xfer); - } - } - None => { - info!("None"); - } - } - - // if sbg.xfer.complete() { - // cx.shared.em.run(|| { - // let buf = match sbg.buf_select { - // false => { - // sbg.buf_select = true; - // sbg.xfer.recycle_source(unsafe { &mut *BUF_DST })? - // } - // true => { - // sbg.buf_select = false; - // sbg.xfer.recycle_source(unsafe { &mut *BUF_DST2 })? - // } - // }; - // // let buf_clone = buf.clone(); - // sbg.sbg_device.read_data(buf); - // // spawn!(sbg_sd(buf_clone))?; - // Ok(()) - // }); - // } -} - -/// Stored right before an allocation. Stores information that is needed to deallocate memory. -#[derive(Copy, Clone)] -struct AllocInfo { - layout: Layout, - ptr: *mut u8, -} - -/// Custom malloc for the SBG library. This uses the HEAP object initialized at the start of the -/// [`SBGManager`]. The [`Layout`] of the allocation is stored right before the returned pointed, -/// which makes it possible to implement [`free`] without any other data structures. -#[no_mangle] -pub extern "C" fn malloc(size: usize) -> *mut c_void { - if size == 0 { - return ptr::null_mut(); - } - - // Get a layout for both the requested size - let header_layout = Layout::new::(); - let requested_layout = Layout::from_size_align(size, 8).unwrap(); - let (layout, offset) = header_layout.extend(requested_layout).unwrap(); - - // Ask the allocator for memory - let orig_ptr = unsafe { HEAP.alloc(layout) }; - if orig_ptr.is_null() { - return orig_ptr as *mut c_void; - } - - // Compute the pointer that we will return - let result_ptr = unsafe { orig_ptr.add(offset) }; - - // Store the allocation information right before the returned pointer - let info_ptr = unsafe { result_ptr.sub(size_of::()) as *mut AllocInfo }; - unsafe { - info_ptr.write_unaligned(AllocInfo { - layout, - ptr: orig_ptr, - }); - } - - result_ptr as *mut c_void -} - -/// Custom free implementation for the SBG library. This uses the stored allocation information -/// right before the pointer to free up the resources. -/// -/// SAFETY: The value passed to ptr must have been obtained from a previous call to [`malloc`]. -#[no_mangle] -pub unsafe extern "C" fn free(ptr: *mut c_void) { - assert!(!ptr.is_null()); - - let info_ptr = unsafe { ptr.sub(size_of::()) as *const AllocInfo }; - let info = unsafe { info_ptr.read_unaligned() }; - unsafe { - HEAP.dealloc(info.ptr, info.layout); - } -} +use crate::types::{ConfigSBG, SBGBuffer, SBGTransfer}; +use atsamd_hal::clock::v2::gclk::Gclk0Id; +use atsamd_hal::clock::v2::pclk::Pclk; +use atsamd_hal::dmac; +use atsamd_hal::dmac::Transfer; +use atsamd_hal::sercom::{IoSet6}; +use atsamd_hal::gpio::{Pin, Reset, PB03, PB02, PB01, PushPullOutput}; +use atsamd_hal::pac::{MCLK, RTC}; +// use atsamd_hal::prelude::_atsamd21_hal_time_U32Ext; +use atsamd_hal::rtc::Rtc; +use core::alloc::{GlobalAlloc, Layout}; +use core::ffi::c_void; +use core::mem::size_of; +use core::ptr; +// use atsamd_hal::time::*; +use atsamd_hal::prelude::*; +use defmt::info; +use common_arm::spawn; +use crate::app::sbg_sd_task as sbg_sd; +use crate::app::{sbg_handle_data}; +use atsamd_hal::sercom::{uart, Sercom, Sercom5}; +use embedded_alloc::Heap; +use rtic::Mutex; +use sbg_rs::sbg; +use sbg_rs::sbg::{CallbackData, SBG, SBG_BUFFER_SIZE}; + + +pub static mut BUF_DST: SBGBuffer = &mut [0; SBG_BUFFER_SIZE]; + +// Simple heap required by the SBG library +static HEAP: Heap = Heap::empty(); + +pub struct SBGManager { + sbg_device: SBG, + xfer: Option, + buf_select: bool, +} + +impl SBGManager { + pub fn new( + rx: Pin, + tx: Pin, + pclk_sercom5: Pclk, + mclk: &mut MCLK, + sercom5: Sercom5, + rtc: RTC, + mut dma_channel: dmac::Channel, + ) -> Self { + /* Initialize the Heap */ + { + use core::mem::MaybeUninit; + const HEAP_SIZE: usize = 1024; + static mut HEAP_MEM: [MaybeUninit; HEAP_SIZE] = [MaybeUninit::uninit(); HEAP_SIZE]; + unsafe { HEAP.init(HEAP_MEM.as_ptr() as usize, HEAP_SIZE) } + } + + let pads_sbg = uart::Pads::::default().rx(rx).tx(tx); + let uart_sbg = ConfigSBG::new(mclk, sercom5, pads_sbg, pclk_sercom5.freq()) + .baud( + 115200.Hz(), + uart::BaudMode::Fractional(uart::Oversampling::Bits8), + ) + .enable(); + + let (sbg_rx, sbg_tx) = uart_sbg.split(); + + /* DMAC config */ + dma_channel + .as_mut() + .enable_interrupts(dmac::InterruptFlags::new().with_tcmpl(true)); + let xfer = Transfer::new(dma_channel, sbg_rx, unsafe { &mut *BUF_DST }, false) + .expect("DMA err") + .begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); + + // There is a bug within the HAL that improperly configures the RTC + // in count32 mode. This is circumvented by first using clock mode then + // converting to count32 mode. + let rtc_temp = Rtc::clock_mode(rtc, 1024.Hz(), mclk); + let mut rtc = rtc_temp.into_count32_mode(); + rtc.set_count32(0); + + let sbg: sbg::SBG = sbg::SBG::new(sbg_tx, rtc, |data| { + sbg_handle_data::spawn(data).ok(); + }); + + SBGManager { + sbg_device: sbg, + buf_select: false, + xfer: Some(xfer), + } + } +} + +pub fn sbg_handle_data(mut cx: sbg_handle_data::Context, data: CallbackData) { + cx.shared.data_manager.lock(|manager| match data { + CallbackData::UtcTime(x) => manager.utc_time = Some(x), + CallbackData::Air(x) => manager.air = Some(x), + CallbackData::EkfQuat(x) => manager.ekf_quat = Some(x), + CallbackData::EkfNav(x) => manager.ekf_nav = Some(x), + CallbackData::Imu(x) => manager.imu = Some(x), + CallbackData::GpsVel(x) => manager.gps_vel = Some(x), + }); +} + +pub fn sbg_sd_task(mut cx: crate::app::sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]) { + cx.shared.sd_manager.lock(|manager| { + if let Some(mut file) = manager.file.take() { + manager.write(&mut file, &data); + manager.file = Some(file); // give the file back after use + } else { + if let Ok(mut file) = manager.open_file("sbg.txt") { + manager.write(&mut file, &data); + manager.file = Some(file); + } + } + }); +} +/** + * Handles the DMA interrupt. + * Handles the SBG data. + */ +pub fn sbg_dma(cx: crate::app::sbg_dma::Context) { + let sbg = cx.local.sbg_manager; + + match &mut sbg.xfer { + Some(xfer) => { + if xfer.complete() { + let (chan0, source, buf) = sbg.xfer.take().unwrap().stop(); + let mut xfer = dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).unwrap().begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); + let buf_clone = buf.clone(); + sbg.sbg_device.read_data(buf); + unsafe{BUF_DST.copy_from_slice(&[0;SBG_BUFFER_SIZE])}; + xfer.block_transfer_interrupt(); + sbg.xfer = Some(xfer); + cx.shared.em.run(|| { + spawn!(sbg_sd(buf_clone)); + Ok(()) + }); + } + } + None => { // it should be impossible to reach here. + info!("None"); + } + } +} + +/// Stored right before an allocation. Stores information that is needed to deallocate memory. +#[derive(Copy, Clone)] +struct AllocInfo { + layout: Layout, + ptr: *mut u8, +} + +/// Custom malloc for the SBG library. This uses the HEAP object initialized at the start of the +/// [`SBGManager`]. The [`Layout`] of the allocation is stored right before the returned pointed, +/// which makes it possible to implement [`free`] without any other data structures. +#[no_mangle] +pub extern "C" fn malloc(size: usize) -> *mut c_void { + if size == 0 { + return ptr::null_mut(); + } + + // Get a layout for both the requested size + let header_layout = Layout::new::(); + let requested_layout = Layout::from_size_align(size, 8).unwrap(); + let (layout, offset) = header_layout.extend(requested_layout).unwrap(); + + // Ask the allocator for memory + let orig_ptr = unsafe { HEAP.alloc(layout) }; + if orig_ptr.is_null() { + return orig_ptr as *mut c_void; + } + + // Compute the pointer that we will return + let result_ptr = unsafe { orig_ptr.add(offset) }; + + // Store the allocation information right before the returned pointer + let info_ptr = unsafe { result_ptr.sub(size_of::()) as *mut AllocInfo }; + unsafe { + info_ptr.write_unaligned(AllocInfo { + layout, + ptr: orig_ptr, + }); + } + + result_ptr as *mut c_void +} + +/// Custom free implementation for the SBG library. This uses the stored allocation information +/// right before the pointer to free up the resources. +/// +/// SAFETY: The value passed to ptr must have been obtained from a previous call to [`malloc`]. +#[no_mangle] +pub unsafe extern "C" fn free(ptr: *mut c_void) { + assert!(!ptr.is_null()); + + let info_ptr = unsafe { ptr.sub(size_of::()) as *const AllocInfo }; + let info = unsafe { info_ptr.read_unaligned() }; + unsafe { + HEAP.dealloc(info.ptr, info.layout); + } +} diff --git a/boards/sensor/src/sd_manager.rs b/boards/sensor/src/sd_manager.rs index f062e1d7..c81da1e4 100644 --- a/boards/sensor/src/sd_manager.rs +++ b/boards/sensor/src/sd_manager.rs @@ -1,146 +1,148 @@ -use core::marker::PhantomData; - -use crate::types::SdController; -use atsamd_hal::gpio::{Output, Pin, PushPull, PB10, PB09, PB11, PB08}; -use atsamd_hal::pac; -use atsamd_hal::sercom::{spi, Sercom4, IoSet2}; -use atsamd_hal::time::Hertz; -use defmt::{info, warn}; -use embedded_sdmmc as sd; - -/// Time source for `[SdInterface]`. It doesn't return any useful information for now, and will -/// always return an arbitrary time. -pub struct TimeSink { - _marker: PhantomData<*const ()>, -} - -impl TimeSink { - fn new() -> Self { - TimeSink { - _marker: PhantomData, - } - } -} - -impl sd::TimeSource for TimeSink { - fn get_timestamp(&self) -> sd::Timestamp { - sd::Timestamp { - year_since_1970: 0, - zero_indexed_month: 0, - zero_indexed_day: 0, - hours: 0, - minutes: 0, - seconds: 0, - } - } -} - -/// Wrapper for the SD Card. For now, the pins are hard-coded. -pub struct SdManager { - pub sd_controller: SdController, - pub volume: sd::Volume, - pub root_directory: sd::Directory, - pub file: sd::File, -} - -impl SdManager { - pub fn new( - mclk: &pac::MCLK, - sercom: pac::SERCOM4, - freq: Hertz, - cs: Pin>, - sck: Pin>, - miso: Pin>, - mosi: Pin>, - ) -> Self { - let pads_spi = spi::Pads::::default() - .sclk(sck) - .data_in(miso) - .data_out(mosi); - let sdmmc_spi = spi::Config::new(mclk, sercom, pads_spi, freq) - .length::() - .bit_order(spi::BitOrder::MsbFirst) - .spi_mode(spi::MODE_0) - .enable(); - let time_sink: TimeSink = TimeSink::new(); // Need to give this a DateTime object for actual timing. - let mut sd_cont = sd::Controller::new(sd::SdMmcSpi::new(sdmmc_spi, cs), time_sink); - match sd_cont.device().init() { - Ok(_) => match sd_cont.device().card_size_bytes() { - Ok(size) => info!("Card is {} bytes", size), - Err(_) => warn!("Cannot get card size"), - }, - Err(_) => { - warn!("Cannot get SD card"); - panic!("Cannot get SD card."); - } - } - - let mut volume = match sd_cont.get_volume(sd::VolumeIdx(0)) { - Ok(volume) => volume, - Err(_) => { - warn!("Cannot get volume 0"); - panic!("Cannot get volume 0"); - } - }; - - let root_directory = match sd_cont.open_root_dir(&volume) { - Ok(root_directory) => root_directory, - Err(_) => { - warn!("Cannot get root"); - panic!("Cannot get root"); - } - }; - let file = sd_cont.open_file_in_dir( - &mut volume, - &root_directory, - "test2.txt", - sd::Mode::ReadWriteCreateOrTruncate, - ); - let file = match file { - Ok(file) => file, - Err(_) => { - warn!("Cannot create file."); - panic!("Cannot create file."); - } - }; - - SdManager { - sd_controller: sd_cont, - volume, - root_directory, - file, - } - } - pub fn write( - &mut self, - file: &mut sd::File, - buffer: &[u8], - ) -> Result> { - self.sd_controller.write(&mut self.volume, file, buffer) - } - pub fn write_str( - &mut self, - file: &mut sd::File, - msg: &str, - ) -> Result> { - let buffer: &[u8] = msg.as_bytes(); - self.sd_controller.write(&mut self.volume, file, buffer) - } - pub fn open_file(&mut self, file_name: &str) -> Result> { - self.sd_controller.open_file_in_dir( - &mut self.volume, - &self.root_directory, - file_name, - sd::Mode::ReadWriteCreateOrTruncate, - ) - } - pub fn close_file(&mut self, file: sd::File) -> Result<(), sd::Error> { - self.sd_controller.close_file(&self.volume, file) - } - pub fn close(mut self) { - self.sd_controller - .close_dir(&self.volume, self.root_directory); - } -} - +use core::marker::PhantomData; + +use crate::types::SdController; +use atsamd_hal::gpio::{Output, Pin, PushPull, PB10, PB09, PB11, PB08}; +use atsamd_hal::pac; +use atsamd_hal::sercom::{spi, Sercom4, IoSet2}; +use atsamd_hal::time::Hertz; +use defmt::{info, warn}; +use embedded_sdmmc as sd; + +/// Time source for `[SdInterface]`. It doesn't return any useful information for now, and will +/// always return an arbitrary time. +pub struct TimeSink { + _marker: PhantomData<*const ()>, +} + +impl TimeSink { + fn new() -> Self { + TimeSink { + _marker: PhantomData, + } + } +} + +impl sd::TimeSource for TimeSink { + fn get_timestamp(&self) -> sd::Timestamp { + sd::Timestamp { + year_since_1970: 0, + zero_indexed_month: 0, + zero_indexed_day: 0, + hours: 0, + minutes: 0, + seconds: 0, + } + } +} + +/// Wrapper for the SD Card. For now, the pins are hard-coded. +pub struct SdManager { + pub sd_controller: SdController, + pub volume: sd::Volume, + pub root_directory: sd::Directory, + pub file: Option, +} + +impl SdManager { + pub fn new( + mclk: &pac::MCLK, + sercom: pac::SERCOM4, + freq: Hertz, + cs: Pin>, + sck: Pin>, + miso: Pin>, + mosi: Pin>, + ) -> Self { + let pads_spi = spi::Pads::::default() + .sclk(sck) + .data_in(miso) + .data_out(mosi); + let sdmmc_spi = spi::Config::new(mclk, sercom, pads_spi, freq) + .length::() + .bit_order(spi::BitOrder::MsbFirst) + .spi_mode(spi::MODE_0) + .enable(); + let time_sink: TimeSink = TimeSink::new(); // Need to give this a DateTime object for actual timing. + let mut sd_cont = sd::Controller::new(sd::SdMmcSpi::new(sdmmc_spi, cs), time_sink); + match sd_cont.device().init() { + Ok(_) => match sd_cont.device().card_size_bytes() { + Ok(size) => info!("Card is {} bytes", size), + Err(_) => panic!("Cannot get card size"), + }, + Err(_) => { + panic!("Cannot get SD card."); + } + } + + let mut volume = match sd_cont.get_volume(sd::VolumeIdx(0)) { + Ok(volume) => volume, + Err(_) => { + panic!("Cannot get volume 0"); + } + }; + + let root_directory = match sd_cont.open_root_dir(&volume) { + Ok(root_directory) => root_directory, + Err(_) => { + panic!("Cannot get root"); + } + }; + let file = sd_cont.open_file_in_dir( + &mut volume, + &root_directory, + "test2.txt", + sd::Mode::ReadWriteCreateOrTruncate, + ); + let file = match file { + Ok(file) => file, + Err(_) => { + panic!("Cannot create file."); + } + }; + + SdManager { + sd_controller: sd_cont, + volume, + root_directory, + file: Some(file), + } + } + pub fn write( + &mut self, + file: &mut sd::File, // this should be an option + buffer: &[u8], + ) -> Result> { + self.sd_controller.write(&mut self.volume, file, buffer) + } + pub fn write_str( + &mut self, + file: &mut sd::File, + msg: &str, + ) -> Result> { + let buffer: &[u8] = msg.as_bytes(); + self.sd_controller.write(&mut self.volume, file, buffer) + } + pub fn open_file(&mut self, file_name: &str) -> Result> { + self.sd_controller.open_file_in_dir( + &mut self.volume, + &self.root_directory, + file_name, + sd::Mode::ReadWriteCreateOrTruncate, + ) + } + pub fn close_current_file(&mut self) -> Result<(), sd::Error> { + if let Some(file) = self.file.take() { + return self.close_file(file); + } + Ok(()) // no file to close + } + pub fn close_file(&mut self, file: sd::File) -> Result<(), sd::Error> { + self.sd_controller.close_file(&self.volume, file) + } + pub fn close(mut self) { + self.sd_controller + .close_dir(&self.volume, self.root_directory); + } +} + unsafe impl Send for SdManager {} \ No newline at end of file diff --git a/boards/sensor/src/types.rs b/boards/sensor/src/types.rs index ad7c2b76..4846d09d 100644 --- a/boards/sensor/src/types.rs +++ b/boards/sensor/src/types.rs @@ -1,47 +1,47 @@ -use crate::sd_manager::TimeSink; -use atsamd_hal as hal; -use atsamd_hal::gpio::*; -use atsamd_hal::sercom::uart::EightBit; -use atsamd_hal::sercom::uart::Uart; -use atsamd_hal::sercom::{spi, uart, Sercom5, IoSet6}; -use embedded_sdmmc as sd; -use hal::dmac; -use hal::dmac::BufferPair; -use hal::sercom::IoSet2; - - -use hal::sercom::Sercom4; -use messages::sender::Sender; -use messages::sender::Sender::SensorBoard; -use sbg_rs::sbg::SBG_BUFFER_SIZE; - -// ------- -// Sender ID -// ------- -pub static COM_ID: Sender = SensorBoard; - -// ------- -// SBG -// ------- -pub type PadsSBG = uart::PadsFromIds; -pub type ConfigSBG = uart::Config; -pub type SBGTransfer = dmac::Transfer< - dmac::Channel, - BufferPair, SBGBuffer>, ->; -pub type SBGBuffer = &'static mut [u8; SBG_BUFFER_SIZE]; - -// ------- -// SD Card -// ------- -pub type SdPads = spi::Pads< - Sercom4, - IoSet2, - Pin>, - Pin>, - Pin>, ->; -pub type SdController = sd::Controller< - sd::SdMmcSpi, spi::Duplex>, Pin>>, - TimeSink, ->; +use crate::sd_manager::TimeSink; +use atsamd_hal as hal; +use atsamd_hal::gpio::*; +use atsamd_hal::sercom::uart::EightBit; +use atsamd_hal::sercom::uart::Uart; +use atsamd_hal::sercom::{spi, uart, Sercom5, IoSet6}; +use embedded_sdmmc as sd; +use hal::dmac; +use hal::dmac::BufferPair; +use hal::sercom::IoSet2; + + +use hal::sercom::Sercom4; +use messages::sender::Sender; +use messages::sender::Sender::SensorBoard; +use sbg_rs::sbg::SBG_BUFFER_SIZE; + +// ------- +// Sender ID +// ------- +pub static COM_ID: Sender = SensorBoard; + +// ------- +// SBG +// ------- +pub type PadsSBG = uart::PadsFromIds; +pub type ConfigSBG = uart::Config; +pub type SBGTransfer = dmac::Transfer< + dmac::Channel, + BufferPair, SBGBuffer>, +>; +pub type SBGBuffer = &'static mut [u8; SBG_BUFFER_SIZE]; + +// ------- +// SD Card +// ------- +pub type SdPads = spi::Pads< + Sercom4, + IoSet2, + Pin>, + Pin>, + Pin>, +>; +pub type SdController = sd::Controller< + sd::SdMmcSpi, spi::Duplex>, Pin>>, + TimeSink, +>; diff --git a/examples/rtic/src/main.rs b/examples/rtic/src/main.rs index e4be45fc..3419586f 100644 --- a/examples/rtic/src/main.rs +++ b/examples/rtic/src/main.rs @@ -1,78 +1,78 @@ -#![no_std] -#![no_main] - -use atsamd_hal as hal; -use defmt::info; -use defmt_rtt as _; -use hal::gpio::Pins; -use hal::gpio::PA14; -use hal::gpio::{Pin, PushPullOutput}; -use hal::prelude::*; -use hal::time::Hertz; -use panic_halt as _; -use systick_monotonic::*; - -// "dispatchers" here can be any unused interrupts -#[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0])] -mod app { - use super::*; - - #[shared] - struct Shared {} - - #[local] - struct Local { - led: Pin, - } - - #[monotonic(binds = SysTick, default = true)] - type SysMono = Systick<100>; // 100 Hz / 10 ms granularity - - #[init] - fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { - let mut peripherals = cx.device; - let mut core = cx.core; - - // External 32KHz clock for stability - let mut clocks = hal::clock::GenericClockController::with_external_32kosc( - peripherals.GCLK, - &mut peripherals.MCLK, - &mut peripherals.OSC32KCTRL, - &mut peripherals.OSCCTRL, - &mut peripherals.NVMCTRL, - ); - - let pins = Pins::new(peripherals.PORT); - let led = pins.pa14.into_push_pull_output(); - - // Tell the MCU to sleep deeply for maximum power savings - core.SCB.set_sleepdeep(); - - // Spawn the LED blink task right after init - blink::spawn().ok(); - - // Use the system's Systick for RTIC to keep track of the time - let sysclk: Hertz = clocks.gclk0().into(); - let mono = Systick::new(core.SYST, sysclk.to_Hz()); - - (Shared {}, Local { led }, init::Monotonics(mono)) - } - - #[idle] - fn idle(_cx: idle::Context) -> ! { - loop { - // Put the MCU to sleep until an interrupt happens - rtic::export::wfi(); - } - } - - #[task(local = [led])] - fn blink(cx: blink::Context) { - cx.local.led.toggle().unwrap(); - - let time = monotonics::now().duration_since_epoch().to_secs(); - info!("Seconds since epoch: {}", time); - - blink::spawn_after(ExtU64::secs(1)).ok(); - } -} +#![no_std] +#![no_main] + +use atsamd_hal as hal; +use defmt::info; +use defmt_rtt as _; +use hal::gpio::Pins; +use hal::gpio::PA14; +use hal::gpio::{Pin, PushPullOutput}; +use hal::prelude::*; +use hal::time::Hertz; +use panic_halt as _; +use systick_monotonic::*; + +// "dispatchers" here can be any unused interrupts +#[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0])] +mod app { + use super::*; + + #[shared] + struct Shared {} + + #[local] + struct Local { + led: Pin, + } + + #[monotonic(binds = SysTick, default = true)] + type SysMono = Systick<100>; // 100 Hz / 10 ms granularity + + #[init] + fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { + let mut peripherals = cx.device; + let mut core = cx.core; + + // External 32KHz clock for stability + let mut clocks = hal::clock::GenericClockController::with_external_32kosc( + peripherals.GCLK, + &mut peripherals.MCLK, + &mut peripherals.OSC32KCTRL, + &mut peripherals.OSCCTRL, + &mut peripherals.NVMCTRL, + ); + + let pins = Pins::new(peripherals.PORT); + let led = pins.pa14.into_push_pull_output(); + + // Tell the MCU to sleep deeply for maximum power savings + core.SCB.set_sleepdeep(); + + // Spawn the LED blink task right after init + blink::spawn().ok(); + + // Use the system's Systick for RTIC to keep track of the time + let sysclk: Hertz = clocks.gclk0().into(); + let mono = Systick::new(core.SYST, sysclk.to_Hz()); + + (Shared {}, Local { led }, init::Monotonics(mono)) + } + + #[idle] + fn idle(_cx: idle::Context) -> ! { + loop { + // Put the MCU to sleep until an interrupt happens + rtic::export::wfi(); + } + } + + #[task(local = [led])] + fn blink(cx: blink::Context) { + cx.local.led.toggle().unwrap(); + + let time = monotonics::now().duration_since_epoch().to_secs(); + info!("Seconds since epoch: {}", time); + + blink::spawn_after(ExtU64::secs(1)).ok(); + } +} diff --git a/libraries/common-arm/memory.x b/libraries/common-arm/memory.x index 59d0511d..690b7767 100644 --- a/libraries/common-arm/memory.x +++ b/libraries/common-arm/memory.x @@ -1,15 +1,15 @@ -MEMORY -{ - /* NOTE K = KiBi = 1024 bytes */ - FLASH : ORIGIN = 0x00000000, LENGTH = 256K - CAN : ORIGIN = 0x20000000, LENGTH = 64K - RAM : ORIGIN = 0x20010000, LENGTH = 64K -} -SECTIONS -{ - .can (NOLOAD) : - { - *(.can .can.*); - } > CAN -} +MEMORY +{ + /* NOTE K = KiBi = 1024 bytes */ + FLASH : ORIGIN = 0x00000000, LENGTH = 256K + CAN : ORIGIN = 0x20000000, LENGTH = 64K + RAM : ORIGIN = 0x20010000, LENGTH = 64K +} +SECTIONS +{ + .can (NOLOAD) : + { + *(.can .can.*); + } > CAN +} /* _stack_start is optional and we can define this later */ \ No newline at end of file diff --git a/libraries/messages/src/command.rs b/libraries/messages/src/command.rs index 4cd33576..31aa8e6f 100644 --- a/libraries/messages/src/command.rs +++ b/libraries/messages/src/command.rs @@ -1,51 +1,61 @@ -use derive_more::From; -use defmt::Format; -use serde::{Deserialize, Serialize}; - -#[cfg(test)] -use proptest_derive::Arbitrary; - -#[cfg(feature = "ts")] -use ts_rs::TS; - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct Command { - pub data: CommandData, -} - -#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub enum CommandData { - DeployDrogue(DeployDrogue), - DeployMain(DeployMain), -} - -#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct DeployDrogue { - pub val: bool, -} - -#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct DeployMain { - pub val: bool, - // Auth? -} - -impl Command { - pub fn new(data: impl Into) -> Self { - Command { - data: data.into(), - } - } +use derive_more::From; +use defmt::Format; +use serde::{Deserialize, Serialize}; +use crate::sender::Sender; + +#[cfg(test)] +use proptest_derive::Arbitrary; + +#[cfg(feature = "ts")] +use ts_rs::TS; + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Command { + pub data: CommandData, +} + +#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub enum CommandData { + DeployDrogue(DeployDrogue), + DeployMain(DeployMain), + PowerDown(PowerDown), +} + +#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct DeployDrogue { + pub val: bool, +} + +#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct DeployMain { + pub val: bool, + // Auth? +} + +#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct PowerDown { + pub board: Sender, // This isn't proper naming !! This is the board to be powered down. Changes name of sender.rs to board.rs. +} + +impl Command { + pub fn new(data: impl Into) -> Self { + Command { + data: data.into(), + } + } } \ No newline at end of file diff --git a/libraries/messages/src/lib.rs b/libraries/messages/src/lib.rs index 0fb9febb..45e5cacc 100644 --- a/libraries/messages/src/lib.rs +++ b/libraries/messages/src/lib.rs @@ -1,93 +1,93 @@ -#![cfg_attr(all(not(feature = "std"), not(test)), no_std)] - -//! # HYDRA Messages -//! -//! This crate contains all the message definitions that will be used for inter-board communication -//! and ground-station communication. - -use crate::sender::Sender; -use crate::sensor::Sensor; -use crate::state::State; -use crate::command::Command; -use defmt::Format; -use derive_more::From; -use fugit::Instant; -use serde::{Deserialize, Serialize}; -/// This is to help control versions. -pub use mavlink; - -#[cfg(test)] -use proptest_derive::Arbitrary; - -#[cfg(feature = "ts")] -use ts_rs::TS; - -mod logging; -pub mod sender; -pub mod sensor; -pub mod command; -pub mod state; - -pub const MAX_SIZE: usize = 64; - -pub use logging::{ErrorContext, Event, Log, LogLevel}; - -/// Topmost message. Encloses all the other possible messages, and is the only thing that should -/// be sent over the wire. -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -#[cfg_attr(test, derive(Arbitrary))] -pub struct Message { - /// Time in milliseconds since epoch. Note that the epoch here can be arbitrary and is not the - /// Unix epoch. - pub timestamp: u64, - - /// The original sender of this message. - pub sender: Sender, - - /// The data contained in this message. - pub data: Data, -} - -#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -#[cfg_attr(test, derive(Arbitrary))] -#[serde(rename_all = "lowercase")] -pub enum Data { - State(State), - Sensor(Sensor), - Log(Log), - Command(Command), -} - -impl Message { - pub fn new( - timestamp: &Instant, - sender: Sender, - data: impl Into, - ) -> Self { - Message { - timestamp: timestamp.duration_since_epoch().to_millis(), - sender, - data: data.into(), - } - } -} - -#[cfg(test)] -mod test { - use crate::{Message, MAX_SIZE}; - use proptest::prelude::*; - - proptest! { - #[test] - fn message_size(msg: Message) { - let bytes = postcard::to_allocvec(&msg).unwrap(); - - dbg!(msg); - assert!(dbg!(bytes.len()) <= MAX_SIZE); - } - } -} +#![cfg_attr(all(not(feature = "std"), not(test)), no_std)] + +//! # HYDRA Messages +//! +//! This crate contains all the message definitions that will be used for inter-board communication +//! and ground-station communication. + +use crate::sender::Sender; +use crate::sensor::Sensor; +use crate::state::State; +use crate::command::Command; +use defmt::Format; +use derive_more::From; +use fugit::Instant; +use serde::{Deserialize, Serialize}; +/// This is to help control versions. +pub use mavlink; + +#[cfg(test)] +use proptest_derive::Arbitrary; + +#[cfg(feature = "ts")] +use ts_rs::TS; + +mod logging; +pub mod sender; +pub mod sensor; +pub mod command; +pub mod state; + +pub const MAX_SIZE: usize = 64; + +pub use logging::{ErrorContext, Event, Log, LogLevel}; + +/// Topmost message. Encloses all the other possible messages, and is the only thing that should +/// be sent over the wire. +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +#[cfg_attr(test, derive(Arbitrary))] +pub struct Message { + /// Time in milliseconds since epoch. Note that the epoch here can be arbitrary and is not the + /// Unix epoch. + pub timestamp: u64, + + /// The original sender of this message. + pub sender: Sender, + + /// The data contained in this message. + pub data: Data, +} + +#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +#[cfg_attr(test, derive(Arbitrary))] +#[serde(rename_all = "lowercase")] +pub enum Data { + State(State), + Sensor(Sensor), + Log(Log), + Command(Command), +} + +impl Message { + pub fn new( + timestamp: &Instant, + sender: Sender, + data: impl Into, + ) -> Self { + Message { + timestamp: timestamp.duration_since_epoch().to_millis(), + sender, + data: data.into(), + } + } +} + +#[cfg(test)] +mod test { + use crate::{Message, MAX_SIZE}; + use proptest::prelude::*; + + proptest! { + #[test] + fn message_size(msg: Message) { + let bytes = postcard::to_allocvec(&msg).unwrap(); + + dbg!(msg); + assert!(dbg!(bytes.len()) <= MAX_SIZE); + } + } +} diff --git a/libraries/messages/src/sender.rs b/libraries/messages/src/sender.rs index 7d34cf32..223e88c2 100644 --- a/libraries/messages/src/sender.rs +++ b/libraries/messages/src/sender.rs @@ -7,6 +7,7 @@ use proptest_derive::Arbitrary; #[cfg(feature = "ts")] use ts_rs::TS; +// I don't agree with the naming, We can use these as Ids to sent commands to that specific board. #[derive(Serialize, Deserialize, Clone, Debug, Format, Copy)] #[cfg_attr(test, derive(Arbitrary))] #[cfg_attr(feature = "ts", derive(TS))] diff --git a/libraries/messages/src/sensor.rs b/libraries/messages/src/sensor.rs index df8badfb..30e1dd16 100644 --- a/libraries/messages/src/sensor.rs +++ b/libraries/messages/src/sensor.rs @@ -31,6 +31,45 @@ pub enum SensorData { Imu1(Imu1), Imu2(Imu2), GpsVel(GpsVel), + Current(Current), + Voltage(Voltage), + Regulator(Regulator), + Temperature(Temperature), +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Regulator { + pub status: bool, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Voltage { + pub voltage: f32, + pub rolling_avg: f32, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Current { + pub current: f32, + pub rolling_avg: f32, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Temperature { + pub temperature: f32, + pub rolling_avg: f32, } #[derive(Serialize, Deserialize, Clone, Debug, Format)] diff --git a/libraries/messages/src/state.rs b/libraries/messages/src/state.rs index 2704906c..9a2c8c5f 100644 --- a/libraries/messages/src/state.rs +++ b/libraries/messages/src/state.rs @@ -1,38 +1,38 @@ -use derive_more::From; -use defmt::Format; -use serde::{Deserialize, Serialize}; - -#[cfg(test)] -use proptest_derive::Arbitrary; - -#[cfg(feature = "ts")] -use ts_rs::TS; - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct State { - pub data: StateData, -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub enum StateData { - Initializing, - WaitForTakeoff, - Ascent, - Descent, - TerminalDescent, - Abort, -} - -impl State { - pub fn new(data: impl Into) -> Self { - State { - data: data.into(), - } - } +use defmt::Format; +use serde::{Deserialize, Serialize}; + +#[cfg(test)] +use proptest_derive::Arbitrary; + +#[cfg(feature = "ts")] +use ts_rs::TS; + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct State { + pub data: StateData, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub enum StateData { + Initializing, + WaitForTakeoff, + Ascent, + Descent, + TerminalDescent, + WaitForRecovery, + Abort, +} + +impl State { + pub fn new(data: impl Into) -> Self { + State { + data: data.into(), + } + } } \ No newline at end of file diff --git a/libraries/sbg-rs/Cargo.toml b/libraries/sbg-rs/Cargo.toml index 2e049b76..8e3e60a1 100644 --- a/libraries/sbg-rs/Cargo.toml +++ b/libraries/sbg-rs/Cargo.toml @@ -1,20 +1,20 @@ -[package] -name = "sbg-rs" -version = "0.1.0" -edition = "2021" - -# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html - -[dependencies] -embedded-hal = "0.2.7" -nb = "1.0.0" -defmt = "0.3.2" -atsamd-hal = { workspace = true } -cortex-m = { workspace = true } -cortex-m-rt = "^0.7.0" -messages = { path = "../../libraries/messages" } -common-arm = { path = "../../libraries/common-arm" } -heapless = "0.7.16" - -[build-dependencies] +[package] +name = "sbg-rs" +version = "0.1.0" +edition = "2021" + +# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html + +[dependencies] +embedded-hal = "0.2.7" +nb = "1.0.0" +defmt = "0.3.2" +atsamd-hal = { workspace = true } +cortex-m = { workspace = true } +cortex-m-rt = "^0.7.0" +messages = { path = "../../libraries/messages" } +common-arm = { path = "../../libraries/common-arm" } +heapless = "0.7.16" + +[build-dependencies] cmake = "0.1" \ No newline at end of file diff --git a/libraries/sbg-rs/src/sbg.rs b/libraries/sbg-rs/src/sbg.rs index 2d4a66c4..d5165179 100644 --- a/libraries/sbg-rs/src/sbg.rs +++ b/libraries/sbg-rs/src/sbg.rs @@ -1,548 +1,548 @@ -use crate::bindings::{ - self, _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING, - _SbgEComLog_SBG_ECOM_LOG_AIR_DATA, _SbgEComLog_SBG_ECOM_LOG_EKF_NAV, - _SbgEComLog_SBG_ECOM_LOG_GPS1_VEL, _SbgEComLog_SBG_ECOM_LOG_UTC_TIME, - _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, _SbgErrorCode_SBG_NO_ERROR, - _SbgErrorCode_SBG_NULL_POINTER, _SbgErrorCode_SBG_READ_ERROR, _SbgErrorCode_SBG_WRITE_ERROR, - sbgEComCmdOutputSetConf, sbgEComHandle, -}; -use crate::bindings::{ - _SbgBinaryLogData, _SbgDebugLogType, _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, _SbgEComHandle, - _SbgEComLog_SBG_ECOM_LOG_EKF_QUAT, _SbgEComLog_SBG_ECOM_LOG_IMU_DATA, - _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, _SbgEComProtocol, _SbgErrorCode, _SbgInterface, -}; -use atsamd_hal as hal; -use core::ffi::{c_void}; -use core::ptr::null_mut; -use core::slice::{from_raw_parts, from_raw_parts_mut}; -use core::sync::atomic::AtomicUsize; -use defmt::{flush, warn, error, info}; -use embedded_hal::serial::Write; -use hal::gpio::{PB16, PB17, PB03, PB02}; -use hal::sercom::uart::Duplex; -use hal::sercom::uart::{self, EightBit, Uart}; -use hal::sercom::{IoSet1, IoSet6, Sercom5}; -use messages::sensor::*; -use heapless::Deque; - -type Pads = uart::PadsFromIds; -type PadsCDC = uart::PadsFromIds; -type Config = uart::Config; - -/** - * Max buffer size for SBG messages. - */ -pub const SBG_BUFFER_SIZE: usize = 1024; - -/** - * Represents the index of the buffer that is currently being used. - */ -static mut BUF_INDEX: AtomicUsize = AtomicUsize::new(0); -/** - * Points to the buffer that is currently being used. - */ -static mut BUF: &[u8; SBG_BUFFER_SIZE] = &[0; SBG_BUFFER_SIZE]; - -static mut DEQ: Deque = Deque::new(); - -/** - * Holds the RTC instance. This is used to get the current time. - */ -static mut RTC: Option> = None; - -static mut DATA_CALLBACK: Option = None; - -pub enum CallbackData { - UtcTime(UtcTime), - Air(Air), - EkfQuat(EkfQuat), - EkfNav((EkfNav1, EkfNav2)), - Imu((Imu1, Imu2)), - GpsVel(GpsVel), -} - -struct UARTSBGInterface { - interface: *mut bindings::SbgInterface, -} - -pub struct SBG { - UARTSBGInterface: UARTSBGInterface, - serial_device: Uart, - handle: _SbgEComHandle, - isInitialized: bool, -} - -impl SBG { - /** - * Creates a new SBG instance. - * Takes ownership of the serial device and RTC instance. - */ - pub fn new( - mut serial_device: Uart, - rtc: hal::rtc::Rtc, - callback: fn(CallbackData), - ) -> Self { - // SAFETY: We are accessing a static variable. - // This is safe because we are the only ones who have access to it. - // Panic if the RTC instance is already taken, this - // only can happen if the SBG instance is created twice. - if unsafe { RTC.is_some() } { - panic!("RTC instance is already taken!"); - } - // SAFETY: We are assigning the RTC instance to a static variable. - // This is safe because we are the only ones who have access to it. - unsafe { RTC = Some(rtc) }; - let interface = UARTSBGInterface { - interface: &mut _SbgInterface { - handle: &mut serial_device as *mut Uart as *mut c_void, - type_: 0, - name: [0; 48], - pDestroyFunc: Some(SBG::SbgDestroyFunc), - pWriteFunc: Some(SBG::SbgInterfaceWriteFunc), - pReadFunc: Some(SBG::SbgInterfaceReadFunc), - pFlushFunc: Some(SBG::SbgFlushFunc), - pSetSpeedFunc: Some(SBG::SbgSetSpeedFunc), - pGetSpeedFunc: Some(SBG::SbgGetSpeedFunc), - pDelayFunc: Some(SBG::SbgDelayFunc), - }, - }; - let pLargeBuffer: *mut u8 = null_mut(); - let protocol: _SbgEComProtocol = _SbgEComProtocol { - pLinkedInterface: interface.interface, - rxBuffer: [0; 4096usize], - rxBufferSize: 0, - discardSize: 0, - nextLargeTxId: 0, - pLargeBuffer, - largeBufferSize: 0, - msgClass: 0, - msgId: 0, - transferId: 0, - pageIndex: 0, - nrPages: 0, - }; - let handle: _SbgEComHandle = _SbgEComHandle { - protocolHandle: protocol, - pReceiveLogCallback: Some(SBG::SbgEComReceiveLogFunc), - pUserArg: null_mut(), - numTrials: 3, - cmdDefaultTimeOut: 500, - }; - - unsafe { DATA_CALLBACK = Some(callback) } - - let isInitialized = false; - - SBG { - UARTSBGInterface: interface, - serial_device, - handle: handle, - isInitialized, - } - } - /** - * Returns true if the SBG is initialized. - */ - pub fn isInitialized(&self) -> bool { - self.isInitialized - } - /** - * Reads SBG data frames for a buffer and returns the most recent data. - */ - pub fn read_data(&mut self, buffer: &'static [u8; SBG_BUFFER_SIZE]) { - // SAFETY: We are assigning a static mut variable. - // Buf can only be accessed from functions called by sbgEComHandle after this assignment. - // unsafe { BUF = buffer }; - for i in buffer { - unsafe{DEQ.push_back(*i)}; - } - // SAFETY: We are assigning a static variable. - // This is safe because are the only thread reading since SBG is locked. - unsafe { - *BUF_INDEX.get_mut() = 0; - } - // SAFETY: We are calling a C function. - // This is safe because it is assumed the SBG library is safe. - unsafe { - sbgEComHandle(&mut self.handle); - } - } - - /** - * Configures the SBG to output the following data - * Air data - * IMU data - * Extended Kalman Filter Euler data - * Extended Kalman Filter Quaternions - * Extended Kalman Filter Navigation data - */ - pub fn setup(&mut self) -> u32 { - // SAFETY: We are calling a C function. - // This is safe because it is assumed the SBG library is safe. - let errorCode: _SbgErrorCode = unsafe { - sbgEComCmdOutputSetConf( - &mut self.handle, - _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, - _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, - _SbgEComLog_SBG_ECOM_LOG_GPS1_VEL, - _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, - ) - }; - if errorCode != _SbgErrorCode_SBG_NO_ERROR { - warn!("Unable to configure UTC Time logs to 40 cycles"); - } - - // SAFETY: We are calling a C function. - // This is safe because it is assumed the SBG library is safe. - let errorCode: _SbgErrorCode = unsafe { - sbgEComCmdOutputSetConf( - &mut self.handle, - _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, - _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, - _SbgEComLog_SBG_ECOM_LOG_UTC_TIME, - _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, - ) - }; - if errorCode != _SbgErrorCode_SBG_NO_ERROR { - warn!("Unable to configure UTC Time logs to 40 cycles"); - } - - // SAFETY: We are calling a C function. - // This is safe because it is assumed the SBG library is safe. - let errorCode: _SbgErrorCode = unsafe { - sbgEComCmdOutputSetConf( - &mut self.handle, - _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, - _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, - _SbgEComLog_SBG_ECOM_LOG_AIR_DATA, - _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, - ) - }; - if errorCode != _SbgErrorCode_SBG_NO_ERROR { - warn!("Unable to configure Air Data logs to 40 cycles"); - } - - // SAFETY: We are calling a C function. - // This is safe because it is assumed the SBG library is safe. - let errorCode = unsafe { - sbgEComCmdOutputSetConf( - &mut self.handle, - _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, - _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, - _SbgEComLog_SBG_ECOM_LOG_EKF_QUAT, - _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, - ) - }; - if errorCode != _SbgErrorCode_SBG_NO_ERROR { - warn!("Unable to configure EKF Quat logs to 40 cycles"); - } - // SAFETY: We are calling a C function. - // This is safe because it is assumed the SBG library is safe. - let errorCode = unsafe { - sbgEComCmdOutputSetConf( - &mut self.handle, - _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, - _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, - _SbgEComLog_SBG_ECOM_LOG_EKF_NAV, - _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, - ) - }; - if errorCode != _SbgErrorCode_SBG_NO_ERROR { - warn!("Unable to configure EKF Nav logs to 40 cycles"); - } - // SAFETY: We are calling a C function. - // This is safe because it is assumed the SBG library is safe. - let errorCode = unsafe { - sbgEComCmdOutputSetConf( - &mut self.handle, - _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, - _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, - _SbgEComLog_SBG_ECOM_LOG_IMU_DATA, - _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, - ) - }; - if errorCode != _SbgErrorCode_SBG_NO_ERROR { - warn!("Unable to configure IMU logs to 40 cycles"); - } else { - self.isInitialized = true; - }; - errorCode - } - - /** - * Allows the SBG interface to read data from the serial ports. - */ - pub unsafe extern "C" fn SbgInterfaceReadFunc( - _pInterface: *mut _SbgInterface, - pBuffer: *mut c_void, - pBytesRead: *mut usize, - mut bytesToRead: usize, - ) -> _SbgErrorCode { - if pBuffer.is_null() { - return _SbgErrorCode_SBG_NULL_POINTER; - } - if pBytesRead.is_null() { - return _SbgErrorCode_SBG_NULL_POINTER; - } - // SAFETY: We are casting a c_void pointer to a u8 pointer and then creating a slice from it. - // This is safe because we ensure pBuffer is valid, pBuffer is not accessed during the lifetime of this function, - // and the SBGECom library ensures the buffer given is of the correct size. - let array: &mut [u8] = unsafe { from_raw_parts_mut(pBuffer as *mut u8, bytesToRead) }; - // SAFETY: We are accessing a static mut variable. - // This is safe because we ensure that the variable is only accessed in this function. - let index = unsafe { *BUF_INDEX.get_mut() }; - let mut readBytes = 0; - for i in 0..(bytesToRead) { - if let Some(front) = DEQ.pop_front() { - readBytes += 1; - array[i] = front; - } else { - // info!("No item in dequeue"); - break; - } - } - // info!("Bytes Read {}", readBytes); - unsafe {*pBytesRead = readBytes}; - return _SbgErrorCode_SBG_NO_ERROR; - - // if index + bytesToRead > SBG_BUFFER_SIZE { - // // Read what we can. - // bytesToRead = SBG_BUFFER_SIZE - index; - // if bytesToRead == 0 { - // // SAFETY: We are accessing a mutable pointer. - // // This is safe because the pointer cannot be null - // // and the SBGECom library ensures that the pointer - // // is not accessed during the lifetime of this function. - // unsafe { *pBytesRead = 0 }; - // return _SbgErrorCode_SBG_READ_ERROR; // no data - // } - // let end = bytesToRead + index; - // // SAFETY: We are accessing a static mut variable. - // // This is safe because we ensure that the variable is only accessed in this function. - // array[0..bytesToRead - 1].copy_from_slice(unsafe { &BUF[index..end - 1] }); - // // SAFETY: We are accessing a static mut variable. - // // This is safe because we ensure that the variable is only accessed in this function. - // unsafe { *BUF_INDEX.get_mut() = index + bytesToRead }; - // // SAFETY: We are accessing a mutable pointer. - // // This is safe because the pointer cannot be null - // // and the SBGECom library ensures that the pointer - // // is not accessed during the lifetime of this function. - // unsafe { *pBytesRead = bytesToRead }; - // return _SbgErrorCode_SBG_NO_ERROR; - // } - // let end = bytesToRead + index; - // // SAFETY: We are accessing a static mut variable. - // // This is safe because we ensure that the variable is only accessed in this function. - // array[0..bytesToRead - 1].copy_from_slice(unsafe { &BUF[index..end - 1] }); - // // SAFETY: We are accessing a static mut variable. - // // This is safe because we ensure that the variable is only accessed in this function. - // unsafe { *BUF_INDEX.get_mut() = index + bytesToRead }; - // // SAFETY: We are accessing a mutable pointer. - // // This is safe because the pointer cannot be null - // // and the SBGECom library ensures that the pointer - // // is not accessed during the lifetime of this function. - // unsafe { *pBytesRead = bytesToRead }; - - // _SbgErrorCode_SBG_NO_ERROR - } - - /** - * Allows the SBG interface to write to the UART peripheral - */ - pub unsafe extern "C" fn SbgInterfaceWriteFunc( - pInterface: *mut _SbgInterface, - pBuffer: *const c_void, - bytesToWrite: usize, - ) -> _SbgErrorCode { - if pInterface.is_null() { - return _SbgErrorCode_SBG_NULL_POINTER; - } - if pBuffer.is_null() { - return _SbgErrorCode_SBG_NULL_POINTER; - } - // SAFETY: We are casting a c_void pointer to a Uart peripheral pointer. - // This is safe because we only have one sbg object and we ensure that - // the peripheral pointer is not accessed during the lifetime of this function. - let serial: *mut Uart = - unsafe { (*pInterface).handle as *mut Uart }; - // SAFETY: We are casting a c_void pointer to a u8 pointer and then creating a slice from it. - // This is safe because we ensure pBuffer is valid, pBuffer is not accessed during the lifetime of this function, - // and the SBGECom library ensures the buffer given is of the correct size. - let array: &[u8] = unsafe { from_raw_parts(pBuffer as *const u8, bytesToWrite) }; - let mut counter: usize = 0; - loop { - if bytesToWrite == counter { - break; - } - // SAFETY: We are accessing a Uart Peripheral pointer. - // This is safe because we ensure that the pointer is not accessed during the lifetime of this function. - let result = unsafe { nb::block!(serial.as_mut().unwrap().write(array[counter])) }; - match result { - Ok(_) => counter += 1, - Err(_) => return _SbgErrorCode_SBG_WRITE_ERROR, - } - } - _SbgErrorCode_SBG_NO_ERROR - } - - /** - * Callback function for handling logs. - */ - pub unsafe extern "C" fn SbgEComReceiveLogFunc( - _pHandle: *mut _SbgEComHandle, - msgClass: u32, - msg: u32, - pLogData: *const _SbgBinaryLogData, - _pUserArg: *mut c_void, - ) -> _SbgErrorCode { - if pLogData.is_null() { - return _SbgErrorCode_SBG_NULL_POINTER; - } - - // SAFETY: DATA_CALLBACK is set once, before this function is called, - // so no race conditions can happen. - if let Some(callback) = unsafe { DATA_CALLBACK } { - if msgClass == _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0 { - // SAFETY: pLogData is not null, and we are checking the union flag before accessing it - unsafe { - match msg { - _SbgEComLog_SBG_ECOM_LOG_AIR_DATA => { - callback(CallbackData::Air((*pLogData).airData.into())) - } - _SbgEComLog_SBG_ECOM_LOG_EKF_QUAT => { - callback(CallbackData::EkfQuat((*pLogData).ekfQuatData.into())) - } - _SbgEComLog_SBG_ECOM_LOG_IMU_DATA => { - callback(CallbackData::Imu((*pLogData).imuData.into())) - } - _SbgEComLog_SBG_ECOM_LOG_EKF_NAV => { - callback(CallbackData::EkfNav((*pLogData).ekfNavData.into())) - } - _ => (), - } - } - } - } - - _SbgErrorCode_SBG_NO_ERROR - } - - /** - * The SBG interface does not need to be destroyed. - */ - pub extern "C" fn SbgDestroyFunc(_pInterface: *mut _SbgInterface) -> _SbgErrorCode { - _SbgErrorCode_SBG_NO_ERROR - } - - /** - * Flushes the UART peripheral. - */ - pub unsafe extern "C" fn SbgFlushFunc( - pInterface: *mut _SbgInterface, - _flags: u32, - ) -> _SbgErrorCode { - if pInterface.is_null() { - return _SbgErrorCode_SBG_NULL_POINTER; - } - // SAFETY: We are casting a c_void pointer to a Uart peripheral pointer. - // This is safe because we only have one sbg object and we ensure that - // the peripheral pointer is not accessed during the lifetime of this function. - let serial: *mut Uart = - unsafe { (*pInterface).handle as *mut Uart }; - let result = unsafe { serial.as_mut().unwrap().flush() }; - match result { - Ok(_) => return _SbgErrorCode_SBG_NO_ERROR, - Err(_) => return _SbgErrorCode_SBG_READ_ERROR, - } - } - - /** - * The baud rate is fixed to 115200 and hence this function does nothing. - */ - pub extern "C" fn SbgSetSpeedFunc( - _pInterface: *mut _SbgInterface, - _speed: u32, - ) -> _SbgErrorCode { - _SbgErrorCode_SBG_NO_ERROR - } - - /** - * The baud rate is fixed to 115200 - */ - pub extern "C" fn SbgGetSpeedFunc(_pInterface: *const _SbgInterface) -> u32 { - 115200 - } - - /** - * Optional method used to compute an expected delay to transmit/receive X bytes - */ - pub extern "C" fn SbgDelayFunc(_pInterface: *const _SbgInterface, _numBytes: usize) -> u32 { - 501 - } -} - -// SAFETY: No one besides us has the raw pointer to the SBG struct. -// We can safely transfer the SBG struct between threads. -unsafe impl Send for SBG {} - -/** - * Logs the message to the console. - * Needs to be updated to handle the Variadic arguments. - */ -#[no_mangle] -pub unsafe extern "C" fn sbgPlatformDebugLogMsg( - _pFileName: *const ::core::ffi::c_char, - _pFunctionName: *const ::core::ffi::c_char, - _line: u32, - _pCategory: *const ::core::ffi::c_char, - logType: _SbgDebugLogType, - _errorCode: _SbgErrorCode, - _pFormat: *const ::core::ffi::c_char, -) { - // if pFileName.is_null() || pFunctionName.is_null() || pCategory.is_null() || pFormat.is_null() { - // return; - // } - // // SAFETY: We are converting a raw pointer to a CStr and then to a str. - // // This is safe because we check if the pointers are null and - // // the pointers can only be accessed during the lifetime of this function. - // let file = unsafe { CStr::from_ptr(pFileName).to_str().unwrap() }; - // let function = unsafe { CStr::from_ptr(pFunctionName).to_str().unwrap() }; - // let _category = unsafe { CStr::from_ptr(pCategory).to_str().unwrap() }; - // let _format = unsafe { CStr::from_ptr(pFormat).to_str().unwrap() }; - - match logType { - // silently handle errors - // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR => error!("SBG Error"), - _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING => warn!("SBG Warning"), - // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_INFO => info!("SBG Info {} {}", file, function), - // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_DEBUG => debug!("SBG Debug {} {}", file, function), - _ => (), - }; - flush(); -} - -/** - * Returns the number of milliseconds that have passed. - */ -#[no_mangle] -pub extern "C" fn sbgGetTime() -> u32 { - // SAFETY: We are accessing a static mut variable. - // This is safe because this is the only place where we access the RTC. - unsafe { - match &RTC { - Some(x) => x.count32(), - None => 0, // bad error handling but we can't panic, maybe we should force the timeout to be zero in the event there is no RTC. - } - } -} - -/** - * Sleeps the sbg execution - */ -#[no_mangle] -pub extern "C" fn sbgSleep(ms: u32) { - let start_time = sbgGetTime(); - while (sbgGetTime() - start_time) < ms { - // do nothing - } -} +use crate::bindings::{ + self, _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING, + _SbgEComLog_SBG_ECOM_LOG_AIR_DATA, _SbgEComLog_SBG_ECOM_LOG_EKF_NAV, + _SbgEComLog_SBG_ECOM_LOG_GPS1_VEL, _SbgEComLog_SBG_ECOM_LOG_UTC_TIME, + _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, _SbgErrorCode_SBG_NO_ERROR, + _SbgErrorCode_SBG_NULL_POINTER, _SbgErrorCode_SBG_READ_ERROR, _SbgErrorCode_SBG_WRITE_ERROR, + sbgEComCmdOutputSetConf, sbgEComHandle, +}; +use crate::bindings::{ + _SbgBinaryLogData, _SbgDebugLogType, _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, _SbgEComHandle, + _SbgEComLog_SBG_ECOM_LOG_EKF_QUAT, _SbgEComLog_SBG_ECOM_LOG_IMU_DATA, + _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, _SbgEComProtocol, _SbgErrorCode, _SbgInterface, +}; +use atsamd_hal as hal; +use core::ffi::{c_void}; +use core::ptr::null_mut; +use core::slice::{from_raw_parts, from_raw_parts_mut}; +use core::sync::atomic::AtomicUsize; +use defmt::{flush, warn, error, info}; +use embedded_hal::serial::Write; +use hal::gpio::{PB16, PB17, PB03, PB02}; +use hal::sercom::uart::Duplex; +use hal::sercom::uart::{self, EightBit, Uart}; +use hal::sercom::{IoSet1, IoSet6, Sercom5}; +use messages::sensor::*; +use heapless::Deque; + +type Pads = uart::PadsFromIds; +type PadsCDC = uart::PadsFromIds; +type Config = uart::Config; + +/** + * Max buffer size for SBG messages. + */ +pub const SBG_BUFFER_SIZE: usize = 1024; + +/** + * Represents the index of the buffer that is currently being used. + */ +static mut BUF_INDEX: AtomicUsize = AtomicUsize::new(0); +/** + * Points to the buffer that is currently being used. + */ +static mut BUF: &[u8; SBG_BUFFER_SIZE] = &[0; SBG_BUFFER_SIZE]; + +static mut DEQ: Deque = Deque::new(); + +/** + * Holds the RTC instance. This is used to get the current time. + */ +static mut RTC: Option> = None; + +static mut DATA_CALLBACK: Option = None; + +pub enum CallbackData { + UtcTime(UtcTime), + Air(Air), + EkfQuat(EkfQuat), + EkfNav((EkfNav1, EkfNav2)), + Imu((Imu1, Imu2)), + GpsVel(GpsVel), +} + +struct UARTSBGInterface { + interface: *mut bindings::SbgInterface, +} + +pub struct SBG { + UARTSBGInterface: UARTSBGInterface, + serial_device: Uart, + handle: _SbgEComHandle, + isInitialized: bool, +} + +impl SBG { + /** + * Creates a new SBG instance. + * Takes ownership of the serial device and RTC instance. + */ + pub fn new( + mut serial_device: Uart, + rtc: hal::rtc::Rtc, + callback: fn(CallbackData), + ) -> Self { + // SAFETY: We are accessing a static variable. + // This is safe because we are the only ones who have access to it. + // Panic if the RTC instance is already taken, this + // only can happen if the SBG instance is created twice. + if unsafe { RTC.is_some() } { + panic!("RTC instance is already taken!"); + } + // SAFETY: We are assigning the RTC instance to a static variable. + // This is safe because we are the only ones who have access to it. + unsafe { RTC = Some(rtc) }; + let interface = UARTSBGInterface { + interface: &mut _SbgInterface { + handle: &mut serial_device as *mut Uart as *mut c_void, + type_: 0, + name: [0; 48], + pDestroyFunc: Some(SBG::SbgDestroyFunc), + pWriteFunc: Some(SBG::SbgInterfaceWriteFunc), + pReadFunc: Some(SBG::SbgInterfaceReadFunc), + pFlushFunc: Some(SBG::SbgFlushFunc), + pSetSpeedFunc: Some(SBG::SbgSetSpeedFunc), + pGetSpeedFunc: Some(SBG::SbgGetSpeedFunc), + pDelayFunc: Some(SBG::SbgDelayFunc), + }, + }; + let pLargeBuffer: *mut u8 = null_mut(); + let protocol: _SbgEComProtocol = _SbgEComProtocol { + pLinkedInterface: interface.interface, + rxBuffer: [0; 4096usize], + rxBufferSize: 0, + discardSize: 0, + nextLargeTxId: 0, + pLargeBuffer, + largeBufferSize: 0, + msgClass: 0, + msgId: 0, + transferId: 0, + pageIndex: 0, + nrPages: 0, + }; + let handle: _SbgEComHandle = _SbgEComHandle { + protocolHandle: protocol, + pReceiveLogCallback: Some(SBG::SbgEComReceiveLogFunc), + pUserArg: null_mut(), + numTrials: 3, + cmdDefaultTimeOut: 500, + }; + + unsafe { DATA_CALLBACK = Some(callback) } + + let isInitialized = false; + + SBG { + UARTSBGInterface: interface, + serial_device, + handle: handle, + isInitialized, + } + } + /** + * Returns true if the SBG is initialized. + */ + pub fn isInitialized(&self) -> bool { + self.isInitialized + } + /** + * Reads SBG data frames for a buffer and returns the most recent data. + */ + pub fn read_data(&mut self, buffer: &'static [u8; SBG_BUFFER_SIZE]) { + // SAFETY: We are assigning a static mut variable. + // Buf can only be accessed from functions called by sbgEComHandle after this assignment. + // unsafe { BUF = buffer }; + for i in buffer { + unsafe{DEQ.push_back(*i)}; + } + // SAFETY: We are assigning a static variable. + // This is safe because are the only thread reading since SBG is locked. + unsafe { + *BUF_INDEX.get_mut() = 0; + } + // SAFETY: We are calling a C function. + // This is safe because it is assumed the SBG library is safe. + unsafe { + sbgEComHandle(&mut self.handle); + } + } + + /** + * Configures the SBG to output the following data + * Air data + * IMU data + * Extended Kalman Filter Euler data + * Extended Kalman Filter Quaternions + * Extended Kalman Filter Navigation data + */ + pub fn setup(&mut self) -> u32 { + // SAFETY: We are calling a C function. + // This is safe because it is assumed the SBG library is safe. + let errorCode: _SbgErrorCode = unsafe { + sbgEComCmdOutputSetConf( + &mut self.handle, + _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, + _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, + _SbgEComLog_SBG_ECOM_LOG_GPS1_VEL, + _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, + ) + }; + if errorCode != _SbgErrorCode_SBG_NO_ERROR { + warn!("Unable to configure UTC Time logs to 40 cycles"); + } + + // SAFETY: We are calling a C function. + // This is safe because it is assumed the SBG library is safe. + let errorCode: _SbgErrorCode = unsafe { + sbgEComCmdOutputSetConf( + &mut self.handle, + _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, + _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, + _SbgEComLog_SBG_ECOM_LOG_UTC_TIME, + _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, + ) + }; + if errorCode != _SbgErrorCode_SBG_NO_ERROR { + warn!("Unable to configure UTC Time logs to 40 cycles"); + } + + // SAFETY: We are calling a C function. + // This is safe because it is assumed the SBG library is safe. + let errorCode: _SbgErrorCode = unsafe { + sbgEComCmdOutputSetConf( + &mut self.handle, + _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, + _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, + _SbgEComLog_SBG_ECOM_LOG_AIR_DATA, + _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, + ) + }; + if errorCode != _SbgErrorCode_SBG_NO_ERROR { + warn!("Unable to configure Air Data logs to 40 cycles"); + } + + // SAFETY: We are calling a C function. + // This is safe because it is assumed the SBG library is safe. + let errorCode = unsafe { + sbgEComCmdOutputSetConf( + &mut self.handle, + _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, + _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, + _SbgEComLog_SBG_ECOM_LOG_EKF_QUAT, + _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, + ) + }; + if errorCode != _SbgErrorCode_SBG_NO_ERROR { + warn!("Unable to configure EKF Quat logs to 40 cycles"); + } + // SAFETY: We are calling a C function. + // This is safe because it is assumed the SBG library is safe. + let errorCode = unsafe { + sbgEComCmdOutputSetConf( + &mut self.handle, + _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, + _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, + _SbgEComLog_SBG_ECOM_LOG_EKF_NAV, + _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, + ) + }; + if errorCode != _SbgErrorCode_SBG_NO_ERROR { + warn!("Unable to configure EKF Nav logs to 40 cycles"); + } + // SAFETY: We are calling a C function. + // This is safe because it is assumed the SBG library is safe. + let errorCode = unsafe { + sbgEComCmdOutputSetConf( + &mut self.handle, + _SbgEComOutputPort_SBG_ECOM_OUTPUT_PORT_A, + _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0, + _SbgEComLog_SBG_ECOM_LOG_IMU_DATA, + _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, + ) + }; + if errorCode != _SbgErrorCode_SBG_NO_ERROR { + warn!("Unable to configure IMU logs to 40 cycles"); + } else { + self.isInitialized = true; + }; + errorCode + } + + /** + * Allows the SBG interface to read data from the serial ports. + */ + pub unsafe extern "C" fn SbgInterfaceReadFunc( + _pInterface: *mut _SbgInterface, + pBuffer: *mut c_void, + pBytesRead: *mut usize, + mut bytesToRead: usize, + ) -> _SbgErrorCode { + if pBuffer.is_null() { + return _SbgErrorCode_SBG_NULL_POINTER; + } + if pBytesRead.is_null() { + return _SbgErrorCode_SBG_NULL_POINTER; + } + // SAFETY: We are casting a c_void pointer to a u8 pointer and then creating a slice from it. + // This is safe because we ensure pBuffer is valid, pBuffer is not accessed during the lifetime of this function, + // and the SBGECom library ensures the buffer given is of the correct size. + let array: &mut [u8] = unsafe { from_raw_parts_mut(pBuffer as *mut u8, bytesToRead) }; + // SAFETY: We are accessing a static mut variable. + // This is safe because we ensure that the variable is only accessed in this function. + let index = unsafe { *BUF_INDEX.get_mut() }; + let mut readBytes = 0; + for i in 0..(bytesToRead) { + if let Some(front) = DEQ.pop_front() { + readBytes += 1; + array[i] = front; + } else { + // info!("No item in dequeue"); + break; + } + } + // info!("Bytes Read {}", readBytes); + unsafe {*pBytesRead = readBytes}; + return _SbgErrorCode_SBG_NO_ERROR; + + // if index + bytesToRead > SBG_BUFFER_SIZE { + // // Read what we can. + // bytesToRead = SBG_BUFFER_SIZE - index; + // if bytesToRead == 0 { + // // SAFETY: We are accessing a mutable pointer. + // // This is safe because the pointer cannot be null + // // and the SBGECom library ensures that the pointer + // // is not accessed during the lifetime of this function. + // unsafe { *pBytesRead = 0 }; + // return _SbgErrorCode_SBG_READ_ERROR; // no data + // } + // let end = bytesToRead + index; + // // SAFETY: We are accessing a static mut variable. + // // This is safe because we ensure that the variable is only accessed in this function. + // array[0..bytesToRead - 1].copy_from_slice(unsafe { &BUF[index..end - 1] }); + // // SAFETY: We are accessing a static mut variable. + // // This is safe because we ensure that the variable is only accessed in this function. + // unsafe { *BUF_INDEX.get_mut() = index + bytesToRead }; + // // SAFETY: We are accessing a mutable pointer. + // // This is safe because the pointer cannot be null + // // and the SBGECom library ensures that the pointer + // // is not accessed during the lifetime of this function. + // unsafe { *pBytesRead = bytesToRead }; + // return _SbgErrorCode_SBG_NO_ERROR; + // } + // let end = bytesToRead + index; + // // SAFETY: We are accessing a static mut variable. + // // This is safe because we ensure that the variable is only accessed in this function. + // array[0..bytesToRead - 1].copy_from_slice(unsafe { &BUF[index..end - 1] }); + // // SAFETY: We are accessing a static mut variable. + // // This is safe because we ensure that the variable is only accessed in this function. + // unsafe { *BUF_INDEX.get_mut() = index + bytesToRead }; + // // SAFETY: We are accessing a mutable pointer. + // // This is safe because the pointer cannot be null + // // and the SBGECom library ensures that the pointer + // // is not accessed during the lifetime of this function. + // unsafe { *pBytesRead = bytesToRead }; + + // _SbgErrorCode_SBG_NO_ERROR + } + + /** + * Allows the SBG interface to write to the UART peripheral + */ + pub unsafe extern "C" fn SbgInterfaceWriteFunc( + pInterface: *mut _SbgInterface, + pBuffer: *const c_void, + bytesToWrite: usize, + ) -> _SbgErrorCode { + if pInterface.is_null() { + return _SbgErrorCode_SBG_NULL_POINTER; + } + if pBuffer.is_null() { + return _SbgErrorCode_SBG_NULL_POINTER; + } + // SAFETY: We are casting a c_void pointer to a Uart peripheral pointer. + // This is safe because we only have one sbg object and we ensure that + // the peripheral pointer is not accessed during the lifetime of this function. + let serial: *mut Uart = + unsafe { (*pInterface).handle as *mut Uart }; + // SAFETY: We are casting a c_void pointer to a u8 pointer and then creating a slice from it. + // This is safe because we ensure pBuffer is valid, pBuffer is not accessed during the lifetime of this function, + // and the SBGECom library ensures the buffer given is of the correct size. + let array: &[u8] = unsafe { from_raw_parts(pBuffer as *const u8, bytesToWrite) }; + let mut counter: usize = 0; + loop { + if bytesToWrite == counter { + break; + } + // SAFETY: We are accessing a Uart Peripheral pointer. + // This is safe because we ensure that the pointer is not accessed during the lifetime of this function. + let result = unsafe { nb::block!(serial.as_mut().unwrap().write(array[counter])) }; + match result { + Ok(_) => counter += 1, + Err(_) => return _SbgErrorCode_SBG_WRITE_ERROR, + } + } + _SbgErrorCode_SBG_NO_ERROR + } + + /** + * Callback function for handling logs. + */ + pub unsafe extern "C" fn SbgEComReceiveLogFunc( + _pHandle: *mut _SbgEComHandle, + msgClass: u32, + msg: u32, + pLogData: *const _SbgBinaryLogData, + _pUserArg: *mut c_void, + ) -> _SbgErrorCode { + if pLogData.is_null() { + return _SbgErrorCode_SBG_NULL_POINTER; + } + + // SAFETY: DATA_CALLBACK is set once, before this function is called, + // so no race conditions can happen. + if let Some(callback) = unsafe { DATA_CALLBACK } { + if msgClass == _SbgEComClass_SBG_ECOM_CLASS_LOG_ECOM_0 { + // SAFETY: pLogData is not null, and we are checking the union flag before accessing it + unsafe { + match msg { + _SbgEComLog_SBG_ECOM_LOG_AIR_DATA => { + callback(CallbackData::Air((*pLogData).airData.into())) + } + _SbgEComLog_SBG_ECOM_LOG_EKF_QUAT => { + callback(CallbackData::EkfQuat((*pLogData).ekfQuatData.into())) + } + _SbgEComLog_SBG_ECOM_LOG_IMU_DATA => { + callback(CallbackData::Imu((*pLogData).imuData.into())) + } + _SbgEComLog_SBG_ECOM_LOG_EKF_NAV => { + callback(CallbackData::EkfNav((*pLogData).ekfNavData.into())) + } + _ => (), + } + } + } + } + + _SbgErrorCode_SBG_NO_ERROR + } + + /** + * The SBG interface does not need to be destroyed. + */ + pub extern "C" fn SbgDestroyFunc(_pInterface: *mut _SbgInterface) -> _SbgErrorCode { + _SbgErrorCode_SBG_NO_ERROR + } + + /** + * Flushes the UART peripheral. + */ + pub unsafe extern "C" fn SbgFlushFunc( + pInterface: *mut _SbgInterface, + _flags: u32, + ) -> _SbgErrorCode { + if pInterface.is_null() { + return _SbgErrorCode_SBG_NULL_POINTER; + } + // SAFETY: We are casting a c_void pointer to a Uart peripheral pointer. + // This is safe because we only have one sbg object and we ensure that + // the peripheral pointer is not accessed during the lifetime of this function. + let serial: *mut Uart = + unsafe { (*pInterface).handle as *mut Uart }; + let result = unsafe { serial.as_mut().unwrap().flush() }; + match result { + Ok(_) => return _SbgErrorCode_SBG_NO_ERROR, + Err(_) => return _SbgErrorCode_SBG_READ_ERROR, + } + } + + /** + * The baud rate is fixed to 115200 and hence this function does nothing. + */ + pub extern "C" fn SbgSetSpeedFunc( + _pInterface: *mut _SbgInterface, + _speed: u32, + ) -> _SbgErrorCode { + _SbgErrorCode_SBG_NO_ERROR + } + + /** + * The baud rate is fixed to 115200 + */ + pub extern "C" fn SbgGetSpeedFunc(_pInterface: *const _SbgInterface) -> u32 { + 115200 + } + + /** + * Optional method used to compute an expected delay to transmit/receive X bytes + */ + pub extern "C" fn SbgDelayFunc(_pInterface: *const _SbgInterface, _numBytes: usize) -> u32 { + 501 + } +} + +// SAFETY: No one besides us has the raw pointer to the SBG struct. +// We can safely transfer the SBG struct between threads. +unsafe impl Send for SBG {} + +/** + * Logs the message to the console. + * Needs to be updated to handle the Variadic arguments. + */ +#[no_mangle] +pub unsafe extern "C" fn sbgPlatformDebugLogMsg( + _pFileName: *const ::core::ffi::c_char, + _pFunctionName: *const ::core::ffi::c_char, + _line: u32, + _pCategory: *const ::core::ffi::c_char, + logType: _SbgDebugLogType, + _errorCode: _SbgErrorCode, + _pFormat: *const ::core::ffi::c_char, +) { + // if pFileName.is_null() || pFunctionName.is_null() || pCategory.is_null() || pFormat.is_null() { + // return; + // } + // // SAFETY: We are converting a raw pointer to a CStr and then to a str. + // // This is safe because we check if the pointers are null and + // // the pointers can only be accessed during the lifetime of this function. + // let file = unsafe { CStr::from_ptr(pFileName).to_str().unwrap() }; + // let function = unsafe { CStr::from_ptr(pFunctionName).to_str().unwrap() }; + // let _category = unsafe { CStr::from_ptr(pCategory).to_str().unwrap() }; + // let _format = unsafe { CStr::from_ptr(pFormat).to_str().unwrap() }; + + match logType { + // silently handle errors + // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_ERROR => error!("SBG Error"), + _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING => warn!("SBG Warning"), + // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_INFO => info!("SBG Info {} {}", file, function), + // _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_DEBUG => debug!("SBG Debug {} {}", file, function), + _ => (), + }; + flush(); +} + +/** + * Returns the number of milliseconds that have passed. + */ +#[no_mangle] +pub extern "C" fn sbgGetTime() -> u32 { + // SAFETY: We are accessing a static mut variable. + // This is safe because this is the only place where we access the RTC. + unsafe { + match &RTC { + Some(x) => x.count32(), + None => 0, // bad error handling but we can't panic, maybe we should force the timeout to be zero in the event there is no RTC. + } + } +} + +/** + * Sleeps the sbg execution + */ +#[no_mangle] +pub extern "C" fn sbgSleep(ms: u32) { + let start_time = sbgGetTime(); + while (sbgGetTime() - start_time) < ms { + // do nothing + } +} From a36fbd60189e4f3f46ea3e471516076bcd427df1 Mon Sep 17 00:00:00 2001 From: Noah Sprenger <69169402+NoahSprenger@users.noreply.github.com> Date: Mon, 21 Aug 2023 22:19:05 -0400 Subject: [PATCH 16/30] Update build.yml Release builds due to memory constraints. --- .github/workflows/build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index cc297233..b84ede75 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -38,7 +38,7 @@ jobs: - uses: actions-rs/cargo@v1 name: "Build all binaries" with: - command: build + command: build -r # TODO: Broken, need to fix them # - uses: actions-rs/cargo@v1 # name: "Compile Device Tests (no running)" From 8805ef7e719b3885598912e82f1a5e42c514b72b Mon Sep 17 00:00:00 2001 From: Noah Sprenger <69169402+NoahSprenger@users.noreply.github.com> Date: Mon, 21 Aug 2023 22:23:45 -0400 Subject: [PATCH 17/30] Update build.yml --- .github/workflows/build.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index b84ede75..916dbf0c 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -38,7 +38,8 @@ jobs: - uses: actions-rs/cargo@v1 name: "Build all binaries" with: - command: build -r + command: build + args: release # TODO: Broken, need to fix them # - uses: actions-rs/cargo@v1 # name: "Compile Device Tests (no running)" From 727d2929a41a5146cc6897a799c711d0844c70cd Mon Sep 17 00:00:00 2001 From: Noah Sprenger <69169402+NoahSprenger@users.noreply.github.com> Date: Mon, 21 Aug 2023 22:30:45 -0400 Subject: [PATCH 18/30] Update build.yml --- .github/workflows/build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 916dbf0c..84a660cc 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -39,7 +39,7 @@ jobs: name: "Build all binaries" with: command: build - args: release + args: --release # TODO: Broken, need to fix them # - uses: actions-rs/cargo@v1 # name: "Compile Device Tests (no running)" From 76066da86e6e1c11f09187c79fa497130895631d Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Tue, 22 Aug 2023 19:11:07 +0000 Subject: [PATCH 19/30] Cleanup Linter Warnings --- .github/workflows/build.yml | 128 +- Cargo.lock | 3026 ++++++++--------- README.md | 88 +- boards/communication/src/data_manager.rs | 7 +- boards/communication/src/main.rs | 12 +- boards/recovery/src/state_machine/mod.rs | 33 +- .../src/state_machine/states/initializing.rs | 40 +- .../state_machine/states/wait_for_recovery.rs | 83 +- boards/sensor/src/data_manager.rs | 142 +- boards/sensor/src/main.rs | 11 +- boards/sensor/src/sbg_manager.rs | 22 +- libraries/messages/src/sender.rs | 66 +- libraries/messages/src/sensor.rs | 444 +-- 13 files changed, 2058 insertions(+), 2044 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 84a660cc..10545784 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -1,64 +1,64 @@ -on: - push: - branches: [ master ] - pull_request: - -name: Build - -jobs: - build: - name: All - runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v2 - - name: Install packages - run: sudo apt update && sudo apt install -y cmake - - name: Install Arm GNU Toolchain (arm-none-eabi-gcc) - uses: carlosperate/arm-none-eabi-gcc-action@v1 - with: - release: '12.2.Rel1' - - uses: actions-rs/toolchain@v1 - with: - toolchain: stable - target: thumbv7em-none-eabihf - - uses: actions/cache@v3 - with: - path: | - ~/.cargo/bin/ - ~/.cargo/registry/index/ - ~/.cargo/registry/cache/ - ~/.cargo/git/db/ - target/ - key: ${{ runner.os }}-cargo-${{ hashFiles('**/Cargo.lock') }} - - uses: actions-rs/cargo@v1 - name: "Install cargo-make" - with: - command: install - args: --force cargo-make - - uses: actions-rs/cargo@v1 - name: "Build all binaries" - with: - command: build - args: --release -# TODO: Broken, need to fix them -# - uses: actions-rs/cargo@v1 -# name: "Compile Device Tests (no running)" -# with: -# command: make -# args: test-device --no-run - - uses: actions-rs/cargo@v1 - name: "Run Host Tests" - with: - command: make - args: test-host - - uses: actions-rs/cargo@v1 - name: "Generate Typescript bindings" - with: - command: make - args: generate-ts-bindings - - uses: actions/upload-artifact@v3 - name: "Upload Binding Artifacts" - with: - name: bindings - path: ./libraries/messages/bindings - +on: + push: + branches: [ master ] + pull_request: + +name: Build + +jobs: + build: + name: All + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v2 + - name: Install packages + run: sudo apt update && sudo apt install -y cmake + - name: Install Arm GNU Toolchain (arm-none-eabi-gcc) + uses: carlosperate/arm-none-eabi-gcc-action@v1 + with: + release: '12.2.Rel1' + - uses: actions-rs/toolchain@v1 + with: + toolchain: stable + target: thumbv7em-none-eabihf + - uses: actions/cache@v3 + with: + path: | + ~/.cargo/bin/ + ~/.cargo/registry/index/ + ~/.cargo/registry/cache/ + ~/.cargo/git/db/ + target/ + key: ${{ runner.os }}-cargo-${{ hashFiles('**/Cargo.lock') }} + - uses: actions-rs/cargo@v1 + name: "Install cargo-make" + with: + command: install + args: --force cargo-make + - uses: actions-rs/cargo@v1 + name: "Build all binaries" + with: + command: build + args: --release +# TODO: Broken, need to fix them +# - uses: actions-rs/cargo@v1 +# name: "Compile Device Tests (no running)" +# with: +# command: make +# args: test-device --no-run + - uses: actions-rs/cargo@v1 + name: "Run Host Tests" + with: + command: make + args: test-host + - uses: actions-rs/cargo@v1 + name: "Generate Typescript bindings" + with: + command: make + args: generate-ts-bindings + - uses: actions/upload-artifact@v3 + name: "Upload Binding Artifacts" + with: + name: bindings + path: ./libraries/messages/bindings + diff --git a/Cargo.lock b/Cargo.lock index b1e19754..b7ca65a1 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -1,1513 +1,1513 @@ -# This file is automatically @generated by Cargo. -# It is not intended for manual editing. -version = 3 - -[[package]] -name = "Inflector" -version = "0.11.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "fe438c63458706e03479442743baae6c88256498e6431708f6dfc520a26515d3" - -[[package]] -name = "aes" -version = "0.7.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9e8b47f52ea9bae42228d07ec09eb676433d7c4ed1ebdf0f1d1c29ed446f1ab8" -dependencies = [ - "cfg-if", - "cipher", - "cpufeatures", - "opaque-debug", -] - -[[package]] -name = "atomic-polyfill" -version = "0.1.11" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e3ff7eb3f316534d83a8a2c3d1674ace8a5a71198eba31e2e2b597833f699b28" -dependencies = [ - "critical-section", -] - -[[package]] -name = "atsamd-hal" -version = "0.16.0" -source = "git+https://github.com/atsamd-rs/atsamd#0820f0df58eb8705ddfa6533ed76953d18e6b992" -dependencies = [ - "aes", - "atsame51j", - "bitfield 0.13.2", - "bitflags 1.3.2", - "cipher", - "cortex-m", - "embedded-hal", - "fugit", - "mcan-core", - "modular-bitfield", - "nb 1.1.0", - "num-traits", - "opaque-debug", - "paste", - "rand_core", - "seq-macro", - "typenum", - "vcell", - "void", -] - -[[package]] -name = "atsame51j" -version = "0.12.0" -source = "git+https://github.com/atsamd-rs/atsamd#0820f0df58eb8705ddfa6533ed76953d18e6b992" -dependencies = [ - "cortex-m", - "cortex-m-rt", - "vcell", -] - -[[package]] -name = "autocfg" -version = "1.1.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d468802bab17cbc0cc575e9b053f41e72aa36bfa6b7f55e3529ffa43161b97fa" - -[[package]] -name = "bare-metal" -version = "0.2.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "5deb64efa5bd81e31fcd1938615a6d98c82eafcbcd787162b6f63b91d6bac5b3" -dependencies = [ - "rustc_version 0.2.3", -] - -[[package]] -name = "bare-metal" -version = "1.0.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f8fe8f5a8a398345e52358e18ff07cc17a568fbca5c6f73873d3a62056309603" - -[[package]] -name = "bit-set" -version = "0.5.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "0700ddab506f33b20a03b13996eccd309a48e5ff77d0d95926aa0210fb4e95f1" -dependencies = [ - "bit-vec", -] - -[[package]] -name = "bit-vec" -version = "0.6.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "349f9b6a179ed607305526ca489b34ad0a41aed5f7980fa90eb03160b69598fb" - -[[package]] -name = "bitfield" -version = "0.13.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "46afbd2983a5d5a7bd740ccb198caf5b82f45c40c09c0eed36052d91cb92e719" - -[[package]] -name = "bitfield" -version = "0.14.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "2d7e60934ceec538daadb9d8432424ed043a904d8e0243f3c6446bce549a46ac" - -[[package]] -name = "bitflags" -version = "1.3.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "bef38d45163c2f1dde094a7dfd33ccf595c92905c8f8f4fdc18d06fb1037718a" - -[[package]] -name = "bitflags" -version = "2.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b4682ae6287fcf752ecaabbfcc7b6f9b72aa33933dc23a554d853aea8eea8635" - -[[package]] -name = "byteorder" -version = "1.4.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "14c189c53d098945499cdfa7ecc63567cf3886b3332b312a5b4585d8d3a6a610" - -[[package]] -name = "cc" -version = "1.0.82" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "305fe645edc1442a0fa8b6726ba61d422798d37a52e12eaecf4b022ebbb88f01" -dependencies = [ - "libc", -] - -[[package]] -name = "cfg-if" -version = "1.0.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "baf1de4339761588bc0619e3cbc0120ee582ebb74b53b4efbf79117bd2da40fd" - -[[package]] -name = "cipher" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "7ee52072ec15386f770805afd189a01c8841be8696bed250fa2f13c4c0d6dfb7" -dependencies = [ - "generic-array", -] - -[[package]] -name = "cmake" -version = "0.1.50" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a31c789563b815f77f4250caee12365734369f942439b7defd71e18a48197130" -dependencies = [ - "cc", -] - -[[package]] -name = "cobs" -version = "0.2.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "67ba02a97a2bd10f4b59b25c7973101c79642302776489e030cd13cdab09ed15" - -[[package]] -name = "common-arm" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "cortex-m", - "cortex-m-rt", - "defmt", - "defmt-rtt", - "derive_more", - "embedded-hal", - "embedded-sdmmc", - "heapless", - "mcan", - "messages", - "nb 1.1.0", - "postcard", -] - -[[package]] -name = "common-arm-test" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "defmt", - "defmt-rtt", - "defmt-test", - "panic-probe", -] - -[[package]] -name = "communication" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "cortex-m-rtic", - "defmt", - "embedded-sdmmc", - "heapless", - "messages", - "panic-halt", - "postcard", - "systick-monotonic", - "typenum", -] - -[[package]] -name = "convert_case" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6245d59a3e82a7fc217c5828a6692dbc6dfb63a0c8c90495621f7b9d79704a0e" - -[[package]] -name = "cortex-m" -version = "0.7.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8ec610d8f49840a5b376c69663b6369e71f4b34484b9b2eb29fb918d92516cb9" -dependencies = [ - "bare-metal 0.2.5", - "bitfield 0.13.2", - "critical-section", - "embedded-hal", - "volatile-register", -] - -[[package]] -name = "cortex-m-rt" -version = "0.7.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "ee84e813d593101b1723e13ec38b6ab6abbdbaaa4546553f5395ed274079ddb1" -dependencies = [ - "cortex-m-rt-macros", -] - -[[package]] -name = "cortex-m-rt-macros" -version = "0.7.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f0f6f3e36f203cfedbc78b357fb28730aa2c6dc1ab060ee5c2405e843988d3c7" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", -] - -[[package]] -name = "cortex-m-rtic" -version = "1.1.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d696ae7390bdb9f7978f71ca7144256a2c4616240a6df9002da3c451f9fc8f02" -dependencies = [ - "bare-metal 1.0.0", - "cortex-m", - "cortex-m-rtic-macros", - "heapless", - "rtic-core", - "rtic-monotonic", - "version_check", -] - -[[package]] -name = "cortex-m-rtic-macros" -version = "1.1.6" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "eefb40b1ca901c759d29526e5c8a0a1b246c20caaa5b4cc5d0f0b94debecd4c7" -dependencies = [ - "proc-macro-error", - "proc-macro2 1.0.66", - "quote 1.0.32", - "rtic-syntax", - "syn 1.0.109", -] - -[[package]] -name = "cpufeatures" -version = "0.2.9" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a17b76ff3a4162b0b27f354a0c87015ddad39d35f9c0c36607a3bdd175dde1f1" -dependencies = [ - "libc", -] - -[[package]] -name = "crc-any" -version = "2.4.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "774646b687f63643eb0f4bf13dc263cb581c8c9e57973b6ddf78bda3994d88df" - -[[package]] -name = "critical-section" -version = "1.1.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "7059fff8937831a9ae6f0fe4d658ffabf58f2ca96aa9dec1c889f936f705f216" - -[[package]] -name = "defmt" -version = "0.3.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a8a2d011b2fee29fb7d659b83c43fce9a2cb4df453e16d441a51448e448f3f98" -dependencies = [ - "bitflags 1.3.2", - "defmt-macros", -] - -[[package]] -name = "defmt-macros" -version = "0.3.6" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "54f0216f6c5acb5ae1a47050a6645024e6edafc2ee32d421955eccfef12ef92e" -dependencies = [ - "defmt-parser", - "proc-macro-error", - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 2.0.28", -] - -[[package]] -name = "defmt-parser" -version = "0.3.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "269924c02afd7f94bc4cecbfa5c379f6ffcf9766b3408fe63d22c728654eccd0" -dependencies = [ - "thiserror", -] - -[[package]] -name = "defmt-rtt" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "609923761264dd99ed9c7d209718cda4631c5fe84668e0f0960124cbb844c49f" -dependencies = [ - "critical-section", - "defmt", -] - -[[package]] -name = "defmt-test" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4df24f1ca104a0c1bce2047d8a21aa9fa29695e5d662118eb48daedb97edca88" -dependencies = [ - "cortex-m", - "cortex-m-rt", - "defmt", - "defmt-test-macros", -] - -[[package]] -name = "defmt-test-macros" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "94a0dfea4063d72e1ba20494dfbc4667f67420869328cf3670b5824a38a22dc1" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", -] - -[[package]] -name = "derive_more" -version = "0.99.17" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4fb810d30a7c1953f91334de7244731fc3f3c10d7fe163338a35b9f640960321" -dependencies = [ - "convert_case", - "proc-macro2 1.0.66", - "quote 1.0.32", - "rustc_version 0.4.0", - "syn 1.0.109", -] - -[[package]] -name = "embedded-alloc" -version = "0.5.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8931e47e33c5d3194fbcf9cc82df0919193bd2fa40008f388eb1d28fd9c9ea6b" -dependencies = [ - "critical-section", - "linked_list_allocator", -] - -[[package]] -name = "embedded-can" -version = "0.4.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e9d2e857f87ac832df68fa498d18ddc679175cf3d2e4aa893988e5601baf9438" -dependencies = [ - "nb 1.1.0", -] - -[[package]] -name = "embedded-hal" -version = "0.2.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "35949884794ad573cf46071e41c9b60efb0cb311e3ca01f7af807af1debc66ff" -dependencies = [ - "nb 0.1.3", - "void", -] - -[[package]] -name = "embedded-sdmmc" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6d3bf0a2b5becb87e9a329d9290f131e4d10fec39b56d129926826a7cbea1e7a" -dependencies = [ - "byteorder", - "embedded-hal", - "log", - "nb 0.1.3", -] - -[[package]] -name = "enum_dispatch" -version = "0.3.12" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8f33313078bb8d4d05a2733a94ac4c2d8a0df9a2b84424ebf4f33bfc224a890e" -dependencies = [ - "once_cell", - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 2.0.28", -] - -[[package]] -name = "errno" -version = "0.3.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6b30f669a7961ef1631673d2766cc92f52d64f7ef354d4fe0ddfd30ed52f0f4f" -dependencies = [ - "errno-dragonfly", - "libc", - "windows-sys", -] - -[[package]] -name = "errno-dragonfly" -version = "0.1.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "aa68f1b12764fab894d2755d2518754e71b4fd80ecfb822714a1206c2aab39bf" -dependencies = [ - "cc", - "libc", -] - -[[package]] -name = "fastrand" -version = "2.0.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6999dc1837253364c2ebb0704ba97994bd874e8f195d665c50b7548f6ea92764" - -[[package]] -name = "fnv" -version = "1.0.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "3f9eec918d3f24069decb9af1554cad7c880e2da24a9afd88aca000531ab82c1" - -[[package]] -name = "fugit" -version = "0.3.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "17186ad64927d5ac8f02c1e77ccefa08ccd9eaa314d5a4772278aa204a22f7e7" -dependencies = [ - "gcd", -] - -[[package]] -name = "gcd" -version = "2.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "1d758ba1b47b00caf47f24925c0074ecb20d6dfcffe7f6d53395c0465674841a" - -[[package]] -name = "generic-array" -version = "0.14.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "85649ca51fd72272d7821adaf274ad91c288277713d9c18820d8499a7ff69e9a" -dependencies = [ - "typenum", - "version_check", -] - -[[package]] -name = "getrandom" -version = "0.2.10" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "be4136b2a15dd319360be1c07d9933517ccf0be8f16bf62a3bee4f0d618df427" -dependencies = [ - "cfg-if", - "libc", - "wasi", -] - -[[package]] -name = "hash32" -version = "0.2.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b0c35f58762feb77d74ebe43bdbc3210f09be9fe6742234d573bacc26ed92b67" -dependencies = [ - "byteorder", -] - -[[package]] -name = "hashbrown" -version = "0.12.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8a9ee70c43aaf417c914396645a0fa852624801b24ebb7ae78fe8272889ac888" - -[[package]] -name = "heapless" -version = "0.7.16" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "db04bc24a18b9ea980628ecf00e6c0264f3c1426dac36c00cb49b6fbad8b0743" -dependencies = [ - "atomic-polyfill", - "hash32", - "rustc_version 0.4.0", - "serde", - "spin", - "stable_deref_trait", -] - -[[package]] -name = "indexmap" -version = "1.9.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "bd070e393353796e801d209ad339e89596eb4c8d430d18ede6a1cced8fafbd99" -dependencies = [ - "autocfg", - "hashbrown", -] - -[[package]] -name = "ioctl-rs" -version = "0.1.6" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f7970510895cee30b3e9128319f2cefd4bde883a39f38baa279567ba3a7eb97d" -dependencies = [ - "libc", -] - -[[package]] -name = "lazy_static" -version = "1.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e2abad23fbc42b3700f2f279844dc832adb2b2eb069b2df918f455c4e18cc646" - -[[package]] -name = "libc" -version = "0.2.147" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b4668fb0ea861c1df094127ac5f1da3409a82116a4ba74fca2e58ef927159bb3" - -[[package]] -name = "libm" -version = "0.2.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f7012b1bbb0719e1097c47611d3898568c546d597c2e74d66f6087edd5233ff4" - -[[package]] -name = "linked_list_allocator" -version = "0.10.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9afa463f5405ee81cdb9cc2baf37e08ec7e4c8209442b5d72c04cfb2cd6e6286" - -[[package]] -name = "linux-raw-sys" -version = "0.4.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "57bcfdad1b858c2db7c38303a6d2ad4dfaf5eb53dfeb0910128b2c26d6158503" - -[[package]] -name = "lock_api" -version = "0.4.10" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "c1cc9717a20b1bb222f333e6a92fd32f7d8a18ddc5a3191a11af45dcbf4dcd16" -dependencies = [ - "autocfg", - "scopeguard", -] - -[[package]] -name = "log" -version = "0.4.20" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b5e6163cb8c49088c2c36f57875e58ccd8c87c7427f7fbd50ea6710b2f3f2e8f" - -[[package]] -name = "mavlink" -version = "0.11.1" -source = "git+https://github.com/uorocketry/rust-mavlink?branch=hydra_dialect#0e0bedd0f37ccad490ea693ad80c2ecffb3d6351" -dependencies = [ - "bitflags 1.3.2", - "byteorder", - "crc-any", - "embedded-hal", - "heapless", - "lazy_static", - "nb 1.1.0", - "num-derive", - "num-traits", - "proc-macro2 1.0.66", - "quick-xml", - "quote 1.0.32", - "serde", - "serial", -] - -[[package]] -name = "mcan" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "1db1ad48f562b804bfe83828dc0d87622ea96bdc435a8513ecaa45a5f88d2f2f" -dependencies = [ - "bitfield 0.14.0", - "embedded-can", - "fugit", - "generic-array", - "mcan-core", - "nb 1.1.0", - "vcell", -] - -[[package]] -name = "mcan-core" -version = "0.2.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8b3dee4ff5269e2465cc856d37103cce916c1ef73b4377f006c963872e69f7ca" -dependencies = [ - "fugit", -] - -[[package]] -name = "memchr" -version = "2.5.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "2dffe52ecf27772e601905b7522cb4ef790d2cc203488bbd0e2fe85fcb74566d" - -[[package]] -name = "messages" -version = "0.1.0" -dependencies = [ - "defmt", - "derive_more", - "fugit", - "heapless", - "mavlink", - "postcard", - "proptest", - "proptest-derive", - "serde", - "ts-rs", -] - -[[package]] -name = "modular-bitfield" -version = "0.11.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a53d79ba8304ac1c4f9eb3b9d281f21f7be9d4626f72ce7df4ad8fbde4f38a74" -dependencies = [ - "modular-bitfield-impl", - "static_assertions", -] - -[[package]] -name = "modular-bitfield-impl" -version = "0.11.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "5a7d5f7076603ebc68de2dc6a650ec331a062a13abaa346975be747bbfa4b789" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", -] - -[[package]] -name = "nb" -version = "0.1.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "801d31da0513b6ec5214e9bf433a77966320625a37860f910be265be6e18d06f" -dependencies = [ - "nb 1.1.0", -] - -[[package]] -name = "nb" -version = "1.1.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8d5439c4ad607c3c23abf66de8c8bf57ba8adcd1f129e699851a6e43935d339d" - -[[package]] -name = "num-derive" -version = "0.3.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "876a53fff98e03a936a674b29568b0e605f06b29372c2489ff4de23f1949743d" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", -] - -[[package]] -name = "num-traits" -version = "0.2.16" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f30b0abd723be7e2ffca1272140fac1a2f084c77ec3e123c192b66af1ee9e6c2" -dependencies = [ - "autocfg", - "libm", -] - -[[package]] -name = "once_cell" -version = "1.18.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "dd8b5dd2ae5ed71462c540258bedcb51965123ad7e7ccf4b9a8cafaa4a63576d" - -[[package]] -name = "opaque-debug" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "624a8340c38c1b80fd549087862da4ba43e08858af025b236e509b6649fc13d5" - -[[package]] -name = "panic-halt" -version = "0.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "de96540e0ebde571dc55c73d60ef407c653844e6f9a1e2fdbd40c07b9252d812" - -[[package]] -name = "panic-probe" -version = "0.3.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "aa6fa5645ef5a760cd340eaa92af9c1ce131c8c09e7f8926d8a24b59d26652b9" -dependencies = [ - "cortex-m", - "defmt", -] - -[[package]] -name = "paste" -version = "1.0.14" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "de3145af08024dea9fa9914f381a17b8fc6034dfb00f3a84013f7ff43f29ed4c" - -[[package]] -name = "postcard" -version = "1.0.6" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "c9ee729232311d3cd113749948b689627618133b1c5012b77342c1950b25eaeb" -dependencies = [ - "cobs", - "defmt", - "heapless", - "serde", -] - -[[package]] -name = "power" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "cortex-m-rtic", - "defmt", - "enum_dispatch", - "heapless", - "messages", - "panic-halt", - "postcard", - "systick-monotonic", - "typenum", -] - -[[package]] -name = "ppv-lite86" -version = "0.2.17" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "5b40af805b3121feab8a3c29f04d8ad262fa8e0561883e7653e024ae4479e6de" - -[[package]] -name = "proc-macro-error" -version = "1.0.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "da25490ff9892aab3fcf7c36f08cfb902dd3e71ca0f9f9517bea02a73a5ce38c" -dependencies = [ - "proc-macro-error-attr", - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", - "version_check", -] - -[[package]] -name = "proc-macro-error-attr" -version = "1.0.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a1be40180e52ecc98ad80b184934baf3d0d29f979574e439af5a55274b35f869" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "version_check", -] - -[[package]] -name = "proc-macro2" -version = "0.4.30" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "cf3d2011ab5c909338f7887f4fc896d35932e29146c12c8d01da6b22a80ba759" -dependencies = [ - "unicode-xid", -] - -[[package]] -name = "proc-macro2" -version = "1.0.66" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "18fb31db3f9bddb2ea821cde30a9f70117e3f119938b5ee630b7403aa6e2ead9" -dependencies = [ - "unicode-ident", -] - -[[package]] -name = "proptest" -version = "1.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4e35c06b98bf36aba164cc17cb25f7e232f5c4aeea73baa14b8a9f0d92dbfa65" -dependencies = [ - "bit-set", - "bitflags 1.3.2", - "byteorder", - "lazy_static", - "num-traits", - "rand", - "rand_chacha", - "rand_xorshift", - "regex-syntax", - "rusty-fork", - "tempfile", - "unarray", -] - -[[package]] -name = "proptest-derive" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "90b46295382dc76166cb7cf2bb4a97952464e4b7ed5a43e6cd34e1fec3349ddc" -dependencies = [ - "proc-macro2 0.4.30", - "quote 0.6.13", - "syn 0.15.44", -] - -[[package]] -name = "quick-error" -version = "1.2.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a1d01941d82fa2ab50be1e79e6714289dd7cde78eba4c074bc5a4374f650dfe0" - -[[package]] -name = "quick-xml" -version = "0.26.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "7f50b1c63b38611e7d4d7f68b82d3ad0cc71a2ad2e7f61fc10f1328d917c93cd" -dependencies = [ - "memchr", -] - -[[package]] -name = "quote" -version = "0.6.13" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6ce23b6b870e8f94f81fb0a363d65d86675884b34a09043c81e5562f11c1f8e1" -dependencies = [ - "proc-macro2 0.4.30", -] - -[[package]] -name = "quote" -version = "1.0.32" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "50f3b39ccfb720540debaa0164757101c08ecb8d326b15358ce76a62c7e85965" -dependencies = [ - "proc-macro2 1.0.66", -] - -[[package]] -name = "rand" -version = "0.8.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "34af8d1a0e25924bc5b7c43c079c942339d8f0a8b57c39049bef581b46327404" -dependencies = [ - "libc", - "rand_chacha", - "rand_core", -] - -[[package]] -name = "rand_chacha" -version = "0.3.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e6c10a63a0fa32252be49d21e7709d4d4baf8d231c2dbce1eaa8141b9b127d88" -dependencies = [ - "ppv-lite86", - "rand_core", -] - -[[package]] -name = "rand_core" -version = "0.6.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "ec0be4795e2f6a28069bec0b5ff3e2ac9bafc99e6a9a7dc3547996c5c816922c" -dependencies = [ - "getrandom", -] - -[[package]] -name = "rand_xorshift" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d25bf25ec5ae4a3f1b92f929810509a2f53d7dca2f50b794ff57e3face536c8f" -dependencies = [ - "rand_core", -] - -[[package]] -name = "recovery" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "cortex-m-rtic", - "defmt", - "enum_dispatch", - "heapless", - "messages", - "panic-halt", - "postcard", - "systick-monotonic", - "typenum", -] - -[[package]] -name = "redox_syscall" -version = "0.3.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "567664f262709473930a4bf9e51bf2ebf3348f2e748ccc50dea20646858f8f29" -dependencies = [ - "bitflags 1.3.2", -] - -[[package]] -name = "regex-syntax" -version = "0.6.29" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f162c6dd7b008981e4d40210aca20b4bd0f9b60ca9271061b07f78537722f2e1" - -[[package]] -name = "rtic-core" -version = "1.0.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d9369355b04d06a3780ec0f51ea2d225624db777acbc60abd8ca4832da5c1a42" - -[[package]] -name = "rtic-monotonic" -version = "1.0.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "fb8b0b822d1a366470b9cea83a1d4e788392db763539dc4ba022bcc787fece82" - -[[package]] -name = "rtic-syntax" -version = "1.0.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "5f5e215601dc467752c2bddc6284a622c6f3d2bab569d992adcd5ab7e4cb9478" -dependencies = [ - "indexmap", - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", -] - -[[package]] -name = "rtic_example" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "cortex-m-rtic", - "defmt", - "defmt-rtt", - "fugit", - "heapless", - "messages", - "panic-halt", - "postcard", - "systick-monotonic", - "typenum", -] - -[[package]] -name = "rustc_version" -version = "0.2.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "138e3e0acb6c9fb258b19b67cb8abd63c00679d2851805ea151465464fe9030a" -dependencies = [ - "semver 0.9.0", -] - -[[package]] -name = "rustc_version" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "bfa0f585226d2e68097d4f95d113b15b83a82e819ab25717ec0590d9584ef366" -dependencies = [ - "semver 1.0.18", -] - -[[package]] -name = "rustix" -version = "0.38.8" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "19ed4fa021d81c8392ce04db050a3da9a60299050b7ae1cf482d862b54a7218f" -dependencies = [ - "bitflags 2.4.0", - "errno", - "libc", - "linux-raw-sys", - "windows-sys", -] - -[[package]] -name = "rusty-fork" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "cb3dcc6e454c328bb824492db107ab7c0ae8fcffe4ad210136ef014458c1bc4f" -dependencies = [ - "fnv", - "quick-error", - "tempfile", - "wait-timeout", -] - -[[package]] -name = "sbg-rs" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "cmake", - "common-arm", - "cortex-m", - "cortex-m-rt", - "defmt", - "embedded-hal", - "heapless", - "messages", - "nb 1.1.0", -] - -[[package]] -name = "scopeguard" -version = "1.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "94143f37725109f92c262ed2cf5e59bce7498c01bcc1502d7b9afe439a4e9f49" - -[[package]] -name = "semver" -version = "0.9.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "1d7eb9ef2c18661902cc47e535f9bc51b78acd254da71d375c2f6720d9a40403" -dependencies = [ - "semver-parser", -] - -[[package]] -name = "semver" -version = "1.0.18" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b0293b4b29daaf487284529cc2f5675b8e57c61f70167ba415a463651fd6a918" - -[[package]] -name = "semver-parser" -version = "0.7.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "388a1df253eca08550bef6c72392cfe7c30914bf41df5269b68cbd6ff8f570a3" - -[[package]] -name = "sensor" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "cortex-m-rtic", - "defmt", - "embedded-alloc", - "embedded-sdmmc", - "heapless", - "messages", - "panic-halt", - "postcard", - "sbg-rs", - "systick-monotonic", - "typenum", -] - -[[package]] -name = "seq-macro" -version = "0.3.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a3f0bf26fd526d2a95683cd0f87bf103b8539e2ca1ef48ce002d67aad59aa0b4" - -[[package]] -name = "serde" -version = "1.0.183" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "32ac8da02677876d532745a130fc9d8e6edfa81a269b107c5b00829b91d8eb3c" -dependencies = [ - "serde_derive", -] - -[[package]] -name = "serde_derive" -version = "1.0.183" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "aafe972d60b0b9bee71a91b92fee2d4fb3c9d7e8f6b179aa99f27203d99a4816" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 2.0.28", -] - -[[package]] -name = "serial" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a1237a96570fc377c13baa1b88c7589ab66edced652e43ffb17088f003db3e86" -dependencies = [ - "serial-core", - "serial-unix", - "serial-windows", -] - -[[package]] -name = "serial-core" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "3f46209b345401737ae2125fe5b19a77acce90cd53e1658cda928e4fe9a64581" -dependencies = [ - "libc", -] - -[[package]] -name = "serial-unix" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f03fbca4c9d866e24a459cbca71283f545a37f8e3e002ad8c70593871453cab7" -dependencies = [ - "ioctl-rs", - "libc", - "serial-core", - "termios", -] - -[[package]] -name = "serial-windows" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "15c6d3b776267a75d31bbdfd5d36c0ca051251caafc285827052bc53bcdc8162" -dependencies = [ - "libc", - "serial-core", -] - -[[package]] -name = "simple_example" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "defmt", - "defmt-rtt", - "panic-halt", -] - -[[package]] -name = "spin" -version = "0.9.8" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6980e8d7511241f8acf4aebddbb1ff938df5eebe98691418c4468d0b72a96a67" -dependencies = [ - "lock_api", -] - -[[package]] -name = "stable_deref_trait" -version = "1.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a8f112729512f8e442d81f95a8a7ddf2b7c6b8a1a6f509a95864142b30cab2d3" - -[[package]] -name = "static_assertions" -version = "1.1.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a2eb9349b6444b326872e140eb1cf5e7c522154d69e7a0ffb0fb81c06b37543f" - -[[package]] -name = "syn" -version = "0.15.44" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9ca4b3b69a77cbe1ffc9e198781b7acb0c7365a883670e8f1c1bc66fba79a5c5" -dependencies = [ - "proc-macro2 0.4.30", - "quote 0.6.13", - "unicode-xid", -] - -[[package]] -name = "syn" -version = "1.0.109" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "72b64191b275b66ffe2469e8af2c1cfe3bafa67b529ead792a6d0160888b4237" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "unicode-ident", -] - -[[package]] -name = "syn" -version = "2.0.28" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "04361975b3f5e348b2189d8dc55bc942f278b2d482a6a0365de5bdd62d351567" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "unicode-ident", -] - -[[package]] -name = "systick-monotonic" -version = "1.0.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "67fb822d5c615a0ae3a4795ee5b1d06381c7faf488d861c0a4fa8e6a88d5ff84" -dependencies = [ - "cortex-m", - "fugit", - "rtic-monotonic", -] - -[[package]] -name = "tempfile" -version = "3.7.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "dc02fddf48964c42031a0b3fe0428320ecf3a73c401040fc0096f97794310651" -dependencies = [ - "cfg-if", - "fastrand", - "redox_syscall", - "rustix", - "windows-sys", -] - -[[package]] -name = "termcolor" -version = "1.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "be55cf8942feac5c765c2c993422806843c9a9a45d4d5c407ad6dd2ea95eb9b6" -dependencies = [ - "winapi-util", -] - -[[package]] -name = "termios" -version = "0.2.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d5d9cf598a6d7ce700a4e6a9199da127e6819a61e64b68609683cc9a01b5683a" -dependencies = [ - "libc", -] - -[[package]] -name = "thiserror" -version = "1.0.44" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "611040a08a0439f8248d1990b111c95baa9c704c805fa1f62104b39655fd7f90" -dependencies = [ - "thiserror-impl", -] - -[[package]] -name = "thiserror-impl" -version = "1.0.44" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "090198534930841fab3a5d1bb637cde49e339654e606195f8d9c76eeb081dc96" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 2.0.28", -] - -[[package]] -name = "ts-rs" -version = "6.2.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4added4070a4fdf9df03457206cd2e4b12417c8560a2954d91ffcbe60177a56a" -dependencies = [ - "thiserror", - "ts-rs-macros", -] - -[[package]] -name = "ts-rs-macros" -version = "6.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9f807fdb3151fee75df7485b901a89624358cd07a67a8fb1a5831bf5a07681ff" -dependencies = [ - "Inflector", - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", - "termcolor", -] - -[[package]] -name = "typenum" -version = "1.16.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "497961ef93d974e23eb6f433eb5fe1b7930b659f06d12dec6fc44a8f554c0bba" - -[[package]] -name = "unarray" -version = "0.1.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "eaea85b334db583fe3274d12b4cd1880032beab409c0d774be044d4480ab9a94" - -[[package]] -name = "unicode-ident" -version = "1.0.11" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "301abaae475aa91687eb82514b328ab47a211a533026cb25fc3e519b86adfc3c" - -[[package]] -name = "unicode-xid" -version = "0.1.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "fc72304796d0818e357ead4e000d19c9c174ab23dc11093ac919054d20a6a7fc" - -[[package]] -name = "vcell" -version = "0.1.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "77439c1b53d2303b20d9459b1ade71a83c716e3f9c34f3228c00e6f185d6c002" - -[[package]] -name = "version_check" -version = "0.9.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "49874b5167b65d7193b8aba1567f5c7d93d001cafc34600cee003eda787e483f" - -[[package]] -name = "void" -version = "1.0.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6a02e4885ed3bc0f2de90ea6dd45ebcbb66dacffe03547fadbb0eeae2770887d" - -[[package]] -name = "volatile-register" -version = "0.2.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9ee8f19f9d74293faf70901bc20ad067dc1ad390d2cbf1e3f75f721ffee908b6" -dependencies = [ - "vcell", -] - -[[package]] -name = "wait-timeout" -version = "0.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9f200f5b12eb75f8c1ed65abd4b2db8a6e1b138a20de009dacee265a2498f3f6" -dependencies = [ - "libc", -] - -[[package]] -name = "wasi" -version = "0.11.0+wasi-snapshot-preview1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9c8d87e72b64a3b4db28d11ce29237c246188f4f51057d65a7eab63b7987e423" - -[[package]] -name = "winapi" -version = "0.3.9" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "5c839a674fcd7a98952e593242ea400abe93992746761e38641405d28b00f419" -dependencies = [ - "winapi-i686-pc-windows-gnu", - "winapi-x86_64-pc-windows-gnu", -] - -[[package]] -name = "winapi-i686-pc-windows-gnu" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "ac3b87c63620426dd9b991e5ce0329eff545bccbbb34f3be09ff6fb6ab51b7b6" - -[[package]] -name = "winapi-util" -version = "0.1.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "70ec6ce85bb158151cae5e5c87f95a8e97d2c0c4b001223f33a334e3ce5de178" -dependencies = [ - "winapi", -] - -[[package]] -name = "winapi-x86_64-pc-windows-gnu" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "712e227841d057c1ee1cd2fb22fa7e5a5461ae8e48fa2ca79ec42cfc1931183f" - -[[package]] -name = "windows-sys" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "677d2418bec65e3338edb076e806bc1ec15693c5d0104683f2efe857f61056a9" -dependencies = [ - "windows-targets", -] - -[[package]] -name = "windows-targets" -version = "0.48.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "05d4b17490f70499f20b9e791dcf6a299785ce8af4d709018206dc5b4953e95f" -dependencies = [ - "windows_aarch64_gnullvm", - "windows_aarch64_msvc", - "windows_i686_gnu", - "windows_i686_msvc", - "windows_x86_64_gnu", - "windows_x86_64_gnullvm", - "windows_x86_64_msvc", -] - -[[package]] -name = "windows_aarch64_gnullvm" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "91ae572e1b79dba883e0d315474df7305d12f569b400fcf90581b06062f7e1bc" - -[[package]] -name = "windows_aarch64_msvc" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b2ef27e0d7bdfcfc7b868b317c1d32c641a6fe4629c171b8928c7b08d98d7cf3" - -[[package]] -name = "windows_i686_gnu" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "622a1962a7db830d6fd0a69683c80a18fda201879f0f447f065a3b7467daa241" - -[[package]] -name = "windows_i686_msvc" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4542c6e364ce21bf45d69fdd2a8e455fa38d316158cfd43b3ac1c5b1b19f8e00" - -[[package]] -name = "windows_x86_64_gnu" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "ca2b8a661f7628cbd23440e50b05d705db3686f894fc9580820623656af974b1" - -[[package]] -name = "windows_x86_64_gnullvm" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "7896dbc1f41e08872e9d5e8f8baa8fdd2677f29468c4e156210174edc7f7b953" - -[[package]] -name = "windows_x86_64_msvc" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "1a515f5799fe4961cb532f983ce2b23082366b898e52ffbce459c86f67c8378a" +# This file is automatically @generated by Cargo. +# It is not intended for manual editing. +version = 3 + +[[package]] +name = "Inflector" +version = "0.11.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "fe438c63458706e03479442743baae6c88256498e6431708f6dfc520a26515d3" + +[[package]] +name = "aes" +version = "0.7.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9e8b47f52ea9bae42228d07ec09eb676433d7c4ed1ebdf0f1d1c29ed446f1ab8" +dependencies = [ + "cfg-if", + "cipher", + "cpufeatures", + "opaque-debug", +] + +[[package]] +name = "atomic-polyfill" +version = "0.1.11" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e3ff7eb3f316534d83a8a2c3d1674ace8a5a71198eba31e2e2b597833f699b28" +dependencies = [ + "critical-section", +] + +[[package]] +name = "atsamd-hal" +version = "0.16.0" +source = "git+https://github.com/atsamd-rs/atsamd#0820f0df58eb8705ddfa6533ed76953d18e6b992" +dependencies = [ + "aes", + "atsame51j", + "bitfield 0.13.2", + "bitflags 1.3.2", + "cipher", + "cortex-m", + "embedded-hal", + "fugit", + "mcan-core", + "modular-bitfield", + "nb 1.1.0", + "num-traits", + "opaque-debug", + "paste", + "rand_core", + "seq-macro", + "typenum", + "vcell", + "void", +] + +[[package]] +name = "atsame51j" +version = "0.12.0" +source = "git+https://github.com/atsamd-rs/atsamd#0820f0df58eb8705ddfa6533ed76953d18e6b992" +dependencies = [ + "cortex-m", + "cortex-m-rt", + "vcell", +] + +[[package]] +name = "autocfg" +version = "1.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d468802bab17cbc0cc575e9b053f41e72aa36bfa6b7f55e3529ffa43161b97fa" + +[[package]] +name = "bare-metal" +version = "0.2.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5deb64efa5bd81e31fcd1938615a6d98c82eafcbcd787162b6f63b91d6bac5b3" +dependencies = [ + "rustc_version 0.2.3", +] + +[[package]] +name = "bare-metal" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f8fe8f5a8a398345e52358e18ff07cc17a568fbca5c6f73873d3a62056309603" + +[[package]] +name = "bit-set" +version = "0.5.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0700ddab506f33b20a03b13996eccd309a48e5ff77d0d95926aa0210fb4e95f1" +dependencies = [ + "bit-vec", +] + +[[package]] +name = "bit-vec" +version = "0.6.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "349f9b6a179ed607305526ca489b34ad0a41aed5f7980fa90eb03160b69598fb" + +[[package]] +name = "bitfield" +version = "0.13.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "46afbd2983a5d5a7bd740ccb198caf5b82f45c40c09c0eed36052d91cb92e719" + +[[package]] +name = "bitfield" +version = "0.14.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "2d7e60934ceec538daadb9d8432424ed043a904d8e0243f3c6446bce549a46ac" + +[[package]] +name = "bitflags" +version = "1.3.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bef38d45163c2f1dde094a7dfd33ccf595c92905c8f8f4fdc18d06fb1037718a" + +[[package]] +name = "bitflags" +version = "2.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b4682ae6287fcf752ecaabbfcc7b6f9b72aa33933dc23a554d853aea8eea8635" + +[[package]] +name = "byteorder" +version = "1.4.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "14c189c53d098945499cdfa7ecc63567cf3886b3332b312a5b4585d8d3a6a610" + +[[package]] +name = "cc" +version = "1.0.82" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "305fe645edc1442a0fa8b6726ba61d422798d37a52e12eaecf4b022ebbb88f01" +dependencies = [ + "libc", +] + +[[package]] +name = "cfg-if" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "baf1de4339761588bc0619e3cbc0120ee582ebb74b53b4efbf79117bd2da40fd" + +[[package]] +name = "cipher" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7ee52072ec15386f770805afd189a01c8841be8696bed250fa2f13c4c0d6dfb7" +dependencies = [ + "generic-array", +] + +[[package]] +name = "cmake" +version = "0.1.50" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a31c789563b815f77f4250caee12365734369f942439b7defd71e18a48197130" +dependencies = [ + "cc", +] + +[[package]] +name = "cobs" +version = "0.2.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "67ba02a97a2bd10f4b59b25c7973101c79642302776489e030cd13cdab09ed15" + +[[package]] +name = "common-arm" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "cortex-m", + "cortex-m-rt", + "defmt", + "defmt-rtt", + "derive_more", + "embedded-hal", + "embedded-sdmmc", + "heapless", + "mcan", + "messages", + "nb 1.1.0", + "postcard", +] + +[[package]] +name = "common-arm-test" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "defmt", + "defmt-rtt", + "defmt-test", + "panic-probe", +] + +[[package]] +name = "communication" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "cortex-m-rtic", + "defmt", + "embedded-sdmmc", + "heapless", + "messages", + "panic-halt", + "postcard", + "systick-monotonic", + "typenum", +] + +[[package]] +name = "convert_case" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6245d59a3e82a7fc217c5828a6692dbc6dfb63a0c8c90495621f7b9d79704a0e" + +[[package]] +name = "cortex-m" +version = "0.7.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8ec610d8f49840a5b376c69663b6369e71f4b34484b9b2eb29fb918d92516cb9" +dependencies = [ + "bare-metal 0.2.5", + "bitfield 0.13.2", + "critical-section", + "embedded-hal", + "volatile-register", +] + +[[package]] +name = "cortex-m-rt" +version = "0.7.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ee84e813d593101b1723e13ec38b6ab6abbdbaaa4546553f5395ed274079ddb1" +dependencies = [ + "cortex-m-rt-macros", +] + +[[package]] +name = "cortex-m-rt-macros" +version = "0.7.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f0f6f3e36f203cfedbc78b357fb28730aa2c6dc1ab060ee5c2405e843988d3c7" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", +] + +[[package]] +name = "cortex-m-rtic" +version = "1.1.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d696ae7390bdb9f7978f71ca7144256a2c4616240a6df9002da3c451f9fc8f02" +dependencies = [ + "bare-metal 1.0.0", + "cortex-m", + "cortex-m-rtic-macros", + "heapless", + "rtic-core", + "rtic-monotonic", + "version_check", +] + +[[package]] +name = "cortex-m-rtic-macros" +version = "1.1.6" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "eefb40b1ca901c759d29526e5c8a0a1b246c20caaa5b4cc5d0f0b94debecd4c7" +dependencies = [ + "proc-macro-error", + "proc-macro2 1.0.66", + "quote 1.0.32", + "rtic-syntax", + "syn 1.0.109", +] + +[[package]] +name = "cpufeatures" +version = "0.2.9" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a17b76ff3a4162b0b27f354a0c87015ddad39d35f9c0c36607a3bdd175dde1f1" +dependencies = [ + "libc", +] + +[[package]] +name = "crc-any" +version = "2.4.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "774646b687f63643eb0f4bf13dc263cb581c8c9e57973b6ddf78bda3994d88df" + +[[package]] +name = "critical-section" +version = "1.1.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7059fff8937831a9ae6f0fe4d658ffabf58f2ca96aa9dec1c889f936f705f216" + +[[package]] +name = "defmt" +version = "0.3.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a8a2d011b2fee29fb7d659b83c43fce9a2cb4df453e16d441a51448e448f3f98" +dependencies = [ + "bitflags 1.3.2", + "defmt-macros", +] + +[[package]] +name = "defmt-macros" +version = "0.3.6" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "54f0216f6c5acb5ae1a47050a6645024e6edafc2ee32d421955eccfef12ef92e" +dependencies = [ + "defmt-parser", + "proc-macro-error", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 2.0.28", +] + +[[package]] +name = "defmt-parser" +version = "0.3.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "269924c02afd7f94bc4cecbfa5c379f6ffcf9766b3408fe63d22c728654eccd0" +dependencies = [ + "thiserror", +] + +[[package]] +name = "defmt-rtt" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "609923761264dd99ed9c7d209718cda4631c5fe84668e0f0960124cbb844c49f" +dependencies = [ + "critical-section", + "defmt", +] + +[[package]] +name = "defmt-test" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4df24f1ca104a0c1bce2047d8a21aa9fa29695e5d662118eb48daedb97edca88" +dependencies = [ + "cortex-m", + "cortex-m-rt", + "defmt", + "defmt-test-macros", +] + +[[package]] +name = "defmt-test-macros" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "94a0dfea4063d72e1ba20494dfbc4667f67420869328cf3670b5824a38a22dc1" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", +] + +[[package]] +name = "derive_more" +version = "0.99.17" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4fb810d30a7c1953f91334de7244731fc3f3c10d7fe163338a35b9f640960321" +dependencies = [ + "convert_case", + "proc-macro2 1.0.66", + "quote 1.0.32", + "rustc_version 0.4.0", + "syn 1.0.109", +] + +[[package]] +name = "embedded-alloc" +version = "0.5.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8931e47e33c5d3194fbcf9cc82df0919193bd2fa40008f388eb1d28fd9c9ea6b" +dependencies = [ + "critical-section", + "linked_list_allocator", +] + +[[package]] +name = "embedded-can" +version = "0.4.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e9d2e857f87ac832df68fa498d18ddc679175cf3d2e4aa893988e5601baf9438" +dependencies = [ + "nb 1.1.0", +] + +[[package]] +name = "embedded-hal" +version = "0.2.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "35949884794ad573cf46071e41c9b60efb0cb311e3ca01f7af807af1debc66ff" +dependencies = [ + "nb 0.1.3", + "void", +] + +[[package]] +name = "embedded-sdmmc" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6d3bf0a2b5becb87e9a329d9290f131e4d10fec39b56d129926826a7cbea1e7a" +dependencies = [ + "byteorder", + "embedded-hal", + "log", + "nb 0.1.3", +] + +[[package]] +name = "enum_dispatch" +version = "0.3.12" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8f33313078bb8d4d05a2733a94ac4c2d8a0df9a2b84424ebf4f33bfc224a890e" +dependencies = [ + "once_cell", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 2.0.28", +] + +[[package]] +name = "errno" +version = "0.3.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6b30f669a7961ef1631673d2766cc92f52d64f7ef354d4fe0ddfd30ed52f0f4f" +dependencies = [ + "errno-dragonfly", + "libc", + "windows-sys", +] + +[[package]] +name = "errno-dragonfly" +version = "0.1.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "aa68f1b12764fab894d2755d2518754e71b4fd80ecfb822714a1206c2aab39bf" +dependencies = [ + "cc", + "libc", +] + +[[package]] +name = "fastrand" +version = "2.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6999dc1837253364c2ebb0704ba97994bd874e8f195d665c50b7548f6ea92764" + +[[package]] +name = "fnv" +version = "1.0.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3f9eec918d3f24069decb9af1554cad7c880e2da24a9afd88aca000531ab82c1" + +[[package]] +name = "fugit" +version = "0.3.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "17186ad64927d5ac8f02c1e77ccefa08ccd9eaa314d5a4772278aa204a22f7e7" +dependencies = [ + "gcd", +] + +[[package]] +name = "gcd" +version = "2.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1d758ba1b47b00caf47f24925c0074ecb20d6dfcffe7f6d53395c0465674841a" + +[[package]] +name = "generic-array" +version = "0.14.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "85649ca51fd72272d7821adaf274ad91c288277713d9c18820d8499a7ff69e9a" +dependencies = [ + "typenum", + "version_check", +] + +[[package]] +name = "getrandom" +version = "0.2.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "be4136b2a15dd319360be1c07d9933517ccf0be8f16bf62a3bee4f0d618df427" +dependencies = [ + "cfg-if", + "libc", + "wasi", +] + +[[package]] +name = "hash32" +version = "0.2.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b0c35f58762feb77d74ebe43bdbc3210f09be9fe6742234d573bacc26ed92b67" +dependencies = [ + "byteorder", +] + +[[package]] +name = "hashbrown" +version = "0.12.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8a9ee70c43aaf417c914396645a0fa852624801b24ebb7ae78fe8272889ac888" + +[[package]] +name = "heapless" +version = "0.7.16" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "db04bc24a18b9ea980628ecf00e6c0264f3c1426dac36c00cb49b6fbad8b0743" +dependencies = [ + "atomic-polyfill", + "hash32", + "rustc_version 0.4.0", + "serde", + "spin", + "stable_deref_trait", +] + +[[package]] +name = "indexmap" +version = "1.9.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bd070e393353796e801d209ad339e89596eb4c8d430d18ede6a1cced8fafbd99" +dependencies = [ + "autocfg", + "hashbrown", +] + +[[package]] +name = "ioctl-rs" +version = "0.1.6" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f7970510895cee30b3e9128319f2cefd4bde883a39f38baa279567ba3a7eb97d" +dependencies = [ + "libc", +] + +[[package]] +name = "lazy_static" +version = "1.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e2abad23fbc42b3700f2f279844dc832adb2b2eb069b2df918f455c4e18cc646" + +[[package]] +name = "libc" +version = "0.2.147" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b4668fb0ea861c1df094127ac5f1da3409a82116a4ba74fca2e58ef927159bb3" + +[[package]] +name = "libm" +version = "0.2.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f7012b1bbb0719e1097c47611d3898568c546d597c2e74d66f6087edd5233ff4" + +[[package]] +name = "linked_list_allocator" +version = "0.10.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9afa463f5405ee81cdb9cc2baf37e08ec7e4c8209442b5d72c04cfb2cd6e6286" + +[[package]] +name = "linux-raw-sys" +version = "0.4.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "57bcfdad1b858c2db7c38303a6d2ad4dfaf5eb53dfeb0910128b2c26d6158503" + +[[package]] +name = "lock_api" +version = "0.4.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "c1cc9717a20b1bb222f333e6a92fd32f7d8a18ddc5a3191a11af45dcbf4dcd16" +dependencies = [ + "autocfg", + "scopeguard", +] + +[[package]] +name = "log" +version = "0.4.20" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b5e6163cb8c49088c2c36f57875e58ccd8c87c7427f7fbd50ea6710b2f3f2e8f" + +[[package]] +name = "mavlink" +version = "0.11.1" +source = "git+https://github.com/uorocketry/rust-mavlink?branch=hydra_dialect#0e0bedd0f37ccad490ea693ad80c2ecffb3d6351" +dependencies = [ + "bitflags 1.3.2", + "byteorder", + "crc-any", + "embedded-hal", + "heapless", + "lazy_static", + "nb 1.1.0", + "num-derive", + "num-traits", + "proc-macro2 1.0.66", + "quick-xml", + "quote 1.0.32", + "serde", + "serial", +] + +[[package]] +name = "mcan" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1db1ad48f562b804bfe83828dc0d87622ea96bdc435a8513ecaa45a5f88d2f2f" +dependencies = [ + "bitfield 0.14.0", + "embedded-can", + "fugit", + "generic-array", + "mcan-core", + "nb 1.1.0", + "vcell", +] + +[[package]] +name = "mcan-core" +version = "0.2.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8b3dee4ff5269e2465cc856d37103cce916c1ef73b4377f006c963872e69f7ca" +dependencies = [ + "fugit", +] + +[[package]] +name = "memchr" +version = "2.5.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "2dffe52ecf27772e601905b7522cb4ef790d2cc203488bbd0e2fe85fcb74566d" + +[[package]] +name = "messages" +version = "0.1.0" +dependencies = [ + "defmt", + "derive_more", + "fugit", + "heapless", + "mavlink", + "postcard", + "proptest", + "proptest-derive", + "serde", + "ts-rs", +] + +[[package]] +name = "modular-bitfield" +version = "0.11.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a53d79ba8304ac1c4f9eb3b9d281f21f7be9d4626f72ce7df4ad8fbde4f38a74" +dependencies = [ + "modular-bitfield-impl", + "static_assertions", +] + +[[package]] +name = "modular-bitfield-impl" +version = "0.11.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5a7d5f7076603ebc68de2dc6a650ec331a062a13abaa346975be747bbfa4b789" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", +] + +[[package]] +name = "nb" +version = "0.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "801d31da0513b6ec5214e9bf433a77966320625a37860f910be265be6e18d06f" +dependencies = [ + "nb 1.1.0", +] + +[[package]] +name = "nb" +version = "1.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8d5439c4ad607c3c23abf66de8c8bf57ba8adcd1f129e699851a6e43935d339d" + +[[package]] +name = "num-derive" +version = "0.3.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "876a53fff98e03a936a674b29568b0e605f06b29372c2489ff4de23f1949743d" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", +] + +[[package]] +name = "num-traits" +version = "0.2.16" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f30b0abd723be7e2ffca1272140fac1a2f084c77ec3e123c192b66af1ee9e6c2" +dependencies = [ + "autocfg", + "libm", +] + +[[package]] +name = "once_cell" +version = "1.18.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "dd8b5dd2ae5ed71462c540258bedcb51965123ad7e7ccf4b9a8cafaa4a63576d" + +[[package]] +name = "opaque-debug" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "624a8340c38c1b80fd549087862da4ba43e08858af025b236e509b6649fc13d5" + +[[package]] +name = "panic-halt" +version = "0.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "de96540e0ebde571dc55c73d60ef407c653844e6f9a1e2fdbd40c07b9252d812" + +[[package]] +name = "panic-probe" +version = "0.3.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "aa6fa5645ef5a760cd340eaa92af9c1ce131c8c09e7f8926d8a24b59d26652b9" +dependencies = [ + "cortex-m", + "defmt", +] + +[[package]] +name = "paste" +version = "1.0.14" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "de3145af08024dea9fa9914f381a17b8fc6034dfb00f3a84013f7ff43f29ed4c" + +[[package]] +name = "postcard" +version = "1.0.6" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "c9ee729232311d3cd113749948b689627618133b1c5012b77342c1950b25eaeb" +dependencies = [ + "cobs", + "defmt", + "heapless", + "serde", +] + +[[package]] +name = "power" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "cortex-m-rtic", + "defmt", + "enum_dispatch", + "heapless", + "messages", + "panic-halt", + "postcard", + "systick-monotonic", + "typenum", +] + +[[package]] +name = "ppv-lite86" +version = "0.2.17" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5b40af805b3121feab8a3c29f04d8ad262fa8e0561883e7653e024ae4479e6de" + +[[package]] +name = "proc-macro-error" +version = "1.0.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "da25490ff9892aab3fcf7c36f08cfb902dd3e71ca0f9f9517bea02a73a5ce38c" +dependencies = [ + "proc-macro-error-attr", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", + "version_check", +] + +[[package]] +name = "proc-macro-error-attr" +version = "1.0.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a1be40180e52ecc98ad80b184934baf3d0d29f979574e439af5a55274b35f869" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "version_check", +] + +[[package]] +name = "proc-macro2" +version = "0.4.30" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "cf3d2011ab5c909338f7887f4fc896d35932e29146c12c8d01da6b22a80ba759" +dependencies = [ + "unicode-xid", +] + +[[package]] +name = "proc-macro2" +version = "1.0.66" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "18fb31db3f9bddb2ea821cde30a9f70117e3f119938b5ee630b7403aa6e2ead9" +dependencies = [ + "unicode-ident", +] + +[[package]] +name = "proptest" +version = "1.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4e35c06b98bf36aba164cc17cb25f7e232f5c4aeea73baa14b8a9f0d92dbfa65" +dependencies = [ + "bit-set", + "bitflags 1.3.2", + "byteorder", + "lazy_static", + "num-traits", + "rand", + "rand_chacha", + "rand_xorshift", + "regex-syntax", + "rusty-fork", + "tempfile", + "unarray", +] + +[[package]] +name = "proptest-derive" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "90b46295382dc76166cb7cf2bb4a97952464e4b7ed5a43e6cd34e1fec3349ddc" +dependencies = [ + "proc-macro2 0.4.30", + "quote 0.6.13", + "syn 0.15.44", +] + +[[package]] +name = "quick-error" +version = "1.2.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a1d01941d82fa2ab50be1e79e6714289dd7cde78eba4c074bc5a4374f650dfe0" + +[[package]] +name = "quick-xml" +version = "0.26.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7f50b1c63b38611e7d4d7f68b82d3ad0cc71a2ad2e7f61fc10f1328d917c93cd" +dependencies = [ + "memchr", +] + +[[package]] +name = "quote" +version = "0.6.13" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6ce23b6b870e8f94f81fb0a363d65d86675884b34a09043c81e5562f11c1f8e1" +dependencies = [ + "proc-macro2 0.4.30", +] + +[[package]] +name = "quote" +version = "1.0.32" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "50f3b39ccfb720540debaa0164757101c08ecb8d326b15358ce76a62c7e85965" +dependencies = [ + "proc-macro2 1.0.66", +] + +[[package]] +name = "rand" +version = "0.8.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "34af8d1a0e25924bc5b7c43c079c942339d8f0a8b57c39049bef581b46327404" +dependencies = [ + "libc", + "rand_chacha", + "rand_core", +] + +[[package]] +name = "rand_chacha" +version = "0.3.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e6c10a63a0fa32252be49d21e7709d4d4baf8d231c2dbce1eaa8141b9b127d88" +dependencies = [ + "ppv-lite86", + "rand_core", +] + +[[package]] +name = "rand_core" +version = "0.6.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ec0be4795e2f6a28069bec0b5ff3e2ac9bafc99e6a9a7dc3547996c5c816922c" +dependencies = [ + "getrandom", +] + +[[package]] +name = "rand_xorshift" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d25bf25ec5ae4a3f1b92f929810509a2f53d7dca2f50b794ff57e3face536c8f" +dependencies = [ + "rand_core", +] + +[[package]] +name = "recovery" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "cortex-m-rtic", + "defmt", + "enum_dispatch", + "heapless", + "messages", + "panic-halt", + "postcard", + "systick-monotonic", + "typenum", +] + +[[package]] +name = "redox_syscall" +version = "0.3.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "567664f262709473930a4bf9e51bf2ebf3348f2e748ccc50dea20646858f8f29" +dependencies = [ + "bitflags 1.3.2", +] + +[[package]] +name = "regex-syntax" +version = "0.6.29" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f162c6dd7b008981e4d40210aca20b4bd0f9b60ca9271061b07f78537722f2e1" + +[[package]] +name = "rtic-core" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d9369355b04d06a3780ec0f51ea2d225624db777acbc60abd8ca4832da5c1a42" + +[[package]] +name = "rtic-monotonic" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "fb8b0b822d1a366470b9cea83a1d4e788392db763539dc4ba022bcc787fece82" + +[[package]] +name = "rtic-syntax" +version = "1.0.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5f5e215601dc467752c2bddc6284a622c6f3d2bab569d992adcd5ab7e4cb9478" +dependencies = [ + "indexmap", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", +] + +[[package]] +name = "rtic_example" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "cortex-m-rtic", + "defmt", + "defmt-rtt", + "fugit", + "heapless", + "messages", + "panic-halt", + "postcard", + "systick-monotonic", + "typenum", +] + +[[package]] +name = "rustc_version" +version = "0.2.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "138e3e0acb6c9fb258b19b67cb8abd63c00679d2851805ea151465464fe9030a" +dependencies = [ + "semver 0.9.0", +] + +[[package]] +name = "rustc_version" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bfa0f585226d2e68097d4f95d113b15b83a82e819ab25717ec0590d9584ef366" +dependencies = [ + "semver 1.0.18", +] + +[[package]] +name = "rustix" +version = "0.38.8" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "19ed4fa021d81c8392ce04db050a3da9a60299050b7ae1cf482d862b54a7218f" +dependencies = [ + "bitflags 2.4.0", + "errno", + "libc", + "linux-raw-sys", + "windows-sys", +] + +[[package]] +name = "rusty-fork" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "cb3dcc6e454c328bb824492db107ab7c0ae8fcffe4ad210136ef014458c1bc4f" +dependencies = [ + "fnv", + "quick-error", + "tempfile", + "wait-timeout", +] + +[[package]] +name = "sbg-rs" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "cmake", + "common-arm", + "cortex-m", + "cortex-m-rt", + "defmt", + "embedded-hal", + "heapless", + "messages", + "nb 1.1.0", +] + +[[package]] +name = "scopeguard" +version = "1.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "94143f37725109f92c262ed2cf5e59bce7498c01bcc1502d7b9afe439a4e9f49" + +[[package]] +name = "semver" +version = "0.9.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1d7eb9ef2c18661902cc47e535f9bc51b78acd254da71d375c2f6720d9a40403" +dependencies = [ + "semver-parser", +] + +[[package]] +name = "semver" +version = "1.0.18" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b0293b4b29daaf487284529cc2f5675b8e57c61f70167ba415a463651fd6a918" + +[[package]] +name = "semver-parser" +version = "0.7.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "388a1df253eca08550bef6c72392cfe7c30914bf41df5269b68cbd6ff8f570a3" + +[[package]] +name = "sensor" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "cortex-m-rtic", + "defmt", + "embedded-alloc", + "embedded-sdmmc", + "heapless", + "messages", + "panic-halt", + "postcard", + "sbg-rs", + "systick-monotonic", + "typenum", +] + +[[package]] +name = "seq-macro" +version = "0.3.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a3f0bf26fd526d2a95683cd0f87bf103b8539e2ca1ef48ce002d67aad59aa0b4" + +[[package]] +name = "serde" +version = "1.0.183" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "32ac8da02677876d532745a130fc9d8e6edfa81a269b107c5b00829b91d8eb3c" +dependencies = [ + "serde_derive", +] + +[[package]] +name = "serde_derive" +version = "1.0.183" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "aafe972d60b0b9bee71a91b92fee2d4fb3c9d7e8f6b179aa99f27203d99a4816" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 2.0.28", +] + +[[package]] +name = "serial" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a1237a96570fc377c13baa1b88c7589ab66edced652e43ffb17088f003db3e86" +dependencies = [ + "serial-core", + "serial-unix", + "serial-windows", +] + +[[package]] +name = "serial-core" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3f46209b345401737ae2125fe5b19a77acce90cd53e1658cda928e4fe9a64581" +dependencies = [ + "libc", +] + +[[package]] +name = "serial-unix" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f03fbca4c9d866e24a459cbca71283f545a37f8e3e002ad8c70593871453cab7" +dependencies = [ + "ioctl-rs", + "libc", + "serial-core", + "termios", +] + +[[package]] +name = "serial-windows" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "15c6d3b776267a75d31bbdfd5d36c0ca051251caafc285827052bc53bcdc8162" +dependencies = [ + "libc", + "serial-core", +] + +[[package]] +name = "simple_example" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "defmt", + "defmt-rtt", + "panic-halt", +] + +[[package]] +name = "spin" +version = "0.9.8" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6980e8d7511241f8acf4aebddbb1ff938df5eebe98691418c4468d0b72a96a67" +dependencies = [ + "lock_api", +] + +[[package]] +name = "stable_deref_trait" +version = "1.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a8f112729512f8e442d81f95a8a7ddf2b7c6b8a1a6f509a95864142b30cab2d3" + +[[package]] +name = "static_assertions" +version = "1.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a2eb9349b6444b326872e140eb1cf5e7c522154d69e7a0ffb0fb81c06b37543f" + +[[package]] +name = "syn" +version = "0.15.44" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9ca4b3b69a77cbe1ffc9e198781b7acb0c7365a883670e8f1c1bc66fba79a5c5" +dependencies = [ + "proc-macro2 0.4.30", + "quote 0.6.13", + "unicode-xid", +] + +[[package]] +name = "syn" +version = "1.0.109" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "72b64191b275b66ffe2469e8af2c1cfe3bafa67b529ead792a6d0160888b4237" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "unicode-ident", +] + +[[package]] +name = "syn" +version = "2.0.28" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "04361975b3f5e348b2189d8dc55bc942f278b2d482a6a0365de5bdd62d351567" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "unicode-ident", +] + +[[package]] +name = "systick-monotonic" +version = "1.0.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "67fb822d5c615a0ae3a4795ee5b1d06381c7faf488d861c0a4fa8e6a88d5ff84" +dependencies = [ + "cortex-m", + "fugit", + "rtic-monotonic", +] + +[[package]] +name = "tempfile" +version = "3.7.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "dc02fddf48964c42031a0b3fe0428320ecf3a73c401040fc0096f97794310651" +dependencies = [ + "cfg-if", + "fastrand", + "redox_syscall", + "rustix", + "windows-sys", +] + +[[package]] +name = "termcolor" +version = "1.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "be55cf8942feac5c765c2c993422806843c9a9a45d4d5c407ad6dd2ea95eb9b6" +dependencies = [ + "winapi-util", +] + +[[package]] +name = "termios" +version = "0.2.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d5d9cf598a6d7ce700a4e6a9199da127e6819a61e64b68609683cc9a01b5683a" +dependencies = [ + "libc", +] + +[[package]] +name = "thiserror" +version = "1.0.44" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "611040a08a0439f8248d1990b111c95baa9c704c805fa1f62104b39655fd7f90" +dependencies = [ + "thiserror-impl", +] + +[[package]] +name = "thiserror-impl" +version = "1.0.44" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "090198534930841fab3a5d1bb637cde49e339654e606195f8d9c76eeb081dc96" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 2.0.28", +] + +[[package]] +name = "ts-rs" +version = "6.2.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4added4070a4fdf9df03457206cd2e4b12417c8560a2954d91ffcbe60177a56a" +dependencies = [ + "thiserror", + "ts-rs-macros", +] + +[[package]] +name = "ts-rs-macros" +version = "6.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9f807fdb3151fee75df7485b901a89624358cd07a67a8fb1a5831bf5a07681ff" +dependencies = [ + "Inflector", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", + "termcolor", +] + +[[package]] +name = "typenum" +version = "1.16.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "497961ef93d974e23eb6f433eb5fe1b7930b659f06d12dec6fc44a8f554c0bba" + +[[package]] +name = "unarray" +version = "0.1.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "eaea85b334db583fe3274d12b4cd1880032beab409c0d774be044d4480ab9a94" + +[[package]] +name = "unicode-ident" +version = "1.0.11" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "301abaae475aa91687eb82514b328ab47a211a533026cb25fc3e519b86adfc3c" + +[[package]] +name = "unicode-xid" +version = "0.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "fc72304796d0818e357ead4e000d19c9c174ab23dc11093ac919054d20a6a7fc" + +[[package]] +name = "vcell" +version = "0.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "77439c1b53d2303b20d9459b1ade71a83c716e3f9c34f3228c00e6f185d6c002" + +[[package]] +name = "version_check" +version = "0.9.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "49874b5167b65d7193b8aba1567f5c7d93d001cafc34600cee003eda787e483f" + +[[package]] +name = "void" +version = "1.0.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6a02e4885ed3bc0f2de90ea6dd45ebcbb66dacffe03547fadbb0eeae2770887d" + +[[package]] +name = "volatile-register" +version = "0.2.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9ee8f19f9d74293faf70901bc20ad067dc1ad390d2cbf1e3f75f721ffee908b6" +dependencies = [ + "vcell", +] + +[[package]] +name = "wait-timeout" +version = "0.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9f200f5b12eb75f8c1ed65abd4b2db8a6e1b138a20de009dacee265a2498f3f6" +dependencies = [ + "libc", +] + +[[package]] +name = "wasi" +version = "0.11.0+wasi-snapshot-preview1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9c8d87e72b64a3b4db28d11ce29237c246188f4f51057d65a7eab63b7987e423" + +[[package]] +name = "winapi" +version = "0.3.9" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5c839a674fcd7a98952e593242ea400abe93992746761e38641405d28b00f419" +dependencies = [ + "winapi-i686-pc-windows-gnu", + "winapi-x86_64-pc-windows-gnu", +] + +[[package]] +name = "winapi-i686-pc-windows-gnu" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ac3b87c63620426dd9b991e5ce0329eff545bccbbb34f3be09ff6fb6ab51b7b6" + +[[package]] +name = "winapi-util" +version = "0.1.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "70ec6ce85bb158151cae5e5c87f95a8e97d2c0c4b001223f33a334e3ce5de178" +dependencies = [ + "winapi", +] + +[[package]] +name = "winapi-x86_64-pc-windows-gnu" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "712e227841d057c1ee1cd2fb22fa7e5a5461ae8e48fa2ca79ec42cfc1931183f" + +[[package]] +name = "windows-sys" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "677d2418bec65e3338edb076e806bc1ec15693c5d0104683f2efe857f61056a9" +dependencies = [ + "windows-targets", +] + +[[package]] +name = "windows-targets" +version = "0.48.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "05d4b17490f70499f20b9e791dcf6a299785ce8af4d709018206dc5b4953e95f" +dependencies = [ + "windows_aarch64_gnullvm", + "windows_aarch64_msvc", + "windows_i686_gnu", + "windows_i686_msvc", + "windows_x86_64_gnu", + "windows_x86_64_gnullvm", + "windows_x86_64_msvc", +] + +[[package]] +name = "windows_aarch64_gnullvm" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "91ae572e1b79dba883e0d315474df7305d12f569b400fcf90581b06062f7e1bc" + +[[package]] +name = "windows_aarch64_msvc" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b2ef27e0d7bdfcfc7b868b317c1d32c641a6fe4629c171b8928c7b08d98d7cf3" + +[[package]] +name = "windows_i686_gnu" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "622a1962a7db830d6fd0a69683c80a18fda201879f0f447f065a3b7467daa241" + +[[package]] +name = "windows_i686_msvc" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4542c6e364ce21bf45d69fdd2a8e455fa38d316158cfd43b3ac1c5b1b19f8e00" + +[[package]] +name = "windows_x86_64_gnu" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ca2b8a661f7628cbd23440e50b05d705db3686f894fc9580820623656af974b1" + +[[package]] +name = "windows_x86_64_gnullvm" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7896dbc1f41e08872e9d5e8f8baa8fdd2677f29468c4e156210174edc7f7b953" + +[[package]] +name = "windows_x86_64_msvc" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1a515f5799fe4961cb532f983ce2b23082366b898e52ffbce459c86f67c8378a" diff --git a/README.md b/README.md index fc820f6c..5e63e925 100644 --- a/README.md +++ b/README.md @@ -1,44 +1,44 @@ -# HYDRA   [![Build Status]][actions] [![docs-badge]][docs] -*HYper Dynamic Rocketry Avionics* - -[Build Status]: https://github.com/uorocketry/hydra/actions/workflows/build.yml/badge.svg -[actions]: https://github.com/uorocketry/hydra/actions?query=branch%3Amaster -[docs-badge]: https://img.shields.io/github/actions/workflow/status/uorocketry/hydra/docs.yml?label=docs -[docs]: http://hydra-docs.uorocketry.ca/common_arm - -**uORocketry's next-generation avionics system** - ---- - -## Getting Started - -1. Install Rust: https://www.rust-lang.org/tools/install -2. Build: `cargo build` -3. Install probe-run: `cargo install --git https://github.com/uorocketry/probe-run` - - `probe-run` currently requires a patch to flash our chip, so please use the above version while the patch is upstreamed -4, Install cargo-make: `cargo install cargo-make` -4. Flash: `cargo run --bin main` -5. Run tests: `cargo make test-host` or `cargo make test-device` - -For more detailed instructions on flashing, debugging, and more, please see [the wiki](https://avwiki.uorocketry.ca/en/Avionics/HYDRA/Software). - -## Documentation - -Run `cargo doc --open` to build and open the documentation. Most documentation for this repo is contained in the `common-arm` crate. - -Documentation is also automatically built and deployed to https://hydra-docs.uorocketry.ca/common_arm - -## Project Structure -The project is structured in a way to allow reuse of the code across various boards and other projects. - -- `boards`: Folder containing each individual board's binary crates. Any code in those crates should only contain logic specific to the board. -- `debug`: Useful files for debugging, such as GDB and OpenOCD configuration. -- `examples`: Example projects that can be used to quickly start a new board. Simply copy and paste one of those creates to the `boards` folder, and rename as needed. -- `libraries`: - - `common-arm`: Common code that depends on embedded-specific logic or crates. - -## License - -This project is licensed under GPLv3-only. - -We please ask for any derivatives of this work to be kept open-source, even if such derivative is only for internal use. +# HYDRA   [![Build Status]][actions] [![docs-badge]][docs] +*HYper Dynamic Rocketry Avionics* + +[Build Status]: https://github.com/uorocketry/hydra/actions/workflows/build.yml/badge.svg +[actions]: https://github.com/uorocketry/hydra/actions?query=branch%3Amaster +[docs-badge]: https://img.shields.io/github/actions/workflow/status/uorocketry/hydra/docs.yml?label=docs +[docs]: http://hydra-docs.uorocketry.ca/common_arm + +**uORocketry's next-generation avionics system** + +--- + +## Getting Started + +1. Install Rust: https://www.rust-lang.org/tools/install +2. Build: `cargo build` +3. Install probe-run: `cargo install --git https://github.com/uorocketry/probe-run` + - `probe-run` currently requires a patch to flash our chip, so please use the above version while the patch is upstreamed +4, Install cargo-make: `cargo install cargo-make` +4. Flash: `cargo run --bin main` +5. Run tests: `cargo make test-host` or `cargo make test-device` + +For more detailed instructions on flashing, debugging, and more, please see [the wiki](https://avwiki.uorocketry.ca/en/Avionics/HYDRA/Software). + +## Documentation + +Run `cargo doc --open` to build and open the documentation. Most documentation for this repo is contained in the `common-arm` crate. + +Documentation is also automatically built and deployed to https://hydra-docs.uorocketry.ca/common_arm + +## Project Structure +The project is structured in a way to allow reuse of the code across various boards and other projects. + +- `boards`: Folder containing each individual board's binary crates. Any code in those crates should only contain logic specific to the board. +- `debug`: Useful files for debugging, such as GDB and OpenOCD configuration. +- `examples`: Example projects that can be used to quickly start a new board. Simply copy and paste one of those creates to the `boards` folder, and rename as needed. +- `libraries`: + - `common-arm`: Common code that depends on embedded-specific logic or crates. + +## License + +This project is licensed under GPLv3-only. + +We please ask for any derivatives of this work to be kept open-source, even if such derivative is only for internal use. diff --git a/boards/communication/src/data_manager.rs b/boards/communication/src/data_manager.rs index 05b94670..0b6441ee 100644 --- a/boards/communication/src/data_manager.rs +++ b/boards/communication/src/data_manager.rs @@ -41,7 +41,7 @@ impl DataManager { } pub fn clone_states(&self) -> [Option; 1] { [ - self.state.clone().map(|x| x.into()), + self.state.clone(), ] } pub fn handle_data(&mut self, data: Message) { @@ -75,11 +75,8 @@ impl DataManager { info!("impl power related"); } }, - messages::Data::State(state) => match state.data { - _ => { - info!("state: {}", state.data.clone()); + messages::Data::State(state) => { self.state = Some(state.data); - } } _ => { info!("unkown"); diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index d7a2bfe3..2628e4f0 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -192,19 +192,17 @@ mod app { } #[task(capacity = 10, local = [sd_manager], shared = [&em])] - fn sd_dump(mut cx: sd_dump::Context, m: Message) { - let mut manager = cx.local.sd_manager; + fn sd_dump(cx: sd_dump::Context, m: Message) { + let manager = cx.local.sd_manager; cx.shared.em.run(|| { let mut buf: [u8; 255] = [0; 255]; let msg_ser = postcard::to_slice_cobs(&m, &mut buf)?; if let Some(mut file) = manager.file.take() { manager.write(&mut file, &msg_ser)?; manager.file = Some(file); - } else { - if let Ok(mut file) = manager.open_file("log.txt") { - manager.write(&mut file, &msg_ser)?; - manager.file = Some(file); - } + } else if let Ok(mut file) = manager.open_file("log.txt") { + manager.write(&mut file, &msg_ser)?; + manager.file = Some(file); } Ok(()) }); diff --git a/boards/recovery/src/state_machine/mod.rs b/boards/recovery/src/state_machine/mod.rs index 30aac831..3a8fa220 100644 --- a/boards/recovery/src/state_machine/mod.rs +++ b/boards/recovery/src/state_machine/mod.rs @@ -61,6 +61,12 @@ impl StateMachine { } } +impl Default for StateMachine { + fn default() -> Self { + Self::new() + } +} + // All events are found here pub enum RocketEvents { DeployDrogue, @@ -96,16 +102,17 @@ impl From for RocketStates { } } } -impl Into for RocketStates { - fn into(self) -> state::StateData { - match self { - RocketStates::Initializing(_) => state::StateData::Initializing, - RocketStates::WaitForTakeoff(_) => state::StateData::WaitForTakeoff, - RocketStates::Ascent(_) => state::StateData::Ascent, - RocketStates::Descent(_) => state::StateData::Descent, - RocketStates::TerminalDescent(_) => state::StateData::TerminalDescent, - RocketStates::WaitForRecovery(_) => state::StateData::WaitForRecovery, - RocketStates::Abort(_) => state::StateData::Abort, - } - } -} \ No newline at end of file +// Linter: an implementation of From is preferred since it gives you Into<_> for free where the reverse isn't true +// impl Into for RocketStates { +// fn into(self) -> state::StateData { +// match self { +// RocketStates::Initializing(_) => state::StateData::Initializing, +// RocketStates::WaitForTakeoff(_) => state::StateData::WaitForTakeoff, +// RocketStates::Ascent(_) => state::StateData::Ascent, +// RocketStates::Descent(_) => state::StateData::Descent, +// RocketStates::TerminalDescent(_) => state::StateData::TerminalDescent, +// RocketStates::WaitForRecovery(_) => state::StateData::WaitForRecovery, +// RocketStates::Abort(_) => state::StateData::Abort, +// } +// } +// } \ No newline at end of file diff --git a/boards/recovery/src/state_machine/states/initializing.rs b/boards/recovery/src/state_machine/states/initializing.rs index 51d98b62..b9adab77 100644 --- a/boards/recovery/src/state_machine/states/initializing.rs +++ b/boards/recovery/src/state_machine/states/initializing.rs @@ -1,20 +1,20 @@ -use defmt::{write, Format, Formatter}; - -use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; -use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; -use crate::transition; - -#[derive(Debug, Clone)] -pub struct Initializing {} - -impl State for Initializing { - fn step(&mut self, _context: &mut StateMachineContext) -> Option { - transition!(self, WaitForTakeoff) - } -} - -impl Format for Initializing { - fn format(&self, f: Formatter) { - write!(f, "Initializing") - } -} +use defmt::{write, Format, Formatter}; + +use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; +use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; +use crate::transition; + +#[derive(Debug, Clone)] +pub struct Initializing {} + +impl State for Initializing { + fn step(&mut self, _context: &mut StateMachineContext) -> Option { + transition!(self, WaitForTakeoff) + } +} + +impl Format for Initializing { + fn format(&self, f: Formatter) { + write!(f, "Initializing") + } +} diff --git a/boards/recovery/src/state_machine/states/wait_for_recovery.rs b/boards/recovery/src/state_machine/states/wait_for_recovery.rs index e8f36d12..14704ad6 100644 --- a/boards/recovery/src/state_machine/states/wait_for_recovery.rs +++ b/boards/recovery/src/state_machine/states/wait_for_recovery.rs @@ -1,39 +1,44 @@ -use super::TerminalDescent; -use crate::app::monotonics; -use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; -use crate::types::COM_ID; -use crate::{no_transition, transition}; -use rtic::mutex::Mutex; -use defmt::{write, Format, Formatter, info}; -use messages::command::{Command, CommandData, PowerDown}; -use messages::Message; -use messages::sender::Sender::SensorBoard; - -#[derive(Debug, Clone)] -pub struct WaitForRecovery {} - -impl State for WaitForRecovery { - fn enter(&self, context: &mut StateMachineContext) { - // send a command over CAN to shut down non-critical systems for recovery. - let sensor_power_down = PowerDown { - board: SensorBoard - }; - let message = Message::new(&monotonics::now(), COM_ID, Command::new(sensor_power_down)); - context.shared_resources.can0.lock(|can| can.send_message(message)); // unhandled result - } - fn step(&mut self, context: &mut StateMachineContext) -> Option { - no_transition!() // this is our final resting place. We should also powerdown this board. - } -} - -impl TransitionInto for TerminalDescent { - fn transition(&self) -> WaitForRecovery { - WaitForRecovery {} - } -} - -impl Format for WaitForRecovery { - fn format(&self, f: Formatter) { - write!(f, "Descent") - } -} +use super::TerminalDescent; +use crate::app::monotonics; +use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; +use crate::types::COM_ID; +use crate::{no_transition, transition}; +use rtic::mutex::Mutex; +use defmt::{write, Format, Formatter, info}; +use messages::command::{Command, CommandData, PowerDown}; +use messages::Message; +use messages::sender::Sender::SensorBoard; + +#[derive(Debug, Clone)] +pub struct WaitForRecovery {} + +impl State for WaitForRecovery { + fn enter(&self, context: &mut StateMachineContext) { + // send a command over CAN to shut down non-critical systems for recovery. + let sensor_power_down = PowerDown { + board: SensorBoard + }; + let message = Message::new(&monotonics::now(), COM_ID, Command::new(sensor_power_down)); + context.shared_resources.can0.lock(|can| { + context.shared_resources.em.run(||{ + can.send_message(message)?; + Ok(()) + }) + }); + } + fn step(&mut self, context: &mut StateMachineContext) -> Option { + no_transition!() // this is our final resting place. We should also powerdown this board. + } +} + +impl TransitionInto for TerminalDescent { + fn transition(&self) -> WaitForRecovery { + WaitForRecovery {} + } +} + +impl Format for WaitForRecovery { + fn format(&self, f: Formatter) { + write!(f, "Descent") + } +} diff --git a/boards/sensor/src/data_manager.rs b/boards/sensor/src/data_manager.rs index b50982a6..0bb3fd8b 100644 --- a/boards/sensor/src/data_manager.rs +++ b/boards/sensor/src/data_manager.rs @@ -1,71 +1,71 @@ -use common_arm::spawn; -use messages::sender::Sender; -use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime}; -use messages::Message; -use crate::app::sleep_system; - -#[derive(Clone)] -pub struct DataManager { - pub air: Option, - pub ekf_nav: Option<(EkfNav1, EkfNav2)>, - pub ekf_quat: Option, - pub imu: Option<(Imu1, Imu2)>, - pub utc_time: Option, - pub gps_vel: Option, -} - -impl DataManager { - pub fn new() -> Self { - Self { - air: None, - ekf_nav: None, - ekf_quat: None, - imu: None, - utc_time: None, - gps_vel: None, - } - } - - pub fn clone_sensors(&self) -> [Option; 8] { - [ - self.air.clone().map(|x| x.into()), - self.ekf_nav.clone().map(|x| x.0.into()), - self.ekf_nav.clone().map(|x| x.1.into()), - self.ekf_quat.clone().map(|x| x.into()), - self.imu.clone().map(|x| x.0.into()), - self.imu.clone().map(|x| x.1.into()), - self.utc_time.clone().map(|x| x.into()), - self.gps_vel.clone().map(|x| x.into()), - ] - } - - pub fn handle_data(&mut self, data: Message) { - match data.data { - messages::Data::Command(command) => match command.data { - messages::command::CommandData::PowerDown(info) => { - match info.board { - Sender::SensorBoard => { - // sleep the system. - spawn!(sleep_system); - } - _ => { - // don't care - } - } - } - _ => { - // We don't care atm about these other commands. - } - } - _ => { - // we can disregard all other messages for now. - } - } - } -} - -impl Default for DataManager { - fn default() -> Self { - Self::new() - } -} +use common_arm::spawn; +use messages::sender::Sender; +use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime}; +use messages::Message; +use crate::app::sleep_system; + +#[derive(Clone)] +pub struct DataManager { + pub air: Option, + pub ekf_nav: Option<(EkfNav1, EkfNav2)>, + pub ekf_quat: Option, + pub imu: Option<(Imu1, Imu2)>, + pub utc_time: Option, + pub gps_vel: Option, +} + +impl DataManager { + pub fn new() -> Self { + Self { + air: None, + ekf_nav: None, + ekf_quat: None, + imu: None, + utc_time: None, + gps_vel: None, + } + } + + pub fn clone_sensors(&self) -> [Option; 8] { + [ + self.air.clone().map(|x| x.into()), + self.ekf_nav.clone().map(|x| x.0.into()), + self.ekf_nav.clone().map(|x| x.1.into()), + self.ekf_quat.clone().map(|x| x.into()), + self.imu.clone().map(|x| x.0.into()), + self.imu.clone().map(|x| x.1.into()), + self.utc_time.clone().map(|x| x.into()), + self.gps_vel.clone().map(|x| x.into()), + ] + } + + pub fn handle_data(&mut self, data: Message) { + match data.data { + messages::Data::Command(command) => match command.data { + messages::command::CommandData::PowerDown(info) => { + match info.board { + Sender::SensorBoard => { + // sleep the system. + spawn!(sleep_system); + } + _ => { + // don't care + } + } + } + _ => { + // We don't care atm about these other commands. + } + } + _ => { + // we can disregard all other messages for now. + } + } + } +} + +impl Default for DataManager { + fn default() -> Self { + Self::new() + } +} diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index dde16fe2..247a612f 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -160,12 +160,17 @@ mod app { loop {} } - #[task(local = [sbg_power_pin], shared = [sd_manager])] + #[task(local = [sbg_power_pin], shared = [sd_manager, &em])] fn sleep_system(mut cx: sleep_system::Context) { // close out sd files. - cx.shared.sd_manager.lock(|sd| sd.close_current_file()); + cx.shared.sd_manager.lock(|sd| { + cx.shared.em.run(|| { + sd.close_current_file(); + Ok(()) + }); + }); // power down sbg - cx.local.sbg_power_pin.set_low(); + cx.local.sbg_power_pin.set_low(); // define hydra error for this error type. // Call core.SCB.set_deepsleep for even less power consumption. } diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index 5251c525..0f71cf14 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -33,7 +33,6 @@ static HEAP: Heap = Heap::empty(); pub struct SBGManager { sbg_device: SBG, xfer: Option, - buf_select: bool, } impl SBGManager { @@ -85,7 +84,6 @@ impl SBGManager { SBGManager { sbg_device: sbg, - buf_select: false, xfer: Some(xfer), } } @@ -105,13 +103,17 @@ pub fn sbg_handle_data(mut cx: sbg_handle_data::Context, data: CallbackData) { pub fn sbg_sd_task(mut cx: crate::app::sbg_sd_task::Context, data: [u8; SBG_BUFFER_SIZE]) { cx.shared.sd_manager.lock(|manager| { if let Some(mut file) = manager.file.take() { - manager.write(&mut file, &data); + cx.shared.em.run(|| { + manager.write(&mut file, &data)?; + Ok(()) + }); manager.file = Some(file); // give the file back after use - } else { - if let Ok(mut file) = manager.open_file("sbg.txt") { - manager.write(&mut file, &data); - manager.file = Some(file); - } + } else if let Ok(mut file) = manager.open_file("sbg.txt") { + cx.shared.em.run(|| { + manager.write(&mut file, &data)?; + Ok(()) + }); + manager.file = Some(file); } }); } @@ -127,13 +129,13 @@ pub fn sbg_dma(cx: crate::app::sbg_dma::Context) { if xfer.complete() { let (chan0, source, buf) = sbg.xfer.take().unwrap().stop(); let mut xfer = dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).unwrap().begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); - let buf_clone = buf.clone(); + let buf_copy = buf.copy(); sbg.sbg_device.read_data(buf); unsafe{BUF_DST.copy_from_slice(&[0;SBG_BUFFER_SIZE])}; xfer.block_transfer_interrupt(); sbg.xfer = Some(xfer); cx.shared.em.run(|| { - spawn!(sbg_sd(buf_clone)); + spawn!(sbg_sd(buf_copy)); Ok(()) }); } diff --git a/libraries/messages/src/sender.rs b/libraries/messages/src/sender.rs index 223e88c2..adbdd40d 100644 --- a/libraries/messages/src/sender.rs +++ b/libraries/messages/src/sender.rs @@ -1,33 +1,33 @@ -use defmt::Format; -use serde::{Deserialize, Serialize}; - -#[cfg(test)] -use proptest_derive::Arbitrary; - -#[cfg(feature = "ts")] -use ts_rs::TS; - -// I don't agree with the naming, We can use these as Ids to sent commands to that specific board. -#[derive(Serialize, Deserialize, Clone, Debug, Format, Copy)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub enum Sender { - GroundStation, - SensorBoard, - RecoveryBoard, - CommunicationBoard, - PowerBoard -} - -impl From for u16 { - fn from(sender: Sender) -> Self { - match sender { - Sender::GroundStation => 0, - Sender::SensorBoard => 1, - Sender::RecoveryBoard => 2, - Sender::CommunicationBoard => 3, - Sender::PowerBoard => 4 - } - } -} +use defmt::Format; +use serde::{Deserialize, Serialize}; + +#[cfg(test)] +use proptest_derive::Arbitrary; + +#[cfg(feature = "ts")] +use ts_rs::TS; + +// I don't agree with the naming, We can use these as Ids to sent commands to that specific board. +#[derive(Serialize, Deserialize, Clone, Debug, Format, Copy)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub enum Sender { + GroundStation, + SensorBoard, + RecoveryBoard, + CommunicationBoard, + PowerBoard +} + +impl From for u16 { + fn from(sender: Sender) -> Self { + match sender { + Sender::GroundStation => 0, + Sender::SensorBoard => 1, + Sender::RecoveryBoard => 2, + Sender::CommunicationBoard => 3, + Sender::PowerBoard => 4 + } + } +} diff --git a/libraries/messages/src/sensor.rs b/libraries/messages/src/sensor.rs index 30e1dd16..3f917550 100644 --- a/libraries/messages/src/sensor.rs +++ b/libraries/messages/src/sensor.rs @@ -1,222 +1,222 @@ -use defmt::Format; -use derive_more::From; -use serde::{Deserialize, Serialize}; - -#[cfg(test)] -use proptest_derive::Arbitrary; - -#[cfg(feature = "ts")] -use ts_rs::TS; - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct Sensor { - /// Used to differentiate between multiple components on the same sender. Unused right now. - pub component_id: u8, - pub data: SensorData, -} - -#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub enum SensorData { - UtcTime(UtcTime), - Air(Air), - EkfQuat(EkfQuat), - EkfNav1(EkfNav1), - EkfNav2(EkfNav2), - Imu1(Imu1), - Imu2(Imu2), - GpsVel(GpsVel), - Current(Current), - Voltage(Voltage), - Regulator(Regulator), - Temperature(Temperature), -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct Regulator { - pub status: bool, -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct Voltage { - pub voltage: f32, - pub rolling_avg: f32, -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct Current { - pub current: f32, - pub rolling_avg: f32, -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct Temperature { - pub temperature: f32, - pub rolling_avg: f32, -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct UtcTime { - #[doc = "< Time in us since the sensor power up."] - pub time_stamp: u32, - #[doc = "< UTC time and clock status information"] - pub status: u16, - #[doc = "< Year for example: 2013."] - pub year: u16, - #[doc = "< Month in year [1 .. 12]."] - pub month: i8, - #[doc = "< Day in month [1 .. 31]."] - pub day: i8, - #[doc = "< Hour in day [0 .. 23]."] - pub hour: i8, - #[doc = "< Minute in hour [0 .. 59]."] - pub minute: i8, - #[doc = "< Second in minute [0 .. 60]. (60 is used only when a leap second is added)"] - pub second: i8, - #[doc = "< Nanosecond of current second in ns."] - pub nano_second: i32, - #[doc = "< GPS time of week in ms."] - pub gps_time_of_week: u32, -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct Air { - #[doc = "< Time in us since the sensor power up OR measurement delay in us."] - pub time_stamp: u32, - #[doc = "< Airdata sensor status bitmask."] - pub status: u16, - #[doc = "< Raw absolute pressure measured by the barometer sensor in Pascals."] - pub pressure_abs: f32, - #[doc = "< Altitude computed from barometric altimeter in meters and positive upward."] - pub altitude: f32, - #[doc = "< Raw differential pressure measured by the pitot tube in Pascal."] - pub pressure_diff: f32, - #[doc = "< True airspeed measured by a pitot tube in m.s^-1 and positive forward."] - pub true_airspeed: f32, - #[doc = "< Outside air temperature in °C that could be used to compute true airspeed from differential pressure."] - pub air_temperature: f32, -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct EkfQuat { - #[doc = "< Time in us since the sensor power up."] - pub time_stamp: u32, - #[doc = "< Orientation quaternion stored in W, X, Y, Z form."] - pub quaternion: [f32; 4usize], - #[doc = "< Roll, Pitch and Yaw angles 1 sigma standard deviation in rad."] - pub euler_std_dev: [f32; 3usize], - #[doc = "< EKF solution status bitmask and enum."] - pub status: u32, -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct EkfNav1 { - #[doc = "< Time in us since the sensor power up."] - pub time_stamp: u32, - #[doc = "< North, East, Down velocity in m.s^-1."] - pub velocity: [f32; 3usize], - #[doc = "< North, East, Down velocity 1 sigma standard deviation in m.s^-1."] - pub velocity_std_dev: [f32; 3usize], -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct EkfNav2 { - #[doc = "< Latitude, Longitude in degrees positive North and East.\nAltitude above Mean Sea Level in meters."] - pub position: [f64; 3usize], - #[doc = "< Altitude difference between the geoid and the Ellipsoid in meters (Height above Ellipsoid = altitude + undulation)."] - pub undulation: f32, - #[doc = "< Latitude, longitude and altitude 1 sigma standard deviation in meters."] - pub position_std_dev: [f32; 3usize], - #[doc = "< EKF solution status bitmask and enum."] - pub status: u32, -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct Imu1 { - #[doc = "< Time in us since the sensor power up."] - pub time_stamp: u32, - #[doc = "< IMU status bitmask."] - pub status: u16, - #[doc = "< X, Y, Z accelerometers in m.s^-2."] - pub accelerometers: [f32; 3usize], - #[doc = "< X, Y, Z gyroscopes in rad.s^-1."] - pub gyroscopes: [f32; 3usize], -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct Imu2 { - #[doc = "< Internal temperature in °C."] - pub temperature: f32, - #[doc = "< X, Y, Z delta velocity in m.s^-2."] - pub delta_velocity: [f32; 3usize], - #[doc = "< X, Y, Z delta angle in rad.s^-1."] - pub delta_angle: [f32; 3usize], -} - -#[derive(Serialize, Deserialize, Clone, Debug, Format)] -#[cfg_attr(test, derive(Arbitrary))] -#[cfg_attr(feature = "ts", derive(TS))] -#[cfg_attr(feature = "ts", ts(export))] -pub struct GpsVel { - #[doc = "< Time in us since the sensor power up."] - pub time_stamp: u32, - #[doc = "< GPS velocity status, type and bitmask."] - pub status: u32, - #[doc = "< GPS time of week in ms."] - pub time_of_week: u32, - #[doc = "< GPS North, East, Down velocity in m.s^-1."] - pub velocity: [f32; 3usize], - #[doc = "< GPS North, East, Down velocity 1 sigma accuracy in m.s^-1."] - pub velocity_acc: [f32; 3usize], - #[doc = "< Track ground course in degrees."] - pub course: f32, - #[doc = "< Course accuracy in degrees."] - pub course_acc: f32, -} - -impl Sensor { - pub fn new(data: impl Into) -> Self { - Sensor { - component_id: 0, - data: data.into(), - } - } -} +use defmt::Format; +use derive_more::From; +use serde::{Deserialize, Serialize}; + +#[cfg(test)] +use proptest_derive::Arbitrary; + +#[cfg(feature = "ts")] +use ts_rs::TS; + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Sensor { + /// Used to differentiate between multiple components on the same sender. Unused right now. + pub component_id: u8, + pub data: SensorData, +} + +#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub enum SensorData { + UtcTime(UtcTime), + Air(Air), + EkfQuat(EkfQuat), + EkfNav1(EkfNav1), + EkfNav2(EkfNav2), + Imu1(Imu1), + Imu2(Imu2), + GpsVel(GpsVel), + Current(Current), + Voltage(Voltage), + Regulator(Regulator), + Temperature(Temperature), +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Regulator { + pub status: bool, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Voltage { + pub voltage: f32, + pub rolling_avg: f32, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Current { + pub current: f32, + pub rolling_avg: f32, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Temperature { + pub temperature: f32, + pub rolling_avg: f32, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct UtcTime { + #[doc = "< Time in us since the sensor power up."] + pub time_stamp: u32, + #[doc = "< UTC time and clock status information"] + pub status: u16, + #[doc = "< Year for example: 2013."] + pub year: u16, + #[doc = "< Month in year [1 .. 12]."] + pub month: i8, + #[doc = "< Day in month [1 .. 31]."] + pub day: i8, + #[doc = "< Hour in day [0 .. 23]."] + pub hour: i8, + #[doc = "< Minute in hour [0 .. 59]."] + pub minute: i8, + #[doc = "< Second in minute [0 .. 60]. (60 is used only when a leap second is added)"] + pub second: i8, + #[doc = "< Nanosecond of current second in ns."] + pub nano_second: i32, + #[doc = "< GPS time of week in ms."] + pub gps_time_of_week: u32, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Air { + #[doc = "< Time in us since the sensor power up OR measurement delay in us."] + pub time_stamp: u32, + #[doc = "< Airdata sensor status bitmask."] + pub status: u16, + #[doc = "< Raw absolute pressure measured by the barometer sensor in Pascals."] + pub pressure_abs: f32, + #[doc = "< Altitude computed from barometric altimeter in meters and positive upward."] + pub altitude: f32, + #[doc = "< Raw differential pressure measured by the pitot tube in Pascal."] + pub pressure_diff: f32, + #[doc = "< True airspeed measured by a pitot tube in m.s^-1 and positive forward."] + pub true_airspeed: f32, + #[doc = "< Outside air temperature in °C that could be used to compute true airspeed from differential pressure."] + pub air_temperature: f32, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct EkfQuat { + #[doc = "< Time in us since the sensor power up."] + pub time_stamp: u32, + #[doc = "< Orientation quaternion stored in W, X, Y, Z form."] + pub quaternion: [f32; 4usize], + #[doc = "< Roll, Pitch and Yaw angles 1 sigma standard deviation in rad."] + pub euler_std_dev: [f32; 3usize], + #[doc = "< EKF solution status bitmask and enum."] + pub status: u32, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct EkfNav1 { + #[doc = "< Time in us since the sensor power up."] + pub time_stamp: u32, + #[doc = "< North, East, Down velocity in m.s^-1."] + pub velocity: [f32; 3usize], + #[doc = "< North, East, Down velocity 1 sigma standard deviation in m.s^-1."] + pub velocity_std_dev: [f32; 3usize], +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct EkfNav2 { + #[doc = "< Latitude, Longitude in degrees positive North and East.\nAltitude above Mean Sea Level in meters."] + pub position: [f64; 3usize], + #[doc = "< Altitude difference between the geoid and the Ellipsoid in meters (Height above Ellipsoid = altitude + undulation)."] + pub undulation: f32, + #[doc = "< Latitude, longitude and altitude 1 sigma standard deviation in meters."] + pub position_std_dev: [f32; 3usize], + #[doc = "< EKF solution status bitmask and enum."] + pub status: u32, +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Imu1 { + #[doc = "< Time in us since the sensor power up."] + pub time_stamp: u32, + #[doc = "< IMU status bitmask."] + pub status: u16, + #[doc = "< X, Y, Z accelerometers in m.s^-2."] + pub accelerometers: [f32; 3usize], + #[doc = "< X, Y, Z gyroscopes in rad.s^-1."] + pub gyroscopes: [f32; 3usize], +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct Imu2 { + #[doc = "< Internal temperature in °C."] + pub temperature: f32, + #[doc = "< X, Y, Z delta velocity in m.s^-2."] + pub delta_velocity: [f32; 3usize], + #[doc = "< X, Y, Z delta angle in rad.s^-1."] + pub delta_angle: [f32; 3usize], +} + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct GpsVel { + #[doc = "< Time in us since the sensor power up."] + pub time_stamp: u32, + #[doc = "< GPS velocity status, type and bitmask."] + pub status: u32, + #[doc = "< GPS time of week in ms."] + pub time_of_week: u32, + #[doc = "< GPS North, East, Down velocity in m.s^-1."] + pub velocity: [f32; 3usize], + #[doc = "< GPS North, East, Down velocity 1 sigma accuracy in m.s^-1."] + pub velocity_acc: [f32; 3usize], + #[doc = "< Track ground course in degrees."] + pub course: f32, + #[doc = "< Course accuracy in degrees."] + pub course_acc: f32, +} + +impl Sensor { + pub fn new(data: impl Into) -> Self { + Sensor { + component_id: 0, + data: data.into(), + } + } +} From a6e287d11e91c34c447e9c43a791060caa8ab407 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Tue, 22 Aug 2023 21:41:58 -0400 Subject: [PATCH 20/30] Fix power down --- boards/communication/src/main.rs | 1 - boards/recovery/src/communication.rs | 1 + boards/recovery/src/data_manager.rs | 5 ++-- boards/recovery/src/main.rs | 2 +- boards/recovery/src/state_machine/mod.rs | 26 +++++++++---------- .../state_machine/states/wait_for_recovery.rs | 22 +++++++++------- boards/sensor/src/data_manager.rs | 13 +++------- boards/sensor/src/main.rs | 3 ++- boards/sensor/src/sbg_manager.rs | 4 +-- 9 files changed, 36 insertions(+), 41 deletions(-) diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index 2628e4f0..d0a37d36 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -173,7 +173,6 @@ mod app { /// Probably should use this ( ノ^ω^)ノ - /// I see no need for this and this loses the sender information pub fn queue_gs_message(d: impl Into) { let message = Message::new(&monotonics::now(), COM_ID, d.into()); diff --git a/boards/recovery/src/communication.rs b/boards/recovery/src/communication.rs index e30867da..0485b85c 100644 --- a/boards/recovery/src/communication.rs +++ b/boards/recovery/src/communication.rs @@ -138,6 +138,7 @@ impl CanDevice0 { } pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { let payload: Vec = postcard::to_vec(&m)?; + info!("{}", m.clone()); self.can.tx.transmit_queued( tx::MessageBuilder { id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index 4956ba43..e056ac38 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -53,7 +53,7 @@ impl DataManager { prev = i; } match avg_sum / 7.0 { // 7 because we have 8 points. - x if !(-100.0..=-2.0).contains(&x) => { + x if !(-100.0..=-5.0).contains(&x) => { info!("avg: {}", avg_sum / 7.0); return false; } @@ -92,8 +92,7 @@ impl DataManager { prev = i; } match avg_sum / 7.0 { - // if we aren't going faster than +- 1 m/s it is safe to assume we have landed. - x if (1.0..=-1.0).contains(&x) => { + x if x > -4.0 && x < 4.0 => { info!("avg: {}", avg_sum / 7.0); return true; } diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 77718502..4ef0b19d 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -147,7 +147,7 @@ mod app { cx.shared.data_manager.lock(|data| { data.set_state(cx.local.state_machine.get_state()); }); - spawn_after!(run_sm, ExtU64::millis(500)).ok(); + spawn_after!(run_sm, ExtU64::millis(200)).ok(); } /// Handles the CAN0 interrupt. diff --git a/boards/recovery/src/state_machine/mod.rs b/boards/recovery/src/state_machine/mod.rs index 3a8fa220..f90cda93 100644 --- a/boards/recovery/src/state_machine/mod.rs +++ b/boards/recovery/src/state_machine/mod.rs @@ -103,16 +103,16 @@ impl From for RocketStates { } } // Linter: an implementation of From is preferred since it gives you Into<_> for free where the reverse isn't true -// impl Into for RocketStates { -// fn into(self) -> state::StateData { -// match self { -// RocketStates::Initializing(_) => state::StateData::Initializing, -// RocketStates::WaitForTakeoff(_) => state::StateData::WaitForTakeoff, -// RocketStates::Ascent(_) => state::StateData::Ascent, -// RocketStates::Descent(_) => state::StateData::Descent, -// RocketStates::TerminalDescent(_) => state::StateData::TerminalDescent, -// RocketStates::WaitForRecovery(_) => state::StateData::WaitForRecovery, -// RocketStates::Abort(_) => state::StateData::Abort, -// } -// } -// } \ No newline at end of file +impl Into for RocketStates { + fn into(self) -> state::StateData { + match self { + RocketStates::Initializing(_) => state::StateData::Initializing, + RocketStates::WaitForTakeoff(_) => state::StateData::WaitForTakeoff, + RocketStates::Ascent(_) => state::StateData::Ascent, + RocketStates::Descent(_) => state::StateData::Descent, + RocketStates::TerminalDescent(_) => state::StateData::TerminalDescent, + RocketStates::WaitForRecovery(_) => state::StateData::WaitForRecovery, + RocketStates::Abort(_) => state::StateData::Abort, + } + } +} \ No newline at end of file diff --git a/boards/recovery/src/state_machine/states/wait_for_recovery.rs b/boards/recovery/src/state_machine/states/wait_for_recovery.rs index 14704ad6..9b43d3e4 100644 --- a/boards/recovery/src/state_machine/states/wait_for_recovery.rs +++ b/boards/recovery/src/state_machine/states/wait_for_recovery.rs @@ -15,16 +15,18 @@ pub struct WaitForRecovery {} impl State for WaitForRecovery { fn enter(&self, context: &mut StateMachineContext) { // send a command over CAN to shut down non-critical systems for recovery. - let sensor_power_down = PowerDown { - board: SensorBoard - }; - let message = Message::new(&monotonics::now(), COM_ID, Command::new(sensor_power_down)); - context.shared_resources.can0.lock(|can| { - context.shared_resources.em.run(||{ - can.send_message(message)?; - Ok(()) - }) - }); + for i in 0..10 { + let sensor_power_down = PowerDown { + board: SensorBoard + }; + let message = Message::new(&monotonics::now(), COM_ID, Command::new(sensor_power_down)); + context.shared_resources.can0.lock(|can| { + context.shared_resources.em.run(||{ + can.send_message(message)?; + Ok(()) + }) + }); + } } fn step(&mut self, context: &mut StateMachineContext) -> Option { no_transition!() // this is our final resting place. We should also powerdown this board. diff --git a/boards/sensor/src/data_manager.rs b/boards/sensor/src/data_manager.rs index 0bb3fd8b..07d689cf 100644 --- a/boards/sensor/src/data_manager.rs +++ b/boards/sensor/src/data_manager.rs @@ -3,6 +3,7 @@ use messages::sender::Sender; use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime}; use messages::Message; use crate::app::sleep_system; +use defmt::info; #[derive(Clone)] pub struct DataManager { @@ -42,16 +43,8 @@ impl DataManager { pub fn handle_data(&mut self, data: Message) { match data.data { messages::Data::Command(command) => match command.data { - messages::command::CommandData::PowerDown(info) => { - match info.board { - Sender::SensorBoard => { - // sleep the system. - spawn!(sleep_system); - } - _ => { - // don't care - } - } + messages::command::CommandData::PowerDown(info) => { + spawn!(sleep_system); } _ => { // We don't care atm about these other commands. diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index 247a612f..61303286 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -162,6 +162,7 @@ mod app { #[task(local = [sbg_power_pin], shared = [sd_manager, &em])] fn sleep_system(mut cx: sleep_system::Context) { + info!("Power Down"); // close out sd files. cx.shared.sd_manager.lock(|sd| { cx.shared.em.run(|| { @@ -174,7 +175,7 @@ mod app { // Call core.SCB.set_deepsleep for even less power consumption. } - #[task(binds = CAN0, shared = [can, data_manager])] + #[task(priority = 3, binds = CAN0, shared = [can, data_manager])] fn can0(mut cx: can0::Context) { cx.shared.can.lock(|can| { cx.shared.data_manager.lock(|manager| can.process_data(manager)) diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index 0f71cf14..4eb95dc9 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -129,13 +129,13 @@ pub fn sbg_dma(cx: crate::app::sbg_dma::Context) { if xfer.complete() { let (chan0, source, buf) = sbg.xfer.take().unwrap().stop(); let mut xfer = dmac::Transfer::new(chan0, source, unsafe{&mut *BUF_DST}, false).unwrap().begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); - let buf_copy = buf.copy(); + let buf_clone = buf.clone(); sbg.sbg_device.read_data(buf); unsafe{BUF_DST.copy_from_slice(&[0;SBG_BUFFER_SIZE])}; xfer.block_transfer_interrupt(); sbg.xfer = Some(xfer); cx.shared.em.run(|| { - spawn!(sbg_sd(buf_copy)); + spawn!(sbg_sd(buf_clone)); Ok(()) }); } From 7efb4398523bee4c6ff494dce91d7b28e4fcc445 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Wed, 23 Aug 2023 16:59:00 +0000 Subject: [PATCH 21/30] Update Recovery Algorithm --- boards/recovery/src/data_manager.rs | 12 ++++++++---- boards/recovery/src/main.rs | 2 +- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index e056ac38..00191be1 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -49,12 +49,15 @@ impl DataManager { if time_diff == 0.0 { continue; } - avg_sum += (i.0 - prev.0)/time_diff; + let slope = (i.0 - prev.0)/time_diff; + if slope > -100.0 { + return false; // this is done since a shock wave would go extreme high to low resulting in a middle average. + } + avg_sum += slope; prev = i; } match avg_sum / 7.0 { // 7 because we have 8 points. x if !(-100.0..=-5.0).contains(&x) => { - info!("avg: {}", avg_sum / 7.0); return false; } _ => { @@ -91,8 +94,9 @@ impl DataManager { avg_sum += (i.0 - prev.0)/time_diff; prev = i; } - match avg_sum / 7.0 { - x if x > -4.0 && x < 4.0 => { + match avg_sum / 7.0 { + // inclusive range + x if (-4.0..=4.0).contains(&x) => { info!("avg: {}", avg_sum / 7.0); return true; } diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 4ef0b19d..77718502 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -147,7 +147,7 @@ mod app { cx.shared.data_manager.lock(|data| { data.set_state(cx.local.state_machine.get_state()); }); - spawn_after!(run_sm, ExtU64::millis(200)).ok(); + spawn_after!(run_sm, ExtU64::millis(500)).ok(); } /// Handles the CAN0 interrupt. From 6fc5ec5427ec4e19d3aa32bdee16d575aff27981 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Wed, 23 Aug 2023 17:06:58 +0000 Subject: [PATCH 22/30] Update Recovery Algorithm, bad comperator --- boards/recovery/src/data_manager.rs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index 00191be1..4dcd7ee5 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -50,7 +50,7 @@ impl DataManager { continue; } let slope = (i.0 - prev.0)/time_diff; - if slope > -100.0 { + if slope < -100.0 { return false; // this is done since a shock wave would go extreme high to low resulting in a middle average. } avg_sum += slope; From 9055e037d31446c4a3021c99784d4f2a2376a3db Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Wed, 23 Aug 2023 19:29:32 -0400 Subject: [PATCH 23/30] change --- boards/recovery/src/communication.rs | 1 - boards/recovery/src/data_manager.rs | 2 -- 2 files changed, 3 deletions(-) diff --git a/boards/recovery/src/communication.rs b/boards/recovery/src/communication.rs index 0485b85c..e30867da 100644 --- a/boards/recovery/src/communication.rs +++ b/boards/recovery/src/communication.rs @@ -138,7 +138,6 @@ impl CanDevice0 { } pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { let payload: Vec = postcard::to_vec(&m)?; - info!("{}", m.clone()); self.can.tx.transmit_queued( tx::MessageBuilder { id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index 4dcd7ee5..af180a29 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -129,8 +129,6 @@ impl DataManager { if let Some(recent) = self.historical_barometer_altitude.recent() { if recent.1 != tup_data.1 { self.historical_barometer_altitude.write(tup_data); - } else { - info!("duplicate data {}", tup_data.1); } } else { self.historical_barometer_altitude.write(tup_data); From 48cf93b618e49d1944eab64cb60526e747920603 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Wed, 23 Aug 2023 22:17:49 -0400 Subject: [PATCH 24/30] Add GpsPos Log from SBG --- boards/recovery/src/main.rs | 1 + boards/sensor/src/data_manager.rs | 8 +++-- boards/sensor/src/main.rs | 2 ++ boards/sensor/src/sbg_manager.rs | 1 + libraries/messages/src/sensor.rs | 43 +++++++++++++++++++++++++ libraries/sbg-rs/src/data_conversion.rs | 28 ++++++++++++++-- libraries/sbg-rs/src/sbg.rs | 5 +++ 7 files changed, 84 insertions(+), 4 deletions(-) diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 77718502..988cb949 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -101,6 +101,7 @@ mod app { run_sm::spawn().ok(); state_send::spawn().ok(); blink::spawn().ok(); + fire_drogue::spawn_after(ExtU64::secs(10)).ok(); /* Monotonic clock */ let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); diff --git a/boards/sensor/src/data_manager.rs b/boards/sensor/src/data_manager.rs index 07d689cf..053c5cb0 100644 --- a/boards/sensor/src/data_manager.rs +++ b/boards/sensor/src/data_manager.rs @@ -1,6 +1,6 @@ use common_arm::spawn; use messages::sender::Sender; -use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime}; +use messages::sensor::{GpsPos1, GpsPos2, Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime}; use messages::Message; use crate::app::sleep_system; use defmt::info; @@ -13,6 +13,7 @@ pub struct DataManager { pub imu: Option<(Imu1, Imu2)>, pub utc_time: Option, pub gps_vel: Option, + pub gps_pos: Option<(GpsPos1, GpsPos2)>, } impl DataManager { @@ -24,10 +25,11 @@ impl DataManager { imu: None, utc_time: None, gps_vel: None, + gps_pos: None, } } - pub fn clone_sensors(&self) -> [Option; 8] { + pub fn clone_sensors(&self) -> [Option; 10] { [ self.air.clone().map(|x| x.into()), self.ekf_nav.clone().map(|x| x.0.into()), @@ -37,6 +39,8 @@ impl DataManager { self.imu.clone().map(|x| x.1.into()), self.utc_time.clone().map(|x| x.into()), self.gps_vel.clone().map(|x| x.into()), + self.gps_pos.clone().map(|x| x.0.into()), + self.gps_pos.clone().map(|x| x.1.into()), ] } diff --git a/boards/sensor/src/main.rs b/boards/sensor/src/main.rs index 61303286..53a6d0eb 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -36,6 +36,8 @@ use types::*; #[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] mod app { + use defmt::flush; + use super::*; #[shared] diff --git a/boards/sensor/src/sbg_manager.rs b/boards/sensor/src/sbg_manager.rs index 4eb95dc9..9208ade9 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -97,6 +97,7 @@ pub fn sbg_handle_data(mut cx: sbg_handle_data::Context, data: CallbackData) { CallbackData::EkfNav(x) => manager.ekf_nav = Some(x), CallbackData::Imu(x) => manager.imu = Some(x), CallbackData::GpsVel(x) => manager.gps_vel = Some(x), + CallbackData::GpsPos(x) => manager.gps_pos = Some(x), }); } diff --git a/libraries/messages/src/sensor.rs b/libraries/messages/src/sensor.rs index 3f917550..63ad0522 100644 --- a/libraries/messages/src/sensor.rs +++ b/libraries/messages/src/sensor.rs @@ -31,12 +31,55 @@ pub enum SensorData { Imu1(Imu1), Imu2(Imu2), GpsVel(GpsVel), + GpsPos1(GpsPos1), + GpsPos2(GpsPos2), Current(Current), Voltage(Voltage), Regulator(Regulator), Temperature(Temperature), } +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct GpsPos1 { + #[doc = "< Time in us since the sensor power up."] + pub timeStamp: u32, + #[doc = "< GPS position status, type and bitmask."] + pub status: u32, + #[doc = "< GPS time of week in ms."] + pub timeOfWeek: u32, + #[doc = "< Latitude in degrees, positive north."] + pub latitude: f64, + #[doc = "< Longitude in degrees, positive east."] + pub longitude: f64, + #[doc = "< Altitude above Mean Sea Level in meters."] + pub altitude: f64, + #[doc = "< Altitude difference between the geoid and the Ellipsoid in meters (Height above Ellipsoid = altitude + undulation)."] + pub undulation: f32, +} + + +#[derive(Serialize, Deserialize, Clone, Debug, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct GpsPos2 { + #[doc = "< 1 sigma latitude accuracy in meters."] + pub latitudeAccuracy: f32, + #[doc = "< 1 sigma longitude accuracy in meters."] + pub longitudeAccuracy: f32, + #[doc = "< 1 sigma altitude accuracy in meters."] + pub altitudeAccuracy: f32, + #[doc = "< Number of space vehicles used to compute the solution (since version 1.4)."] + pub numSvUsed: u8, + #[doc = "< Base station id for differential corrections (0-4095). Set to 0xFFFF if differential corrections are not used (since version 1.4)."] + pub baseStationId: u16, + #[doc = "< Differential correction age in 0.01 seconds. Set to 0XFFFF if differential corrections are not used (since version 1.4)."] + pub differentialAge: u16, +} + #[derive(Serialize, Deserialize, Clone, Debug, Format)] #[cfg_attr(test, derive(Arbitrary))] #[cfg_attr(feature = "ts", derive(TS))] diff --git a/libraries/sbg-rs/src/data_conversion.rs b/libraries/sbg-rs/src/data_conversion.rs index 1e0007e5..84dc95d0 100644 --- a/libraries/sbg-rs/src/data_conversion.rs +++ b/libraries/sbg-rs/src/data_conversion.rs @@ -1,7 +1,31 @@ use crate::bindings::{ - SbgLogAirData, SbgLogEkfNavData, SbgLogEkfQuatData, SbgLogGpsVel, SbgLogImuData, SbgLogUtcData, + SbgLogAirData, SbgLogEkfNavData, SbgLogEkfQuatData, SbgLogGpsVel, SbgLogImuData, SbgLogUtcData, SbgLogGpsPos, }; -use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, UtcTime}; +use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, UtcTime, GpsPos1, GpsPos2}; + +impl From for (GpsPos1, GpsPos2) { + fn from(value: SbgLogGpsPos) -> Self { + ( + GpsPos1 { + timeStamp: value.timeStamp, + status: value.status, + timeOfWeek: value.timeOfWeek, + latitude: value.latitude, + longitude: value.longitude, + altitude: value.altitude, + undulation: value.undulation, + }, + GpsPos2 { + latitudeAccuracy: value.latitudeAccuracy, + longitudeAccuracy: value.longitudeAccuracy, + altitudeAccuracy: value.altitudeAccuracy, + numSvUsed: value.numSvUsed, + baseStationId: value.baseStationId, + differentialAge: value.differentialAge, + }, + ) + } +} impl From for UtcTime { fn from(value: SbgLogUtcData) -> Self { diff --git a/libraries/sbg-rs/src/sbg.rs b/libraries/sbg-rs/src/sbg.rs index d5165179..cef06c56 100644 --- a/libraries/sbg-rs/src/sbg.rs +++ b/libraries/sbg-rs/src/sbg.rs @@ -2,6 +2,7 @@ use crate::bindings::{ self, _SbgDebugLogType_SBG_DEBUG_LOG_TYPE_WARNING, _SbgEComLog_SBG_ECOM_LOG_AIR_DATA, _SbgEComLog_SBG_ECOM_LOG_EKF_NAV, _SbgEComLog_SBG_ECOM_LOG_GPS1_VEL, _SbgEComLog_SBG_ECOM_LOG_UTC_TIME, + _SbgEComLog_SBG_ECOM_LOG_GPS1_POS, _SbgEComOutputMode_SBG_ECOM_OUTPUT_MODE_DIV_40, _SbgErrorCode_SBG_NO_ERROR, _SbgErrorCode_SBG_NULL_POINTER, _SbgErrorCode_SBG_READ_ERROR, _SbgErrorCode_SBG_WRITE_ERROR, sbgEComCmdOutputSetConf, sbgEComHandle, @@ -59,6 +60,7 @@ pub enum CallbackData { EkfNav((EkfNav1, EkfNav2)), Imu((Imu1, Imu2)), GpsVel(GpsVel), + GpsPos((GpsPos1, GpsPos2)), } struct UARTSBGInterface { @@ -418,6 +420,9 @@ impl SBG { _SbgEComLog_SBG_ECOM_LOG_EKF_NAV => { callback(CallbackData::EkfNav((*pLogData).ekfNavData.into())) } + _SbgEComLog_SBG_ECOM_LOG_GPS1_POS => { + callback(CallbackData::GpsPos((*pLogData).gpsPosData.into())) + } _ => (), } } From cea759c05d0633270522c6b5b58cdb272471f85d Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Thu, 24 Aug 2023 20:01:16 -0400 Subject: [PATCH 25/30] Add rate Switching --- boards/communication/src/data_manager.rs | 37 +++++++++++++++++-- boards/communication/src/main.rs | 19 ++++++++-- boards/recovery/src/data_manager.rs | 3 ++ boards/recovery/src/main.rs | 1 - .../src/state_machine/states/ascent.rs | 18 +++++++++ .../state_machine/states/wait_for_recovery.rs | 7 +++- libraries/messages/src/command.rs | 18 +++++++++ 7 files changed, 95 insertions(+), 8 deletions(-) diff --git a/boards/communication/src/data_manager.rs b/boards/communication/src/data_manager.rs index 0b6441ee..fdb9f52d 100644 --- a/boards/communication/src/data_manager.rs +++ b/boards/communication/src/data_manager.rs @@ -1,5 +1,6 @@ -use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime}; +use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime, GpsPos1, GpsPos2}; use messages::Message; +use messages::command::{Command, CommandData, RadioRateChange, RadioRate}; use messages::state::{State, StateData}; use defmt::info; @@ -11,7 +12,9 @@ pub struct DataManager { pub imu: (Option, Option), pub utc_time: Option, pub gps_vel: Option, + pub gps_pos: (Option, Option), pub state: Option, + pub logging_rate: Option, } impl DataManager { @@ -23,11 +26,23 @@ impl DataManager { imu: (None, None), utc_time: None, gps_vel: None, + gps_pos: (None, None), state: None, + logging_rate: Some(RadioRate::Slow), // start slow. } } - pub fn clone_sensors(&self) -> [Option; 8] { + pub fn get_logging_rate(&mut self) -> RadioRate { + if let Some(rate) = self.logging_rate.take() { + let rate_cln = rate.clone(); + self.logging_rate = Some(rate); + return rate_cln + } + self.logging_rate = Some(RadioRate::Slow); + return RadioRate::Slow + } + + pub fn clone_sensors(&self) -> [Option; 10] { [ self.air.clone().map(|x| x.into()), self.ekf_nav.0.clone().map(|x| x.into()), @@ -37,6 +52,8 @@ impl DataManager { self.imu.1.clone().map(|x| x.into()), self.utc_time.clone().map(|x| x.into()), self.gps_vel.clone().map(|x| x.into()), + self.gps_pos.0.clone().map(|x| x.into()), + self.gps_pos.1.clone().map(|x| x.into()), ] } pub fn clone_states(&self) -> [Option; 1] { @@ -71,12 +88,26 @@ impl DataManager { messages::sensor::SensorData::UtcTime(utc_time_data) => { self.utc_time = Some(utc_time_data); }, + messages::sensor::SensorData::GpsPos1(gps) => { + self.gps_pos.0 = Some(gps); + }, + messages::sensor::SensorData::GpsPos2(gps) => { + self.gps_pos.1 = Some(gps); + } _ => { info!("impl power related"); } }, messages::Data::State(state) => { - self.state = Some(state.data); + self.state = Some(state.data); + }, + messages::Data::Command(command) => match command.data { + messages::command::CommandData::RadioRateChange(command_data) => { + self.logging_rate = Some(command_data.rate); + }, + _ => { + + } } _ => { info!("unkown"); diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index d0a37d36..8fccf969 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -32,6 +32,7 @@ use panic_halt as _; use systick_monotonic::*; use types::*; use defmt::{info, flush}; +use messages::command::RadioRate; #[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] mod app { @@ -212,10 +213,15 @@ mod app { */ #[task(shared = [data_manager, &em])] fn sensor_send(mut cx: sensor_send::Context) { - let sensor_data = cx + let (sensor_data, logging_rate) = cx .shared .data_manager - .lock(|data_manager| data_manager.clone_sensors()); + .lock(|data_manager| { + ( + data_manager.clone_sensors(), + data_manager.get_logging_rate() + ) + }); let messages = sensor_data .into_iter() @@ -229,7 +235,14 @@ mod app { } Ok(()) }); - spawn_after!(sensor_send, ExtU64::millis(250)).ok(); + match logging_rate { + RadioRate::Fast => { + spawn_after!(sensor_send, ExtU64::millis(250)).ok(); + }, + RadioRate::Slow => { + spawn_after!(sensor_send, ExtU64::millis(2000)).ok(); + } + } } #[task(shared = [data_manager, &em])] diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index af180a29..e4cba6a9 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -168,6 +168,9 @@ impl DataManager { }, messages::command::CommandData::PowerDown(_) => { // don't handle for now. + }, + _ => { + } } _ => { diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 988cb949..77718502 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -101,7 +101,6 @@ mod app { run_sm::spawn().ok(); state_send::spawn().ok(); blink::spawn().ok(); - fire_drogue::spawn_after(ExtU64::secs(10)).ok(); /* Monotonic clock */ let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); diff --git a/boards/recovery/src/state_machine/states/ascent.rs b/boards/recovery/src/state_machine/states/ascent.rs index b3efa120..fdcb6f9b 100644 --- a/boards/recovery/src/state_machine/states/ascent.rs +++ b/boards/recovery/src/state_machine/states/ascent.rs @@ -2,13 +2,31 @@ use crate::state_machine::states::descent::Descent; use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; use crate::{no_transition, transition}; +use messages::command::{Command, CommandData, PowerDown, RadioRateChange, RadioRate}; +use messages::Message; use defmt::{write, Format, Formatter}; use rtic::mutex::Mutex; +use crate::types::COM_ID; +use crate::app::monotonics; #[derive(Debug, Clone)] pub struct Ascent {} impl State for Ascent { + fn enter(&self, context: &mut StateMachineContext) { + for i in 0..10 { + let radio_rate_change = RadioRateChange { + rate: RadioRate::Fast, + }; + let message_com = Message::new(&monotonics::now(), COM_ID, Command::new(radio_rate_change)); + context.shared_resources.can0.lock(|can| { + context.shared_resources.em.run(||{ + can.send_message(message_com)?; + Ok(()) + }) + }); + } + } fn step(&mut self, context: &mut StateMachineContext) -> Option { context .shared_resources diff --git a/boards/recovery/src/state_machine/states/wait_for_recovery.rs b/boards/recovery/src/state_machine/states/wait_for_recovery.rs index 9b43d3e4..4f944a63 100644 --- a/boards/recovery/src/state_machine/states/wait_for_recovery.rs +++ b/boards/recovery/src/state_machine/states/wait_for_recovery.rs @@ -5,7 +5,7 @@ use crate::types::COM_ID; use crate::{no_transition, transition}; use rtic::mutex::Mutex; use defmt::{write, Format, Formatter, info}; -use messages::command::{Command, CommandData, PowerDown}; +use messages::command::{Command, CommandData, PowerDown, RadioRateChange, RadioRate}; use messages::Message; use messages::sender::Sender::SensorBoard; @@ -19,10 +19,15 @@ impl State for WaitForRecovery { let sensor_power_down = PowerDown { board: SensorBoard }; + let radio_rate_change = RadioRateChange { + rate: RadioRate::Slow, + }; let message = Message::new(&monotonics::now(), COM_ID, Command::new(sensor_power_down)); + let message_com = Message::new(&monotonics::now(), COM_ID, Command::new(radio_rate_change)); context.shared_resources.can0.lock(|can| { context.shared_resources.em.run(||{ can.send_message(message)?; + can.send_message(message_com)?; Ok(()) }) }); diff --git a/libraries/messages/src/command.rs b/libraries/messages/src/command.rs index 31aa8e6f..e1b731be 100644 --- a/libraries/messages/src/command.rs +++ b/libraries/messages/src/command.rs @@ -25,6 +25,7 @@ pub enum CommandData { DeployDrogue(DeployDrogue), DeployMain(DeployMain), PowerDown(PowerDown), + RadioRateChange(RadioRateChange), } #[derive(Serialize, Deserialize, Clone, Debug, From, Format)] @@ -52,6 +53,23 @@ pub struct PowerDown { pub board: Sender, // This isn't proper naming !! This is the board to be powered down. Changes name of sender.rs to board.rs. } +#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub struct RadioRateChange { + pub rate: RadioRate, +} + +#[derive(Serialize, Deserialize, Clone, Debug, From, Format)] +#[cfg_attr(test, derive(Arbitrary))] +#[cfg_attr(feature = "ts", derive(TS))] +#[cfg_attr(feature = "ts", ts(export))] +pub enum RadioRate { + Fast, + Slow, +} + impl Command { pub fn new(data: impl Into) -> Self { Command { From 518e8be914db12ad7f034b894dfca07241d704b5 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sat, 26 Aug 2023 23:31:53 -0400 Subject: [PATCH 26/30] Change GPIO Manager for recovery board --- boards/recovery/src/data_manager.rs | 10 ++++---- boards/recovery/src/gpio_manager.rs | 30 ++++++++++++++++++++++++ boards/recovery/src/main.rs | 8 ++++--- boards/recovery/src/state_machine/mod.rs | 6 ++--- boards/recovery/src/types.rs | 29 +---------------------- 5 files changed, 43 insertions(+), 40 deletions(-) create mode 100644 boards/recovery/src/gpio_manager.rs diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index e4cba6a9..dcbae290 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -51,12 +51,13 @@ impl DataManager { } let slope = (i.0 - prev.0)/time_diff; if slope < -100.0 { - return false; // this is done since a shock wave would go extreme high to low resulting in a middle average. + return false; } avg_sum += slope; prev = i; } - match avg_sum / 7.0 { // 7 because we have 8 points. + match avg_sum / 7.0 { // 7 because we have 8 points. + // exclusive range x if !(-100.0..=-5.0).contains(&x) => { return false; } @@ -97,11 +98,10 @@ impl DataManager { match avg_sum / 7.0 { // inclusive range x if (-4.0..=4.0).contains(&x) => { - info!("avg: {}", avg_sum / 7.0); return true; } _ => { - info!("avg: {}", avg_sum / 7.0); + // continue } } } @@ -156,7 +156,6 @@ impl DataManager { self.utc_time = Some(utc_time_data); }, _ => { - info!("impl power"); } }, messages::Data::Command(command) => match command.data { @@ -174,7 +173,6 @@ impl DataManager { } } _ => { - info!("unkown"); } } } diff --git a/boards/recovery/src/gpio_manager.rs b/boards/recovery/src/gpio_manager.rs new file mode 100644 index 00000000..5f228b3d --- /dev/null +++ b/boards/recovery/src/gpio_manager.rs @@ -0,0 +1,30 @@ +use atsamd_hal::gpio::{Pin, PushPullOutput, PA09, PA06}; +use atsamd_hal::prelude::*; + +pub struct GPIOManager { + drogue_ematch: Pin, + main_ematch: Pin, +} + +impl GPIOManager { + pub fn new(mut drogue_ematch: Pin, mut main_ematch: Pin) -> Self { + drogue_ematch.set_low().ok(); + main_ematch.set_low().ok(); + Self { + drogue_ematch, + main_ematch + } + } + pub fn fire_drogue(&mut self) { + self.drogue_ematch.set_high().ok(); + } + pub fn fire_main(&mut self) { + self.main_ematch.set_high().ok(); + } + pub fn close_drouge(&mut self) { + self.drogue_ematch.set_low().ok(); + } + pub fn close_main(&mut self) { + self.main_ematch.set_low().ok(); + } +} \ No newline at end of file diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 77718502..b0fe545f 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -3,6 +3,7 @@ mod communication; mod data_manager; +mod gpio_manager; mod state_machine; mod types; @@ -15,6 +16,7 @@ use common_arm::mcan; use common_arm::*; use communication::Capacities; use data_manager::DataManager; +use gpio_manager::GPIOManager; use hal::gpio::{Pin, Pins, PushPullOutput, PB16, PB17}; use hal::prelude::*; use mcan::messageram::SharedMemory; @@ -22,7 +24,6 @@ use messages::*; use panic_halt as _; use state_machine::{StateMachine, StateMachineContext}; use systick_monotonic::*; -use types::GPIOController; use types::COM_ID; use defmt::info; @@ -35,7 +36,7 @@ mod app { em: ErrorManager, data_manager: DataManager, can0: communication::CanDevice0, - gpio: GPIOController, + gpio: GPIOManager, } #[local] @@ -90,7 +91,7 @@ mod app { /* GPIO config */ let led_green = pins.pb16.into_push_pull_output(); let led_red = pins.pb17.into_push_pull_output(); - let gpio = GPIOController::new( + let gpio = GPIOManager::new( pins.pa09.into_push_pull_output(), pins.pa06.into_push_pull_output(), ); @@ -101,6 +102,7 @@ mod app { run_sm::spawn().ok(); state_send::spawn().ok(); blink::spawn().ok(); + fire_main::spawn_after(ExtU64::secs(10)).ok(); /* Monotonic clock */ let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); diff --git a/boards/recovery/src/state_machine/mod.rs b/boards/recovery/src/state_machine/mod.rs index f90cda93..5adef76e 100644 --- a/boards/recovery/src/state_machine/mod.rs +++ b/boards/recovery/src/state_machine/mod.rs @@ -5,7 +5,7 @@ use messages::state; use crate::communication::CanDevice0; use crate::data_manager::DataManager; use crate::state_machine::states::*; -use crate::GPIOController; +use crate::gpio_manager::GPIOManager; pub use black_magic::*; pub use states::Initializing; use core::fmt::Debug; @@ -16,7 +16,7 @@ use rtic::Mutex; pub trait StateMachineSharedResources { fn lock_can(&mut self, f: &dyn Fn(&mut CanDevice0)); fn lock_data_manager(&mut self, f: &dyn Fn(&mut DataManager)); - fn lock_gpio(&mut self, f: &dyn Fn(&mut GPIOController)); + fn lock_gpio(&mut self, f: &dyn Fn(&mut GPIOManager)); } impl<'a> StateMachineSharedResources for crate::app::__rtic_internal_run_smSharedResources<'a> { @@ -26,7 +26,7 @@ impl<'a> StateMachineSharedResources for crate::app::__rtic_internal_run_smShare fn lock_data_manager(&mut self, fun: &dyn Fn(&mut DataManager)) { self.data_manager.lock(fun) } - fn lock_gpio(&mut self, fun: &dyn Fn(&mut GPIOController)) { + fn lock_gpio(&mut self, fun: &dyn Fn(&mut GPIOManager)) { self.gpio.lock(fun) } } diff --git a/boards/recovery/src/types.rs b/boards/recovery/src/types.rs index 7cae5fc6..bc4e098d 100644 --- a/boards/recovery/src/types.rs +++ b/boards/recovery/src/types.rs @@ -6,31 +6,4 @@ use messages::sender::Sender::RecoveryBoard; // ------- // Sender ID // ------- -pub static COM_ID: Sender = RecoveryBoard; - - -pub struct GPIOController { - drogue_ematch: Pin, - main_ematch: Pin, -} - -impl GPIOController { - pub fn new(drogue_ematch: Pin, main_ematch: Pin) -> Self { - Self { - drogue_ematch, - main_ematch - } - } - pub fn fire_drogue(&mut self) { - self.drogue_ematch.set_high().ok(); - } - pub fn fire_main(&mut self) { - self.main_ematch.set_high().ok(); - } - pub fn close_drouge(&mut self) { - self.drogue_ematch.set_low().ok(); - } - pub fn close_main(&mut self) { - self.main_ematch.set_low().ok(); - } -} \ No newline at end of file +pub static COM_ID: Sender = RecoveryBoard; \ No newline at end of file From 667cb4edae928e2ea79aff3e299fd853fe2e6a3d Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sun, 27 Aug 2023 20:12:00 -0400 Subject: [PATCH 27/30] Yolo --- Cargo.lock | 3045 +++++++++-------- boards/camera/Cargo.toml | 21 + boards/camera/src/communication.rs | 187 + boards/camera/src/data_manager.rs | 125 + boards/camera/src/gpio_manager.rs | 22 + boards/camera/src/main.rs | 155 + .../camera/src/state_machine/black_magic.rs | 44 + boards/camera/src/state_machine/mod.rs | 118 + .../camera/src/state_machine/states/abort.rs | 24 + .../camera/src/state_machine/states/ascent.rs | 48 + .../src/state_machine/states/descent.rs | 32 + .../src/state_machine/states/initializing.rs | 20 + boards/camera/src/state_machine/states/mod.rs | 15 + .../state_machine/states/terminal_descent.rs | 36 + .../state_machine/states/wait_for_recovery.rs | 31 + .../state_machine/states/wait_for_takeoff.rs | 36 + boards/camera/src/types.rs | 5 + boards/communication/Cargo.toml | 2 +- boards/communication/src/communication.rs | 28 +- boards/communication/src/data_manager.rs | 34 +- boards/communication/src/main.rs | 90 +- boards/communication/src/types.rs | 16 - boards/recovery/src/main.rs | 36 +- boards/sensor/src/types.rs | 2 +- libraries/common-arm/Cargo.toml | 2 +- libraries/common-arm/src/data_manager.rs | 0 libraries/common-arm/src/lib.rs | 2 + .../common-arm}/src/sd_manager.rs | 292 +- libraries/messages/src/sender.rs | 6 +- 29 files changed, 2716 insertions(+), 1758 deletions(-) create mode 100644 boards/camera/Cargo.toml create mode 100644 boards/camera/src/communication.rs create mode 100644 boards/camera/src/data_manager.rs create mode 100644 boards/camera/src/gpio_manager.rs create mode 100644 boards/camera/src/main.rs create mode 100644 boards/camera/src/state_machine/black_magic.rs create mode 100644 boards/camera/src/state_machine/mod.rs create mode 100644 boards/camera/src/state_machine/states/abort.rs create mode 100644 boards/camera/src/state_machine/states/ascent.rs create mode 100644 boards/camera/src/state_machine/states/descent.rs create mode 100644 boards/camera/src/state_machine/states/initializing.rs create mode 100644 boards/camera/src/state_machine/states/mod.rs create mode 100644 boards/camera/src/state_machine/states/terminal_descent.rs create mode 100644 boards/camera/src/state_machine/states/wait_for_recovery.rs create mode 100644 boards/camera/src/state_machine/states/wait_for_takeoff.rs create mode 100644 boards/camera/src/types.rs create mode 100644 libraries/common-arm/src/data_manager.rs rename {boards/communication => libraries/common-arm}/src/sd_manager.rs (74%) diff --git a/Cargo.lock b/Cargo.lock index b7ca65a1..f838443b 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -1,1513 +1,1532 @@ -# This file is automatically @generated by Cargo. -# It is not intended for manual editing. -version = 3 - -[[package]] -name = "Inflector" -version = "0.11.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "fe438c63458706e03479442743baae6c88256498e6431708f6dfc520a26515d3" - -[[package]] -name = "aes" -version = "0.7.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9e8b47f52ea9bae42228d07ec09eb676433d7c4ed1ebdf0f1d1c29ed446f1ab8" -dependencies = [ - "cfg-if", - "cipher", - "cpufeatures", - "opaque-debug", -] - -[[package]] -name = "atomic-polyfill" -version = "0.1.11" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e3ff7eb3f316534d83a8a2c3d1674ace8a5a71198eba31e2e2b597833f699b28" -dependencies = [ - "critical-section", -] - -[[package]] -name = "atsamd-hal" -version = "0.16.0" -source = "git+https://github.com/atsamd-rs/atsamd#0820f0df58eb8705ddfa6533ed76953d18e6b992" -dependencies = [ - "aes", - "atsame51j", - "bitfield 0.13.2", - "bitflags 1.3.2", - "cipher", - "cortex-m", - "embedded-hal", - "fugit", - "mcan-core", - "modular-bitfield", - "nb 1.1.0", - "num-traits", - "opaque-debug", - "paste", - "rand_core", - "seq-macro", - "typenum", - "vcell", - "void", -] - -[[package]] -name = "atsame51j" -version = "0.12.0" -source = "git+https://github.com/atsamd-rs/atsamd#0820f0df58eb8705ddfa6533ed76953d18e6b992" -dependencies = [ - "cortex-m", - "cortex-m-rt", - "vcell", -] - -[[package]] -name = "autocfg" -version = "1.1.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d468802bab17cbc0cc575e9b053f41e72aa36bfa6b7f55e3529ffa43161b97fa" - -[[package]] -name = "bare-metal" -version = "0.2.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "5deb64efa5bd81e31fcd1938615a6d98c82eafcbcd787162b6f63b91d6bac5b3" -dependencies = [ - "rustc_version 0.2.3", -] - -[[package]] -name = "bare-metal" -version = "1.0.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f8fe8f5a8a398345e52358e18ff07cc17a568fbca5c6f73873d3a62056309603" - -[[package]] -name = "bit-set" -version = "0.5.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "0700ddab506f33b20a03b13996eccd309a48e5ff77d0d95926aa0210fb4e95f1" -dependencies = [ - "bit-vec", -] - -[[package]] -name = "bit-vec" -version = "0.6.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "349f9b6a179ed607305526ca489b34ad0a41aed5f7980fa90eb03160b69598fb" - -[[package]] -name = "bitfield" -version = "0.13.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "46afbd2983a5d5a7bd740ccb198caf5b82f45c40c09c0eed36052d91cb92e719" - -[[package]] -name = "bitfield" -version = "0.14.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "2d7e60934ceec538daadb9d8432424ed043a904d8e0243f3c6446bce549a46ac" - -[[package]] -name = "bitflags" -version = "1.3.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "bef38d45163c2f1dde094a7dfd33ccf595c92905c8f8f4fdc18d06fb1037718a" - -[[package]] -name = "bitflags" -version = "2.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b4682ae6287fcf752ecaabbfcc7b6f9b72aa33933dc23a554d853aea8eea8635" - -[[package]] -name = "byteorder" -version = "1.4.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "14c189c53d098945499cdfa7ecc63567cf3886b3332b312a5b4585d8d3a6a610" - -[[package]] -name = "cc" -version = "1.0.82" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "305fe645edc1442a0fa8b6726ba61d422798d37a52e12eaecf4b022ebbb88f01" -dependencies = [ - "libc", -] - -[[package]] -name = "cfg-if" -version = "1.0.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "baf1de4339761588bc0619e3cbc0120ee582ebb74b53b4efbf79117bd2da40fd" - -[[package]] -name = "cipher" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "7ee52072ec15386f770805afd189a01c8841be8696bed250fa2f13c4c0d6dfb7" -dependencies = [ - "generic-array", -] - -[[package]] -name = "cmake" -version = "0.1.50" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a31c789563b815f77f4250caee12365734369f942439b7defd71e18a48197130" -dependencies = [ - "cc", -] - -[[package]] -name = "cobs" -version = "0.2.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "67ba02a97a2bd10f4b59b25c7973101c79642302776489e030cd13cdab09ed15" - -[[package]] -name = "common-arm" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "cortex-m", - "cortex-m-rt", - "defmt", - "defmt-rtt", - "derive_more", - "embedded-hal", - "embedded-sdmmc", - "heapless", - "mcan", - "messages", - "nb 1.1.0", - "postcard", -] - -[[package]] -name = "common-arm-test" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "defmt", - "defmt-rtt", - "defmt-test", - "panic-probe", -] - -[[package]] -name = "communication" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "cortex-m-rtic", - "defmt", - "embedded-sdmmc", - "heapless", - "messages", - "panic-halt", - "postcard", - "systick-monotonic", - "typenum", -] - -[[package]] -name = "convert_case" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6245d59a3e82a7fc217c5828a6692dbc6dfb63a0c8c90495621f7b9d79704a0e" - -[[package]] -name = "cortex-m" -version = "0.7.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8ec610d8f49840a5b376c69663b6369e71f4b34484b9b2eb29fb918d92516cb9" -dependencies = [ - "bare-metal 0.2.5", - "bitfield 0.13.2", - "critical-section", - "embedded-hal", - "volatile-register", -] - -[[package]] -name = "cortex-m-rt" -version = "0.7.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "ee84e813d593101b1723e13ec38b6ab6abbdbaaa4546553f5395ed274079ddb1" -dependencies = [ - "cortex-m-rt-macros", -] - -[[package]] -name = "cortex-m-rt-macros" -version = "0.7.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f0f6f3e36f203cfedbc78b357fb28730aa2c6dc1ab060ee5c2405e843988d3c7" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", -] - -[[package]] -name = "cortex-m-rtic" -version = "1.1.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d696ae7390bdb9f7978f71ca7144256a2c4616240a6df9002da3c451f9fc8f02" -dependencies = [ - "bare-metal 1.0.0", - "cortex-m", - "cortex-m-rtic-macros", - "heapless", - "rtic-core", - "rtic-monotonic", - "version_check", -] - -[[package]] -name = "cortex-m-rtic-macros" -version = "1.1.6" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "eefb40b1ca901c759d29526e5c8a0a1b246c20caaa5b4cc5d0f0b94debecd4c7" -dependencies = [ - "proc-macro-error", - "proc-macro2 1.0.66", - "quote 1.0.32", - "rtic-syntax", - "syn 1.0.109", -] - -[[package]] -name = "cpufeatures" -version = "0.2.9" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a17b76ff3a4162b0b27f354a0c87015ddad39d35f9c0c36607a3bdd175dde1f1" -dependencies = [ - "libc", -] - -[[package]] -name = "crc-any" -version = "2.4.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "774646b687f63643eb0f4bf13dc263cb581c8c9e57973b6ddf78bda3994d88df" - -[[package]] -name = "critical-section" -version = "1.1.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "7059fff8937831a9ae6f0fe4d658ffabf58f2ca96aa9dec1c889f936f705f216" - -[[package]] -name = "defmt" -version = "0.3.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a8a2d011b2fee29fb7d659b83c43fce9a2cb4df453e16d441a51448e448f3f98" -dependencies = [ - "bitflags 1.3.2", - "defmt-macros", -] - -[[package]] -name = "defmt-macros" -version = "0.3.6" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "54f0216f6c5acb5ae1a47050a6645024e6edafc2ee32d421955eccfef12ef92e" -dependencies = [ - "defmt-parser", - "proc-macro-error", - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 2.0.28", -] - -[[package]] -name = "defmt-parser" -version = "0.3.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "269924c02afd7f94bc4cecbfa5c379f6ffcf9766b3408fe63d22c728654eccd0" -dependencies = [ - "thiserror", -] - -[[package]] -name = "defmt-rtt" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "609923761264dd99ed9c7d209718cda4631c5fe84668e0f0960124cbb844c49f" -dependencies = [ - "critical-section", - "defmt", -] - -[[package]] -name = "defmt-test" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4df24f1ca104a0c1bce2047d8a21aa9fa29695e5d662118eb48daedb97edca88" -dependencies = [ - "cortex-m", - "cortex-m-rt", - "defmt", - "defmt-test-macros", -] - -[[package]] -name = "defmt-test-macros" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "94a0dfea4063d72e1ba20494dfbc4667f67420869328cf3670b5824a38a22dc1" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", -] - -[[package]] -name = "derive_more" -version = "0.99.17" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4fb810d30a7c1953f91334de7244731fc3f3c10d7fe163338a35b9f640960321" -dependencies = [ - "convert_case", - "proc-macro2 1.0.66", - "quote 1.0.32", - "rustc_version 0.4.0", - "syn 1.0.109", -] - -[[package]] -name = "embedded-alloc" -version = "0.5.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8931e47e33c5d3194fbcf9cc82df0919193bd2fa40008f388eb1d28fd9c9ea6b" -dependencies = [ - "critical-section", - "linked_list_allocator", -] - -[[package]] -name = "embedded-can" -version = "0.4.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e9d2e857f87ac832df68fa498d18ddc679175cf3d2e4aa893988e5601baf9438" -dependencies = [ - "nb 1.1.0", -] - -[[package]] -name = "embedded-hal" -version = "0.2.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "35949884794ad573cf46071e41c9b60efb0cb311e3ca01f7af807af1debc66ff" -dependencies = [ - "nb 0.1.3", - "void", -] - -[[package]] -name = "embedded-sdmmc" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6d3bf0a2b5becb87e9a329d9290f131e4d10fec39b56d129926826a7cbea1e7a" -dependencies = [ - "byteorder", - "embedded-hal", - "log", - "nb 0.1.3", -] - -[[package]] -name = "enum_dispatch" -version = "0.3.12" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8f33313078bb8d4d05a2733a94ac4c2d8a0df9a2b84424ebf4f33bfc224a890e" -dependencies = [ - "once_cell", - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 2.0.28", -] - -[[package]] -name = "errno" -version = "0.3.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6b30f669a7961ef1631673d2766cc92f52d64f7ef354d4fe0ddfd30ed52f0f4f" -dependencies = [ - "errno-dragonfly", - "libc", - "windows-sys", -] - -[[package]] -name = "errno-dragonfly" -version = "0.1.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "aa68f1b12764fab894d2755d2518754e71b4fd80ecfb822714a1206c2aab39bf" -dependencies = [ - "cc", - "libc", -] - -[[package]] -name = "fastrand" -version = "2.0.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6999dc1837253364c2ebb0704ba97994bd874e8f195d665c50b7548f6ea92764" - -[[package]] -name = "fnv" -version = "1.0.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "3f9eec918d3f24069decb9af1554cad7c880e2da24a9afd88aca000531ab82c1" - -[[package]] -name = "fugit" -version = "0.3.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "17186ad64927d5ac8f02c1e77ccefa08ccd9eaa314d5a4772278aa204a22f7e7" -dependencies = [ - "gcd", -] - -[[package]] -name = "gcd" -version = "2.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "1d758ba1b47b00caf47f24925c0074ecb20d6dfcffe7f6d53395c0465674841a" - -[[package]] -name = "generic-array" -version = "0.14.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "85649ca51fd72272d7821adaf274ad91c288277713d9c18820d8499a7ff69e9a" -dependencies = [ - "typenum", - "version_check", -] - -[[package]] -name = "getrandom" -version = "0.2.10" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "be4136b2a15dd319360be1c07d9933517ccf0be8f16bf62a3bee4f0d618df427" -dependencies = [ - "cfg-if", - "libc", - "wasi", -] - -[[package]] -name = "hash32" -version = "0.2.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b0c35f58762feb77d74ebe43bdbc3210f09be9fe6742234d573bacc26ed92b67" -dependencies = [ - "byteorder", -] - -[[package]] -name = "hashbrown" -version = "0.12.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8a9ee70c43aaf417c914396645a0fa852624801b24ebb7ae78fe8272889ac888" - -[[package]] -name = "heapless" -version = "0.7.16" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "db04bc24a18b9ea980628ecf00e6c0264f3c1426dac36c00cb49b6fbad8b0743" -dependencies = [ - "atomic-polyfill", - "hash32", - "rustc_version 0.4.0", - "serde", - "spin", - "stable_deref_trait", -] - -[[package]] -name = "indexmap" -version = "1.9.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "bd070e393353796e801d209ad339e89596eb4c8d430d18ede6a1cced8fafbd99" -dependencies = [ - "autocfg", - "hashbrown", -] - -[[package]] -name = "ioctl-rs" -version = "0.1.6" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f7970510895cee30b3e9128319f2cefd4bde883a39f38baa279567ba3a7eb97d" -dependencies = [ - "libc", -] - -[[package]] -name = "lazy_static" -version = "1.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e2abad23fbc42b3700f2f279844dc832adb2b2eb069b2df918f455c4e18cc646" - -[[package]] -name = "libc" -version = "0.2.147" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b4668fb0ea861c1df094127ac5f1da3409a82116a4ba74fca2e58ef927159bb3" - -[[package]] -name = "libm" -version = "0.2.7" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f7012b1bbb0719e1097c47611d3898568c546d597c2e74d66f6087edd5233ff4" - -[[package]] -name = "linked_list_allocator" -version = "0.10.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9afa463f5405ee81cdb9cc2baf37e08ec7e4c8209442b5d72c04cfb2cd6e6286" - -[[package]] -name = "linux-raw-sys" -version = "0.4.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "57bcfdad1b858c2db7c38303a6d2ad4dfaf5eb53dfeb0910128b2c26d6158503" - -[[package]] -name = "lock_api" -version = "0.4.10" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "c1cc9717a20b1bb222f333e6a92fd32f7d8a18ddc5a3191a11af45dcbf4dcd16" -dependencies = [ - "autocfg", - "scopeguard", -] - -[[package]] -name = "log" -version = "0.4.20" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b5e6163cb8c49088c2c36f57875e58ccd8c87c7427f7fbd50ea6710b2f3f2e8f" - -[[package]] -name = "mavlink" -version = "0.11.1" -source = "git+https://github.com/uorocketry/rust-mavlink?branch=hydra_dialect#0e0bedd0f37ccad490ea693ad80c2ecffb3d6351" -dependencies = [ - "bitflags 1.3.2", - "byteorder", - "crc-any", - "embedded-hal", - "heapless", - "lazy_static", - "nb 1.1.0", - "num-derive", - "num-traits", - "proc-macro2 1.0.66", - "quick-xml", - "quote 1.0.32", - "serde", - "serial", -] - -[[package]] -name = "mcan" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "1db1ad48f562b804bfe83828dc0d87622ea96bdc435a8513ecaa45a5f88d2f2f" -dependencies = [ - "bitfield 0.14.0", - "embedded-can", - "fugit", - "generic-array", - "mcan-core", - "nb 1.1.0", - "vcell", -] - -[[package]] -name = "mcan-core" -version = "0.2.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8b3dee4ff5269e2465cc856d37103cce916c1ef73b4377f006c963872e69f7ca" -dependencies = [ - "fugit", -] - -[[package]] -name = "memchr" -version = "2.5.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "2dffe52ecf27772e601905b7522cb4ef790d2cc203488bbd0e2fe85fcb74566d" - -[[package]] -name = "messages" -version = "0.1.0" -dependencies = [ - "defmt", - "derive_more", - "fugit", - "heapless", - "mavlink", - "postcard", - "proptest", - "proptest-derive", - "serde", - "ts-rs", -] - -[[package]] -name = "modular-bitfield" -version = "0.11.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a53d79ba8304ac1c4f9eb3b9d281f21f7be9d4626f72ce7df4ad8fbde4f38a74" -dependencies = [ - "modular-bitfield-impl", - "static_assertions", -] - -[[package]] -name = "modular-bitfield-impl" -version = "0.11.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "5a7d5f7076603ebc68de2dc6a650ec331a062a13abaa346975be747bbfa4b789" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", -] - -[[package]] -name = "nb" -version = "0.1.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "801d31da0513b6ec5214e9bf433a77966320625a37860f910be265be6e18d06f" -dependencies = [ - "nb 1.1.0", -] - -[[package]] -name = "nb" -version = "1.1.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "8d5439c4ad607c3c23abf66de8c8bf57ba8adcd1f129e699851a6e43935d339d" - -[[package]] -name = "num-derive" -version = "0.3.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "876a53fff98e03a936a674b29568b0e605f06b29372c2489ff4de23f1949743d" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", -] - -[[package]] -name = "num-traits" -version = "0.2.16" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f30b0abd723be7e2ffca1272140fac1a2f084c77ec3e123c192b66af1ee9e6c2" -dependencies = [ - "autocfg", - "libm", -] - -[[package]] -name = "once_cell" -version = "1.18.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "dd8b5dd2ae5ed71462c540258bedcb51965123ad7e7ccf4b9a8cafaa4a63576d" - -[[package]] -name = "opaque-debug" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "624a8340c38c1b80fd549087862da4ba43e08858af025b236e509b6649fc13d5" - -[[package]] -name = "panic-halt" -version = "0.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "de96540e0ebde571dc55c73d60ef407c653844e6f9a1e2fdbd40c07b9252d812" - -[[package]] -name = "panic-probe" -version = "0.3.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "aa6fa5645ef5a760cd340eaa92af9c1ce131c8c09e7f8926d8a24b59d26652b9" -dependencies = [ - "cortex-m", - "defmt", -] - -[[package]] -name = "paste" -version = "1.0.14" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "de3145af08024dea9fa9914f381a17b8fc6034dfb00f3a84013f7ff43f29ed4c" - -[[package]] -name = "postcard" -version = "1.0.6" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "c9ee729232311d3cd113749948b689627618133b1c5012b77342c1950b25eaeb" -dependencies = [ - "cobs", - "defmt", - "heapless", - "serde", -] - -[[package]] -name = "power" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "cortex-m-rtic", - "defmt", - "enum_dispatch", - "heapless", - "messages", - "panic-halt", - "postcard", - "systick-monotonic", - "typenum", -] - -[[package]] -name = "ppv-lite86" -version = "0.2.17" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "5b40af805b3121feab8a3c29f04d8ad262fa8e0561883e7653e024ae4479e6de" - -[[package]] -name = "proc-macro-error" -version = "1.0.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "da25490ff9892aab3fcf7c36f08cfb902dd3e71ca0f9f9517bea02a73a5ce38c" -dependencies = [ - "proc-macro-error-attr", - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", - "version_check", -] - -[[package]] -name = "proc-macro-error-attr" -version = "1.0.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a1be40180e52ecc98ad80b184934baf3d0d29f979574e439af5a55274b35f869" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "version_check", -] - -[[package]] -name = "proc-macro2" -version = "0.4.30" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "cf3d2011ab5c909338f7887f4fc896d35932e29146c12c8d01da6b22a80ba759" -dependencies = [ - "unicode-xid", -] - -[[package]] -name = "proc-macro2" -version = "1.0.66" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "18fb31db3f9bddb2ea821cde30a9f70117e3f119938b5ee630b7403aa6e2ead9" -dependencies = [ - "unicode-ident", -] - -[[package]] -name = "proptest" -version = "1.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4e35c06b98bf36aba164cc17cb25f7e232f5c4aeea73baa14b8a9f0d92dbfa65" -dependencies = [ - "bit-set", - "bitflags 1.3.2", - "byteorder", - "lazy_static", - "num-traits", - "rand", - "rand_chacha", - "rand_xorshift", - "regex-syntax", - "rusty-fork", - "tempfile", - "unarray", -] - -[[package]] -name = "proptest-derive" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "90b46295382dc76166cb7cf2bb4a97952464e4b7ed5a43e6cd34e1fec3349ddc" -dependencies = [ - "proc-macro2 0.4.30", - "quote 0.6.13", - "syn 0.15.44", -] - -[[package]] -name = "quick-error" -version = "1.2.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a1d01941d82fa2ab50be1e79e6714289dd7cde78eba4c074bc5a4374f650dfe0" - -[[package]] -name = "quick-xml" -version = "0.26.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "7f50b1c63b38611e7d4d7f68b82d3ad0cc71a2ad2e7f61fc10f1328d917c93cd" -dependencies = [ - "memchr", -] - -[[package]] -name = "quote" -version = "0.6.13" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6ce23b6b870e8f94f81fb0a363d65d86675884b34a09043c81e5562f11c1f8e1" -dependencies = [ - "proc-macro2 0.4.30", -] - -[[package]] -name = "quote" -version = "1.0.32" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "50f3b39ccfb720540debaa0164757101c08ecb8d326b15358ce76a62c7e85965" -dependencies = [ - "proc-macro2 1.0.66", -] - -[[package]] -name = "rand" -version = "0.8.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "34af8d1a0e25924bc5b7c43c079c942339d8f0a8b57c39049bef581b46327404" -dependencies = [ - "libc", - "rand_chacha", - "rand_core", -] - -[[package]] -name = "rand_chacha" -version = "0.3.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "e6c10a63a0fa32252be49d21e7709d4d4baf8d231c2dbce1eaa8141b9b127d88" -dependencies = [ - "ppv-lite86", - "rand_core", -] - -[[package]] -name = "rand_core" -version = "0.6.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "ec0be4795e2f6a28069bec0b5ff3e2ac9bafc99e6a9a7dc3547996c5c816922c" -dependencies = [ - "getrandom", -] - -[[package]] -name = "rand_xorshift" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d25bf25ec5ae4a3f1b92f929810509a2f53d7dca2f50b794ff57e3face536c8f" -dependencies = [ - "rand_core", -] - -[[package]] -name = "recovery" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "cortex-m-rtic", - "defmt", - "enum_dispatch", - "heapless", - "messages", - "panic-halt", - "postcard", - "systick-monotonic", - "typenum", -] - -[[package]] -name = "redox_syscall" -version = "0.3.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "567664f262709473930a4bf9e51bf2ebf3348f2e748ccc50dea20646858f8f29" -dependencies = [ - "bitflags 1.3.2", -] - -[[package]] -name = "regex-syntax" -version = "0.6.29" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f162c6dd7b008981e4d40210aca20b4bd0f9b60ca9271061b07f78537722f2e1" - -[[package]] -name = "rtic-core" -version = "1.0.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d9369355b04d06a3780ec0f51ea2d225624db777acbc60abd8ca4832da5c1a42" - -[[package]] -name = "rtic-monotonic" -version = "1.0.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "fb8b0b822d1a366470b9cea83a1d4e788392db763539dc4ba022bcc787fece82" - -[[package]] -name = "rtic-syntax" -version = "1.0.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "5f5e215601dc467752c2bddc6284a622c6f3d2bab569d992adcd5ab7e4cb9478" -dependencies = [ - "indexmap", - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", -] - -[[package]] -name = "rtic_example" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "cortex-m-rtic", - "defmt", - "defmt-rtt", - "fugit", - "heapless", - "messages", - "panic-halt", - "postcard", - "systick-monotonic", - "typenum", -] - -[[package]] -name = "rustc_version" -version = "0.2.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "138e3e0acb6c9fb258b19b67cb8abd63c00679d2851805ea151465464fe9030a" -dependencies = [ - "semver 0.9.0", -] - -[[package]] -name = "rustc_version" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "bfa0f585226d2e68097d4f95d113b15b83a82e819ab25717ec0590d9584ef366" -dependencies = [ - "semver 1.0.18", -] - -[[package]] -name = "rustix" -version = "0.38.8" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "19ed4fa021d81c8392ce04db050a3da9a60299050b7ae1cf482d862b54a7218f" -dependencies = [ - "bitflags 2.4.0", - "errno", - "libc", - "linux-raw-sys", - "windows-sys", -] - -[[package]] -name = "rusty-fork" -version = "0.3.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "cb3dcc6e454c328bb824492db107ab7c0ae8fcffe4ad210136ef014458c1bc4f" -dependencies = [ - "fnv", - "quick-error", - "tempfile", - "wait-timeout", -] - -[[package]] -name = "sbg-rs" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "cmake", - "common-arm", - "cortex-m", - "cortex-m-rt", - "defmt", - "embedded-hal", - "heapless", - "messages", - "nb 1.1.0", -] - -[[package]] -name = "scopeguard" -version = "1.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "94143f37725109f92c262ed2cf5e59bce7498c01bcc1502d7b9afe439a4e9f49" - -[[package]] -name = "semver" -version = "0.9.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "1d7eb9ef2c18661902cc47e535f9bc51b78acd254da71d375c2f6720d9a40403" -dependencies = [ - "semver-parser", -] - -[[package]] -name = "semver" -version = "1.0.18" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b0293b4b29daaf487284529cc2f5675b8e57c61f70167ba415a463651fd6a918" - -[[package]] -name = "semver-parser" -version = "0.7.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "388a1df253eca08550bef6c72392cfe7c30914bf41df5269b68cbd6ff8f570a3" - -[[package]] -name = "sensor" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "cortex-m-rtic", - "defmt", - "embedded-alloc", - "embedded-sdmmc", - "heapless", - "messages", - "panic-halt", - "postcard", - "sbg-rs", - "systick-monotonic", - "typenum", -] - -[[package]] -name = "seq-macro" -version = "0.3.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a3f0bf26fd526d2a95683cd0f87bf103b8539e2ca1ef48ce002d67aad59aa0b4" - -[[package]] -name = "serde" -version = "1.0.183" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "32ac8da02677876d532745a130fc9d8e6edfa81a269b107c5b00829b91d8eb3c" -dependencies = [ - "serde_derive", -] - -[[package]] -name = "serde_derive" -version = "1.0.183" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "aafe972d60b0b9bee71a91b92fee2d4fb3c9d7e8f6b179aa99f27203d99a4816" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 2.0.28", -] - -[[package]] -name = "serial" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a1237a96570fc377c13baa1b88c7589ab66edced652e43ffb17088f003db3e86" -dependencies = [ - "serial-core", - "serial-unix", - "serial-windows", -] - -[[package]] -name = "serial-core" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "3f46209b345401737ae2125fe5b19a77acce90cd53e1658cda928e4fe9a64581" -dependencies = [ - "libc", -] - -[[package]] -name = "serial-unix" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "f03fbca4c9d866e24a459cbca71283f545a37f8e3e002ad8c70593871453cab7" -dependencies = [ - "ioctl-rs", - "libc", - "serial-core", - "termios", -] - -[[package]] -name = "serial-windows" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "15c6d3b776267a75d31bbdfd5d36c0ca051251caafc285827052bc53bcdc8162" -dependencies = [ - "libc", - "serial-core", -] - -[[package]] -name = "simple_example" -version = "0.1.0" -dependencies = [ - "atsamd-hal", - "common-arm", - "cortex-m", - "cortex-m-rt", - "defmt", - "defmt-rtt", - "panic-halt", -] - -[[package]] -name = "spin" -version = "0.9.8" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6980e8d7511241f8acf4aebddbb1ff938df5eebe98691418c4468d0b72a96a67" -dependencies = [ - "lock_api", -] - -[[package]] -name = "stable_deref_trait" -version = "1.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a8f112729512f8e442d81f95a8a7ddf2b7c6b8a1a6f509a95864142b30cab2d3" - -[[package]] -name = "static_assertions" -version = "1.1.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "a2eb9349b6444b326872e140eb1cf5e7c522154d69e7a0ffb0fb81c06b37543f" - -[[package]] -name = "syn" -version = "0.15.44" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9ca4b3b69a77cbe1ffc9e198781b7acb0c7365a883670e8f1c1bc66fba79a5c5" -dependencies = [ - "proc-macro2 0.4.30", - "quote 0.6.13", - "unicode-xid", -] - -[[package]] -name = "syn" -version = "1.0.109" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "72b64191b275b66ffe2469e8af2c1cfe3bafa67b529ead792a6d0160888b4237" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "unicode-ident", -] - -[[package]] -name = "syn" -version = "2.0.28" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "04361975b3f5e348b2189d8dc55bc942f278b2d482a6a0365de5bdd62d351567" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "unicode-ident", -] - -[[package]] -name = "systick-monotonic" -version = "1.0.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "67fb822d5c615a0ae3a4795ee5b1d06381c7faf488d861c0a4fa8e6a88d5ff84" -dependencies = [ - "cortex-m", - "fugit", - "rtic-monotonic", -] - -[[package]] -name = "tempfile" -version = "3.7.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "dc02fddf48964c42031a0b3fe0428320ecf3a73c401040fc0096f97794310651" -dependencies = [ - "cfg-if", - "fastrand", - "redox_syscall", - "rustix", - "windows-sys", -] - -[[package]] -name = "termcolor" -version = "1.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "be55cf8942feac5c765c2c993422806843c9a9a45d4d5c407ad6dd2ea95eb9b6" -dependencies = [ - "winapi-util", -] - -[[package]] -name = "termios" -version = "0.2.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "d5d9cf598a6d7ce700a4e6a9199da127e6819a61e64b68609683cc9a01b5683a" -dependencies = [ - "libc", -] - -[[package]] -name = "thiserror" -version = "1.0.44" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "611040a08a0439f8248d1990b111c95baa9c704c805fa1f62104b39655fd7f90" -dependencies = [ - "thiserror-impl", -] - -[[package]] -name = "thiserror-impl" -version = "1.0.44" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "090198534930841fab3a5d1bb637cde49e339654e606195f8d9c76eeb081dc96" -dependencies = [ - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 2.0.28", -] - -[[package]] -name = "ts-rs" -version = "6.2.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4added4070a4fdf9df03457206cd2e4b12417c8560a2954d91ffcbe60177a56a" -dependencies = [ - "thiserror", - "ts-rs-macros", -] - -[[package]] -name = "ts-rs-macros" -version = "6.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9f807fdb3151fee75df7485b901a89624358cd07a67a8fb1a5831bf5a07681ff" -dependencies = [ - "Inflector", - "proc-macro2 1.0.66", - "quote 1.0.32", - "syn 1.0.109", - "termcolor", -] - -[[package]] -name = "typenum" -version = "1.16.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "497961ef93d974e23eb6f433eb5fe1b7930b659f06d12dec6fc44a8f554c0bba" - -[[package]] -name = "unarray" -version = "0.1.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "eaea85b334db583fe3274d12b4cd1880032beab409c0d774be044d4480ab9a94" - -[[package]] -name = "unicode-ident" -version = "1.0.11" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "301abaae475aa91687eb82514b328ab47a211a533026cb25fc3e519b86adfc3c" - -[[package]] -name = "unicode-xid" -version = "0.1.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "fc72304796d0818e357ead4e000d19c9c174ab23dc11093ac919054d20a6a7fc" - -[[package]] -name = "vcell" -version = "0.1.3" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "77439c1b53d2303b20d9459b1ade71a83c716e3f9c34f3228c00e6f185d6c002" - -[[package]] -name = "version_check" -version = "0.9.4" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "49874b5167b65d7193b8aba1567f5c7d93d001cafc34600cee003eda787e483f" - -[[package]] -name = "void" -version = "1.0.2" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "6a02e4885ed3bc0f2de90ea6dd45ebcbb66dacffe03547fadbb0eeae2770887d" - -[[package]] -name = "volatile-register" -version = "0.2.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9ee8f19f9d74293faf70901bc20ad067dc1ad390d2cbf1e3f75f721ffee908b6" -dependencies = [ - "vcell", -] - -[[package]] -name = "wait-timeout" -version = "0.2.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9f200f5b12eb75f8c1ed65abd4b2db8a6e1b138a20de009dacee265a2498f3f6" -dependencies = [ - "libc", -] - -[[package]] -name = "wasi" -version = "0.11.0+wasi-snapshot-preview1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "9c8d87e72b64a3b4db28d11ce29237c246188f4f51057d65a7eab63b7987e423" - -[[package]] -name = "winapi" -version = "0.3.9" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "5c839a674fcd7a98952e593242ea400abe93992746761e38641405d28b00f419" -dependencies = [ - "winapi-i686-pc-windows-gnu", - "winapi-x86_64-pc-windows-gnu", -] - -[[package]] -name = "winapi-i686-pc-windows-gnu" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "ac3b87c63620426dd9b991e5ce0329eff545bccbbb34f3be09ff6fb6ab51b7b6" - -[[package]] -name = "winapi-util" -version = "0.1.5" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "70ec6ce85bb158151cae5e5c87f95a8e97d2c0c4b001223f33a334e3ce5de178" -dependencies = [ - "winapi", -] - -[[package]] -name = "winapi-x86_64-pc-windows-gnu" -version = "0.4.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "712e227841d057c1ee1cd2fb22fa7e5a5461ae8e48fa2ca79ec42cfc1931183f" - -[[package]] -name = "windows-sys" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "677d2418bec65e3338edb076e806bc1ec15693c5d0104683f2efe857f61056a9" -dependencies = [ - "windows-targets", -] - -[[package]] -name = "windows-targets" -version = "0.48.1" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "05d4b17490f70499f20b9e791dcf6a299785ce8af4d709018206dc5b4953e95f" -dependencies = [ - "windows_aarch64_gnullvm", - "windows_aarch64_msvc", - "windows_i686_gnu", - "windows_i686_msvc", - "windows_x86_64_gnu", - "windows_x86_64_gnullvm", - "windows_x86_64_msvc", -] - -[[package]] -name = "windows_aarch64_gnullvm" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "91ae572e1b79dba883e0d315474df7305d12f569b400fcf90581b06062f7e1bc" - -[[package]] -name = "windows_aarch64_msvc" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "b2ef27e0d7bdfcfc7b868b317c1d32c641a6fe4629c171b8928c7b08d98d7cf3" - -[[package]] -name = "windows_i686_gnu" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "622a1962a7db830d6fd0a69683c80a18fda201879f0f447f065a3b7467daa241" - -[[package]] -name = "windows_i686_msvc" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "4542c6e364ce21bf45d69fdd2a8e455fa38d316158cfd43b3ac1c5b1b19f8e00" - -[[package]] -name = "windows_x86_64_gnu" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "ca2b8a661f7628cbd23440e50b05d705db3686f894fc9580820623656af974b1" - -[[package]] -name = "windows_x86_64_gnullvm" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "7896dbc1f41e08872e9d5e8f8baa8fdd2677f29468c4e156210174edc7f7b953" - -[[package]] -name = "windows_x86_64_msvc" -version = "0.48.0" -source = "registry+https://github.com/rust-lang/crates.io-index" -checksum = "1a515f5799fe4961cb532f983ce2b23082366b898e52ffbce459c86f67c8378a" +# This file is automatically @generated by Cargo. +# It is not intended for manual editing. +version = 3 + +[[package]] +name = "Inflector" +version = "0.11.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "fe438c63458706e03479442743baae6c88256498e6431708f6dfc520a26515d3" + +[[package]] +name = "aes" +version = "0.7.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9e8b47f52ea9bae42228d07ec09eb676433d7c4ed1ebdf0f1d1c29ed446f1ab8" +dependencies = [ + "cfg-if", + "cipher", + "cpufeatures", + "opaque-debug", +] + +[[package]] +name = "atomic-polyfill" +version = "0.1.11" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e3ff7eb3f316534d83a8a2c3d1674ace8a5a71198eba31e2e2b597833f699b28" +dependencies = [ + "critical-section", +] + +[[package]] +name = "atsamd-hal" +version = "0.16.0" +source = "git+https://github.com/atsamd-rs/atsamd#0820f0df58eb8705ddfa6533ed76953d18e6b992" +dependencies = [ + "aes", + "atsame51j", + "bitfield 0.13.2", + "bitflags 1.3.2", + "cipher", + "cortex-m", + "embedded-hal", + "fugit", + "mcan-core", + "modular-bitfield", + "nb 1.1.0", + "num-traits", + "opaque-debug", + "paste", + "rand_core", + "seq-macro", + "typenum", + "vcell", + "void", +] + +[[package]] +name = "atsame51j" +version = "0.12.0" +source = "git+https://github.com/atsamd-rs/atsamd#0820f0df58eb8705ddfa6533ed76953d18e6b992" +dependencies = [ + "cortex-m", + "cortex-m-rt", + "vcell", +] + +[[package]] +name = "autocfg" +version = "1.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d468802bab17cbc0cc575e9b053f41e72aa36bfa6b7f55e3529ffa43161b97fa" + +[[package]] +name = "bare-metal" +version = "0.2.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5deb64efa5bd81e31fcd1938615a6d98c82eafcbcd787162b6f63b91d6bac5b3" +dependencies = [ + "rustc_version 0.2.3", +] + +[[package]] +name = "bare-metal" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f8fe8f5a8a398345e52358e18ff07cc17a568fbca5c6f73873d3a62056309603" + +[[package]] +name = "bit-set" +version = "0.5.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "0700ddab506f33b20a03b13996eccd309a48e5ff77d0d95926aa0210fb4e95f1" +dependencies = [ + "bit-vec", +] + +[[package]] +name = "bit-vec" +version = "0.6.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "349f9b6a179ed607305526ca489b34ad0a41aed5f7980fa90eb03160b69598fb" + +[[package]] +name = "bitfield" +version = "0.13.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "46afbd2983a5d5a7bd740ccb198caf5b82f45c40c09c0eed36052d91cb92e719" + +[[package]] +name = "bitfield" +version = "0.14.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "2d7e60934ceec538daadb9d8432424ed043a904d8e0243f3c6446bce549a46ac" + +[[package]] +name = "bitflags" +version = "1.3.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bef38d45163c2f1dde094a7dfd33ccf595c92905c8f8f4fdc18d06fb1037718a" + +[[package]] +name = "bitflags" +version = "2.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b4682ae6287fcf752ecaabbfcc7b6f9b72aa33933dc23a554d853aea8eea8635" + +[[package]] +name = "byteorder" +version = "1.4.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "14c189c53d098945499cdfa7ecc63567cf3886b3332b312a5b4585d8d3a6a610" + +[[package]] +name = "camera" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "cortex-m-rtic", + "defmt", + "enum_dispatch", + "heapless", + "messages", + "panic-halt", + "postcard", + "systick-monotonic", + "typenum", +] + +[[package]] +name = "cc" +version = "1.0.82" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "305fe645edc1442a0fa8b6726ba61d422798d37a52e12eaecf4b022ebbb88f01" +dependencies = [ + "libc", +] + +[[package]] +name = "cfg-if" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "baf1de4339761588bc0619e3cbc0120ee582ebb74b53b4efbf79117bd2da40fd" + +[[package]] +name = "cipher" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7ee52072ec15386f770805afd189a01c8841be8696bed250fa2f13c4c0d6dfb7" +dependencies = [ + "generic-array", +] + +[[package]] +name = "cmake" +version = "0.1.50" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a31c789563b815f77f4250caee12365734369f942439b7defd71e18a48197130" +dependencies = [ + "cc", +] + +[[package]] +name = "cobs" +version = "0.2.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "67ba02a97a2bd10f4b59b25c7973101c79642302776489e030cd13cdab09ed15" + +[[package]] +name = "common-arm" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "cortex-m", + "cortex-m-rt", + "defmt", + "defmt-rtt", + "derive_more", + "embedded-hal", + "embedded-sdmmc", + "heapless", + "mcan", + "messages", + "nb 1.1.0", + "postcard", +] + +[[package]] +name = "common-arm-test" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "defmt", + "defmt-rtt", + "defmt-test", + "panic-probe", +] + +[[package]] +name = "communication" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "cortex-m-rtic", + "defmt", + "embedded-sdmmc", + "heapless", + "messages", + "panic-halt", + "postcard", + "systick-monotonic", + "typenum", +] + +[[package]] +name = "convert_case" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6245d59a3e82a7fc217c5828a6692dbc6dfb63a0c8c90495621f7b9d79704a0e" + +[[package]] +name = "cortex-m" +version = "0.7.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8ec610d8f49840a5b376c69663b6369e71f4b34484b9b2eb29fb918d92516cb9" +dependencies = [ + "bare-metal 0.2.5", + "bitfield 0.13.2", + "critical-section", + "embedded-hal", + "volatile-register", +] + +[[package]] +name = "cortex-m-rt" +version = "0.7.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ee84e813d593101b1723e13ec38b6ab6abbdbaaa4546553f5395ed274079ddb1" +dependencies = [ + "cortex-m-rt-macros", +] + +[[package]] +name = "cortex-m-rt-macros" +version = "0.7.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f0f6f3e36f203cfedbc78b357fb28730aa2c6dc1ab060ee5c2405e843988d3c7" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", +] + +[[package]] +name = "cortex-m-rtic" +version = "1.1.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d696ae7390bdb9f7978f71ca7144256a2c4616240a6df9002da3c451f9fc8f02" +dependencies = [ + "bare-metal 1.0.0", + "cortex-m", + "cortex-m-rtic-macros", + "heapless", + "rtic-core", + "rtic-monotonic", + "version_check", +] + +[[package]] +name = "cortex-m-rtic-macros" +version = "1.1.6" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "eefb40b1ca901c759d29526e5c8a0a1b246c20caaa5b4cc5d0f0b94debecd4c7" +dependencies = [ + "proc-macro-error", + "proc-macro2 1.0.66", + "quote 1.0.32", + "rtic-syntax", + "syn 1.0.109", +] + +[[package]] +name = "cpufeatures" +version = "0.2.9" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a17b76ff3a4162b0b27f354a0c87015ddad39d35f9c0c36607a3bdd175dde1f1" +dependencies = [ + "libc", +] + +[[package]] +name = "crc-any" +version = "2.4.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "774646b687f63643eb0f4bf13dc263cb581c8c9e57973b6ddf78bda3994d88df" + +[[package]] +name = "critical-section" +version = "1.1.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7059fff8937831a9ae6f0fe4d658ffabf58f2ca96aa9dec1c889f936f705f216" + +[[package]] +name = "defmt" +version = "0.3.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a8a2d011b2fee29fb7d659b83c43fce9a2cb4df453e16d441a51448e448f3f98" +dependencies = [ + "bitflags 1.3.2", + "defmt-macros", +] + +[[package]] +name = "defmt-macros" +version = "0.3.6" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "54f0216f6c5acb5ae1a47050a6645024e6edafc2ee32d421955eccfef12ef92e" +dependencies = [ + "defmt-parser", + "proc-macro-error", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 2.0.28", +] + +[[package]] +name = "defmt-parser" +version = "0.3.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "269924c02afd7f94bc4cecbfa5c379f6ffcf9766b3408fe63d22c728654eccd0" +dependencies = [ + "thiserror", +] + +[[package]] +name = "defmt-rtt" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "609923761264dd99ed9c7d209718cda4631c5fe84668e0f0960124cbb844c49f" +dependencies = [ + "critical-section", + "defmt", +] + +[[package]] +name = "defmt-test" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4df24f1ca104a0c1bce2047d8a21aa9fa29695e5d662118eb48daedb97edca88" +dependencies = [ + "cortex-m", + "cortex-m-rt", + "defmt", + "defmt-test-macros", +] + +[[package]] +name = "defmt-test-macros" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "94a0dfea4063d72e1ba20494dfbc4667f67420869328cf3670b5824a38a22dc1" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", +] + +[[package]] +name = "derive_more" +version = "0.99.17" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4fb810d30a7c1953f91334de7244731fc3f3c10d7fe163338a35b9f640960321" +dependencies = [ + "convert_case", + "proc-macro2 1.0.66", + "quote 1.0.32", + "rustc_version 0.4.0", + "syn 1.0.109", +] + +[[package]] +name = "embedded-alloc" +version = "0.5.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8931e47e33c5d3194fbcf9cc82df0919193bd2fa40008f388eb1d28fd9c9ea6b" +dependencies = [ + "critical-section", + "linked_list_allocator", +] + +[[package]] +name = "embedded-can" +version = "0.4.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e9d2e857f87ac832df68fa498d18ddc679175cf3d2e4aa893988e5601baf9438" +dependencies = [ + "nb 1.1.0", +] + +[[package]] +name = "embedded-hal" +version = "0.2.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "35949884794ad573cf46071e41c9b60efb0cb311e3ca01f7af807af1debc66ff" +dependencies = [ + "nb 0.1.3", + "void", +] + +[[package]] +name = "embedded-sdmmc" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6d3bf0a2b5becb87e9a329d9290f131e4d10fec39b56d129926826a7cbea1e7a" +dependencies = [ + "byteorder", + "embedded-hal", + "log", + "nb 0.1.3", +] + +[[package]] +name = "enum_dispatch" +version = "0.3.12" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8f33313078bb8d4d05a2733a94ac4c2d8a0df9a2b84424ebf4f33bfc224a890e" +dependencies = [ + "once_cell", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 2.0.28", +] + +[[package]] +name = "errno" +version = "0.3.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6b30f669a7961ef1631673d2766cc92f52d64f7ef354d4fe0ddfd30ed52f0f4f" +dependencies = [ + "errno-dragonfly", + "libc", + "windows-sys", +] + +[[package]] +name = "errno-dragonfly" +version = "0.1.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "aa68f1b12764fab894d2755d2518754e71b4fd80ecfb822714a1206c2aab39bf" +dependencies = [ + "cc", + "libc", +] + +[[package]] +name = "fastrand" +version = "2.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6999dc1837253364c2ebb0704ba97994bd874e8f195d665c50b7548f6ea92764" + +[[package]] +name = "fnv" +version = "1.0.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3f9eec918d3f24069decb9af1554cad7c880e2da24a9afd88aca000531ab82c1" + +[[package]] +name = "fugit" +version = "0.3.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "17186ad64927d5ac8f02c1e77ccefa08ccd9eaa314d5a4772278aa204a22f7e7" +dependencies = [ + "gcd", +] + +[[package]] +name = "gcd" +version = "2.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1d758ba1b47b00caf47f24925c0074ecb20d6dfcffe7f6d53395c0465674841a" + +[[package]] +name = "generic-array" +version = "0.14.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "85649ca51fd72272d7821adaf274ad91c288277713d9c18820d8499a7ff69e9a" +dependencies = [ + "typenum", + "version_check", +] + +[[package]] +name = "getrandom" +version = "0.2.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "be4136b2a15dd319360be1c07d9933517ccf0be8f16bf62a3bee4f0d618df427" +dependencies = [ + "cfg-if", + "libc", + "wasi", +] + +[[package]] +name = "hash32" +version = "0.2.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b0c35f58762feb77d74ebe43bdbc3210f09be9fe6742234d573bacc26ed92b67" +dependencies = [ + "byteorder", +] + +[[package]] +name = "hashbrown" +version = "0.12.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8a9ee70c43aaf417c914396645a0fa852624801b24ebb7ae78fe8272889ac888" + +[[package]] +name = "heapless" +version = "0.7.16" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "db04bc24a18b9ea980628ecf00e6c0264f3c1426dac36c00cb49b6fbad8b0743" +dependencies = [ + "atomic-polyfill", + "hash32", + "rustc_version 0.4.0", + "serde", + "spin", + "stable_deref_trait", +] + +[[package]] +name = "indexmap" +version = "1.9.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bd070e393353796e801d209ad339e89596eb4c8d430d18ede6a1cced8fafbd99" +dependencies = [ + "autocfg", + "hashbrown", +] + +[[package]] +name = "ioctl-rs" +version = "0.1.6" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f7970510895cee30b3e9128319f2cefd4bde883a39f38baa279567ba3a7eb97d" +dependencies = [ + "libc", +] + +[[package]] +name = "lazy_static" +version = "1.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e2abad23fbc42b3700f2f279844dc832adb2b2eb069b2df918f455c4e18cc646" + +[[package]] +name = "libc" +version = "0.2.147" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b4668fb0ea861c1df094127ac5f1da3409a82116a4ba74fca2e58ef927159bb3" + +[[package]] +name = "libm" +version = "0.2.7" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f7012b1bbb0719e1097c47611d3898568c546d597c2e74d66f6087edd5233ff4" + +[[package]] +name = "linked_list_allocator" +version = "0.10.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9afa463f5405ee81cdb9cc2baf37e08ec7e4c8209442b5d72c04cfb2cd6e6286" + +[[package]] +name = "linux-raw-sys" +version = "0.4.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "57bcfdad1b858c2db7c38303a6d2ad4dfaf5eb53dfeb0910128b2c26d6158503" + +[[package]] +name = "lock_api" +version = "0.4.10" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "c1cc9717a20b1bb222f333e6a92fd32f7d8a18ddc5a3191a11af45dcbf4dcd16" +dependencies = [ + "autocfg", + "scopeguard", +] + +[[package]] +name = "log" +version = "0.4.20" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b5e6163cb8c49088c2c36f57875e58ccd8c87c7427f7fbd50ea6710b2f3f2e8f" + +[[package]] +name = "mavlink" +version = "0.11.1" +source = "git+https://github.com/uorocketry/rust-mavlink?branch=hydra_dialect#0e0bedd0f37ccad490ea693ad80c2ecffb3d6351" +dependencies = [ + "bitflags 1.3.2", + "byteorder", + "crc-any", + "embedded-hal", + "heapless", + "lazy_static", + "nb 1.1.0", + "num-derive", + "num-traits", + "proc-macro2 1.0.66", + "quick-xml", + "quote 1.0.32", + "serde", + "serial", +] + +[[package]] +name = "mcan" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1db1ad48f562b804bfe83828dc0d87622ea96bdc435a8513ecaa45a5f88d2f2f" +dependencies = [ + "bitfield 0.14.0", + "embedded-can", + "fugit", + "generic-array", + "mcan-core", + "nb 1.1.0", + "vcell", +] + +[[package]] +name = "mcan-core" +version = "0.2.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8b3dee4ff5269e2465cc856d37103cce916c1ef73b4377f006c963872e69f7ca" +dependencies = [ + "fugit", +] + +[[package]] +name = "memchr" +version = "2.5.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "2dffe52ecf27772e601905b7522cb4ef790d2cc203488bbd0e2fe85fcb74566d" + +[[package]] +name = "messages" +version = "0.1.0" +dependencies = [ + "defmt", + "derive_more", + "fugit", + "heapless", + "mavlink", + "postcard", + "proptest", + "proptest-derive", + "serde", + "ts-rs", +] + +[[package]] +name = "modular-bitfield" +version = "0.11.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a53d79ba8304ac1c4f9eb3b9d281f21f7be9d4626f72ce7df4ad8fbde4f38a74" +dependencies = [ + "modular-bitfield-impl", + "static_assertions", +] + +[[package]] +name = "modular-bitfield-impl" +version = "0.11.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5a7d5f7076603ebc68de2dc6a650ec331a062a13abaa346975be747bbfa4b789" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", +] + +[[package]] +name = "nb" +version = "0.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "801d31da0513b6ec5214e9bf433a77966320625a37860f910be265be6e18d06f" +dependencies = [ + "nb 1.1.0", +] + +[[package]] +name = "nb" +version = "1.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "8d5439c4ad607c3c23abf66de8c8bf57ba8adcd1f129e699851a6e43935d339d" + +[[package]] +name = "num-derive" +version = "0.3.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "876a53fff98e03a936a674b29568b0e605f06b29372c2489ff4de23f1949743d" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", +] + +[[package]] +name = "num-traits" +version = "0.2.16" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f30b0abd723be7e2ffca1272140fac1a2f084c77ec3e123c192b66af1ee9e6c2" +dependencies = [ + "autocfg", + "libm", +] + +[[package]] +name = "once_cell" +version = "1.18.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "dd8b5dd2ae5ed71462c540258bedcb51965123ad7e7ccf4b9a8cafaa4a63576d" + +[[package]] +name = "opaque-debug" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "624a8340c38c1b80fd549087862da4ba43e08858af025b236e509b6649fc13d5" + +[[package]] +name = "panic-halt" +version = "0.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "de96540e0ebde571dc55c73d60ef407c653844e6f9a1e2fdbd40c07b9252d812" + +[[package]] +name = "panic-probe" +version = "0.3.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "aa6fa5645ef5a760cd340eaa92af9c1ce131c8c09e7f8926d8a24b59d26652b9" +dependencies = [ + "cortex-m", + "defmt", +] + +[[package]] +name = "paste" +version = "1.0.14" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "de3145af08024dea9fa9914f381a17b8fc6034dfb00f3a84013f7ff43f29ed4c" + +[[package]] +name = "postcard" +version = "1.0.6" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "c9ee729232311d3cd113749948b689627618133b1c5012b77342c1950b25eaeb" +dependencies = [ + "cobs", + "defmt", + "heapless", + "serde", +] + +[[package]] +name = "power" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "cortex-m-rtic", + "defmt", + "enum_dispatch", + "heapless", + "messages", + "panic-halt", + "postcard", + "systick-monotonic", + "typenum", +] + +[[package]] +name = "ppv-lite86" +version = "0.2.17" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5b40af805b3121feab8a3c29f04d8ad262fa8e0561883e7653e024ae4479e6de" + +[[package]] +name = "proc-macro-error" +version = "1.0.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "da25490ff9892aab3fcf7c36f08cfb902dd3e71ca0f9f9517bea02a73a5ce38c" +dependencies = [ + "proc-macro-error-attr", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", + "version_check", +] + +[[package]] +name = "proc-macro-error-attr" +version = "1.0.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a1be40180e52ecc98ad80b184934baf3d0d29f979574e439af5a55274b35f869" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "version_check", +] + +[[package]] +name = "proc-macro2" +version = "0.4.30" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "cf3d2011ab5c909338f7887f4fc896d35932e29146c12c8d01da6b22a80ba759" +dependencies = [ + "unicode-xid", +] + +[[package]] +name = "proc-macro2" +version = "1.0.66" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "18fb31db3f9bddb2ea821cde30a9f70117e3f119938b5ee630b7403aa6e2ead9" +dependencies = [ + "unicode-ident", +] + +[[package]] +name = "proptest" +version = "1.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4e35c06b98bf36aba164cc17cb25f7e232f5c4aeea73baa14b8a9f0d92dbfa65" +dependencies = [ + "bit-set", + "bitflags 1.3.2", + "byteorder", + "lazy_static", + "num-traits", + "rand", + "rand_chacha", + "rand_xorshift", + "regex-syntax", + "rusty-fork", + "tempfile", + "unarray", +] + +[[package]] +name = "proptest-derive" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "90b46295382dc76166cb7cf2bb4a97952464e4b7ed5a43e6cd34e1fec3349ddc" +dependencies = [ + "proc-macro2 0.4.30", + "quote 0.6.13", + "syn 0.15.44", +] + +[[package]] +name = "quick-error" +version = "1.2.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a1d01941d82fa2ab50be1e79e6714289dd7cde78eba4c074bc5a4374f650dfe0" + +[[package]] +name = "quick-xml" +version = "0.26.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7f50b1c63b38611e7d4d7f68b82d3ad0cc71a2ad2e7f61fc10f1328d917c93cd" +dependencies = [ + "memchr", +] + +[[package]] +name = "quote" +version = "0.6.13" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6ce23b6b870e8f94f81fb0a363d65d86675884b34a09043c81e5562f11c1f8e1" +dependencies = [ + "proc-macro2 0.4.30", +] + +[[package]] +name = "quote" +version = "1.0.32" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "50f3b39ccfb720540debaa0164757101c08ecb8d326b15358ce76a62c7e85965" +dependencies = [ + "proc-macro2 1.0.66", +] + +[[package]] +name = "rand" +version = "0.8.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "34af8d1a0e25924bc5b7c43c079c942339d8f0a8b57c39049bef581b46327404" +dependencies = [ + "libc", + "rand_chacha", + "rand_core", +] + +[[package]] +name = "rand_chacha" +version = "0.3.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "e6c10a63a0fa32252be49d21e7709d4d4baf8d231c2dbce1eaa8141b9b127d88" +dependencies = [ + "ppv-lite86", + "rand_core", +] + +[[package]] +name = "rand_core" +version = "0.6.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ec0be4795e2f6a28069bec0b5ff3e2ac9bafc99e6a9a7dc3547996c5c816922c" +dependencies = [ + "getrandom", +] + +[[package]] +name = "rand_xorshift" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d25bf25ec5ae4a3f1b92f929810509a2f53d7dca2f50b794ff57e3face536c8f" +dependencies = [ + "rand_core", +] + +[[package]] +name = "recovery" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "cortex-m-rtic", + "defmt", + "enum_dispatch", + "heapless", + "messages", + "panic-halt", + "postcard", + "systick-monotonic", + "typenum", +] + +[[package]] +name = "redox_syscall" +version = "0.3.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "567664f262709473930a4bf9e51bf2ebf3348f2e748ccc50dea20646858f8f29" +dependencies = [ + "bitflags 1.3.2", +] + +[[package]] +name = "regex-syntax" +version = "0.6.29" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f162c6dd7b008981e4d40210aca20b4bd0f9b60ca9271061b07f78537722f2e1" + +[[package]] +name = "rtic-core" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d9369355b04d06a3780ec0f51ea2d225624db777acbc60abd8ca4832da5c1a42" + +[[package]] +name = "rtic-monotonic" +version = "1.0.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "fb8b0b822d1a366470b9cea83a1d4e788392db763539dc4ba022bcc787fece82" + +[[package]] +name = "rtic-syntax" +version = "1.0.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5f5e215601dc467752c2bddc6284a622c6f3d2bab569d992adcd5ab7e4cb9478" +dependencies = [ + "indexmap", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", +] + +[[package]] +name = "rtic_example" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "cortex-m-rtic", + "defmt", + "defmt-rtt", + "fugit", + "heapless", + "messages", + "panic-halt", + "postcard", + "systick-monotonic", + "typenum", +] + +[[package]] +name = "rustc_version" +version = "0.2.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "138e3e0acb6c9fb258b19b67cb8abd63c00679d2851805ea151465464fe9030a" +dependencies = [ + "semver 0.9.0", +] + +[[package]] +name = "rustc_version" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "bfa0f585226d2e68097d4f95d113b15b83a82e819ab25717ec0590d9584ef366" +dependencies = [ + "semver 1.0.18", +] + +[[package]] +name = "rustix" +version = "0.38.8" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "19ed4fa021d81c8392ce04db050a3da9a60299050b7ae1cf482d862b54a7218f" +dependencies = [ + "bitflags 2.4.0", + "errno", + "libc", + "linux-raw-sys", + "windows-sys", +] + +[[package]] +name = "rusty-fork" +version = "0.3.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "cb3dcc6e454c328bb824492db107ab7c0ae8fcffe4ad210136ef014458c1bc4f" +dependencies = [ + "fnv", + "quick-error", + "tempfile", + "wait-timeout", +] + +[[package]] +name = "sbg-rs" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "cmake", + "common-arm", + "cortex-m", + "cortex-m-rt", + "defmt", + "embedded-hal", + "heapless", + "messages", + "nb 1.1.0", +] + +[[package]] +name = "scopeguard" +version = "1.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "94143f37725109f92c262ed2cf5e59bce7498c01bcc1502d7b9afe439a4e9f49" + +[[package]] +name = "semver" +version = "0.9.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1d7eb9ef2c18661902cc47e535f9bc51b78acd254da71d375c2f6720d9a40403" +dependencies = [ + "semver-parser", +] + +[[package]] +name = "semver" +version = "1.0.18" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b0293b4b29daaf487284529cc2f5675b8e57c61f70167ba415a463651fd6a918" + +[[package]] +name = "semver-parser" +version = "0.7.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "388a1df253eca08550bef6c72392cfe7c30914bf41df5269b68cbd6ff8f570a3" + +[[package]] +name = "sensor" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "cortex-m-rtic", + "defmt", + "embedded-alloc", + "embedded-sdmmc", + "heapless", + "messages", + "panic-halt", + "postcard", + "sbg-rs", + "systick-monotonic", + "typenum", +] + +[[package]] +name = "seq-macro" +version = "0.3.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a3f0bf26fd526d2a95683cd0f87bf103b8539e2ca1ef48ce002d67aad59aa0b4" + +[[package]] +name = "serde" +version = "1.0.183" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "32ac8da02677876d532745a130fc9d8e6edfa81a269b107c5b00829b91d8eb3c" +dependencies = [ + "serde_derive", +] + +[[package]] +name = "serde_derive" +version = "1.0.183" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "aafe972d60b0b9bee71a91b92fee2d4fb3c9d7e8f6b179aa99f27203d99a4816" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 2.0.28", +] + +[[package]] +name = "serial" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a1237a96570fc377c13baa1b88c7589ab66edced652e43ffb17088f003db3e86" +dependencies = [ + "serial-core", + "serial-unix", + "serial-windows", +] + +[[package]] +name = "serial-core" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "3f46209b345401737ae2125fe5b19a77acce90cd53e1658cda928e4fe9a64581" +dependencies = [ + "libc", +] + +[[package]] +name = "serial-unix" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f03fbca4c9d866e24a459cbca71283f545a37f8e3e002ad8c70593871453cab7" +dependencies = [ + "ioctl-rs", + "libc", + "serial-core", + "termios", +] + +[[package]] +name = "serial-windows" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "15c6d3b776267a75d31bbdfd5d36c0ca051251caafc285827052bc53bcdc8162" +dependencies = [ + "libc", + "serial-core", +] + +[[package]] +name = "simple_example" +version = "0.1.0" +dependencies = [ + "atsamd-hal", + "common-arm", + "cortex-m", + "cortex-m-rt", + "defmt", + "defmt-rtt", + "panic-halt", +] + +[[package]] +name = "spin" +version = "0.9.8" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6980e8d7511241f8acf4aebddbb1ff938df5eebe98691418c4468d0b72a96a67" +dependencies = [ + "lock_api", +] + +[[package]] +name = "stable_deref_trait" +version = "1.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a8f112729512f8e442d81f95a8a7ddf2b7c6b8a1a6f509a95864142b30cab2d3" + +[[package]] +name = "static_assertions" +version = "1.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "a2eb9349b6444b326872e140eb1cf5e7c522154d69e7a0ffb0fb81c06b37543f" + +[[package]] +name = "syn" +version = "0.15.44" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9ca4b3b69a77cbe1ffc9e198781b7acb0c7365a883670e8f1c1bc66fba79a5c5" +dependencies = [ + "proc-macro2 0.4.30", + "quote 0.6.13", + "unicode-xid", +] + +[[package]] +name = "syn" +version = "1.0.109" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "72b64191b275b66ffe2469e8af2c1cfe3bafa67b529ead792a6d0160888b4237" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "unicode-ident", +] + +[[package]] +name = "syn" +version = "2.0.28" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "04361975b3f5e348b2189d8dc55bc942f278b2d482a6a0365de5bdd62d351567" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "unicode-ident", +] + +[[package]] +name = "systick-monotonic" +version = "1.0.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "67fb822d5c615a0ae3a4795ee5b1d06381c7faf488d861c0a4fa8e6a88d5ff84" +dependencies = [ + "cortex-m", + "fugit", + "rtic-monotonic", +] + +[[package]] +name = "tempfile" +version = "3.7.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "dc02fddf48964c42031a0b3fe0428320ecf3a73c401040fc0096f97794310651" +dependencies = [ + "cfg-if", + "fastrand", + "redox_syscall", + "rustix", + "windows-sys", +] + +[[package]] +name = "termcolor" +version = "1.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "be55cf8942feac5c765c2c993422806843c9a9a45d4d5c407ad6dd2ea95eb9b6" +dependencies = [ + "winapi-util", +] + +[[package]] +name = "termios" +version = "0.2.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "d5d9cf598a6d7ce700a4e6a9199da127e6819a61e64b68609683cc9a01b5683a" +dependencies = [ + "libc", +] + +[[package]] +name = "thiserror" +version = "1.0.44" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "611040a08a0439f8248d1990b111c95baa9c704c805fa1f62104b39655fd7f90" +dependencies = [ + "thiserror-impl", +] + +[[package]] +name = "thiserror-impl" +version = "1.0.44" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "090198534930841fab3a5d1bb637cde49e339654e606195f8d9c76eeb081dc96" +dependencies = [ + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 2.0.28", +] + +[[package]] +name = "ts-rs" +version = "6.2.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4added4070a4fdf9df03457206cd2e4b12417c8560a2954d91ffcbe60177a56a" +dependencies = [ + "thiserror", + "ts-rs-macros", +] + +[[package]] +name = "ts-rs-macros" +version = "6.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9f807fdb3151fee75df7485b901a89624358cd07a67a8fb1a5831bf5a07681ff" +dependencies = [ + "Inflector", + "proc-macro2 1.0.66", + "quote 1.0.32", + "syn 1.0.109", + "termcolor", +] + +[[package]] +name = "typenum" +version = "1.16.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "497961ef93d974e23eb6f433eb5fe1b7930b659f06d12dec6fc44a8f554c0bba" + +[[package]] +name = "unarray" +version = "0.1.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "eaea85b334db583fe3274d12b4cd1880032beab409c0d774be044d4480ab9a94" + +[[package]] +name = "unicode-ident" +version = "1.0.11" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "301abaae475aa91687eb82514b328ab47a211a533026cb25fc3e519b86adfc3c" + +[[package]] +name = "unicode-xid" +version = "0.1.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "fc72304796d0818e357ead4e000d19c9c174ab23dc11093ac919054d20a6a7fc" + +[[package]] +name = "vcell" +version = "0.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "77439c1b53d2303b20d9459b1ade71a83c716e3f9c34f3228c00e6f185d6c002" + +[[package]] +name = "version_check" +version = "0.9.4" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "49874b5167b65d7193b8aba1567f5c7d93d001cafc34600cee003eda787e483f" + +[[package]] +name = "void" +version = "1.0.2" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "6a02e4885ed3bc0f2de90ea6dd45ebcbb66dacffe03547fadbb0eeae2770887d" + +[[package]] +name = "volatile-register" +version = "0.2.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9ee8f19f9d74293faf70901bc20ad067dc1ad390d2cbf1e3f75f721ffee908b6" +dependencies = [ + "vcell", +] + +[[package]] +name = "wait-timeout" +version = "0.2.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9f200f5b12eb75f8c1ed65abd4b2db8a6e1b138a20de009dacee265a2498f3f6" +dependencies = [ + "libc", +] + +[[package]] +name = "wasi" +version = "0.11.0+wasi-snapshot-preview1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "9c8d87e72b64a3b4db28d11ce29237c246188f4f51057d65a7eab63b7987e423" + +[[package]] +name = "winapi" +version = "0.3.9" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "5c839a674fcd7a98952e593242ea400abe93992746761e38641405d28b00f419" +dependencies = [ + "winapi-i686-pc-windows-gnu", + "winapi-x86_64-pc-windows-gnu", +] + +[[package]] +name = "winapi-i686-pc-windows-gnu" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ac3b87c63620426dd9b991e5ce0329eff545bccbbb34f3be09ff6fb6ab51b7b6" + +[[package]] +name = "winapi-util" +version = "0.1.5" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "70ec6ce85bb158151cae5e5c87f95a8e97d2c0c4b001223f33a334e3ce5de178" +dependencies = [ + "winapi", +] + +[[package]] +name = "winapi-x86_64-pc-windows-gnu" +version = "0.4.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "712e227841d057c1ee1cd2fb22fa7e5a5461ae8e48fa2ca79ec42cfc1931183f" + +[[package]] +name = "windows-sys" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "677d2418bec65e3338edb076e806bc1ec15693c5d0104683f2efe857f61056a9" +dependencies = [ + "windows-targets", +] + +[[package]] +name = "windows-targets" +version = "0.48.1" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "05d4b17490f70499f20b9e791dcf6a299785ce8af4d709018206dc5b4953e95f" +dependencies = [ + "windows_aarch64_gnullvm", + "windows_aarch64_msvc", + "windows_i686_gnu", + "windows_i686_msvc", + "windows_x86_64_gnu", + "windows_x86_64_gnullvm", + "windows_x86_64_msvc", +] + +[[package]] +name = "windows_aarch64_gnullvm" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "91ae572e1b79dba883e0d315474df7305d12f569b400fcf90581b06062f7e1bc" + +[[package]] +name = "windows_aarch64_msvc" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "b2ef27e0d7bdfcfc7b868b317c1d32c641a6fe4629c171b8928c7b08d98d7cf3" + +[[package]] +name = "windows_i686_gnu" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "622a1962a7db830d6fd0a69683c80a18fda201879f0f447f065a3b7467daa241" + +[[package]] +name = "windows_i686_msvc" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "4542c6e364ce21bf45d69fdd2a8e455fa38d316158cfd43b3ac1c5b1b19f8e00" + +[[package]] +name = "windows_x86_64_gnu" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "ca2b8a661f7628cbd23440e50b05d705db3686f894fc9580820623656af974b1" + +[[package]] +name = "windows_x86_64_gnullvm" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "7896dbc1f41e08872e9d5e8f8baa8fdd2677f29468c4e156210174edc7f7b953" + +[[package]] +name = "windows_x86_64_msvc" +version = "0.48.0" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "1a515f5799fe4961cb532f983ce2b23082366b898e52ffbce459c86f67c8378a" diff --git a/boards/camera/Cargo.toml b/boards/camera/Cargo.toml new file mode 100644 index 00000000..371fdbc6 --- /dev/null +++ b/boards/camera/Cargo.toml @@ -0,0 +1,21 @@ +[package] +name = "camera" +version = "0.1.0" +edition = "2021" + +# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html + +[dependencies] +cortex-m = { workspace = true } +cortex-m-rt = "^0.7.0" +cortex-m-rtic = "1.1.3" +panic-halt = "0.2.0" +systick-monotonic = "1.0.1" +defmt = "0.3.2" +postcard = "1.0.2" +heapless = "0.7.16" +common-arm = { path = "../../libraries/common-arm" } +atsamd-hal = { workspace = true } +messages = { path = "../../libraries/messages" } +typenum = "1.16.0" +enum_dispatch = "0.3.11" \ No newline at end of file diff --git a/boards/camera/src/communication.rs b/boards/camera/src/communication.rs new file mode 100644 index 00000000..34281ace --- /dev/null +++ b/boards/camera/src/communication.rs @@ -0,0 +1,187 @@ +use crate::data_manager::DataManager; +use crate::types::*; +use atsamd_hal::can::Dependencies; +use atsamd_hal::clock::v2::ahb::AhbClk; +use atsamd_hal::clock::v2::gclk::Gclk0Id; +use atsamd_hal::clock::v2::pclk::Pclk; +use atsamd_hal::clock::v2::pclk::PclkToken; +use atsamd_hal::clock::v2::types::Can0; +use atsamd_hal::clock::v2::Source; +use atsamd_hal::dmac; +use atsamd_hal::gpio::{Alternate, AlternateI, Disabled, Floating, Pin, I, PA22, PA23, PB16, PB17}; +use atsamd_hal::pac::CAN0; +use atsamd_hal::pac::MCLK; +use atsamd_hal::pac::SERCOM5; +use atsamd_hal::sercom::Sercom; +use atsamd_hal::sercom::{uart, Sercom5}; +use atsamd_hal::sercom; +use atsamd_hal::sercom::uart::{ TxDuplex, RxDuplex}; +use atsamd_hal::sercom::uart::{Duplex, Uart}; +use atsamd_hal::time::*; +use atsamd_hal::typelevel::Increment; +use common_arm::mcan; +use common_arm::mcan::message::{rx, Raw}; +use common_arm::mcan::tx_buffers::DynTx; +use common_arm::HydraError; +use defmt::flush; +use defmt::info; +use common_arm::spawn; +use heapless::Vec; +use mcan::bus::Can; +use mcan::embedded_can as ecan; +use mcan::interrupt::state::EnabledLine0; +use mcan::interrupt::{Interrupt, OwnedInterruptSet}; +use mcan::message::tx; +use mcan::messageram::SharedMemory; +use mcan::{ + config::{BitTiming, Mode}, + filter::{Action, Filter}, +}; +use messages::mavlink; +use messages::Message; +use postcard::from_bytes; +use systick_monotonic::fugit::RateExtU32; +use typenum::{U0, U128, U32, U64}; + +use atsamd_hal::dmac::Transfer; + +pub struct Capacities; + +impl mcan::messageram::Capacities for Capacities { + type StandardFilters = U128; + type ExtendedFilters = U64; + type RxBufferMessage = rx::Message<64>; + type DedicatedRxBuffers = U64; + type RxFifo0Message = rx::Message<64>; + type RxFifo0 = U64; + type RxFifo1Message = rx::Message<64>; + type RxFifo1 = U64; + type TxMessage = tx::Message<64>; + type TxBuffers = U32; + type DedicatedTxBuffers = U0; + type TxEventFifo = U32; +} + +pub struct CanDevice0 { + pub can: Can< + 'static, + Can0, + Dependencies>, Pin>, CAN0>, + Capacities, + >, + line_interrupts: OwnedInterruptSet, +} + +impl CanDevice0 { + pub fn new( + can_rx: Pin, + can_tx: Pin, + pclk_can: Pclk, + ahb_clock: AhbClk, + peripheral: CAN0, + gclk0: S, + can_memory: &'static mut SharedMemory, + loopback: bool, + ) -> (Self, S::Inc) + where + S: Source + Increment, + { + let (can_dependencies, gclk0) = + Dependencies::new(gclk0, pclk_can, ahb_clock, can_rx, can_tx, peripheral); + + let mut can = + mcan::bus::CanConfigurable::new(200.kHz(), can_dependencies, can_memory).unwrap(); + can.config().mode = Mode::Fd { + allow_bit_rate_switching: false, + data_phase_timing: BitTiming::new(500.kHz()), + }; + + if loopback { + can.config().loopback = true; + } + + let interrupts_to_be_enabled = can + .interrupts() + .split( + [ + Interrupt::RxFifo0NewMessage, + Interrupt::RxFifo0Full, + Interrupt::RxFifo0MessageLost, + ] + .into_iter() + .collect(), + ) + .unwrap(); + + // Line 0 and 1 are connected to the same interrupt line + let line_interrupts = can + .interrupt_configuration() + .enable_line_0(interrupts_to_be_enabled); + + can.filters_standard() + .push(Filter::Classic { + action: Action::StoreFifo0, + filter: ecan::StandardId::new(messages::sender::Sender::SensorBoard.into()) + .unwrap(), + mask: ecan::StandardId::ZERO, + }) + .unwrap_or_else(|_| panic!("Sensor filter")); + + let can = can.finalize().unwrap(); + ( + CanDevice0 { + can, + line_interrupts, + }, + gclk0, + ) + } + pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { + let payload: Vec = postcard::to_vec(&m)?; + self.can.tx.transmit_queued( + tx::MessageBuilder { + id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), + frame_type: tx::FrameType::FlexibleDatarate { + payload: &payload[..], + bit_rate_switching: false, + force_error_state_indicator: false, + }, + store_tx_event: None, + } + .build()?, + )?; + Ok(()) + } + pub fn process_data(&mut self, data_manager: &mut DataManager) { + let line_interrupts = &self.line_interrupts; + for interrupt in line_interrupts.iter_flagged() { + match interrupt { + Interrupt::RxFifo0NewMessage => { + for message in &mut self.can.rx_fifo_0 { + match from_bytes::(message.data()) { + Ok(data) => { + data_manager.handle_data(data); + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + Interrupt::RxFifo1NewMessage => { + for message in &mut self.can.rx_fifo_1 { + match from_bytes::(message.data()) { + Ok(data) => { + data_manager.handle_data(data); + } + Err(e) => { + info!("Error: {:?}", e) + } + } + } + } + _ => (), + } + } + } +} diff --git a/boards/camera/src/data_manager.rs b/boards/camera/src/data_manager.rs new file mode 100644 index 00000000..4e82c75c --- /dev/null +++ b/boards/camera/src/data_manager.rs @@ -0,0 +1,125 @@ +use messages::sensor::{Air}; +use messages::Message; +use messages::state::{State, StateData}; +use defmt::info; +use heapless::HistoryBuffer; + +const MAIN_HEIGHT: f32 = 500.0; // meters +const HEIGHT_MIN: f32 = 300.0; // meters + +pub struct DataManager { + pub air: Option, + pub historical_barometer_altitude: HistoryBuffer<(f32, u32), 8>, +} + +impl DataManager { + pub fn new() -> Self { + let historical_barometer_altitude = HistoryBuffer::new(); + Self { + air: None, + historical_barometer_altitude, + } + } + /// Returns true if the rocket is descending + pub fn is_falling(&self) -> bool { + if self.historical_barometer_altitude.len() < 8 { + return false; + } + let mut buf = self.historical_barometer_altitude.oldest_ordered(); + match buf.next() { + Some(last) => { + let mut avg_sum: f32 = 0.0; + let mut prev = last; + for i in buf { + let time_diff: f32 = (i.1 - prev.1) as f32 / 1_000_000.0; + if time_diff == 0.0 { + continue; + } + let slope = (i.0 - prev.0)/time_diff; + if slope < -100.0 { + return false; + } + avg_sum += slope; + prev = i; + } + match avg_sum / 7.0 { // 7 because we have 8 points. + // exclusive range + x if !(-100.0..=-5.0).contains(&x) => { + return false; + } + _ => { + info!("avg: {}", avg_sum / 7.0); + } + } + } + None => { + return false; + } + } + true + } + pub fn is_launched(&self) -> bool { + match self.air.as_ref() { + Some(air) => air.altitude > HEIGHT_MIN, + None => false, + } + } + pub fn is_landed(&self) -> bool { + if self.historical_barometer_altitude.len() < 8 { + return false; + } + let mut buf = self.historical_barometer_altitude.oldest_ordered(); + match buf.next() { + Some(last) => { + let mut avg_sum: f32 = 0.0; + let mut prev = last; + for i in buf { + let time_diff: f32 = (i.1 - prev.1) as f32 / 1_000_000.0; + if time_diff == 0.0 { + continue; + } + avg_sum += (i.0 - prev.0)/time_diff; + prev = i; + } + match avg_sum / 7.0 { + // inclusive range + x if (-4.0..=4.0).contains(&x) => { + return true; + } + _ => { + // continue + } + } + } + None => { + return false; + } + } + false + } + pub fn is_below_main(&self) -> bool { + match self.air.as_ref() { + Some(air) => air.altitude < MAIN_HEIGHT, + None => false, + } + } + pub fn handle_data(&mut self, data: Message) { + match data.data { + messages::Data::Sensor(sensor) => match sensor.data { + messages::sensor::SensorData::Air(air_data) => { + self.air = Some(air_data); + } + _ => { + } + }, + _ => { + } + } + } +} + +impl Default for DataManager { + fn default() -> Self { + Self::new() + } +} diff --git a/boards/camera/src/gpio_manager.rs b/boards/camera/src/gpio_manager.rs new file mode 100644 index 00000000..5ab28d08 --- /dev/null +++ b/boards/camera/src/gpio_manager.rs @@ -0,0 +1,22 @@ +use atsamd_hal::gpio::{Pin, PushPullOutput, PA09, PA06}; +use atsamd_hal::prelude::*; + +pub struct GPIOManager { + cam1: Pin, + cam2: Pin, +} + +impl GPIOManager { + pub fn new(mut cam1: Pin, mut cam2: Pin) -> Self { + Self { + cam1, + cam2 + } + } + pub fn toggle_cam1(&mut self) { + self.cam1.toggle().ok(); + } + pub fn toggle_cam2(&mut self) { + self.cam2.toggle().ok(); + } +} \ No newline at end of file diff --git a/boards/camera/src/main.rs b/boards/camera/src/main.rs new file mode 100644 index 00000000..2c3a1cce --- /dev/null +++ b/boards/camera/src/main.rs @@ -0,0 +1,155 @@ +#![no_std] +#![no_main] + +mod communication; +mod data_manager; +mod gpio_manager; +mod types; +mod state_machine; + +use communication::Capacities; +use crate::state_machine::{StateMachine, StateMachineContext}; +use crate::data_manager::DataManager; +use crate::gpio_manager::GPIOManager; +use common_arm::ErrorManager; +use atsamd_hal as hal; +use atsamd_hal::clock::v2::pclk::Pclk; +use atsamd_hal::clock::v2::Source; +use common_arm::mcan; +use hal::gpio::Pins; +use mcan::messageram::SharedMemory; +use panic_halt as _; +use systick_monotonic::*; +use common_arm::*; +use hal::gpio::{PB17, PushPullOutput, Pin, PB16}; +use hal::prelude::*; + + +#[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] +mod app { + + use super::*; + + #[shared] + struct Shared { + em: ErrorManager, + data_manager: DataManager, + can0: communication::CanDevice0, + gpio_manager: GPIOManager, + } + + #[local] + struct Local { + state_machine: StateMachine, + led_red: Pin, + led_green: Pin, + } + + #[monotonic(binds = SysTick, default = true)] + type SysMono = Systick<100>; // 100 Hz / 10 ms granularity + + #[init(local = [ + #[link_section = ".can"] + can_memory: SharedMemory = SharedMemory::new() + ])] + fn init(cx: init::Context) -> (Shared, Local, init::Monotonics) { + let mut peripherals = cx.device; + let core = cx.core; + let pins = Pins::new(peripherals.PORT); + + /* Clock setup */ + let (_, clocks, tokens) = atsamd_hal::clock::v2::clock_system_at_reset( + peripherals.OSCCTRL, + peripherals.OSC32KCTRL, + peripherals.GCLK, + peripherals.MCLK, + &mut peripherals.NVMCTRL, + ); + let gclk0 = clocks.gclk0; + + // SAFETY: Misusing the PAC API can break the system. + // This is safe because we only steal the MCLK. + let (_, _, _, mclk) = unsafe { clocks.pac.steal() }; + + /* CAN config */ + let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0); + let (can0, gclk0) = communication::CanDevice0::new( + pins.pa23.into_mode(), + pins.pa22.into_mode(), + pclk_can, + clocks.ahbs.can0, + peripherals.CAN0, + gclk0, + cx.local.can_memory, + false, + ); + + /* Status LED */ + let led_red = pins.pb17.into_push_pull_output(); + let led_green = pins.pb16.into_push_pull_output(); + let gpio = GPIOManager::new( + pins.pa09.into_push_pull_output(), + pins.pa06.into_push_pull_output(), + ); + + let state_machine = StateMachine::new(); + + /* Spawn tasks */ + spawn!(toggle_cams); + + // run_sm::spawn().ok(); + + /* Monotonic clock */ + let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); + + (Shared {em: ErrorManager::new(), data_manager: DataManager::new(), can0, gpio_manager: gpio}, Local {state_machine, led_red , led_green}, init::Monotonics(mono)) + } + + /// Idle task for when no other tasks are running. + #[idle] + fn idle(_: idle::Context) -> ! { + loop {} + } + + #[task(priority = 3, local = [num: u8 = 0], shared = [gpio_manager, &em])] + fn toggle_cams(mut cx: toggle_cams::Context) { + cx.shared.em.run(|| { + cx.shared.gpio_manager.lock(|gpio| { + gpio.toggle_cam1(); + gpio.toggle_cam2(); + }); + Ok(()) + }); + if (*cx.local.num < 3) { + *cx.local.num += 1; + spawn_after!(toggle_cams, ExtU64::millis(250)); + } + } + + /// Runs the state machine. + /// This takes control of the shared resources. + #[task(priority = 3, local = [state_machine], shared = [can0, gpio_manager, data_manager, &em])] + fn run_sm(mut cx: run_sm::Context) { + cx.local.state_machine.run(&mut StateMachineContext { + shared_resources: &mut cx.shared, + }); + spawn_after!(run_sm, ExtU64::millis(500)).ok(); + } + + + /// Simple blink task to test the system. + /// Acts as a heartbeat for the system. + #[task(local = [led_green, led_red], shared = [&em])] + fn blink(cx: blink::Context) { + cx.shared.em.run(|| { + if cx.shared.em.has_error() { + cx.local.led_red.toggle()?; + spawn_after!(blink, ExtU64::millis(200))?; + } else { + cx.local.led_green.toggle()?; + spawn_after!(blink, ExtU64::secs(1))?; + } + Ok(()) + }); + } +} diff --git a/boards/camera/src/state_machine/black_magic.rs b/boards/camera/src/state_machine/black_magic.rs new file mode 100644 index 00000000..1211a839 --- /dev/null +++ b/boards/camera/src/state_machine/black_magic.rs @@ -0,0 +1,44 @@ +use crate::state_machine::{RocketEvents, RocketStates, StateMachineContext}; +use core::fmt::Debug; +use defmt::{info, Format}; +use enum_dispatch::enum_dispatch; + +/// Trait that all states implement. Ignore this, not super important +#[enum_dispatch] +pub trait State: Debug { + fn enter(&self, _context: &mut StateMachineContext) + where + Self: Format, + { + info!("Enter {:?}", self) + } + fn exit(&self) + where + Self: Format, + { + info!("Exit {:?}", self) + } + fn event(&mut self, _event: RocketEvents) -> Option { + None + } + fn step(&mut self, context: &mut StateMachineContext) -> Option; +} + +/// Transition Trait +pub trait TransitionInto { + fn transition(&self) -> T; +} + +#[macro_export] +macro_rules! transition { + ($self:ident, $i:ident) => { + Some(TransitionInto::<$i>::transition($self).into()) + }; +} + +#[macro_export] +macro_rules! no_transition { + () => { + None + }; +} diff --git a/boards/camera/src/state_machine/mod.rs b/boards/camera/src/state_machine/mod.rs new file mode 100644 index 00000000..fd2ee6c1 --- /dev/null +++ b/boards/camera/src/state_machine/mod.rs @@ -0,0 +1,118 @@ +mod black_magic; +mod states; + +use messages::state; +use crate::communication::CanDevice0; +use crate::data_manager::DataManager; +use crate::state_machine::states::*; +use crate::gpio_manager::GPIOManager; +pub use black_magic::*; +pub use states::Initializing; +use core::fmt::Debug; +use defmt::Format; +use enum_dispatch::enum_dispatch; +use rtic::Mutex; + +pub trait StateMachineSharedResources { + fn lock_can(&mut self, f: &dyn Fn(&mut CanDevice0)); + fn lock_data_manager(&mut self, f: &dyn Fn(&mut DataManager)); + fn lock_gpio(&mut self, f: &dyn Fn(&mut GPIOManager)); +} + +impl<'a> StateMachineSharedResources for crate::app::__rtic_internal_run_smSharedResources<'a> { + fn lock_can(&mut self, fun: &dyn Fn(&mut CanDevice0)) { + self.can0.lock(fun) + } + fn lock_data_manager(&mut self, fun: &dyn Fn(&mut DataManager)) { + self.data_manager.lock(fun) + } + fn lock_gpio(&mut self, fun: &dyn Fn(&mut GPIOManager)) { + self.gpio_manager.lock(fun) + } +} + +pub struct StateMachineContext<'a, 'b> { + pub shared_resources: &'b mut crate::app::__rtic_internal_run_smSharedResources<'a> +} +pub struct StateMachine { + state: RocketStates, +} + +// Define some functions to interact with the state machine +impl StateMachine { + pub fn new() -> Self { + let state = Initializing {}; + + StateMachine { + state: state.into(), + } + } + + pub fn run(&mut self, context: &mut StateMachineContext) { + if let Some(new_state) = self.state.step(context) { + self.state.exit(); + new_state.enter(context); + self.state = new_state; + } + } + + pub fn get_state(&self) -> RocketStates { + self.state.clone() + } +} + +impl Default for StateMachine { + fn default() -> Self { + Self::new() + } +} + +// All events are found here +pub enum RocketEvents { + DeployDrogue, + DeployMain, +} + +// All states are defined here. Another struct must be defined for the actual state, and that struct +// must implement the State trait +#[enum_dispatch(State)] +#[derive(Debug, Format, Clone)] +pub enum RocketStates { + Initializing, + WaitForTakeoff, + Ascent, + Descent, + TerminalDescent, + WaitForRecovery, + Abort, +} + +// Not a fan of this. +// Should be able to put this is a shared library. +impl From for RocketStates { + fn from(state: state::StateData) -> Self { + match state { + state::StateData::Initializing => RocketStates::Initializing(Initializing {}), + state::StateData::WaitForTakeoff => RocketStates::WaitForTakeoff(WaitForTakeoff {}), + state::StateData::Ascent => RocketStates::Ascent(Ascent {}), + state::StateData::Descent => RocketStates::Descent(Descent {}), + state::StateData::TerminalDescent => RocketStates::TerminalDescent(TerminalDescent { } ), + state::StateData::WaitForRecovery => RocketStates::WaitForTakeoff(WaitForTakeoff { }), + state::StateData::Abort => RocketStates::Abort(Abort {}), + } + } +} +// Linter: an implementation of From is preferred since it gives you Into<_> for free where the reverse isn't true +impl Into for RocketStates { + fn into(self) -> state::StateData { + match self { + RocketStates::Initializing(_) => state::StateData::Initializing, + RocketStates::WaitForTakeoff(_) => state::StateData::WaitForTakeoff, + RocketStates::Ascent(_) => state::StateData::Ascent, + RocketStates::Descent(_) => state::StateData::Descent, + RocketStates::TerminalDescent(_) => state::StateData::TerminalDescent, + RocketStates::WaitForRecovery(_) => state::StateData::WaitForRecovery, + RocketStates::Abort(_) => state::StateData::Abort, + } + } +} \ No newline at end of file diff --git a/boards/camera/src/state_machine/states/abort.rs b/boards/camera/src/state_machine/states/abort.rs new file mode 100644 index 00000000..92cc71ca --- /dev/null +++ b/boards/camera/src/state_machine/states/abort.rs @@ -0,0 +1,24 @@ +use crate::state_machine::states::initializing::Initializing; +use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; +use defmt::{write, Format, Formatter}; + +#[derive(Debug, Clone)] +pub struct Abort {} + +impl State for Abort { + fn step(&mut self, _context: &mut StateMachineContext) -> Option { + todo!() + } +} + +impl TransitionInto for Initializing { + fn transition(&self) -> Abort { + Abort {} + } +} + +impl Format for Abort { + fn format(&self, f: Formatter) { + write!(f, "Abort") + } +} diff --git a/boards/camera/src/state_machine/states/ascent.rs b/boards/camera/src/state_machine/states/ascent.rs new file mode 100644 index 00000000..1809219a --- /dev/null +++ b/boards/camera/src/state_machine/states/ascent.rs @@ -0,0 +1,48 @@ +use crate::state_machine::states::descent::Descent; +use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; +use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; +use crate::{no_transition, transition}; +use messages::command::{Command, CommandData, PowerDown, RadioRateChange, RadioRate}; +use messages::Message; +use defmt::{write, Format, Formatter}; +use rtic::mutex::Mutex; +use crate::types::COM_ID; +use crate::app::monotonics; +use systick_monotonic::ExtU64; +use crate::app::toggle_cams; +use common_arm::spawn_after; + +#[derive(Debug, Clone)] +pub struct Ascent {} + +impl State for Ascent { + fn enter(&self, context: &mut StateMachineContext) { + for i in 0..3 { + spawn_after!(toggle_cams, ExtU64::millis(2)); + } + } + fn step(&mut self, context: &mut StateMachineContext) -> Option { + context + .shared_resources + .data_manager + .lock(|data| { + if data.is_falling() { + transition!(self, Descent) + } else { + no_transition!() + } + }) + } +} + +impl TransitionInto for WaitForTakeoff { + fn transition(&self) -> Ascent { + Ascent {} + } +} + +impl Format for Ascent { + fn format(&self, f: Formatter) { + write!(f, "Ascent") + } +} diff --git a/boards/camera/src/state_machine/states/descent.rs b/boards/camera/src/state_machine/states/descent.rs new file mode 100644 index 00000000..18596061 --- /dev/null +++ b/boards/camera/src/state_machine/states/descent.rs @@ -0,0 +1,32 @@ +use super::Ascent; +use crate::state_machine::{TerminalDescent, RocketStates, State, StateMachineContext, TransitionInto}; +use crate::{no_transition, transition}; +use rtic::mutex::Mutex; +use defmt::{write, Format, Formatter, info}; + +#[derive(Debug, Clone)] +pub struct Descent {} + +impl State for Descent { + fn step(&mut self, context: &mut StateMachineContext) -> Option { + context.shared_resources.data_manager.lock(|data| { + if data.is_below_main() { + transition!(self, TerminalDescent) + } else { + no_transition!() + } + }) + } +} + +impl TransitionInto for Ascent { + fn transition(&self) -> Descent { + Descent {} + } +} + +impl Format for Descent { + fn format(&self, f: Formatter) { + write!(f, "Descent") + } +} diff --git a/boards/camera/src/state_machine/states/initializing.rs b/boards/camera/src/state_machine/states/initializing.rs new file mode 100644 index 00000000..b9adab77 --- /dev/null +++ b/boards/camera/src/state_machine/states/initializing.rs @@ -0,0 +1,20 @@ +use defmt::{write, Format, Formatter}; + +use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; +use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; +use crate::transition; + +#[derive(Debug, Clone)] +pub struct Initializing {} + +impl State for Initializing { + fn step(&mut self, _context: &mut StateMachineContext) -> Option { + transition!(self, WaitForTakeoff) + } +} + +impl Format for Initializing { + fn format(&self, f: Formatter) { + write!(f, "Initializing") + } +} diff --git a/boards/camera/src/state_machine/states/mod.rs b/boards/camera/src/state_machine/states/mod.rs new file mode 100644 index 00000000..f4d4c3fe --- /dev/null +++ b/boards/camera/src/state_machine/states/mod.rs @@ -0,0 +1,15 @@ +mod initializing; +mod terminal_descent; +mod ascent; +mod descent; +mod wait_for_takeoff; +mod wait_for_recovery; +mod abort; + +pub use crate::state_machine::states::descent::Descent; +pub use crate::state_machine::states::ascent::Ascent; +pub use crate::state_machine::states::initializing::Initializing; +pub use crate::state_machine::states::wait_for_takeoff::WaitForTakeoff; +pub use crate::state_machine::states::terminal_descent::TerminalDescent; +pub use crate::state_machine::states::wait_for_recovery::WaitForRecovery; +pub use crate::state_machine::states::abort::Abort; \ No newline at end of file diff --git a/boards/camera/src/state_machine/states/terminal_descent.rs b/boards/camera/src/state_machine/states/terminal_descent.rs new file mode 100644 index 00000000..47394287 --- /dev/null +++ b/boards/camera/src/state_machine/states/terminal_descent.rs @@ -0,0 +1,36 @@ +use defmt::{write, Format, Formatter, info}; + +use crate::{no_transition, transition}; +use crate::state_machine::{WaitForRecovery, RocketStates, State, StateMachineContext, TransitionInto}; +use rtic::mutex::Mutex; +use super::Descent; + +#[derive(Debug, Clone)] +pub struct TerminalDescent {} + +impl State for TerminalDescent { + fn step(&mut self, context: &mut StateMachineContext) -> Option { + context + .shared_resources + .data_manager + .lock(|data| { + if data.is_landed() { + transition!(self, WaitForRecovery) + } else { + no_transition!() + } + }) + } +} + +impl TransitionInto for Descent { + fn transition(&self) -> TerminalDescent { + TerminalDescent {} + } +} + +impl Format for TerminalDescent { + fn format(&self, f: Formatter) { + write!(f, "Terminal Descent") + } +} diff --git a/boards/camera/src/state_machine/states/wait_for_recovery.rs b/boards/camera/src/state_machine/states/wait_for_recovery.rs new file mode 100644 index 00000000..5ced98af --- /dev/null +++ b/boards/camera/src/state_machine/states/wait_for_recovery.rs @@ -0,0 +1,31 @@ +use super::TerminalDescent; +use crate::app::monotonics; +use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; +use crate::types::COM_ID; +use crate::{no_transition, transition}; +use rtic::mutex::Mutex; +use defmt::{write, Format, Formatter, info}; +use messages::command::{Command, CommandData, PowerDown, RadioRateChange, RadioRate}; +use messages::Message; +use messages::sender::Sender::SensorBoard; + +#[derive(Debug, Clone)] +pub struct WaitForRecovery {} + +impl State for WaitForRecovery { + fn step(&mut self, context: &mut StateMachineContext) -> Option { + no_transition!() // this is our final resting place. We should also powerdown this board. + } +} + +impl TransitionInto for TerminalDescent { + fn transition(&self) -> WaitForRecovery { + WaitForRecovery {} + } +} + +impl Format for WaitForRecovery { + fn format(&self, f: Formatter) { + write!(f, "Descent") + } +} diff --git a/boards/camera/src/state_machine/states/wait_for_takeoff.rs b/boards/camera/src/state_machine/states/wait_for_takeoff.rs new file mode 100644 index 00000000..a63e8743 --- /dev/null +++ b/boards/camera/src/state_machine/states/wait_for_takeoff.rs @@ -0,0 +1,36 @@ +use crate::state_machine::states::ascent::Ascent; +use crate::state_machine::states::initializing::Initializing; +use crate::state_machine::{RocketStates, State, StateMachineContext, TransitionInto}; +use crate::{no_transition, transition}; +use rtic::mutex::Mutex; +use defmt::{write, Format, Formatter}; + +#[derive(Debug, Clone)] +pub struct WaitForTakeoff {} + +impl State for WaitForTakeoff { + fn step(&mut self, context: &mut StateMachineContext) -> Option { + context + .shared_resources + .data_manager + .lock(|data| { + if data.is_launched() { + transition!(self, Ascent) + } else { + no_transition!() + } + }) + } +} + +impl TransitionInto for Initializing { + fn transition(&self) -> WaitForTakeoff { + WaitForTakeoff {} + } +} + +impl Format for WaitForTakeoff { + fn format(&self, f: Formatter) { + write!(f, "WaitForTakeoff") + } +} diff --git a/boards/camera/src/types.rs b/boards/camera/src/types.rs new file mode 100644 index 00000000..72b4b3ca --- /dev/null +++ b/boards/camera/src/types.rs @@ -0,0 +1,5 @@ +use messages::sender::{Sender, Sender::CameraBoard}; +// ------- +// Sender ID +// ------- +pub static COM_ID: Sender = CameraBoard; \ No newline at end of file diff --git a/boards/communication/Cargo.toml b/boards/communication/Cargo.toml index 85829983..0d45d894 100644 --- a/boards/communication/Cargo.toml +++ b/boards/communication/Cargo.toml @@ -18,4 +18,4 @@ common-arm = { path = "../../libraries/common-arm" } atsamd-hal = { workspace = true } messages = { path = "../../libraries/messages" } typenum = "1.16.0" -embedded-sdmmc = "0.3.0" +embedded-sdmmc = "0.3.0" \ No newline at end of file diff --git a/boards/communication/src/communication.rs b/boards/communication/src/communication.rs index 684ee8ca..41ae89aa 100644 --- a/boards/communication/src/communication.rs +++ b/boards/communication/src/communication.rs @@ -1,3 +1,4 @@ +use crate::app::send_internal; use crate::data_manager::DataManager; use crate::types::*; use atsamd_hal::can::Dependencies; @@ -12,21 +13,20 @@ use atsamd_hal::gpio::{Alternate, AlternateI, Disabled, Floating, Pin, I, PA22, use atsamd_hal::pac::CAN0; use atsamd_hal::pac::MCLK; use atsamd_hal::pac::SERCOM5; -use atsamd_hal::sercom::Sercom; -use atsamd_hal::sercom::{uart, Sercom5}; use atsamd_hal::sercom; -use atsamd_hal::sercom::uart::{ TxDuplex, RxDuplex}; use atsamd_hal::sercom::uart::{Duplex, Uart}; +use atsamd_hal::sercom::uart::{RxDuplex, TxDuplex}; +use atsamd_hal::sercom::Sercom; +use atsamd_hal::sercom::{uart, Sercom5}; use atsamd_hal::time::*; use atsamd_hal::typelevel::Increment; use common_arm::mcan; use common_arm::mcan::message::{rx, Raw}; use common_arm::mcan::tx_buffers::DynTx; +use common_arm::spawn; use common_arm::HydraError; use defmt::flush; use defmt::info; -use crate::app::send_internal; -use common_arm::spawn; use heapless::Vec; use mcan::bus::Can; use mcan::embedded_can as ecan; @@ -246,9 +246,13 @@ impl RadioDevice { uart::BaudMode::Fractional(uart::Oversampling::Bits16), ) .enable(); - let (rx, tx) = uart.split(); // tx sends rx uses dma to receive so we need to setup dma here. - dma_channel.as_mut().enable_interrupts(dmac::InterruptFlags::new().with_tcmpl(true)); - let xfer = Transfer::new(dma_channel, rx, unsafe {&mut *BUF_DST}, false).expect("DMA Radio RX").begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); + let (rx, tx) = uart.split(); // tx sends rx uses dma to receive so we need to setup dma here. + dma_channel + .as_mut() + .enable_interrupts(dmac::InterruptFlags::new().with_tcmpl(true)); + let xfer = Transfer::new(dma_channel, rx, unsafe { &mut *BUF_DST }, false) + .expect("DMA Radio RX") + .begin(Sercom5::DMA_RX_TRIGGER, dmac::TriggerAction::BURST); ( RadioDevice { uart: tx, @@ -290,9 +294,7 @@ pub struct RadioManager { } impl RadioManager { - pub fn new( - xfer: RadioTransfer, - ) -> Self { + pub fn new(xfer: RadioTransfer) -> Self { RadioManager { xfer: Some(xfer), buf_select: false, @@ -328,5 +330,5 @@ impl RadioManager { // None => { // info!("none"); // } -// } -// } \ No newline at end of file +// } +// } diff --git a/boards/communication/src/data_manager.rs b/boards/communication/src/data_manager.rs index fdb9f52d..cfe92b33 100644 --- a/boards/communication/src/data_manager.rs +++ b/boards/communication/src/data_manager.rs @@ -1,8 +1,10 @@ -use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, SensorData, UtcTime, GpsPos1, GpsPos2}; -use messages::Message; -use messages::command::{Command, CommandData, RadioRateChange, RadioRate}; -use messages::state::{State, StateData}; use defmt::info; +use messages::command::{Command, CommandData, RadioRate, RadioRateChange}; +use messages::sensor::{ + Air, EkfNav1, EkfNav2, EkfQuat, GpsPos1, GpsPos2, GpsVel, Imu1, Imu2, SensorData, UtcTime, +}; +use messages::state::{State, StateData}; +use messages::Message; #[derive(Clone)] pub struct DataManager { @@ -28,7 +30,7 @@ impl DataManager { gps_vel: None, gps_pos: (None, None), state: None, - logging_rate: Some(RadioRate::Slow), // start slow. + logging_rate: Some(RadioRate::Slow), // start slow. } } @@ -36,10 +38,10 @@ impl DataManager { if let Some(rate) = self.logging_rate.take() { let rate_cln = rate.clone(); self.logging_rate = Some(rate); - return rate_cln - } + return rate_cln; + } self.logging_rate = Some(RadioRate::Slow); - return RadioRate::Slow + return RadioRate::Slow; } pub fn clone_sensors(&self) -> [Option; 10] { @@ -57,9 +59,7 @@ impl DataManager { ] } pub fn clone_states(&self) -> [Option; 1] { - [ - self.state.clone(), - ] + [self.state.clone()] } pub fn handle_data(&mut self, data: Message) { match data.data { @@ -87,10 +87,10 @@ impl DataManager { } messages::sensor::SensorData::UtcTime(utc_time_data) => { self.utc_time = Some(utc_time_data); - }, + } messages::sensor::SensorData::GpsPos1(gps) => { self.gps_pos.0 = Some(gps); - }, + } messages::sensor::SensorData::GpsPos2(gps) => { self.gps_pos.1 = Some(gps); } @@ -100,15 +100,13 @@ impl DataManager { }, messages::Data::State(state) => { self.state = Some(state.data); - }, + } messages::Data::Command(command) => match command.data { messages::command::CommandData::RadioRateChange(command_data) => { self.logging_rate = Some(command_data.rate); - }, - _ => { - } - } + _ => {} + }, _ => { info!("unkown"); } diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index 8fccf969..897aebd5 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -4,38 +4,39 @@ mod communication; mod data_manager; mod types; -mod sd_manager; use atsamd_hal as hal; use atsamd_hal::clock::v2::pclk::Pclk; use atsamd_hal::clock::v2::Source; -use atsamd_hal::dmac::DmaController; use atsamd_hal::dmac; +use atsamd_hal::dmac::DmaController; use common_arm::mcan; +use common_arm::SdManager; use common_arm::*; use communication::Capacities; use communication::{RadioDevice, RadioManager}; use data_manager::DataManager; -use sd_manager::SdManager; // use communication::radio_dma; -use heapless::Vec; +use defmt::{flush, info}; use hal::gpio::Pins; -use hal::gpio::PA05; -use hal::gpio::{Pin, PushPullOutput}; +use hal::gpio::{Alternate, Pin, PushPull, PushPullOutput, C, PA05, PB12, PB13, PB14, PB15}; use hal::prelude::*; +use hal::sercom::{spi, spi::Config, spi::Duplex, spi::Pads, spi::Spi, IoSet1, Sercom4}; +use heapless::Vec; use mcan::messageram::SharedMemory; +use messages::command::RadioRate; use messages::sensor::Sensor; use messages::state::State; use messages::*; use panic_halt as _; use systick_monotonic::*; use types::*; -use defmt::{info, flush}; -use messages::command::RadioRate; #[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] mod app { + use hal::gpio::Output; + use super::*; #[shared] @@ -49,7 +50,21 @@ mod app { struct Local { led: Pin, radio: RadioDevice, - sd_manager: SdManager, + sd_manager: SdManager< + Spi< + Config< + Pads< + hal::pac::SERCOM4, + IoSet1, + Pin>, + Pin>, + Pin>, + >, + >, + Duplex, + >, + Pin>, + >, radio_manager: RadioManager, } @@ -114,15 +129,16 @@ mod app { /* SD config */ let (pclk_sd, gclk0) = Pclk::enable(tokens.pclks.sercom4, gclk0); - let sd_manager = SdManager::new( - &mclk, - peripherals.SERCOM4, - pclk_sd.freq(), - pins.pb14.into_push_pull_output(), - pins.pb13.into_push_pull_output(), - pins.pb15.into_push_pull_output(), - pins.pb12.into_push_pull_output(), - ); + let pads_spi = spi::Pads::::default() + .sclk(pins.pb13) + .data_in(pins.pb15) + .data_out(pins.pb12); + let sdmmc_spi = spi::Config::new(&mclk, peripherals.SERCOM4, pads_spi, pclk_sd.freq()) + .length::() + .bit_order(spi::BitOrder::MsbFirst) + .spi_mode(spi::MODE_0) + .enable(); + let sd_manager = SdManager::new(sdmmc_spi, pins.pb14.into_push_pull_output()); /* Status LED */ let led = pins.pa05.into_push_pull_output(); @@ -141,7 +157,12 @@ mod app { data_manager: DataManager::new(), can0, }, - Local { led, radio, sd_manager, radio_manager }, + Local { + led, + radio, + sd_manager, + radio_manager, + }, init::Monotonics(mono), ) } @@ -172,7 +193,6 @@ mod app { }); } - /// Probably should use this ( ノ^ω^)ノ pub fn queue_gs_message(d: impl Into) { let message = Message::new(&monotonics::now(), COM_ID, d.into()); @@ -195,7 +215,7 @@ mod app { fn sd_dump(cx: sd_dump::Context, m: Message) { let manager = cx.local.sd_manager; cx.shared.em.run(|| { - let mut buf: [u8; 255] = [0; 255]; + let mut buf: [u8; 255] = [0; 255]; let msg_ser = postcard::to_slice_cobs(&m, &mut buf)?; if let Some(mut file) = manager.file.take() { manager.write(&mut file, &msg_ser)?; @@ -213,15 +233,12 @@ mod app { */ #[task(shared = [data_manager, &em])] fn sensor_send(mut cx: sensor_send::Context) { - let (sensor_data, logging_rate) = cx - .shared - .data_manager - .lock(|data_manager| { - ( - data_manager.clone_sensors(), - data_manager.get_logging_rate() - ) - }); + let (sensor_data, logging_rate) = cx.shared.data_manager.lock(|data_manager| { + ( + data_manager.clone_sensors(), + data_manager.get_logging_rate(), + ) + }); let messages = sensor_data .into_iter() @@ -236,9 +253,9 @@ mod app { Ok(()) }); match logging_rate { - RadioRate::Fast => { + RadioRate::Fast => { spawn_after!(sensor_send, ExtU64::millis(250)).ok(); - }, + } RadioRate::Slow => { spawn_after!(sensor_send, ExtU64::millis(2000)).ok(); } @@ -247,14 +264,15 @@ mod app { #[task(shared = [data_manager, &em])] fn state_send(mut cx: state_send::Context) { - let state_data = cx.shared.data_manager.lock(|data_manager| { - data_manager.state.clone() - }); + let state_data = cx + .shared + .data_manager + .lock(|data_manager| data_manager.state.clone()); cx.shared.em.run(|| { if let Some(x) = state_data { let message = Message::new(&monotonics::now(), COM_ID, State::new(x)); spawn!(send_gs, message)?; - } // if there is none we still return since we simply don't have data yet. + } // if there is none we still return since we simply don't have data yet. Ok(()) }); spawn_after!(state_send, ExtU64::secs(5)).ok(); diff --git a/boards/communication/src/types.rs b/boards/communication/src/types.rs index 83d216a9..4cdaf702 100644 --- a/boards/communication/src/types.rs +++ b/boards/communication/src/types.rs @@ -1,4 +1,3 @@ -use crate::sd_manager::TimeSink; use atsamd_hal::{gpio::*, dmac}; use atsamd_hal::sercom::uart::EightBit; use atsamd_hal::sercom::{spi, Sercom4}; @@ -20,21 +19,6 @@ pub static COM_ID: Sender = CommunicationBoard; pub type GroundStationPads = uart::PadsFromIds; pub type GroundStationUartConfig = uart::Config; -// ------- -// SD Card -// ------- -pub type SdPads = spi::Pads< - Sercom4, - IoSet1, - Pin>, - Pin>, - Pin>, ->; -pub type SdController = sd::Controller< - sd::SdMmcSpi, spi::Duplex>, Pin>>, - TimeSink, ->; - pub type RadioTransfer = dmac::Transfer< dmac::Channel, BufferPair, RadioBuffer>, diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index b0fe545f..3d4a882f 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -7,7 +7,6 @@ mod gpio_manager; mod state_machine; mod types; - use atsamd_hal as hal; use atsamd_hal::clock::v2::pclk::Pclk; use atsamd_hal::clock::v2::Source; @@ -102,7 +101,8 @@ mod app { run_sm::spawn().ok(); state_send::spawn().ok(); blink::spawn().ok(); - fire_main::spawn_after(ExtU64::secs(10)).ok(); + fire_main::spawn_after(ExtU64::secs(15)).ok(); + fire_drogue::spawn_after(ExtU64::secs(15)).ok(); /* Monotonic clock */ let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); @@ -125,18 +125,34 @@ mod app { loop {} } - #[task(shared=[gpio])] + #[task(local = [fired: bool = false], shared=[gpio])] fn fire_drogue(mut cx: fire_drogue::Context) { - cx.shared.gpio.lock(|gpio| { - gpio.fire_drogue(); - }); + if !(*cx.local.fired) { + cx.shared.gpio.lock(|gpio| { + gpio.fire_drogue(); + *cx.local.fired = true; + }); + } else { + cx.shared.gpio.lock(|gpio| { + gpio.close_drouge(); + }); + } + spawn_after!(fire_drogue, ExtU64::secs(5)); } - #[task(shared=[gpio])] + #[task(local = [fired: bool = false], shared=[gpio])] fn fire_main(mut cx: fire_main::Context) { - cx.shared.gpio.lock(|gpio| { - gpio.fire_main(); - }); + if !(*cx.local.fired) { + cx.shared.gpio.lock(|gpio| { + gpio.fire_main(); + *cx.local.fired = true; + }); + } else { + cx.shared.gpio.lock(|gpio| { + gpio.close_main(); + }); + } + spawn_after!(fire_main, ExtU64::secs(5)); } /// Runs the state machine. diff --git a/boards/sensor/src/types.rs b/boards/sensor/src/types.rs index 4846d09d..c2a8cbd5 100644 --- a/boards/sensor/src/types.rs +++ b/boards/sensor/src/types.rs @@ -44,4 +44,4 @@ pub type SdPads = spi::Pads< pub type SdController = sd::Controller< sd::SdMmcSpi, spi::Duplex>, Pin>>, TimeSink, ->; +>; \ No newline at end of file diff --git a/libraries/common-arm/Cargo.toml b/libraries/common-arm/Cargo.toml index bc6f7035..ac4b5d05 100644 --- a/libraries/common-arm/Cargo.toml +++ b/libraries/common-arm/Cargo.toml @@ -19,4 +19,4 @@ embedded-sdmmc = "0.3.0" embedded-hal = "0.2.7" mcan = "0.3" nb = "1.1.0" -messages = { path = "../messages" } +messages = { path = "../messages" } \ No newline at end of file diff --git a/libraries/common-arm/src/data_manager.rs b/libraries/common-arm/src/data_manager.rs new file mode 100644 index 00000000..e69de29b diff --git a/libraries/common-arm/src/lib.rs b/libraries/common-arm/src/lib.rs index a8fb9a51..c91bbaf5 100644 --- a/libraries/common-arm/src/lib.rs +++ b/libraries/common-arm/src/lib.rs @@ -10,9 +10,11 @@ pub use mcan; mod error; mod logging; +mod sd_manager; pub use crate::error::error_manager::ErrorManager; pub use crate::error::hydra_error::{ErrorContextTrait, HydraError, SpawnError}; pub use crate::logging::HydraLogging; +pub use crate::sd_manager::SdManager; use defmt_rtt as _; // global logger diff --git a/boards/communication/src/sd_manager.rs b/libraries/common-arm/src/sd_manager.rs similarity index 74% rename from boards/communication/src/sd_manager.rs rename to libraries/common-arm/src/sd_manager.rs index e32fb4fc..bd6bab0c 100644 --- a/boards/communication/src/sd_manager.rs +++ b/libraries/common-arm/src/sd_manager.rs @@ -1,147 +1,145 @@ -use crate::types::SdController; -use core::marker::PhantomData; -use atsamd_hal::gpio::{Output, Pin, PushPull, PA16, PA17, PA18, PA19, PB14, PB13, PB15, PB12}; -use atsamd_hal::pac; -use atsamd_hal::sercom::{spi, IoSet1, Sercom1, Sercom4}; -use atsamd_hal::time::Hertz; -use defmt::{info, warn}; -use embedded_sdmmc as sd; - -/// Time source for `[SdInterface]`. It doesn't return any useful information for now, and will -/// always return an arbitrary time. -pub struct TimeSink { - _marker: PhantomData<*const ()>, -} - -impl TimeSink { - fn new() -> Self { - TimeSink { - _marker: PhantomData, - } - } -} - -impl sd::TimeSource for TimeSink { - fn get_timestamp(&self) -> sd::Timestamp { - sd::Timestamp { - year_since_1970: 0, - zero_indexed_month: 0, - zero_indexed_day: 0, - hours: 0, - minutes: 0, - seconds: 0, - } - } -} - -/// Wrapper for the SD Card. For now, the pins are hard-coded. -pub struct SdManager { - pub sd_controller: SdController, - pub volume: sd::Volume, - pub root_directory: sd::Directory, - pub file: Option, -} - -impl SdManager { - pub fn new( - mclk: &pac::MCLK, - sercom: pac::SERCOM4, - freq: Hertz, - cs: Pin>, - sck: Pin>, - miso: Pin>, - mosi: Pin>, - ) -> Self { - let pads_spi = spi::Pads::::default() - .sclk(sck) - .data_in(miso) - .data_out(mosi); - let sdmmc_spi = spi::Config::new(mclk, sercom, pads_spi, freq) - .length::() - .bit_order(spi::BitOrder::MsbFirst) - .spi_mode(spi::MODE_0) - .enable(); - let time_sink: TimeSink = TimeSink::new(); // Need to give this a DateTime object for actual timing. - let mut sd_cont = sd::Controller::new(sd::SdMmcSpi::new(sdmmc_spi, cs), time_sink); - match sd_cont.device().init() { - Ok(_) => match sd_cont.device().card_size_bytes() { - Ok(size) => info!("Card is {} bytes", size), - Err(_) => panic!("Cannot get card size"), - }, - Err(_) => { - panic!("Cannot get SD card."); - } - } - - let mut volume = match sd_cont.get_volume(sd::VolumeIdx(0)) { - Ok(volume) => volume, - Err(_) => { - panic!("Cannot get volume 0"); - } - }; - - let root_directory = match sd_cont.open_root_dir(&volume) { - Ok(root_directory) => root_directory, - Err(_) => { - panic!("Cannot get root"); - } - }; - let file = sd_cont.open_file_in_dir( - &mut volume, - &root_directory, - "log.txt", - sd::Mode::ReadWriteCreateOrTruncate, - ); - let file = match file { - Ok(file) => file, - Err(_) => { - panic!("Cannot create file."); - } - }; - - SdManager { - sd_controller: sd_cont, - volume, - root_directory, - file: Some(file), - } - } - pub fn write( - &mut self, - file: &mut sd::File, - buffer: &[u8], - ) -> Result> { - self.sd_controller.write(&mut self.volume, file, buffer) - } - pub fn write_str( - &mut self, - file: &mut sd::File, - msg: &str, - ) -> Result> { - let buffer: &[u8] = msg.as_bytes(); - self.sd_controller.write(&mut self.volume, file, buffer) - } - pub fn open_file(&mut self, file_name: &str) -> Result> { - self.sd_controller.open_file_in_dir( - &mut self.volume, - &self.root_directory, - file_name, - sd::Mode::ReadWriteCreateOrTruncate, - ) - } - pub fn close_current_file(&mut self) -> Result<(), sd::Error> { - if let Some(file) = self.file.take() { - return self.close_file(file); - } - Ok(()) - } - pub fn close_file(&mut self, file: sd::File) -> Result<(), sd::Error> { - self.sd_controller.close_file(&self.volume, file) - } - pub fn close(mut self) { - self.sd_controller - .close_dir(&self.volume, self.root_directory); - } -} - -unsafe impl Send for SdManager {} \ No newline at end of file +use core::{marker::PhantomData, fmt::Debug}; +use defmt::{info, warn}; +use atsamd_hal::gpio::{Output, Pin, PushPull, PB14}; +use embedded_sdmmc as sd; +use embedded_hal as hal; +use cortex_m; +use hal::spi::FullDuplex; + +/// Time source for `[SdInterface]`. It doesn't return any useful information for now, and will +/// always return an arbitrary time. +pub struct TimeSink { + _marker: PhantomData<*const ()>, +} + +impl TimeSink { + fn new() -> Self { + TimeSink { + _marker: PhantomData, + } + } +} + +impl sd::TimeSource for TimeSink { + fn get_timestamp(&self) -> sd::Timestamp { + sd::Timestamp { + year_since_1970: 0, + zero_indexed_month: 0, + zero_indexed_day: 0, + hours: 0, + minutes: 0, + seconds: 0, + } + } +} + +/// Wrapper for the SD Card. For now, the pins are hard-coded. +pub struct SdManager +where + SPI: hal::spi::FullDuplex, >::Error: Debug, + CS: hal::digital::v2::OutputPin, +{ + pub sd_controller: sd::Controller, TimeSink>, + pub volume: sd::Volume, + pub root_directory: sd::Directory, + pub file: Option, +} + +impl SdManager +where + SPI: hal::spi::FullDuplex, >::Error: Debug, + CS: hal::digital::v2::OutputPin, +{ + pub fn new( + spi: SPI, + cs: CS + ) -> Self + { + let time_sink: TimeSink = TimeSink::new(); // Need to give this a DateTime object for actual timing. + let mut sd_cont = sd::Controller::new(sd::SdMmcSpi::new(spi, cs), time_sink); + match sd_cont.device().init() { + Ok(_) => match sd_cont.device().card_size_bytes() { + Ok(size) => info!("Card is {} bytes", size), + Err(_) => panic!("Cannot get card size"), + }, + Err(_) => { + panic!("Cannot get SD card."); + } + } + + let mut volume = match sd_cont.get_volume(sd::VolumeIdx(0)) { + Ok(volume) => volume, + Err(_) => { + panic!("Cannot get volume 0"); + } + }; + + let root_directory = match sd_cont.open_root_dir(&volume) { + Ok(root_directory) => root_directory, + Err(_) => { + panic!("Cannot get root"); + } + }; + let file = sd_cont.open_file_in_dir( + &mut volume, + &root_directory, + "log.txt", + sd::Mode::ReadWriteCreateOrTruncate, + ); + let file = match file { + Ok(file) => file, + Err(_) => { + panic!("Cannot create file."); + } + }; + + SdManager { + sd_controller: sd_cont, + volume, + root_directory, + file: Some(file), + } + } + pub fn write( + &mut self, + file: &mut sd::File, + buffer: &[u8], + ) -> Result> { + self.sd_controller.write(&mut self.volume, file, buffer) + } + pub fn write_str( + &mut self, + file: &mut sd::File, + msg: &str, + ) -> Result> { + let buffer: &[u8] = msg.as_bytes(); + self.sd_controller.write(&mut self.volume, file, buffer) + } + pub fn open_file(&mut self, file_name: &str) -> Result> { + self.sd_controller.open_file_in_dir( + &mut self.volume, + &self.root_directory, + file_name, + sd::Mode::ReadWriteCreateOrTruncate, + ) + } + pub fn close_current_file(&mut self) -> Result<(), sd::Error> { + if let Some(file) = self.file.take() { + return self.close_file(file); + } + Ok(()) + } + pub fn close_file(&mut self, file: sd::File) -> Result<(), sd::Error> { + self.sd_controller.close_file(&self.volume, file) + } + pub fn close(mut self) { + self.sd_controller + .close_dir(&self.volume, self.root_directory); + } +} + +unsafe impl Send for SdManager +where + SPI: hal::spi::FullDuplex, >::Error: Debug, + CS: hal::digital::v2::OutputPin, +{} \ No newline at end of file diff --git a/libraries/messages/src/sender.rs b/libraries/messages/src/sender.rs index adbdd40d..27ea91c6 100644 --- a/libraries/messages/src/sender.rs +++ b/libraries/messages/src/sender.rs @@ -17,7 +17,8 @@ pub enum Sender { SensorBoard, RecoveryBoard, CommunicationBoard, - PowerBoard + PowerBoard, + CameraBoard, } impl From for u16 { @@ -27,7 +28,8 @@ impl From for u16 { Sender::SensorBoard => 1, Sender::RecoveryBoard => 2, Sender::CommunicationBoard => 3, - Sender::PowerBoard => 4 + Sender::PowerBoard => 4, + Sender::CameraBoard => 5, } } } From 6ce69c91474ab37df4aa767d0b134c0ca57cc7ad Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sun, 27 Aug 2023 22:19:44 -0400 Subject: [PATCH 28/30] Fix camera. Faster GPIO --- boards/camera/src/main.rs | 2 +- boards/recovery/src/gpio_manager.rs | 6 +++--- boards/recovery/src/main.rs | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/boards/camera/src/main.rs b/boards/camera/src/main.rs index 2c3a1cce..d73559ee 100644 --- a/boards/camera/src/main.rs +++ b/boards/camera/src/main.rs @@ -122,7 +122,7 @@ mod app { }); if (*cx.local.num < 3) { *cx.local.num += 1; - spawn_after!(toggle_cams, ExtU64::millis(250)); + spawn_after!(toggle_cams, ExtU64::millis(100)); } } diff --git a/boards/recovery/src/gpio_manager.rs b/boards/recovery/src/gpio_manager.rs index 5f228b3d..997e9b46 100644 --- a/boards/recovery/src/gpio_manager.rs +++ b/boards/recovery/src/gpio_manager.rs @@ -2,17 +2,17 @@ use atsamd_hal::gpio::{Pin, PushPullOutput, PA09, PA06}; use atsamd_hal::prelude::*; pub struct GPIOManager { - drogue_ematch: Pin, main_ematch: Pin, + drogue_ematch: Pin, } impl GPIOManager { - pub fn new(mut drogue_ematch: Pin, mut main_ematch: Pin) -> Self { + pub fn new(mut main_ematch: Pin, mut drogue_ematch: Pin) -> Self { drogue_ematch.set_low().ok(); main_ematch.set_low().ok(); Self { + main_ematch, drogue_ematch, - main_ematch } } pub fn fire_drogue(&mut self) { diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 3d4a882f..38722fc4 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -91,8 +91,8 @@ mod app { let led_green = pins.pb16.into_push_pull_output(); let led_red = pins.pb17.into_push_pull_output(); let gpio = GPIOManager::new( - pins.pa09.into_push_pull_output(), pins.pa06.into_push_pull_output(), + pins.pa09.into_push_pull_output(), ); /* State Machine config */ let state_machine = StateMachine::new(); From e527a57315d78cc09bb3074f75b731051a2b9640 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Sun, 27 Aug 2023 23:30:12 -0400 Subject: [PATCH 29/30] Don't always pull pyros high --- boards/recovery/src/gpio_manager.rs | 2 +- boards/recovery/src/main.rs | 10 +++++----- boards/recovery/src/state_machine/states/descent.rs | 4 +++- .../src/state_machine/states/terminal_descent.rs | 5 +++-- 4 files changed, 12 insertions(+), 9 deletions(-) diff --git a/boards/recovery/src/gpio_manager.rs b/boards/recovery/src/gpio_manager.rs index 997e9b46..d8ed973e 100644 --- a/boards/recovery/src/gpio_manager.rs +++ b/boards/recovery/src/gpio_manager.rs @@ -21,7 +21,7 @@ impl GPIOManager { pub fn fire_main(&mut self) { self.main_ematch.set_high().ok(); } - pub fn close_drouge(&mut self) { + pub fn close_drogue(&mut self) { self.drogue_ematch.set_low().ok(); } pub fn close_main(&mut self) { diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 38722fc4..777e12df 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -101,8 +101,8 @@ mod app { run_sm::spawn().ok(); state_send::spawn().ok(); blink::spawn().ok(); - fire_main::spawn_after(ExtU64::secs(15)).ok(); - fire_drogue::spawn_after(ExtU64::secs(15)).ok(); + // fire_main::spawn_after(ExtU64::secs(15)).ok(); + // fire_drogue::spawn_after(ExtU64::secs(15)).ok(); /* Monotonic clock */ let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); @@ -132,12 +132,12 @@ mod app { gpio.fire_drogue(); *cx.local.fired = true; }); + spawn_after!(fire_drogue, ExtU64::secs(5)); } else { cx.shared.gpio.lock(|gpio| { - gpio.close_drouge(); + gpio.close_drogue(); }); } - spawn_after!(fire_drogue, ExtU64::secs(5)); } #[task(local = [fired: bool = false], shared=[gpio])] @@ -147,12 +147,12 @@ mod app { gpio.fire_main(); *cx.local.fired = true; }); + spawn_after!(fire_main, ExtU64::secs(5)); } else { cx.shared.gpio.lock(|gpio| { gpio.close_main(); }); } - spawn_after!(fire_main, ExtU64::secs(5)); } /// Runs the state machine. diff --git a/boards/recovery/src/state_machine/states/descent.rs b/boards/recovery/src/state_machine/states/descent.rs index 09ac9436..61d7f7e6 100644 --- a/boards/recovery/src/state_machine/states/descent.rs +++ b/boards/recovery/src/state_machine/states/descent.rs @@ -1,15 +1,17 @@ use super::Ascent; +use crate::app::fire_drogue; use crate::state_machine::{TerminalDescent, RocketStates, State, StateMachineContext, TransitionInto}; use crate::{no_transition, transition}; use rtic::mutex::Mutex; use defmt::{write, Format, Formatter, info}; +use common_arm::spawn; #[derive(Debug, Clone)] pub struct Descent {} impl State for Descent { fn enter(&self, context: &mut StateMachineContext) { - context.shared_resources.gpio.lock(|gpio| gpio.fire_drogue()); + spawn!(fire_drogue); } fn step(&mut self, context: &mut StateMachineContext) -> Option { context.shared_resources.data_manager.lock(|data| { diff --git a/boards/recovery/src/state_machine/states/terminal_descent.rs b/boards/recovery/src/state_machine/states/terminal_descent.rs index a307ff13..f5f02cda 100644 --- a/boards/recovery/src/state_machine/states/terminal_descent.rs +++ b/boards/recovery/src/state_machine/states/terminal_descent.rs @@ -1,16 +1,17 @@ use defmt::{write, Format, Formatter, info}; - +use crate::app::fire_main; use crate::{no_transition, transition}; use crate::state_machine::{WaitForRecovery, RocketStates, State, StateMachineContext, TransitionInto}; use rtic::mutex::Mutex; use super::Descent; +use common_arm::spawn; #[derive(Debug, Clone)] pub struct TerminalDescent {} impl State for TerminalDescent { fn enter(&self,context: &mut StateMachineContext) { - context.shared_resources.gpio.lock(|gpio| gpio.fire_main()); + spawn!(fire_main); } fn step(&mut self, context: &mut StateMachineContext) -> Option { context From 0657cc392bdbb5ae9a7722a4904e4d7345f4a9d3 Mon Sep 17 00:00:00 2001 From: Noah Sprenger Date: Wed, 6 Sep 2023 14:23:21 -0400 Subject: [PATCH 30/30] post comp, idk what got added --- boards/camera/src/communication.rs | 16 --------------- boards/camera/src/data_manager.rs | 4 ++-- boards/camera/src/main.rs | 20 +++++++++++++------ .../camera/src/state_machine/states/ascent.rs | 6 ++---- boards/recovery/src/data_manager.rs | 4 ++-- boards/recovery/src/gpio_manager.rs | 6 +++--- boards/recovery/src/main.rs | 8 ++++---- boards/sensor/src/sd_manager.rs | 2 +- 8 files changed, 28 insertions(+), 38 deletions(-) diff --git a/boards/camera/src/communication.rs b/boards/camera/src/communication.rs index 34281ace..e30a7d54 100644 --- a/boards/camera/src/communication.rs +++ b/boards/camera/src/communication.rs @@ -136,22 +136,6 @@ impl CanDevice0 { gclk0, ) } - pub fn send_message(&mut self, m: Message) -> Result<(), HydraError> { - let payload: Vec = postcard::to_vec(&m)?; - self.can.tx.transmit_queued( - tx::MessageBuilder { - id: ecan::Id::Standard(ecan::StandardId::new(m.sender.into()).unwrap()), - frame_type: tx::FrameType::FlexibleDatarate { - payload: &payload[..], - bit_rate_switching: false, - force_error_state_indicator: false, - }, - store_tx_event: None, - } - .build()?, - )?; - Ok(()) - } pub fn process_data(&mut self, data_manager: &mut DataManager) { let line_interrupts = &self.line_interrupts; for interrupt in line_interrupts.iter_flagged() { diff --git a/boards/camera/src/data_manager.rs b/boards/camera/src/data_manager.rs index 4e82c75c..5349b9c5 100644 --- a/boards/camera/src/data_manager.rs +++ b/boards/camera/src/data_manager.rs @@ -4,8 +4,8 @@ use messages::state::{State, StateData}; use defmt::info; use heapless::HistoryBuffer; -const MAIN_HEIGHT: f32 = 500.0; // meters -const HEIGHT_MIN: f32 = 300.0; // meters +const MAIN_HEIGHT: f32 = 876.0; // meters +const HEIGHT_MIN: f32 = 600.0; // meters pub struct DataManager { pub air: Option, diff --git a/boards/camera/src/main.rs b/boards/camera/src/main.rs index d73559ee..66dcf2b3 100644 --- a/boards/camera/src/main.rs +++ b/boards/camera/src/main.rs @@ -94,11 +94,9 @@ mod app { let state_machine = StateMachine::new(); - /* Spawn tasks */ - spawn!(toggle_cams); - - // run_sm::spawn().ok(); - + /* Spawn tasks */ + run_sm::spawn().ok(); + blink::spawn().ok(); /* Monotonic clock */ let mono = Systick::new(core.SYST, gclk0.freq().to_Hz()); @@ -111,6 +109,16 @@ mod app { loop {} } + /// Handles the CAN0 interrupt. + #[task(binds = CAN0, shared = [can0, data_manager])] + fn can0(mut cx: can0::Context) { + cx.shared.can0.lock(|can| { + cx.shared + .data_manager + .lock(|data_manager| can.process_data(data_manager)); + }); + } + #[task(priority = 3, local = [num: u8 = 0], shared = [gpio_manager, &em])] fn toggle_cams(mut cx: toggle_cams::Context) { cx.shared.em.run(|| { @@ -122,7 +130,7 @@ mod app { }); if (*cx.local.num < 3) { *cx.local.num += 1; - spawn_after!(toggle_cams, ExtU64::millis(100)); + spawn_after!(toggle_cams, ExtU64::millis(150)); } } diff --git a/boards/camera/src/state_machine/states/ascent.rs b/boards/camera/src/state_machine/states/ascent.rs index 1809219a..c86df4d5 100644 --- a/boards/camera/src/state_machine/states/ascent.rs +++ b/boards/camera/src/state_machine/states/ascent.rs @@ -10,16 +10,14 @@ use crate::types::COM_ID; use crate::app::monotonics; use systick_monotonic::ExtU64; use crate::app::toggle_cams; -use common_arm::spawn_after; +use common_arm::spawn; #[derive(Debug, Clone)] pub struct Ascent {} impl State for Ascent { fn enter(&self, context: &mut StateMachineContext) { - for i in 0..3 { - spawn_after!(toggle_cams, ExtU64::millis(2)); - } + spawn!(toggle_cams); } fn step(&mut self, context: &mut StateMachineContext) -> Option { context diff --git a/boards/recovery/src/data_manager.rs b/boards/recovery/src/data_manager.rs index dcbae290..3125ed42 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -6,8 +6,8 @@ use messages::sensor::{Air, EkfNav1, EkfNav2, EkfQuat, GpsVel, Imu1, Imu2, UtcTi use messages::Message; use defmt::{info}; -const MAIN_HEIGHT: f32 = 500.0; // meters -const HEIGHT_MIN: f32 = 300.0; // meters +const MAIN_HEIGHT: f32 = 876.0; // meters ASL +const HEIGHT_MIN: f32 = 600.0; // meters ASL pub struct DataManager { pub air: Option, diff --git a/boards/recovery/src/gpio_manager.rs b/boards/recovery/src/gpio_manager.rs index d8ed973e..a26897ec 100644 --- a/boards/recovery/src/gpio_manager.rs +++ b/boards/recovery/src/gpio_manager.rs @@ -2,12 +2,12 @@ use atsamd_hal::gpio::{Pin, PushPullOutput, PA09, PA06}; use atsamd_hal::prelude::*; pub struct GPIOManager { - main_ematch: Pin, - drogue_ematch: Pin, + main_ematch: Pin, + drogue_ematch: Pin, } impl GPIOManager { - pub fn new(mut main_ematch: Pin, mut drogue_ematch: Pin) -> Self { + pub fn new(mut main_ematch: Pin, mut drogue_ematch: Pin) -> Self { drogue_ematch.set_low().ok(); main_ematch.set_low().ok(); Self { diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 777e12df..9cecc3d3 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -90,9 +90,9 @@ mod app { /* GPIO config */ let led_green = pins.pb16.into_push_pull_output(); let led_red = pins.pb17.into_push_pull_output(); - let gpio = GPIOManager::new( - pins.pa06.into_push_pull_output(), + let gpio = GPIOManager::new( // pins switched from schematic pins.pa09.into_push_pull_output(), + pins.pa06.into_push_pull_output(), ); /* State Machine config */ let state_machine = StateMachine::new(); @@ -125,7 +125,7 @@ mod app { loop {} } - #[task(local = [fired: bool = false], shared=[gpio])] + #[task(priority = 3, local = [fired: bool = false], shared=[gpio])] fn fire_drogue(mut cx: fire_drogue::Context) { if !(*cx.local.fired) { cx.shared.gpio.lock(|gpio| { @@ -140,7 +140,7 @@ mod app { } } - #[task(local = [fired: bool = false], shared=[gpio])] + #[task(priority = 3, local = [fired: bool = false], shared=[gpio])] fn fire_main(mut cx: fire_main::Context) { if !(*cx.local.fired) { cx.shared.gpio.lock(|gpio| { diff --git a/boards/sensor/src/sd_manager.rs b/boards/sensor/src/sd_manager.rs index c81da1e4..6289ac1f 100644 --- a/boards/sensor/src/sd_manager.rs +++ b/boards/sensor/src/sd_manager.rs @@ -90,7 +90,7 @@ impl SdManager { let file = sd_cont.open_file_in_dir( &mut volume, &root_directory, - "test2.txt", + "sbg.txt", sd::Mode::ReadWriteCreateOrTruncate, ); let file = match file {