diff --git a/boards/camera/src/communication.rs b/boards/camera/src/communication.rs index e30a7d54..44ef5c5e 100644 --- a/boards/camera/src/communication.rs +++ b/boards/camera/src/communication.rs @@ -1,32 +1,32 @@ 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::gpio::{Alternate, AlternateI, Pin, I, PA22, PA23}; 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; @@ -37,13 +37,13 @@ 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; diff --git a/boards/camera/src/data_manager.rs b/boards/camera/src/data_manager.rs index 54569fa9..b47309a7 100644 --- a/boards/camera/src/data_manager.rs +++ b/boards/camera/src/data_manager.rs @@ -1,6 +1,6 @@ use messages::sensor::{Air}; use messages::Message; -use messages::state::{State, StateData}; + use defmt::info; use heapless::HistoryBuffer; diff --git a/boards/camera/src/gpio_manager.rs b/boards/camera/src/gpio_manager.rs index 5ab28d08..813222b8 100644 --- a/boards/camera/src/gpio_manager.rs +++ b/boards/camera/src/gpio_manager.rs @@ -7,7 +7,7 @@ pub struct GPIOManager { } impl GPIOManager { - pub fn new(mut cam1: Pin, mut cam2: Pin) -> Self { + pub fn new(cam1: Pin, cam2: Pin) -> Self { Self { cam1, cam2 diff --git a/boards/camera/src/main.rs b/boards/camera/src/main.rs index 66dcf2b3..fa890c62 100644 --- a/boards/camera/src/main.rs +++ b/boards/camera/src/main.rs @@ -69,7 +69,7 @@ mod app { // SAFETY: Misusing the PAC API can break the system. // This is safe because we only steal the MCLK. - let (_, _, _, mclk) = unsafe { clocks.pac.steal() }; + let (_, _, _, _mclk) = unsafe { clocks.pac.steal() }; /* CAN config */ let (pclk_can, gclk0) = Pclk::enable(tokens.pclks.can0, gclk0); @@ -128,9 +128,9 @@ mod app { }); Ok(()) }); - if (*cx.local.num < 3) { + if *cx.local.num < 3 { *cx.local.num += 1; - spawn_after!(toggle_cams, ExtU64::millis(150)); + spawn_after!(toggle_cams, ExtU64::millis(150)).ok(); } } diff --git a/boards/camera/src/state_machine/states/ascent.rs b/boards/camera/src/state_machine/states/ascent.rs index c86df4d5..dcf40fde 100644 --- a/boards/camera/src/state_machine/states/ascent.rs +++ b/boards/camera/src/state_machine/states/ascent.rs @@ -2,13 +2,10 @@ 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; @@ -16,20 +13,17 @@ use common_arm::spawn; pub struct Ascent {} impl State for Ascent { - fn enter(&self, context: &mut StateMachineContext) { - spawn!(toggle_cams); + fn enter(&self, _context: &mut StateMachineContext) { + spawn!(toggle_cams).ok(); } 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!() - } - }) + context.shared_resources.data_manager.lock(|data| { + if data.is_falling() { + transition!(self, Descent) + } else { + no_transition!() + } + }) } } diff --git a/boards/camera/src/state_machine/states/descent.rs b/boards/camera/src/state_machine/states/descent.rs index 18596061..cab492af 100644 --- a/boards/camera/src/state_machine/states/descent.rs +++ b/boards/camera/src/state_machine/states/descent.rs @@ -2,7 +2,7 @@ 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}; +use defmt::{write, Format, Formatter}; #[derive(Debug, Clone)] pub struct Descent {} diff --git a/boards/camera/src/state_machine/states/terminal_descent.rs b/boards/camera/src/state_machine/states/terminal_descent.rs index 47394287..d70a68f2 100644 --- a/boards/camera/src/state_machine/states/terminal_descent.rs +++ b/boards/camera/src/state_machine/states/terminal_descent.rs @@ -1,4 +1,4 @@ -use defmt::{write, Format, Formatter, info}; +use defmt::{write, Format, Formatter}; use crate::{no_transition, transition}; use crate::state_machine::{WaitForRecovery, RocketStates, State, StateMachineContext, TransitionInto}; diff --git a/boards/camera/src/state_machine/states/wait_for_recovery.rs b/boards/camera/src/state_machine/states/wait_for_recovery.rs index 5ced98af..289c3b49 100644 --- a/boards/camera/src/state_machine/states/wait_for_recovery.rs +++ b/boards/camera/src/state_machine/states/wait_for_recovery.rs @@ -1,20 +1,14 @@ use super::TerminalDescent; -use crate::app::monotonics; +use crate::no_transition; 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; +use defmt::{write, Format, Formatter}; #[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. + 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/camera/src/types.rs b/boards/camera/src/types.rs index 72b4b3ca..a8497d2e 100644 --- a/boards/camera/src/types.rs +++ b/boards/camera/src/types.rs @@ -2,4 +2,4 @@ use messages::sender::{Sender, Sender::CameraBoard}; // ------- // Sender ID // ------- -pub static COM_ID: Sender = CameraBoard; \ No newline at end of file +pub static _COM_ID: Sender = CameraBoard; \ No newline at end of file diff --git a/boards/communication/src/communication.rs b/boards/communication/src/communication.rs index 41ae89aa..c35309a6 100644 --- a/boards/communication/src/communication.rs +++ b/boards/communication/src/communication.rs @@ -1,4 +1,3 @@ -use crate::app::send_internal; use crate::data_manager::DataManager; use crate::types::*; use atsamd_hal::can::Dependencies; @@ -14,18 +13,15 @@ use atsamd_hal::pac::CAN0; use atsamd_hal::pac::MCLK; use atsamd_hal::pac::SERCOM5; use atsamd_hal::sercom; -use atsamd_hal::sercom::uart::{Duplex, Uart}; -use atsamd_hal::sercom::uart::{RxDuplex, TxDuplex}; +use atsamd_hal::sercom::uart::{Uart}; +use atsamd_hal::sercom::uart::{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 heapless::Vec; use mcan::bus::Can; @@ -300,7 +296,7 @@ impl RadioManager { buf_select: false, } } - pub fn process_message(&mut self, buf: RadioBuffer) { + pub fn _process_message(&mut self, buf: RadioBuffer) { match from_bytes::(buf) { Ok(msg) => { info!("Radio: {}", msg); diff --git a/boards/communication/src/data_manager.rs b/boards/communication/src/data_manager.rs index cfe92b33..0c5b37fb 100644 --- a/boards/communication/src/data_manager.rs +++ b/boards/communication/src/data_manager.rs @@ -1,9 +1,9 @@ use defmt::info; -use messages::command::{Command, CommandData, RadioRate, RadioRateChange}; +use messages::command::{RadioRate}; use messages::sensor::{ Air, EkfNav1, EkfNav2, EkfQuat, GpsPos1, GpsPos2, GpsVel, Imu1, Imu2, SensorData, UtcTime, }; -use messages::state::{State, StateData}; +use messages::state::{StateData}; use messages::Message; #[derive(Clone)] diff --git a/boards/communication/src/main.rs b/boards/communication/src/main.rs index 897aebd5..5ef31810 100644 --- a/boards/communication/src/main.rs +++ b/boards/communication/src/main.rs @@ -18,12 +18,10 @@ use communication::{RadioDevice, RadioManager}; use data_manager::DataManager; // use communication::radio_dma; -use defmt::{flush, info}; use hal::gpio::Pins; 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; diff --git a/boards/communication/src/types.rs b/boards/communication/src/types.rs index 4cdaf702..f82b0fdb 100644 --- a/boards/communication/src/types.rs +++ b/boards/communication/src/types.rs @@ -1,10 +1,8 @@ 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 atsamd_hal::sercom::{Sercom5, 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; diff --git a/boards/power/src/communication.rs b/boards/power/src/communication.rs index 3e11ed29..e78355b0 100644 --- a/boards/power/src/communication.rs +++ b/boards/power/src/communication.rs @@ -123,7 +123,7 @@ impl CanDevice0 { 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 { @@ -139,7 +139,7 @@ impl CanDevice0 { )?; Ok(()) } - pub fn process_data(&mut self, data_manager: &mut DataManager) { + 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 { diff --git a/boards/power/src/data_manager.rs b/boards/power/src/data_manager.rs index b7cdb6d3..cfb3ea57 100644 --- a/boards/power/src/data_manager.rs +++ b/boards/power/src/data_manager.rs @@ -1,5 +1,5 @@ // import messages -use messages::sensor::{Current, Voltage, Regulator, Temperature, SensorData}; +use messages::sensor::{Current, Regulator, SensorData, Temperature, Voltage}; use messages::Message; pub struct DataManager { @@ -11,14 +11,14 @@ pub struct DataManager { impl DataManager { pub fn new() -> Self { - 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] { + pub fn _clone_power(&self) -> [Option; 13] { [ self.regulator[0].clone().map(|x| x.into()), self.regulator[1].clone().map(|x| x.into()), @@ -35,8 +35,8 @@ impl DataManager { self.temperature[3].clone().map(|x| x.into()), ] } - pub fn handle_data(&mut self, data: Message) { - // to do + pub fn handle_data(&mut self, _data: Message) { + // to do } } @@ -44,4 +44,4 @@ impl Default for DataManager { fn default() -> Self { Self::new() } -} \ No newline at end of file +} diff --git a/boards/power/src/types.rs b/boards/power/src/types.rs index cf6f8db0..4d556224 100644 --- a/boards/power/src/types.rs +++ b/boards/power/src/types.rs @@ -2,4 +2,4 @@ use messages::sender::{Sender, Sender::PowerBoard}; // ------- // Sender ID // ------- -pub static COM_ID: Sender = PowerBoard; \ No newline at end of file +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 f479fa75..42e384f3 100644 --- a/boards/recovery/src/data_manager.rs +++ b/boards/recovery/src/data_manager.rs @@ -159,11 +159,11 @@ impl DataManager { } }, messages::Data::Command(command) => match command.data { - messages::command::CommandData::DeployDrogue(drogue) => { - spawn!(fire_drogue); + messages::command::CommandData::DeployDrogue(_drogue) => { + spawn!(fire_drogue).ok(); }, - messages::command::CommandData::DeployMain(main) => { - spawn!(fire_main); + messages::command::CommandData::DeployMain(_main) => { + spawn!(fire_main).ok(); }, messages::command::CommandData::PowerDown(_) => { // don't handle for now. diff --git a/boards/recovery/src/main.rs b/boards/recovery/src/main.rs index 9cecc3d3..869c91e7 100644 --- a/boards/recovery/src/main.rs +++ b/boards/recovery/src/main.rs @@ -24,7 +24,6 @@ use panic_halt as _; use state_machine::{StateMachine, StateMachineContext}; use systick_monotonic::*; use types::COM_ID; -use defmt::info; #[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] mod app { @@ -132,7 +131,7 @@ mod app { gpio.fire_drogue(); *cx.local.fired = true; }); - spawn_after!(fire_drogue, ExtU64::secs(5)); + spawn_after!(fire_drogue, ExtU64::secs(5)).ok(); } else { cx.shared.gpio.lock(|gpio| { gpio.close_drogue(); @@ -147,7 +146,7 @@ mod app { gpio.fire_main(); *cx.local.fired = true; }); - spawn_after!(fire_main, ExtU64::secs(5)); + spawn_after!(fire_main, ExtU64::secs(5)).ok(); } else { cx.shared.gpio.lock(|gpio| { gpio.close_main(); @@ -208,7 +207,7 @@ mod app { spawn!(send_internal, message)?; Ok(()) }); - spawn_after!(state_send, ExtU64::secs(2)); + spawn_after!(state_send, ExtU64::secs(2)).ok(); } /// Simple blink task to test the system. diff --git a/boards/recovery/src/state_machine/states/ascent.rs b/boards/recovery/src/state_machine/states/ascent.rs index fdcb6f9b..c189459b 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::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::command::{Command, RadioRateChange, RadioRate}; use messages::Message; use defmt::{write, Format, Formatter}; use rtic::mutex::Mutex; @@ -14,7 +14,7 @@ pub struct Ascent {} impl State for Ascent { fn enter(&self, context: &mut StateMachineContext) { - for i in 0..10 { + for _i in 0..10 { let radio_rate_change = RadioRateChange { rate: RadioRate::Fast, }; diff --git a/boards/recovery/src/state_machine/states/descent.rs b/boards/recovery/src/state_machine/states/descent.rs index 61d7f7e6..fd475984 100644 --- a/boards/recovery/src/state_machine/states/descent.rs +++ b/boards/recovery/src/state_machine/states/descent.rs @@ -3,15 +3,15 @@ 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 defmt::{write, Format, Formatter}; use common_arm::spawn; #[derive(Debug, Clone)] pub struct Descent {} impl State for Descent { - fn enter(&self, context: &mut StateMachineContext) { - spawn!(fire_drogue); + fn enter(&self, _context: &mut StateMachineContext) { + spawn!(fire_drogue).ok(); } 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 f5f02cda..12aff896 100644 --- a/boards/recovery/src/state_machine/states/terminal_descent.rs +++ b/boards/recovery/src/state_machine/states/terminal_descent.rs @@ -1,4 +1,4 @@ -use defmt::{write, Format, Formatter, info}; +use defmt::{write, Format, Formatter}; use crate::app::fire_main; use crate::{no_transition, transition}; use crate::state_machine::{WaitForRecovery, RocketStates, State, StateMachineContext, TransitionInto}; @@ -10,8 +10,8 @@ use common_arm::spawn; pub struct TerminalDescent {} impl State for TerminalDescent { - fn enter(&self,context: &mut StateMachineContext) { - spawn!(fire_main); + fn enter(&self, _context: &mut StateMachineContext) { + spawn!(fire_main).ok(); } fn step(&mut self, context: &mut StateMachineContext) -> Option { context 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 1e597479..2ece34f6 100644 --- a/boards/recovery/src/state_machine/states/wait_for_recovery.rs +++ b/boards/recovery/src/state_machine/states/wait_for_recovery.rs @@ -2,10 +2,10 @@ 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 crate::{no_transition}; use rtic::mutex::Mutex; -use defmt::{write, Format, Formatter, info}; -use messages::command::{Command, CommandData, PowerDown, RadioRateChange, RadioRate}; +use defmt::{write, Format, Formatter}; +use messages::command::{Command, PowerDown, RadioRateChange, RadioRate}; use messages::Message; use messages::sender::Sender::SensorBoard; @@ -16,7 +16,7 @@ impl State for WaitForRecovery { fn enter(&self, context: &mut StateMachineContext) { // This should change to a ack and not be sent 10 times // send a command over CAN to shut down non-critical systems for recovery. - for i in 0..10 { + for _i in 0..10 { let sensor_power_down = PowerDown { board: SensorBoard }; @@ -34,7 +34,7 @@ impl State for WaitForRecovery { }); } } - fn step(&mut self, context: &mut StateMachineContext) -> Option { + 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/recovery/src/types.rs b/boards/recovery/src/types.rs index bc4e098d..f6051986 100644 --- a/boards/recovery/src/types.rs +++ b/boards/recovery/src/types.rs @@ -1,5 +1,3 @@ -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 59af1120..ed236c2f 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, Can1}; +use atsamd_hal::clock::v2::types::{Can0}; 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::gpio::{Alternate, AlternateI, Pin, I, PA22, PA23}; +use atsamd_hal::pac::{CAN0}; use atsamd_hal::typelevel::Increment; use common_arm::mcan; @@ -31,7 +31,7 @@ use postcard::from_bytes; use systick_monotonic::fugit::RateExtU32; use typenum::{U0, U128, U32, U64}; -use crate::data_manager::{DataManager, self}; +use crate::data_manager::{DataManager}; pub struct Capacities; diff --git a/boards/sensor/src/data_manager.rs b/boards/sensor/src/data_manager.rs index 053c5cb0..c6ab6a2f 100644 --- a/boards/sensor/src/data_manager.rs +++ b/boards/sensor/src/data_manager.rs @@ -1,9 +1,7 @@ use common_arm::spawn; -use messages::sender::Sender; 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; #[derive(Clone)] pub struct DataManager { @@ -47,8 +45,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) => { - spawn!(sleep_system); + 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 53a6d0eb..662d1658 100644 --- a/boards/sensor/src/main.rs +++ b/boards/sensor/src/main.rs @@ -4,7 +4,6 @@ mod communication; mod data_manager; mod sbg_manager; -mod sd_manager; mod types; use atsamd_hal as hal; @@ -12,20 +11,22 @@ 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::SdManager; +use hal::gpio::Output; 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::{PB16, PB17, PB10, PB01, PushPull}; use hal::gpio::{Pin, PushPullOutput}; use hal::prelude::*; +use hal::sercom::{spi, Sercom4, IoSet2}; 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}; @@ -36,8 +37,6 @@ use types::*; #[rtic::app(device = hal::pac, peripherals = true, dispatchers = [EVSYS_0, EVSYS_1, EVSYS_2])] mod app { - use defmt::flush; - use super::*; #[shared] @@ -45,7 +44,10 @@ mod app { em: ErrorManager, data_manager: DataManager, can: communication::CanDevice0, - sd_manager: SdManager, + sd_manager: SdManager< + SdSpi, + Pin>, + >, } #[local] @@ -101,17 +103,19 @@ mod app { false, ); - // /* SD config */ + /* 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 pads_spi = spi::Pads::::default() + .sclk(pins.pb09) + .data_in(pins.pb11) + .data_out(pins.pb08); + + 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.pb10.into_push_pull_output()); /* SBG config */ let (pclk_sbg, gclk0) = Pclk::enable(tokens.pclks.sercom5, gclk0); @@ -168,12 +172,12 @@ mod app { // close out sd files. cx.shared.sd_manager.lock(|sd| { cx.shared.em.run(|| { - sd.close_current_file(); + _ = sd.close_current_file(); Ok(()) }); }); // power down sbg - cx.local.sbg_power_pin.set_low(); // define hydra error for this error type. + _ = 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 9208ade9..c6772b97 100644 --- a/boards/sensor/src/sbg_manager.rs +++ b/boards/sensor/src/sbg_manager.rs @@ -4,7 +4,7 @@ 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::gpio::{Pin, Reset, PB03, PB02}; use atsamd_hal::pac::{MCLK, RTC}; // use atsamd_hal::prelude::_atsamd21_hal_time_U32Ext; use atsamd_hal::rtc::Rtc; @@ -136,7 +136,7 @@ pub fn sbg_dma(cx: crate::app::sbg_dma::Context) { xfer.block_transfer_interrupt(); sbg.xfer = Some(xfer); cx.shared.em.run(|| { - spawn!(sbg_sd(buf_clone)); + _ = spawn!(sbg_sd, buf_clone); Ok(()) }); } diff --git a/boards/sensor/src/sd_manager.rs b/boards/sensor/src/sd_manager.rs deleted file mode 100644 index 6289ac1f..00000000 --- a/boards/sensor/src/sd_manager.rs +++ /dev/null @@ -1,148 +0,0 @@ -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, - "sbg.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 c2a8cbd5..b957dc5d 100644 --- a/boards/sensor/src/types.rs +++ b/boards/sensor/src/types.rs @@ -1,10 +1,8 @@ -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; @@ -41,7 +39,5 @@ pub type SdPads = spi::Pads< Pin>, Pin>, >; -pub type SdController = sd::Controller< - sd::SdMmcSpi, spi::Duplex>, Pin>>, - TimeSink, ->; \ No newline at end of file + +pub type SdSpi = spi::Spi, spi::Duplex>; \ No newline at end of file diff --git a/libraries/common-arm/src/sd_manager.rs b/libraries/common-arm/src/sd_manager.rs index bd6bab0c..12d1dd0b 100644 --- a/libraries/common-arm/src/sd_manager.rs +++ b/libraries/common-arm/src/sd_manager.rs @@ -1,9 +1,7 @@ use core::{marker::PhantomData, fmt::Debug}; -use defmt::{info, warn}; -use atsamd_hal::gpio::{Output, Pin, PushPull, PB14}; +use defmt::{info}; 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 diff --git a/libraries/messages/src/sensor.rs b/libraries/messages/src/sensor.rs index 63ad0522..bc04937a 100644 --- a/libraries/messages/src/sensor.rs +++ b/libraries/messages/src/sensor.rs @@ -45,11 +45,11 @@ pub enum SensorData { #[cfg_attr(feature = "ts", ts(export))] pub struct GpsPos1 { #[doc = "< Time in us since the sensor power up."] - pub timeStamp: u32, + pub time_stamp: u32, #[doc = "< GPS position status, type and bitmask."] pub status: u32, #[doc = "< GPS time of week in ms."] - pub timeOfWeek: u32, + pub time_of_week: u32, #[doc = "< Latitude in degrees, positive north."] pub latitude: f64, #[doc = "< Longitude in degrees, positive east."] @@ -67,17 +67,17 @@ pub struct GpsPos1 { #[cfg_attr(feature = "ts", ts(export))] pub struct GpsPos2 { #[doc = "< 1 sigma latitude accuracy in meters."] - pub latitudeAccuracy: f32, + pub latitude_accuracy: f32, #[doc = "< 1 sigma longitude accuracy in meters."] - pub longitudeAccuracy: f32, + pub longitude_accuracy: f32, #[doc = "< 1 sigma altitude accuracy in meters."] - pub altitudeAccuracy: f32, + pub altitude_accuracy: f32, #[doc = "< Number of space vehicles used to compute the solution (since version 1.4)."] - pub numSvUsed: u8, + pub num_sv_used: 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, + pub base_station_id: 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, + pub differential_age: u16, } #[derive(Serialize, Deserialize, Clone, Debug, Format)] diff --git a/libraries/sbg-rs/src/data_conversion.rs b/libraries/sbg-rs/src/data_conversion.rs index 84dc95d0..6d4701fe 100644 --- a/libraries/sbg-rs/src/data_conversion.rs +++ b/libraries/sbg-rs/src/data_conversion.rs @@ -7,21 +7,21 @@ impl From for (GpsPos1, GpsPos2) { fn from(value: SbgLogGpsPos) -> Self { ( GpsPos1 { - timeStamp: value.timeStamp, + time_stamp: value.timeStamp, status: value.status, - timeOfWeek: value.timeOfWeek, + time_of_week: 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, + latitude_accuracy: value.latitudeAccuracy, + longitude_accuracy: value.longitudeAccuracy, + altitude_accuracy: value.altitudeAccuracy, + num_sv_used: value.numSvUsed, + base_station_id: value.baseStationId, + differential_age: value.differentialAge, }, ) } diff --git a/libraries/sbg-rs/src/sbg.rs b/libraries/sbg-rs/src/sbg.rs index cef06c56..9135b155 100644 --- a/libraries/sbg-rs/src/sbg.rs +++ b/libraries/sbg-rs/src/sbg.rs @@ -17,7 +17,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, info}; +use defmt::{flush, warn}; use embedded_hal::serial::Write; use hal::gpio::{PB16, PB17, PB03, PB02}; use hal::sercom::uart::Duplex; @@ -156,7 +156,7 @@ impl SBG { // 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)}; + _ = 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. @@ -278,7 +278,7 @@ impl SBG { _pInterface: *mut _SbgInterface, pBuffer: *mut c_void, pBytesRead: *mut usize, - mut bytesToRead: usize, + bytesToRead: usize, ) -> _SbgErrorCode { if pBuffer.is_null() { return _SbgErrorCode_SBG_NULL_POINTER; @@ -292,7 +292,6 @@ impl SBG { 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() { @@ -306,46 +305,6 @@ impl SBG { // 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 } /**