diff --git a/src/ad5680.rs b/src/ad5680.rs index 9af3bd4..aecb73f 100644 --- a/src/ad5680.rs +++ b/src/ad5680.rs @@ -1,12 +1,9 @@ -use stm32f4xx_hal::{ - hal::{ - blocking::spi::Transfer, - digital::v2::OutputPin, - }, - time::MegaHertz, - spi, -}; use crate::timer::sleep; +use stm32f4xx_hal::{ + hal::{blocking::spi::Transfer, digital::v2::OutputPin}, + spi, + time::MegaHertz, +}; /// SPI Mode 1 pub const SPI_MODE: spi::Mode = spi::Mode { @@ -27,11 +24,8 @@ pub struct Dac, S: OutputPin> { impl, S: OutputPin> Dac { pub fn new(spi: SPI, mut sync: S) -> Self { let _ = sync.set_low(); - - Dac { - spi, - sync, - } + + Dac { spi, sync } } fn write(&mut self, buf: &mut [u8]) -> Result<(), SPI::Error> { @@ -47,11 +41,7 @@ impl, S: OutputPin> Dac { pub fn set(&mut self, value: u32) -> Result { let value = value.min(MAX_VALUE); - let mut buf = [ - (value >> 14) as u8, - (value >> 6) as u8, - (value << 2) as u8, - ]; + let mut buf = [(value >> 14) as u8, (value >> 6) as u8, (value << 2) as u8]; self.write(&mut buf)?; Ok(value) } diff --git a/src/ad7172/adc.rs b/src/ad7172/adc.rs index 68ebab3..1a1df3e 100644 --- a/src/ad7172/adc.rs +++ b/src/ad7172/adc.rs @@ -1,18 +1,12 @@ +use super::{ + checksum::{Checksum, ChecksumMode}, + regs::{self, Register, RegisterData}, + DigitalFilterOrder, Input, Mode, PostFilter, RefSource, +}; use core::fmt; use log::{info, warn}; -use stm32f4xx_hal::hal::{ - blocking::spi::Transfer, - digital::v2::OutputPin, -}; -use uom::si::{ - f64::ElectricPotential, - electric_potential::volt, -}; -use super::{ - regs::{self, Register, RegisterData}, - checksum::{ChecksumMode, Checksum}, - Mode, Input, RefSource, PostFilter, DigitalFilterOrder, -}; +use stm32f4xx_hal::hal::{blocking::spi::Transfer, digital::v2::OutputPin}; +use uom::si::{electric_potential::volt, f64::ElectricPotential}; /// AD7172-2 implementation /// @@ -27,7 +21,8 @@ impl, NSS: OutputPin, E: fmt::Debug> Adc pub fn new(spi: SPI, mut nss: NSS) -> Result { let _ = nss.set_high(); let mut adc = Adc { - spi, nss, + spi, + nss, checksum_mode: ChecksumMode::Off, }; adc.reset()?; @@ -55,8 +50,7 @@ impl, NSS: OutputPin, E: fmt::Debug> Adc /// `0x00DX` for AD7172-2 pub fn identify(&mut self) -> Result { - self.read_reg(®s::Id) - .map(|id| id.id()) + self.read_reg(®s::Id).map(|id| id.id()) } pub fn set_checksum_mode(&mut self, mode: ChecksumMode) -> Result<(), SPI::Error> { @@ -76,7 +70,10 @@ impl, NSS: OutputPin, E: fmt::Debug> Adc } pub fn setup_channel( - &mut self, index: u8, in_pos: Input, in_neg: Input + &mut self, + index: u8, + in_pos: Input, + in_neg: Input, ) -> Result<(), SPI::Error> { self.update_reg(®s::SetupCon { index }, |data| { data.set_bipolar(false); @@ -106,7 +103,11 @@ impl, NSS: OutputPin, E: fmt::Debug> Adc let offset = self.read_reg(®s::Offset { index })?.offset(); let gain = self.read_reg(®s::Gain { index })?.gain(); let bipolar = self.read_reg(®s::SetupCon { index })?.bipolar(); - Ok(ChannelCalibration { offset, gain, bipolar }) + Ok(ChannelCalibration { + offset, + gain, + bipolar, + }) } pub fn start_continuous_conversion(&mut self) -> Result<(), SPI::Error> { @@ -119,44 +120,43 @@ impl, NSS: OutputPin, E: fmt::Debug> Adc } pub fn get_postfilter(&mut self, index: u8) -> Result, SPI::Error> { - self.read_reg(®s::FiltCon { index }) - .map(|data| { - if data.enh_filt_en() { - Some(data.enh_filt()) - } else { - None - } - }) + self.read_reg(®s::FiltCon { index }).map(|data| { + if data.enh_filt_en() { + Some(data.enh_filt()) + } else { + None + } + }) } - pub fn set_postfilter(&mut self, index: u8, filter: Option) -> Result<(), SPI::Error> { - self.update_reg(®s::FiltCon { index }, |data| { - match filter { - None => data.set_enh_filt_en(false), - Some(filter) => { - data.set_enh_filt_en(true); - data.set_enh_filt(filter); - } + pub fn set_postfilter( + &mut self, + index: u8, + filter: Option, + ) -> Result<(), SPI::Error> { + self.update_reg(®s::FiltCon { index }, |data| match filter { + None => data.set_enh_filt_en(false), + Some(filter) => { + data.set_enh_filt_en(true); + data.set_enh_filt(filter); } }) } /// Returns the channel the data is from pub fn data_ready(&mut self) -> Result, SPI::Error> { - self.read_reg(®s::Status) - .map(|status| { - if status.ready() { - Some(status.channel()) - } else { - None - } - }) + self.read_reg(®s::Status).map(|status| { + if status.ready() { + Some(status.channel()) + } else { + None + } + }) } /// Get data pub fn read_data(&mut self) -> Result { - self.read_reg(®s::Data) - .map(|data| data.data()) + self.read_reg(®s::Data).map(|data| data.data()) } fn read_reg(&mut self, reg: &R) -> Result { @@ -175,12 +175,21 @@ impl, NSS: OutputPin, E: fmt::Debug> Adc break; } // Retry - warn!("read_reg {:02X}: checksum error: {:?}!={:?}, retrying", reg.address(), checksum_expected, checksum_in); + warn!( + "read_reg {:02X}: checksum error: {:?}!={:?}, retrying", + reg.address(), + checksum_expected, + checksum_in + ); } Ok(reg_data) } - fn write_reg(&mut self, reg: &R, reg_data: &mut R::Data) -> Result<(), SPI::Error> { + fn write_reg( + &mut self, + reg: &R, + reg_data: &mut R::Data, + ) -> Result<(), SPI::Error> { loop { let address = reg.address(); let mut checksum = Checksum::new(match self.checksum_mode { @@ -190,7 +199,7 @@ impl, NSS: OutputPin, E: fmt::Debug> Adc ChecksumMode::Crc => ChecksumMode::Crc, }); checksum.feed(&[address]); - checksum.feed(®_data); + checksum.feed(reg_data); let checksum_out = checksum.result(); let mut data = reg_data.clone(); @@ -201,7 +210,10 @@ impl, NSS: OutputPin, E: fmt::Debug> Adc if *readback_data == **reg_data { return Ok(()); } - warn!("write_reg {:02X}: readback error, {:?}!={:?}, retrying", address, &*readback_data, &**reg_data); + warn!( + "write_reg {:02X}: readback error, {:?}!={:?}, retrying", + address, &*readback_data, &**reg_data + ); } } @@ -225,7 +237,12 @@ impl, NSS: OutputPin, E: fmt::Debug> Adc Ok(()) } - fn transfer<'w>(&mut self, addr: u8, reg_data: &'w mut [u8], checksum: Option) -> Result, SPI::Error> { + fn transfer( + &mut self, + addr: u8, + reg_data: &mut [u8], + checksum: Option, + ) -> Result, SPI::Error> { let mut addr_buf = [addr]; let _ = self.nss.set_low(); @@ -234,8 +251,7 @@ impl, NSS: OutputPin, E: fmt::Debug> Adc Err(e) => Err(e), }; let result = match (result, checksum) { - (Ok(_), None) => - Ok(None), + (Ok(_), None) => Ok(None), (Ok(_), Some(checksum_out)) => { let mut checksum_buf = [checksum_out; 1]; match self.spi.transfer(&mut checksum_buf) { @@ -243,8 +259,7 @@ impl, NSS: OutputPin, E: fmt::Debug> Adc Err(e) => Err(e), } } - (Err(e), _) => - Err(e), + (Err(e), _) => Err(e), }; let _ = self.nss.set_high(); diff --git a/src/ad7172/checksum.rs b/src/ad7172/checksum.rs index 496eb7c..9efe7b9 100644 --- a/src/ad7172/checksum.rs +++ b/src/ad7172/checksum.rs @@ -29,13 +29,13 @@ impl Checksum { fn feed_byte(&mut self, input: u8) { match self.mode { - ChecksumMode::Off => {}, + ChecksumMode::Off => {} ChecksumMode::Xor => self.state ^= input, ChecksumMode::Crc => { for i in 0..8 { let input_mask = 0x80 >> i; - self.state = (self.state << 1) ^ - if ((self.state & 0x80) != 0) != ((input & input_mask) != 0) { + self.state = (self.state << 1) + ^ if ((self.state & 0x80) != 0) != ((input & input_mask) != 0) { 0x07 /* x8 + x2 + x + 1 */ } else { 0 @@ -54,7 +54,7 @@ impl Checksum { pub fn result(&self) -> Option { match self.mode { ChecksumMode::Off => None, - _ => Some(self.state) + _ => Some(self.state), } } } diff --git a/src/ad7172/mod.rs b/src/ad7172/mod.rs index 293ae7f..c22c58d 100644 --- a/src/ad7172/mod.rs +++ b/src/ad7172/mod.rs @@ -1,13 +1,10 @@ use core::fmt; use num_traits::float::Float; -use serde::{Serialize, Deserialize}; -use stm32f4xx_hal::{ - time::MegaHertz, - spi, -}; +use serde::{Deserialize, Serialize}; +use stm32f4xx_hal::{spi, time::MegaHertz}; -pub mod regs; mod checksum; +pub mod regs; pub use checksum::ChecksumMode; mod adc; pub use adc::*; @@ -22,7 +19,6 @@ pub const SPI_CLOCK: MegaHertz = MegaHertz(2); pub const MAX_VALUE: u32 = 0xFF_FFFF; - #[derive(Clone, Copy, Debug)] #[repr(u8)] pub enum Mode { @@ -105,7 +101,8 @@ impl fmt::Display for Input { RefPos => "ref+", RefNeg => "ref-", _ => "", - }.fmt(fmt) + } + .fmt(fmt) } } @@ -141,7 +138,8 @@ impl fmt::Display for RefSource { Internal => "internal", Avdd1MinusAvss => "avdd1-avss", _ => "", - }.fmt(fmt) + } + .fmt(fmt) } } diff --git a/src/ad7172/regs.rs b/src/ad7172/regs.rs index 5b8c9d5..62073ca 100644 --- a/src/ad7172/regs.rs +++ b/src/ad7172/regs.rs @@ -1,6 +1,6 @@ -use core::ops::{Deref, DerefMut}; -use byteorder::{BigEndian, ByteOrder}; use bit_field::BitField; +use byteorder::{BigEndian, ByteOrder}; +use core::ops::{Deref, DerefMut}; use super::*; @@ -9,7 +9,7 @@ pub trait Register { fn address(&self) -> u8; } -pub trait RegisterData: Clone + Deref + DerefMut { +pub trait RegisterData: Clone + Deref + DerefMut { fn empty() -> Self; } @@ -49,7 +49,9 @@ macro_rules! def_reg { } }; ($Reg: ident, u8, $reg: ident, $addr: expr, $size: expr) => { - pub struct $Reg { pub index: u8, } + pub struct $Reg { + pub index: u8, + } impl Register for $Reg { type Data = $reg::Data; fn address(&self) -> u8 { @@ -76,7 +78,7 @@ macro_rules! def_reg { } } } - } + }; } macro_rules! reg_bit { @@ -146,7 +148,7 @@ def_reg!(Status, status, 0x00, 1); impl status::Data { /// Is there new data to read? pub fn ready(&self) -> bool { - ! self.not_ready() + !self.not_ready() } reg_bit!(not_ready, 0, 7, "No data ready indicator"); @@ -159,9 +161,21 @@ impl status::Data { def_reg!(AdcMode, adc_mode, 0x01, 2); impl adc_mode::Data { reg_bits!(delay, set_delay, 0, 0..=2, "Delay after channel switch"); - reg_bit!(sing_cyc, set_sing_cyc, 0, 5, "Can only used with single channel"); + reg_bit!( + sing_cyc, + set_sing_cyc, + 0, + 5, + "Can only used with single channel" + ); reg_bit!(hide_delay, set_hide_delay, 0, 6, "Hide delay"); - reg_bit!(ref_en, set_ref_en, 0, 7, "Enable internal reference, output buffered 2.5 V to REFOUT"); + reg_bit!( + ref_en, + set_ref_en, + 0, + 7, + "Enable internal reference, output buffered 2.5 V to REFOUT" + ); reg_bits!(clockset, set_clocksel, 1, 2..=3, "Clock source"); reg_bits!(mode, set_mode, 1, 4..=6, Mode, "Operating mode"); } @@ -174,15 +188,19 @@ impl if_mode::Data { def_reg!(Data, data, 0x04, 3); impl data::Data { pub fn data(&self) -> u32 { - (u32::from(self.0[0]) << 16) | - (u32::from(self.0[1]) << 8) | - u32::from(self.0[2]) + (u32::from(self.0[0]) << 16) | (u32::from(self.0[1]) << 8) | u32::from(self.0[2]) } } def_reg!(GpioCon, gpio_con, 0x06, 2); impl gpio_con::Data { - reg_bit!(sync_en, set_sync_en, 0, 3, "Enables the SYNC/ERROR pin as a sync input"); + reg_bit!( + sync_en, + set_sync_en, + 0, + 3, + "Enables the SYNC/ERROR pin as a sync input" + ); } def_reg!(Id, id, 0x07, 2); @@ -200,8 +218,7 @@ impl channel::Data { /// Which input is connected to positive input of this channel #[allow(unused)] pub fn a_in_pos(&self) -> Input { - ((self.0[0].get_bits(0..=1) << 3) | - self.0[1].get_bits(5..=7)).into() + ((self.0[0].get_bits(0..=1) << 3) | self.0[1].get_bits(5..=7)).into() } /// Set which input is connected to positive input of this channel #[allow(unused)] @@ -210,27 +227,66 @@ impl channel::Data { self.0[0].set_bits(0..=1, value >> 3); self.0[1].set_bits(5..=7, value & 0x7); } - reg_bits!(a_in_neg, set_a_in_neg, 1, 0..=4, Input, - "Which input is connected to negative input of this channel"); + reg_bits!( + a_in_neg, + set_a_in_neg, + 1, + 0..=4, + Input, + "Which input is connected to negative input of this channel" + ); } def_reg!(SetupCon, u8, setup_con, 0x20, 2); impl setup_con::Data { - reg_bit!(bipolar, set_bipolar, 0, 4, "Unipolar (`false`) or bipolar (`true`) coded output"); + reg_bit!( + bipolar, + set_bipolar, + 0, + 4, + "Unipolar (`false`) or bipolar (`true`) coded output" + ); reg_bit!(refbuf_pos, set_refbuf_pos, 0, 3, "Enable REF+ input buffer"); reg_bit!(refbuf_neg, set_refbuf_neg, 0, 2, "Enable REF- input buffer"); reg_bit!(ainbuf_pos, set_ainbuf_pos, 0, 1, "Enable AIN+ input buffer"); reg_bit!(ainbuf_neg, set_ainbuf_neg, 0, 0, "Enable AIN- input buffer"); reg_bit!(burnout_en, 1, 7, "enables a 10 µA current source on the positive analog input selected and a 10 µA current sink on the negative analog input selected"); - reg_bits!(ref_sel, set_ref_sel, 1, 4..=5, RefSource, "Select reference source for conversion"); + reg_bits!( + ref_sel, + set_ref_sel, + 1, + 4..=5, + RefSource, + "Select reference source for conversion" + ); } def_reg!(FiltCon, u8, filt_con, 0x28, 2); impl filt_con::Data { reg_bit!(sinc3_map, 0, 7, "If set, mapping of filter register changes to directly program the decimation rate of the sinc3 filter"); - reg_bit!(enh_filt_en, set_enh_filt_en, 0, 3, "Enable postfilters for enhanced 50Hz and 60Hz rejection"); - reg_bits!(enh_filt, set_enh_filt, 0, 0..=2, PostFilter, "Select postfilters for enhanced 50Hz and 60Hz rejection"); - reg_bits!(order, set_order, 1, 5..=6, DigitalFilterOrder, "order of the digital filter that processes the modulator data"); + reg_bit!( + enh_filt_en, + set_enh_filt_en, + 0, + 3, + "Enable postfilters for enhanced 50Hz and 60Hz rejection" + ); + reg_bits!( + enh_filt, + set_enh_filt, + 0, + 0..=2, + PostFilter, + "Select postfilters for enhanced 50Hz and 60Hz rejection" + ); + reg_bits!( + order, + set_order, + 1, + 5..=6, + DigitalFilterOrder, + "order of the digital filter that processes the modulator data" + ); reg_bits!(odr, set_odr, 1, 0..=4, "Output data rate"); } @@ -238,9 +294,7 @@ def_reg!(Offset, u8, offset, 0x30, 3); impl offset::Data { #[allow(unused)] pub fn offset(&self) -> u32 { - (u32::from(self.0[0]) << 16) | - (u32::from(self.0[1]) << 8) | - u32::from(self.0[2]) + (u32::from(self.0[0]) << 16) | (u32::from(self.0[1]) << 8) | u32::from(self.0[2]) } #[allow(unused)] pub fn set_offset(&mut self, value: u32) { @@ -254,9 +308,7 @@ def_reg!(Gain, u8, gain, 0x38, 3); impl gain::Data { #[allow(unused)] pub fn gain(&self) -> u32 { - (u32::from(self.0[0]) << 16) | - (u32::from(self.0[1]) << 8) | - u32::from(self.0[2]) + (u32::from(self.0[0]) << 16) | (u32::from(self.0[1]) << 8) | u32::from(self.0[2]) } #[allow(unused)] pub fn set_gain(&mut self, value: u32) { diff --git a/src/channel.rs b/src/channel.rs index 47eef24..b74aaa2 100644 --- a/src/channel.rs +++ b/src/channel.rs @@ -1,14 +1,10 @@ -use stm32f4xx_hal::hal::digital::v2::OutputPin; -use uom::si::{ - f64::ElectricPotential, - electric_potential::volt, -}; use crate::{ - ad5680, - ad7172, + ad5680, ad7172, channel_state::ChannelState, - pins::{ChannelPins, ChannelPinSet}, + pins::{ChannelPinSet, ChannelPins}, }; +use stm32f4xx_hal::hal::digital::v2::OutputPin; +use uom::si::{electric_potential::volt, f64::ElectricPotential}; /// Marker type for the first channel pub struct Channel0; @@ -40,7 +36,8 @@ impl Channel { Channel { state, - dac, vref_meas, + dac, + vref_meas, shdn: pins.shdn, vref_pin: pins.vref_pin, itec_pin: pins.itec_pin, diff --git a/src/channel_state.rs b/src/channel_state.rs index d4c46a1..9872e11 100644 --- a/src/channel_state.rs +++ b/src/channel_state.rs @@ -1,24 +1,19 @@ -use smoltcp::time::{Duration, Instant}; -use uom::si::{ - f64::{ - ElectricPotential, - ElectricCurrent, - ElectricalResistance, - ThermodynamicTemperature, - Time, - }, - electric_potential::volt, - electric_current::ampere, - electrical_resistance::ohm, - thermodynamic_temperature::degree_celsius, - time::millisecond, -}; use crate::{ ad7172, - pid, - config::PwmLimits, - steinhart_hart as sh, command_parser::{CenterPoint, Polarity}, + config::PwmLimits, + pid, steinhart_hart as sh, +}; +use smoltcp::time::{Duration, Instant}; +use uom::si::{ + electric_current::ampere, + electric_potential::volt, + electrical_resistance::ohm, + f64::{ + ElectricCurrent, ElectricPotential, ElectricalResistance, ThermodynamicTemperature, Time, + }, + thermodynamic_temperature::degree_celsius, + time::millisecond, }; const R_INNER: f64 = 2.0 * 5100.0; @@ -48,7 +43,7 @@ impl ChannelState { adc_time: Instant::from_secs(0), // default: 10 Hz adc_interval: Duration::from_millis(100), - center: CenterPoint::Vref, + center: CenterPoint::VRef, dac_value: ElectricPotential::new::(0.0), i_set: ElectricCurrent::new::(0.0), pwm_limits: PwmLimits { @@ -76,8 +71,7 @@ impl ChannelState { /// Update PID state on ADC input, calculate new DAC output pub fn update_pid(&mut self) -> Option { - let temperature = self.get_temperature()? - .get::(); + let temperature = self.get_temperature()?.get::(); let pid_output = self.pid.update(temperature); Some(pid_output) } diff --git a/src/channels.rs b/src/channels.rs index d8300c0..2a503b6 100644 --- a/src/channels.rs +++ b/src/channels.rs @@ -1,3 +1,13 @@ +use crate::timer::sleep; +use crate::{ + ad5680, ad7172, + channel::{Channel, Channel0, Channel1}, + channel_state::ChannelState, + command_handler::JsonBuffer, + command_parser::{CenterPoint, Polarity, PwmPin}, + pins::{self, Channel0VRef, Channel1VRef}, + steinhart_hart, +}; use core::marker::PhantomData; use heapless::{consts::U2, Vec}; use num_traits::Zero; @@ -5,27 +15,16 @@ use serde::{Serialize, Serializer}; use smoltcp::time::Instant; use stm32f4xx_hal::hal; use uom::si::{ - f64::{ElectricCurrent, ElectricPotential, ElectricalResistance, Time}, - electric_potential::{millivolt, volt}, electric_current::ampere, + electric_potential::{millivolt, volt}, electrical_resistance::ohm, + f64::{ElectricCurrent, ElectricPotential, ElectricalResistance, Time}, ratio::ratio, thermodynamic_temperature::degree_celsius, }; -use crate::{ - ad5680, - ad7172, - channel::{Channel, Channel0, Channel1}, - channel_state::ChannelState, - command_parser::{CenterPoint, PwmPin, Polarity}, - command_handler::JsonBuffer, - pins::{self, Channel0VRef, Channel1VRef}, - steinhart_hart, -}; -use crate::timer::sleep; pub enum PinsAdcReadTarget { - VREF, + VRef, DacVfb, ITec, VTec, @@ -73,19 +72,25 @@ impl Channels { adc.set_sync_enable(false).unwrap(); // Setup channels and start ADC - adc.setup_channel(0, ad7172::Input::Ain2, ad7172::Input::Ain3).unwrap(); - let adc_calibration0 = adc.get_calibration(0) - .expect("adc_calibration0"); - adc.setup_channel(1, ad7172::Input::Ain0, ad7172::Input::Ain1).unwrap(); - let adc_calibration1 = adc.get_calibration(1) - .expect("adc_calibration1"); + adc.setup_channel(0, ad7172::Input::Ain2, ad7172::Input::Ain3) + .unwrap(); + let adc_calibration0 = adc.get_calibration(0).expect("adc_calibration0"); + adc.setup_channel(1, ad7172::Input::Ain0, ad7172::Input::Ain1) + .unwrap(); + let adc_calibration1 = adc.get_calibration(1).expect("adc_calibration1"); adc.start_continuous_conversion().unwrap(); let channel0 = Channel::new(pins.channel0, adc_calibration0); let channel1 = Channel::new(pins.channel1, adc_calibration1); let pins_adc = pins.pins_adc; let pwm = pins.pwm; - let mut channels = Channels { channel0, channel1, adc, pins_adc, pwm }; + let mut channels = Channels { + channel0, + channel1, + adc, + pins_adc, + pwm, + }; for channel in 0..CHANNELS { channels.calibrate_dac_value(channel); channels.set_i(channel, ElectricCurrent::new::(0.0)); @@ -126,10 +131,10 @@ impl Channels { /// calculate the TEC i_set centerpoint pub fn get_center(&mut self, channel: usize) -> ElectricPotential { match self.channel_state(channel).center { - CenterPoint::Vref => - self.adc_read(channel, PinsAdcReadTarget::VREF, 8), - CenterPoint::Override(center_point) => - ElectricPotential::new::(center_point.into()), + CenterPoint::VRef => self.adc_read(channel, PinsAdcReadTarget::VRef, 8), + CenterPoint::Override(center_point) => { + ElectricPotential::new::(center_point.into()) + } } } @@ -146,7 +151,7 @@ impl Channels { /// i_set DAC fn set_dac(&mut self, channel: usize, voltage: ElectricPotential) -> ElectricPotential { - let value = ((voltage / DAC_OUT_V_MAX).get::() * (ad5680::MAX_VALUE as f64)) as u32 ; + let value = ((voltage / DAC_OUT_V_MAX).get::() * (ad5680::MAX_VALUE as f64)) as u32; match channel { 0 => self.channel0.dac.set(value).unwrap(), 1 => self.channel1.dac.set(value).unwrap(), @@ -163,7 +168,7 @@ impl Channels { Polarity::Normal => 1.0, Polarity::Reversed => -1.0, }; - let vref_meas = match channel.into() { + let vref_meas = match channel { 0 => self.channel0.vref_meas, 1 => self.channel1.vref_meas, _ => unreachable!(), @@ -172,54 +177,57 @@ impl Channels { let r_sense = ElectricalResistance::new::(R_SENSE); let voltage = negate * i_set * 10.0 * r_sense + center_point; let voltage = self.set_dac(channel, voltage); - let i_set = negate * (voltage - center_point) / (10.0 * r_sense); - i_set + + negate * (voltage - center_point) / (10.0 * r_sense) } /// AN4073: ADC Reading Dispersion can be reduced through Averaging - pub fn adc_read(&mut self, channel: usize, adc_read_target: PinsAdcReadTarget, avg_pt: u16) -> ElectricPotential { + pub fn adc_read( + &mut self, + channel: usize, + adc_read_target: PinsAdcReadTarget, + avg_pt: u16, + ) -> ElectricPotential { let mut sample: u32 = 0; match channel { 0 => { sample = match adc_read_target { - PinsAdcReadTarget::VREF => { - match &self.channel0.vref_pin { - Channel0VRef::Analog(vref_pin) => { - for _ in (0..avg_pt).rev() { - sample += self - .pins_adc - .convert(vref_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480) - as u32; - } - sample / avg_pt as u32 - }, - Channel0VRef::Disabled(_) => {2048 as u32} + PinsAdcReadTarget::VRef => match &self.channel0.vref_pin { + Channel0VRef::Analog(vref_pin) => { + for _ in (0..avg_pt).rev() { + sample += self.pins_adc.convert( + vref_pin, + stm32f4xx_hal::adc::config::SampleTime::Cycles_480, + ) as u32; + } + sample / avg_pt as u32 } - } + Channel0VRef::Disabled(_) => 2048_u32, + }, PinsAdcReadTarget::DacVfb => { for _ in (0..avg_pt).rev() { - sample += self - .pins_adc - .convert(&self.channel0.dac_feedback_pin,stm32f4xx_hal::adc::config::SampleTime::Cycles_480) - as u32; + sample += self.pins_adc.convert( + &self.channel0.dac_feedback_pin, + stm32f4xx_hal::adc::config::SampleTime::Cycles_480, + ) as u32; } sample / avg_pt as u32 } PinsAdcReadTarget::ITec => { for _ in (0..avg_pt).rev() { - sample += self - .pins_adc - .convert(&self.channel0.itec_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480) - as u32; + sample += self.pins_adc.convert( + &self.channel0.itec_pin, + stm32f4xx_hal::adc::config::SampleTime::Cycles_480, + ) as u32; } sample / avg_pt as u32 } PinsAdcReadTarget::VTec => { for _ in (0..avg_pt).rev() { - sample += self - .pins_adc - .convert(&self.channel0.tec_u_meas_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480) - as u32; + sample += self.pins_adc.convert( + &self.channel0.tec_u_meas_pin, + stm32f4xx_hal::adc::config::SampleTime::Cycles_480, + ) as u32; } sample / avg_pt as u32 } @@ -229,44 +237,42 @@ impl Channels { } 1 => { sample = match adc_read_target { - PinsAdcReadTarget::VREF => { - match &self.channel1.vref_pin { - Channel1VRef::Analog(vref_pin) => { - for _ in (0..avg_pt).rev() { - sample += self - .pins_adc - .convert(vref_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480) - as u32; - } - sample / avg_pt as u32 - }, - Channel1VRef::Disabled(_) => {2048 as u32} + PinsAdcReadTarget::VRef => match &self.channel1.vref_pin { + Channel1VRef::Analog(vref_pin) => { + for _ in (0..avg_pt).rev() { + sample += self.pins_adc.convert( + vref_pin, + stm32f4xx_hal::adc::config::SampleTime::Cycles_480, + ) as u32; + } + sample / avg_pt as u32 } - } + Channel1VRef::Disabled(_) => 2048_u32, + }, PinsAdcReadTarget::DacVfb => { for _ in (0..avg_pt).rev() { - sample += self - .pins_adc - .convert(&self.channel1.dac_feedback_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480) - as u32; + sample += self.pins_adc.convert( + &self.channel1.dac_feedback_pin, + stm32f4xx_hal::adc::config::SampleTime::Cycles_480, + ) as u32; } sample / avg_pt as u32 } PinsAdcReadTarget::ITec => { for _ in (0..avg_pt).rev() { - sample += self - .pins_adc - .convert(&self.channel1.itec_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480) - as u32; + sample += self.pins_adc.convert( + &self.channel1.itec_pin, + stm32f4xx_hal::adc::config::SampleTime::Cycles_480, + ) as u32; } sample / avg_pt as u32 } PinsAdcReadTarget::VTec => { for _ in (0..avg_pt).rev() { - sample += self - .pins_adc - .convert(&self.channel1.tec_u_meas_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480) - as u32; + sample += self.pins_adc.convert( + &self.channel1.tec_u_meas_pin, + stm32f4xx_hal::adc::config::SampleTime::Cycles_480, + ) as u32; } sample / avg_pt as u32 } @@ -274,7 +280,7 @@ impl Channels { let mv = self.pins_adc.sample_to_millivolts(sample as u16); ElectricPotential::new::(mv as f64) } - _ => unreachable!() + _ => unreachable!(), } } @@ -282,25 +288,25 @@ impl Channels { /// /// The thermostat DAC applies a control voltage signal to the CTLI pin of MAX driver chip to control its output current. /// The CTLI input signal is centered around VREF of the MAX chip. Applying VREF to CTLI sets the output current to 0. - /// + /// /// This calibration routine measures the VREF voltage and the DAC output with the STM32 ADC, and uses a breadth-first - /// search to find the DAC setting that will produce a DAC output voltage closest to VREF. This DAC output voltage will - /// be stored and used in subsequent i_set routines to bias the current control signal to the measured VREF, reducing + /// search to find the DAC setting that will produce a DAC output voltage closest to VREF. This DAC output voltage will + /// be stored and used in subsequent i_set routines to bias the current control signal to the measured VREF, reducing /// the offset error of the current control signal. /// /// The input offset of the STM32 ADC is eliminated by using the same ADC for the measurements, and by only using the /// difference in VREF and DAC output for the calibration. - /// - /// This routine should be called only once after boot, repeated reading of the vref signal and changing of the stored + /// + /// This routine should be called only once after boot, repeated reading of the vref signal and changing of the stored /// VREF measurement can introduce significant noise at the current output, degrading the stabilily performance of the - /// thermostat. + /// thermostat. pub fn calibrate_dac_value(&mut self, channel: usize) { let samples = 50; let mut target_voltage = ElectricPotential::new::(0.0); for _ in 0..samples { - target_voltage = target_voltage + self.get_center(channel); + target_voltage += self.get_center(channel); } - target_voltage = target_voltage / samples as f64; + target_voltage /= samples as f64; let mut start_value = 1; let mut best_error = ElectricPotential::new::(100.0); @@ -371,7 +377,9 @@ impl Channels { // Get current passing through TEC pub fn get_tec_i(&mut self, channel: usize) -> ElectricCurrent { - let tec_i = (self.adc_read(channel, PinsAdcReadTarget::ITec, 16) - self.adc_read(channel, PinsAdcReadTarget::VREF, 16)) / ElectricalResistance::new::(0.4); + let tec_i = (self.adc_read(channel, PinsAdcReadTarget::ITec, 16) + - self.adc_read(channel, PinsAdcReadTarget::VRef, 16)) + / ElectricalResistance::new::(0.4); match self.channel_state(channel).polarity { Polarity::Normal => tec_i, Polarity::Reversed => -tec_i, @@ -380,37 +388,34 @@ impl Channels { // Get voltage across TEC pub fn get_tec_v(&mut self, channel: usize) -> ElectricPotential { - (self.adc_read(channel, PinsAdcReadTarget::VTec, 16) - ElectricPotential::new::(1.5)) * 4.0 + (self.adc_read(channel, PinsAdcReadTarget::VTec, 16) - ElectricPotential::new::(1.5)) + * 4.0 } fn set_pwm(&mut self, channel: usize, pin: PwmPin, duty: f64) -> f64 { - fn set>(pin: &mut P, duty: f64) -> f64 { + fn set>(pin: &mut P, duty: f64) -> f64 { let max = pin.get_max_duty(); let value = ((duty * (max as f64)) as u16).min(max); pin.set_duty(value); value as f64 / (max as f64) } match (channel, pin) { - (_, PwmPin::ISet) => - panic!("i_set is no pwm pin"), - (0, PwmPin::MaxIPos) => - set(&mut self.pwm.max_i_pos0, duty), - (0, PwmPin::MaxINeg) => - set(&mut self.pwm.max_i_neg0, duty), - (0, PwmPin::MaxV) => - set(&mut self.pwm.max_v0, duty), - (1, PwmPin::MaxIPos) => - set(&mut self.pwm.max_i_pos1, duty), - (1, PwmPin::MaxINeg) => - set(&mut self.pwm.max_i_neg1, duty), - (1, PwmPin::MaxV) => - set(&mut self.pwm.max_v1, duty), - _ => - unreachable!(), + (_, PwmPin::ISet) => panic!("i_set is no pwm pin"), + (0, PwmPin::MaxIPos) => set(&mut self.pwm.max_i_pos0, duty), + (0, PwmPin::MaxINeg) => set(&mut self.pwm.max_i_neg0, duty), + (0, PwmPin::MaxV) => set(&mut self.pwm.max_v0, duty), + (1, PwmPin::MaxIPos) => set(&mut self.pwm.max_i_pos1, duty), + (1, PwmPin::MaxINeg) => set(&mut self.pwm.max_i_neg1, duty), + (1, PwmPin::MaxV) => set(&mut self.pwm.max_v1, duty), + _ => unreachable!(), } } - pub fn set_max_v(&mut self, channel: usize, max_v: ElectricPotential) -> (ElectricPotential, ElectricPotential) { + pub fn set_max_v( + &mut self, + channel: usize, + max_v: ElectricPotential, + ) -> (ElectricPotential, ElectricPotential) { let max = 4.0 * ElectricPotential::new::(3.3); let max_v = max_v.min(MAX_TEC_V).max(ElectricPotential::zero()); let duty = (max_v / max).get::(); @@ -419,7 +424,11 @@ impl Channels { (duty * max, max) } - pub fn set_max_i_pos(&mut self, channel: usize, max_i_pos: ElectricCurrent) -> (ElectricCurrent, ElectricCurrent) { + pub fn set_max_i_pos( + &mut self, + channel: usize, + max_i_pos: ElectricCurrent, + ) -> (ElectricCurrent, ElectricCurrent) { let max = ElectricCurrent::new::(3.0); let max_i_pos = max_i_pos.min(MAX_TEC_I).max(ElectricCurrent::zero()); let duty = (max_i_pos / MAX_TEC_I_DUTY_TO_CURRENT_RATE).get::(); @@ -431,7 +440,11 @@ impl Channels { (duty * MAX_TEC_I_DUTY_TO_CURRENT_RATE, max) } - pub fn set_max_i_neg(&mut self, channel: usize, max_i_neg: ElectricCurrent) -> (ElectricCurrent, ElectricCurrent) { + pub fn set_max_i_neg( + &mut self, + channel: usize, + max_i_neg: ElectricCurrent, + ) -> (ElectricCurrent, ElectricCurrent) { let max = ElectricCurrent::new::(3.0); let max_i_neg = max_i_neg.min(MAX_TEC_I).max(ElectricCurrent::zero()); let duty = (max_i_neg / MAX_TEC_I_DUTY_TO_CURRENT_RATE).get::(); @@ -469,7 +482,8 @@ impl Channels { interval: state.get_adc_interval(), adc: state.get_adc(), sens: state.get_sens(), - temperature: state.get_temperature() + temperature: state + .get_temperature() .map(|temperature| temperature.get::()), pid_engaged: state.pid_engaged, i_set, @@ -528,7 +542,10 @@ impl Channels { } fn postfilter_summary(&mut self, channel: usize) -> PostFilterSummary { - let rate = self.adc.get_postfilter(channel as u8).unwrap() + let rate = self + .adc + .get_postfilter(channel as u8) + .unwrap() .and_then(|filter| filter.output_rate()); PostFilterSummary { channel, rate } } @@ -546,7 +563,9 @@ impl Channels { SteinhartHartSummary { channel, params } } - pub fn steinhart_hart_summaries_json(&mut self) -> Result { + pub fn steinhart_hart_summaries_json( + &mut self, + ) -> Result { let mut summaries = Vec::<_, U2>::new(); for channel in 0..CHANNELS { let _ = summaries.push(self.steinhart_hart_summary(channel)); @@ -589,10 +608,8 @@ impl Serialize for CenterPointJson { S: Serializer, { match self.0 { - CenterPoint::Vref => - serializer.serialize_str("vref"), - CenterPoint::Override(vref) => - serializer.serialize_f32(vref), + CenterPoint::VRef => serializer.serialize_str("vref"), + CenterPoint::Override(vref) => serializer.serialize_f32(vref), } } } diff --git a/src/command_handler.rs b/src/command_handler.rs index 6fd1d1e..74106be 100644 --- a/src/command_handler.rs +++ b/src/command_handler.rs @@ -1,45 +1,26 @@ -use smoltcp::socket::TcpSocket; -use log::{error, warn}; -use core::fmt::Write; -use heapless::{consts::U1024, Vec}; use super::{ - net, - command_parser::{ - Ipv4Config, - Command, - ShowCommand, - CenterPoint, - PidParameter, - PwmPin, - ShParameter, - Polarity - }, ad7172, - CHANNEL_CONFIG_KEY, - channels::{ - Channels, - CHANNELS + channels::{Channels, CHANNELS}, + command_parser::{ + CenterPoint, Command, Ipv4Config, PidParameter, Polarity, PwmPin, ShParameter, ShowCommand, }, config::ChannelConfig, dfu, flash_store::FlashStore, - FanCtrl, hw_rev::HWRev, + net, FanCtrl, CHANNEL_CONFIG_KEY, }; +use core::fmt::Write; +use heapless::{consts::U1024, Vec}; +use log::{error, warn}; +use smoltcp::socket::TcpSocket; -use uom::{ - si::{ - f64::{ - ElectricCurrent, - ElectricPotential, - ElectricalResistance, - ThermodynamicTemperature, - }, - electric_current::ampere, - electric_potential::volt, - electrical_resistance::ohm, - thermodynamic_temperature::degree_celsius, - }, +use uom::si::{ + electric_current::ampere, + electric_potential::volt, + electrical_resistance::ohm, + f64::{ElectricCurrent, ElectricPotential, ElectricalResistance, ThermodynamicTemperature}, + thermodynamic_temperature::degree_celsius, }; #[derive(Debug, Clone, PartialEq)] @@ -52,9 +33,9 @@ pub enum Handler { #[derive(Clone, Debug, PartialEq)] pub enum Error { - ReportError, - PostFilterRateError, - FlashError + Report, + PostFilterRate, + Flash, } pub type JsonBuffer = Vec; @@ -66,19 +47,19 @@ fn send_line(socket: &mut TcpSocket, data: &[u8]) -> bool { // instead of sending incomplete line warn!( "TCP socket has only {}/{} needed {}", - send_free + 1, socket.send_capacity(), data.len(), + send_free + 1, + socket.send_capacity(), + data.len(), ); } else { - match socket.send_slice(&data) { + match socket.send_slice(data) { Ok(sent) if sent == data.len() => { let _ = socket.send_slice(b"\n"); // success - return true + return true; } - Ok(sent) => - warn!("sent only {}/{} bytes", sent, data.len()), - Err(e) => - error!("error sending line: {:?}", e), + Ok(sent) => warn!("sent only {}/{} bytes", sent, data.len()), + Err(e) => error!("error sending line: {:?}", e), } } // not success @@ -86,7 +67,6 @@ fn send_line(socket: &mut TcpSocket, data: &[u8]) -> bool { } impl Handler { - fn show_report(socket: &mut TcpSocket, channels: &mut Channels) -> Result { match channels.reports_json() { Ok(buf) => { @@ -95,7 +75,7 @@ impl Handler { Err(e) => { error!("unable to serialize report: {:?}", e); let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e); - return Err(Error::ReportError); + return Err(Error::Report); } } Ok(Handler::Handled) @@ -109,7 +89,7 @@ impl Handler { Err(e) => { error!("unable to serialize pid summary: {:?}", e); let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e); - return Err(Error::ReportError); + return Err(Error::Report); } } Ok(Handler::Handled) @@ -123,13 +103,16 @@ impl Handler { Err(e) => { error!("unable to serialize pwm summary: {:?}", e); let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e); - return Err(Error::ReportError); + return Err(Error::Report); } } Ok(Handler::Handled) } - fn show_steinhart_hart(socket: &mut TcpSocket, channels: &mut Channels) -> Result { + fn show_steinhart_hart( + socket: &mut TcpSocket, + channels: &mut Channels, + ) -> Result { match channels.steinhart_hart_summaries_json() { Ok(buf) => { send_line(socket, &buf); @@ -137,13 +120,13 @@ impl Handler { Err(e) => { error!("unable to serialize steinhart-hart summaries: {:?}", e); let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e); - return Err(Error::ReportError); + return Err(Error::Report); } } Ok(Handler::Handled) } - fn show_post_filter (socket: &mut TcpSocket, channels: &mut Channels) -> Result { + fn show_post_filter(socket: &mut TcpSocket, channels: &mut Channels) -> Result { match channels.postfilter_summaries_json() { Ok(buf) => { send_line(socket, &buf); @@ -151,13 +134,13 @@ impl Handler { Err(e) => { error!("unable to serialize postfilter summary: {:?}", e); let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e); - return Err(Error::ReportError); + return Err(Error::Report); } } Ok(Handler::Handled) } - fn show_ipv4 (socket: &mut TcpSocket, ipv4_config: &mut Ipv4Config) -> Result { + fn show_ipv4(socket: &mut TcpSocket, ipv4_config: &mut Ipv4Config) -> Result { let (cidr, gateway) = net::split_ipv4_config(ipv4_config.clone()); let _ = write!(socket, "{{\"addr\":\"{}\"", cidr); gateway.map(|gateway| write!(socket, ",\"gateway\":\"{}\"", gateway)); @@ -165,19 +148,34 @@ impl Handler { Ok(Handler::Handled) } - fn engage_pid (socket: &mut TcpSocket, channels: &mut Channels, channel: usize) -> Result { + fn engage_pid( + socket: &mut TcpSocket, + channels: &mut Channels, + channel: usize, + ) -> Result { channels.channel_state(channel).pid_engaged = true; send_line(socket, b"{}"); Ok(Handler::Handled) } - fn set_polarity(socket: &mut TcpSocket, channels: &mut Channels, channel: usize, polarity: Polarity) -> Result { + fn set_polarity( + socket: &mut TcpSocket, + channels: &mut Channels, + channel: usize, + polarity: Polarity, + ) -> Result { channels.set_polarity(channel, polarity); send_line(socket, b"{}"); Ok(Handler::Handled) } - fn set_pwm (socket: &mut TcpSocket, channels: &mut Channels, channel: usize, pin: PwmPin, value: f64) -> Result { + fn set_pwm( + socket: &mut TcpSocket, + channels: &mut Channels, + channel: usize, + pin: PwmPin, + value: f64, + ) -> Result { match pin { PwmPin::ISet => { channels.channel_state(channel).pid_engaged = false; @@ -202,7 +200,12 @@ impl Handler { Ok(Handler::Handled) } - fn set_center_point(socket: &mut TcpSocket, channels: &mut Channels, channel: usize, center: CenterPoint) -> Result { + fn set_center_point( + socket: &mut TcpSocket, + channels: &mut Channels, + channel: usize, + center: CenterPoint, + ) -> Result { let i_set = channels.get_i(channel); let state = channels.channel_state(channel); state.center = center; @@ -213,28 +216,34 @@ impl Handler { Ok(Handler::Handled) } - fn set_pid (socket: &mut TcpSocket, channels: &mut Channels, channel: usize, parameter: PidParameter, value: f64) -> Result { + fn set_pid( + socket: &mut TcpSocket, + channels: &mut Channels, + channel: usize, + parameter: PidParameter, + value: f64, + ) -> Result { let pid = &mut channels.channel_state(channel).pid; use super::command_parser::PidParameter::*; match parameter { - Target => - pid.target = value, - KP => - pid.parameters.kp = value as f32, - KI => - pid.update_ki(value as f32), - KD => - pid.parameters.kd = value as f32, - OutputMin => - pid.parameters.output_min = value as f32, - OutputMax => - pid.parameters.output_max = value as f32, + Target => pid.target = value, + KP => pid.parameters.kp = value as f32, + KI => pid.update_ki(value as f32), + KD => pid.parameters.kd = value as f32, + OutputMin => pid.parameters.output_min = value as f32, + OutputMax => pid.parameters.output_max = value as f32, } send_line(socket, b"{}"); Ok(Handler::Handled) } - fn set_steinhart_hart (socket: &mut TcpSocket, channels: &mut Channels, channel: usize, parameter: ShParameter, value: f64) -> Result { + fn set_steinhart_hart( + socket: &mut TcpSocket, + channels: &mut Channels, + channel: usize, + parameter: ShParameter, + value: f64, + ) -> Result { let sh = &mut channels.channel_state(channel).sh; use super::command_parser::ShParameter::*; match parameter { @@ -246,32 +255,52 @@ impl Handler { Ok(Handler::Handled) } - fn reset_post_filter (socket: &mut TcpSocket, channels: &mut Channels, channel: usize) -> Result { + fn reset_post_filter( + socket: &mut TcpSocket, + channels: &mut Channels, + channel: usize, + ) -> Result { channels.adc.set_postfilter(channel as u8, None).unwrap(); send_line(socket, b"{}"); Ok(Handler::Handled) } - fn set_post_filter (socket: &mut TcpSocket, channels: &mut Channels, channel: usize, rate: f32) -> Result { + fn set_post_filter( + socket: &mut TcpSocket, + channels: &mut Channels, + channel: usize, + rate: f32, + ) -> Result { let filter = ad7172::PostFilter::closest(rate); match filter { Some(filter) => { - channels.adc.set_postfilter(channel as u8, Some(filter)).unwrap(); + channels + .adc + .set_postfilter(channel as u8, Some(filter)) + .unwrap(); send_line(socket, b"{}"); } None => { error!("unable to choose postfilter for rate {:.3}", rate); - send_line(socket, b"{{\"error\": \"unable to choose postfilter rate\"}}"); - return Err(Error::PostFilterRateError); + send_line( + socket, + b"{{\"error\": \"unable to choose postfilter rate\"}}", + ); + return Err(Error::PostFilterRate); } } Ok(Handler::Handled) } - fn load_channel (socket: &mut TcpSocket, channels: &mut Channels, store: &mut FlashStore, channel: Option) -> Result { - for c in 0..CHANNELS { + fn load_channel( + socket: &mut TcpSocket, + channels: &mut Channels, + store: &mut FlashStore, + channel: Option, + ) -> Result { + for (c, key) in CHANNEL_CONFIG_KEY.iter().enumerate().take(CHANNELS) { if channel.is_none() || channel == Some(c) { - match store.read_value::(CHANNEL_CONFIG_KEY[c]) { + match store.read_value::(key) { Ok(Some(config)) => { config.apply(channels, c); send_line(socket, b"{}"); @@ -283,7 +312,7 @@ impl Handler { Err(e) => { error!("unable to load config from flash: {:?}", e); let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e); - return Err(Error::FlashError); + return Err(Error::Flash); } } } @@ -291,19 +320,24 @@ impl Handler { Ok(Handler::Handled) } - fn save_channel (socket: &mut TcpSocket, channels: &mut Channels, channel: Option, store: &mut FlashStore) -> Result { - for c in 0..CHANNELS { + fn save_channel( + socket: &mut TcpSocket, + channels: &mut Channels, + channel: Option, + store: &mut FlashStore, + ) -> Result { + for (c, key) in CHANNEL_CONFIG_KEY.iter().enumerate().take(CHANNELS) { let mut store_value_buf = [0u8; 256]; if channel.is_none() || channel == Some(c) { let config = ChannelConfig::new(channels, c); - match store.write_value(CHANNEL_CONFIG_KEY[c], &config, &mut store_value_buf) { + match store.write_value(key, &config, &mut store_value_buf) { Ok(()) => { send_line(socket, b"{}"); } Err(e) => { error!("unable to save channel {} config to flash: {:?}", c, e); let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e); - return Err(Error::FlashError); + return Err(Error::Flash); } } } @@ -311,7 +345,11 @@ impl Handler { Ok(Handler::Handled) } - fn set_ipv4 (socket: &mut TcpSocket, store: &mut FlashStore, config: Ipv4Config) -> Result { + fn set_ipv4( + socket: &mut TcpSocket, + store: &mut FlashStore, + config: Ipv4Config, + ) -> Result { let _ = store .write_value("ipv4", &config, [0; 16]) .map_err(|e| error!("unable to save ipv4 config to flash: {:?}", e)); @@ -320,7 +358,7 @@ impl Handler { Ok(Handler::NewIPV4(new_ipv4_config.unwrap())) } - fn reset (channels: &mut Channels) -> Result { + fn reset(channels: &mut Channels) -> Result { for i in 0..CHANNELS { channels.power_down(i); } @@ -328,7 +366,7 @@ impl Handler { Ok(Handler::Reset) } - fn dfu (channels: &mut Channels) -> Result { + fn dfu(channels: &mut Channels) -> Result { for i in 0..CHANNELS { channels.power_down(i); } @@ -339,9 +377,16 @@ impl Handler { Ok(Handler::Reset) } - fn set_fan(socket: &mut TcpSocket, fan_pwm: u32, fan_ctrl: &mut FanCtrl) -> Result { + fn set_fan( + socket: &mut TcpSocket, + fan_pwm: u32, + fan_ctrl: &mut FanCtrl, + ) -> Result { if !fan_ctrl.fan_available() { - send_line(socket, b"{ \"warning\": \"this thermostat doesn't have a fan!\" }"); + send_line( + socket, + b"{ \"warning\": \"this thermostat doesn't have a fan!\" }", + ); return Ok(Handler::Handled); } fan_ctrl.set_auto_mode(false); @@ -363,14 +408,17 @@ impl Handler { Err(e) => { error!("unable to serialize fan summary: {:?}", e); let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e); - Err(Error::ReportError) + Err(Error::Report) } } } fn fan_auto(socket: &mut TcpSocket, fan_ctrl: &mut FanCtrl) -> Result { if !fan_ctrl.fan_available() { - send_line(socket, b"{ \"warning\": \"this thermostat doesn't have a fan!\" }"); + send_line( + socket, + b"{ \"warning\": \"this thermostat doesn't have a fan!\" }", + ); return Ok(Handler::Handled); } fan_ctrl.set_auto_mode(true); @@ -382,7 +430,13 @@ impl Handler { Ok(Handler::Handled) } - fn fan_curve(socket: &mut TcpSocket, fan_ctrl: &mut FanCtrl, k_a: f32, k_b: f32, k_c: f32) -> Result { + fn fan_curve( + socket: &mut TcpSocket, + fan_ctrl: &mut FanCtrl, + k_a: f32, + k_b: f32, + k_c: f32, + ) -> Result { fan_ctrl.set_curve(k_a, k_b, k_c); send_line(socket, b"{}"); Ok(Handler::Handled) @@ -403,39 +457,73 @@ impl Handler { Err(e) => { error!("unable to serialize HWRev summary: {:?}", e); let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e); - Err(Error::ReportError) + Err(Error::Report) } } } - pub fn handle_command(command: Command, socket: &mut TcpSocket, channels: &mut Channels, store: &mut FlashStore, ipv4_config: &mut Ipv4Config, fan_ctrl: &mut FanCtrl, hwrev: HWRev) -> Result { + pub fn handle_command( + command: Command, + socket: &mut TcpSocket, + channels: &mut Channels, + store: &mut FlashStore, + ipv4_config: &mut Ipv4Config, + fan_ctrl: &mut FanCtrl, + hwrev: HWRev, + ) -> Result { match command { Command::Quit => Ok(Handler::CloseSocket), Command::Show(ShowCommand::Input) => Handler::show_report(socket, channels), Command::Show(ShowCommand::Pid) => Handler::show_pid(socket, channels), Command::Show(ShowCommand::Pwm) => Handler::show_pwm(socket, channels), - Command::Show(ShowCommand::SteinhartHart) => Handler::show_steinhart_hart(socket, channels), + Command::Show(ShowCommand::SteinhartHart) => { + Handler::show_steinhart_hart(socket, channels) + } Command::Show(ShowCommand::PostFilter) => Handler::show_post_filter(socket, channels), Command::Show(ShowCommand::Ipv4) => Handler::show_ipv4(socket, ipv4_config), Command::PwmPid { channel } => Handler::engage_pid(socket, channels, channel), - Command::PwmPolarity { channel, polarity } => Handler::set_polarity(socket, channels, channel, polarity), - Command::Pwm { channel, pin, value } => Handler::set_pwm(socket, channels, channel, pin, value), - Command::CenterPoint { channel, center } => Handler::set_center_point(socket, channels, channel, center), - Command::Pid { channel, parameter, value } => Handler::set_pid(socket, channels, channel, parameter, value), - Command::SteinhartHart { channel, parameter, value } => Handler::set_steinhart_hart(socket, channels, channel, parameter, value), - Command::PostFilter { channel, rate: None } => Handler::reset_post_filter(socket, channels, channel), - Command::PostFilter { channel, rate: Some(rate) } => Handler::set_post_filter(socket, channels, channel, rate), + Command::PwmPolarity { channel, polarity } => { + Handler::set_polarity(socket, channels, channel, polarity) + } + Command::Pwm { + channel, + pin, + value, + } => Handler::set_pwm(socket, channels, channel, pin, value), + Command::CenterPoint { channel, center } => { + Handler::set_center_point(socket, channels, channel, center) + } + Command::Pid { + channel, + parameter, + value, + } => Handler::set_pid(socket, channels, channel, parameter, value), + Command::SteinhartHart { + channel, + parameter, + value, + } => Handler::set_steinhart_hart(socket, channels, channel, parameter, value), + Command::PostFilter { + channel, + rate: None, + } => Handler::reset_post_filter(socket, channels, channel), + Command::PostFilter { + channel, + rate: Some(rate), + } => Handler::set_post_filter(socket, channels, channel, rate), Command::Load { channel } => Handler::load_channel(socket, channels, store, channel), Command::Save { channel } => Handler::save_channel(socket, channels, channel, store), Command::Ipv4(config) => Handler::set_ipv4(socket, store, config), Command::Reset => Handler::reset(channels), Command::Dfu => Handler::dfu(channels), - Command::FanSet {fan_pwm} => Handler::set_fan(socket, fan_pwm, fan_ctrl), + Command::FanSet { fan_pwm } => Handler::set_fan(socket, fan_pwm, fan_ctrl), Command::ShowFan => Handler::show_fan(socket, fan_ctrl), Command::FanAuto => Handler::fan_auto(socket, fan_ctrl), - Command::FanCurve { k_a, k_b, k_c } => Handler::fan_curve(socket, fan_ctrl, k_a, k_b, k_c), + Command::FanCurve { k_a, k_b, k_c } => { + Handler::fan_curve(socket, fan_ctrl, k_a, k_b, k_c) + } Command::FanCurveDefaults => Handler::fan_defaults(socket, fan_ctrl), Command::ShowHWRev => Handler::show_hwrev(socket, hwrev), } } -} \ No newline at end of file +} diff --git a/src/command_parser.rs b/src/command_parser.rs index 5eb3589..f4c720b 100644 --- a/src/command_parser.rs +++ b/src/command_parser.rs @@ -2,19 +2,20 @@ use core::fmt; use core::num::ParseIntError; use core::str::{from_utf8, Utf8Error}; use nom::{ - IResult, branch::alt, bytes::complete::{is_a, tag, take_while1}, - character::{is_digit, complete::{char, one_of}}, + character::{ + complete::{char, one_of}, + is_digit, + }, combinator::{complete, map, opt, value}, - sequence::preceded, - multi::{fold_many0, fold_many1}, error::ErrorKind, - Needed, + multi::{fold_many0, fold_many1}, + sequence::preceded, + IResult, Needed, }; use num_traits::{Num, ParseFloatError}; -use serde::{Serialize, Deserialize}; - +use serde::{Deserialize, Serialize}; #[derive(Clone, Debug, PartialEq)] pub enum Error { @@ -30,12 +31,9 @@ pub enum Error { impl<'t> From> for Error { fn from(e: nom::Err<(&'t [u8], ErrorKind)>) -> Self { match e { - nom::Err::Incomplete(_) => - Error::Incomplete, - nom::Err::Error((_, e)) => - Error::Parser(e), - nom::Err::Failure((_, e)) => - Error::Parser(e), + nom::Err::Incomplete(_) => Error::Incomplete, + nom::Err::Error((_, e)) => Error::Parser(e), + nom::Err::Failure((_, e)) => Error::Parser(e), } } } @@ -61,8 +59,7 @@ impl From for Error { impl fmt::Display for Error { fn fmt(&self, fmt: &mut fmt::Formatter) -> Result<(), fmt::Error> { match self { - Error::Incomplete => - "incomplete input".fmt(fmt), + Error::Incomplete => "incomplete input".fmt(fmt), Error::UnexpectedInput(c) => { "unexpected input: ".fmt(fmt)?; c.fmt(fmt) @@ -79,9 +76,7 @@ impl fmt::Display for Error { "parsing int: ".fmt(fmt)?; (e as &dyn core::fmt::Debug).fmt(fmt) } - Error::ParseFloat => { - "parsing float".fmt(fmt) - } + Error::ParseFloat => "parsing float".fmt(fmt), } } } @@ -131,7 +126,7 @@ pub enum PwmPin { #[derive(Debug, Clone, PartialEq, Serialize, Deserialize)] pub enum CenterPoint { - Vref, + VRef, Override(f32), } @@ -188,7 +183,7 @@ pub enum Command { }, Dfu, FanSet { - fan_pwm: u32 + fan_pwm: u32, }, FanAuto, ShowFan, @@ -202,12 +197,7 @@ pub enum Command { } fn end(input: &[u8]) -> IResult<&[u8], ()> { - complete( - fold_many0( - one_of("\r\n\t "), - (), |(), _| () - ) - )(input) + complete(fold_many0(one_of("\r\n\t "), (), |(), _| ()))(input) } fn whitespace(input: &[u8]) -> IResult<&[u8], ()> { @@ -215,28 +205,21 @@ fn whitespace(input: &[u8]) -> IResult<&[u8], ()> { } fn unsigned(input: &[u8]) -> IResult<&[u8], Result> { - take_while1(is_digit)(input) - .map(|(input, digits)| { - let result = - from_utf8(digits) - .map_err(|e| e.into()) - .and_then(|digits| u32::from_str_radix(digits, 10) - .map_err(|e| e.into()) - ); - (input, result) - }) + take_while1(is_digit)(input).map(|(input, digits)| { + let result = from_utf8(digits) + .map_err(|e| e.into()) + .and_then(|digits| digits.parse::().map_err(|e| e.into())); + (input, result) + }) } fn float(input: &[u8]) -> IResult<&[u8], Result> { let (input, sign) = opt(is_a("-"))(input)?; let negative = sign.is_some(); - let (input, digits) = take_while1(|c| is_digit(c) || c == '.' as u8)(input)?; - let result = - from_utf8(digits) + let (input, digits) = take_while1(|c| is_digit(c) || c == b'.')(input)?; + let result = from_utf8(digits) .map_err(|e| e.into()) - .and_then(|digits| f64::from_str_radix(digits, 10) - .map_err(|e| e.into()) - ) + .and_then(|digits| f64::from_str_radix(digits, 10).map_err(|e| e.into())) .map(|result: f64| if negative { -result } else { result }); Ok((input, result)) } @@ -249,57 +232,32 @@ fn report(input: &[u8]) -> IResult<&[u8], Command> { preceded( tag("report"), // `report` - Report once - value(Command::Show(ShowCommand::Input), end) + value(Command::Show(ShowCommand::Input), end), )(input) } fn pwm_setup(input: &[u8]) -> IResult<&[u8], Result<(PwmPin, f64), Error>> { - let result_with_pin = |pin: PwmPin| - move |result: Result| - result.map(|value| (pin, value)); + let result_with_pin = + |pin: PwmPin| move |result: Result| result.map(|value| (pin, value)); alt(( map( - preceded( - tag("i_set"), - preceded( - whitespace, - float - ) - ), - result_with_pin(PwmPin::ISet) + preceded(tag("i_set"), preceded(whitespace, float)), + result_with_pin(PwmPin::ISet), ), map( - preceded( - tag("max_i_pos"), - preceded( - whitespace, - float - ) - ), - result_with_pin(PwmPin::MaxIPos) + preceded(tag("max_i_pos"), preceded(whitespace, float)), + result_with_pin(PwmPin::MaxIPos), ), map( - preceded( - tag("max_i_neg"), - preceded( - whitespace, - float - ) - ), - result_with_pin(PwmPin::MaxINeg) + preceded(tag("max_i_neg"), preceded(whitespace, float)), + result_with_pin(PwmPin::MaxINeg), ), map( - preceded( - tag("max_v"), - preceded( - whitespace, - float - ) - ), - result_with_pin(PwmPin::MaxV) - )) - )(input) + preceded(tag("max_v"), preceded(whitespace, float)), + result_with_pin(PwmPin::MaxV), + ), + ))(input) } /// `pwm <0-1> pid` - Set PWM to be controlled by PID @@ -312,10 +270,11 @@ fn pwm_polarity(input: &[u8]) -> IResult<&[u8], Polarity> { tag("polarity"), preceded( whitespace, - alt((value(Polarity::Normal, tag("normal")), - value(Polarity::Reversed, tag("reversed")) - )) - ) + alt(( + value(Polarity::Normal, tag("normal")), + value(Polarity::Reversed, tag("reversed")), + )), + ), )(input) } @@ -338,17 +297,22 @@ fn pwm(input: &[u8]) -> IResult<&[u8], Result> { |input| { let (input, config) = pwm_setup(input)?; match config { - Ok((pin, value)) => - Ok((input, Ok(Command::Pwm { channel, pin, value }))), - Err(e) => - Ok((input, Err(e))), + Ok((pin, value)) => Ok(( + input, + Ok(Command::Pwm { + channel, + pin, + value, + }), + )), + Err(e) => Ok((input, Err(e))), } }, ))(input)?; end(input)?; Ok((input, result)) }, - value(Ok(Command::Show(ShowCommand::Pwm)), end) + value(Ok(Command::Show(ShowCommand::Pwm)), end), ))(input) } @@ -357,36 +321,39 @@ fn center_point(input: &[u8]) -> IResult<&[u8], Result> { let (input, _) = whitespace(input)?; let (input, channel) = channel(input)?; let (input, _) = whitespace(input)?; - let (input, center) = alt(( - value(Ok(CenterPoint::Vref), tag("vref")), - |input| { - let (input, value) = float(input)?; - Ok((input, value.map(|value| CenterPoint::Override(value as f32)))) - } - ))(input)?; + let (input, center) = alt((value(Ok(CenterPoint::VRef), tag("vref")), |input| { + let (input, value) = float(input)?; + Ok(( + input, + value.map(|value| CenterPoint::Override(value as f32)), + )) + }))(input)?; end(input)?; - Ok((input, center.map(|center| Command::CenterPoint { - channel, - center, - }))) + Ok(( + input, + center.map(|center| Command::CenterPoint { channel, center }), + )) } /// `pid <0-1> ` fn pid_parameter(input: &[u8]) -> IResult<&[u8], Result> { let (input, channel) = channel(input)?; let (input, _) = whitespace(input)?; - let (input, parameter) = - alt((value(PidParameter::Target, tag("target")), - value(PidParameter::KP, tag("kp")), - value(PidParameter::KI, tag("ki")), - value(PidParameter::KD, tag("kd")), - value(PidParameter::OutputMin, tag("output_min")), - value(PidParameter::OutputMax, tag("output_max")), - ))(input)?; + let (input, parameter) = alt(( + value(PidParameter::Target, tag("target")), + value(PidParameter::KP, tag("kp")), + value(PidParameter::KI, tag("ki")), + value(PidParameter::KD, tag("kd")), + value(PidParameter::OutputMin, tag("output_min")), + value(PidParameter::OutputMax, tag("output_max")), + ))(input)?; let (input, _) = whitespace(input)?; let (input, value) = float(input)?; - let result = value - .map(|value| Command::Pid { channel, parameter, value }); + let result = value.map(|value| Command::Pid { + channel, + parameter, + value, + }); Ok((input, result)) } @@ -394,11 +361,8 @@ fn pid_parameter(input: &[u8]) -> IResult<&[u8], Result> { fn pid(input: &[u8]) -> IResult<&[u8], Result> { let (input, _) = tag("pid")(input)?; alt(( - preceded( - whitespace, - pid_parameter - ), - value(Ok(Command::Show(ShowCommand::Pid)), end) + preceded(whitespace, pid_parameter), + value(Ok(Command::Show(ShowCommand::Pid)), end), ))(input) } @@ -406,15 +370,18 @@ fn pid(input: &[u8]) -> IResult<&[u8], Result> { fn steinhart_hart_parameter(input: &[u8]) -> IResult<&[u8], Result> { let (input, channel) = channel(input)?; let (input, _) = whitespace(input)?; - let (input, parameter) = - alt((value(ShParameter::T0, tag("t0")), - value(ShParameter::B, tag("b")), - value(ShParameter::R0, tag("r0")) - ))(input)?; + let (input, parameter) = alt(( + value(ShParameter::T0, tag("t0")), + value(ShParameter::B, tag("b")), + value(ShParameter::R0, tag("r0")), + ))(input)?; let (input, _) = whitespace(input)?; let (input, value) = float(input)?; - let result = value - .map(|value| Command::SteinhartHart { channel, parameter, value }); + let result = value.map(|value| Command::SteinhartHart { + channel, + parameter, + value, + }); Ok((input, result)) } @@ -422,42 +389,38 @@ fn steinhart_hart_parameter(input: &[u8]) -> IResult<&[u8], Result IResult<&[u8], Result> { let (input, _) = tag("s-h")(input)?; alt(( - preceded( - whitespace, - steinhart_hart_parameter - ), - value(Ok(Command::Show(ShowCommand::SteinhartHart)), end) + preceded(whitespace, steinhart_hart_parameter), + value(Ok(Command::Show(ShowCommand::SteinhartHart)), end), ))(input) } fn postfilter(input: &[u8]) -> IResult<&[u8], Result> { let (input, _) = tag("postfilter")(input)?; alt(( - preceded( - whitespace, - |input| { - let (input, channel) = channel(input)?; - let (input, _) = whitespace(input)?; - alt(( - value(Ok(Command::PostFilter { + preceded(whitespace, |input| { + let (input, channel) = channel(input)?; + let (input, _) = whitespace(input)?; + alt(( + value( + Ok(Command::PostFilter { channel, rate: None, - }), tag("off")), - move |input| { - let (input, _) = tag("rate")(input)?; - let (input, _) = whitespace(input)?; - let (input, rate) = float(input)?; - let result = rate - .map(|rate| Command::PostFilter { - channel, - rate: Some(rate as f32), - }); - Ok((input, result)) - } - ))(input) - } - ), - value(Ok(Command::Show(ShowCommand::PostFilter)), end) + }), + tag("off"), + ), + move |input| { + let (input, _) = tag("rate")(input)?; + let (input, _) = whitespace(input)?; + let (input, rate) = float(input)?; + let result = rate.map(|rate| Command::PostFilter { + channel, + rate: Some(rate as f32), + }); + Ok((input, result)) + }, + ))(input) + }), + value(Ok(Command::Show(ShowCommand::PostFilter)), end), ))(input) } @@ -470,7 +433,7 @@ fn load(input: &[u8]) -> IResult<&[u8], Result> { let (input, _) = end(input)?; Ok((input, Some(channel))) }, - value(None, end) + value(None, end), ))(input)?; let result = Ok(Command::Load { channel }); @@ -486,7 +449,7 @@ fn save(input: &[u8]) -> IResult<&[u8], Result> { let (input, _) = end(input)?; Ok((input, Some(channel))) }, - value(None, end) + value(None, end), ))(input)?; let result = Ok(Command::Save { channel }); @@ -548,12 +511,17 @@ fn fan(input: &[u8]) -> IResult<&[u8], Result> { }, |input| { let (input, value) = unsigned(input)?; - Ok((input, Ok(Command::FanSet { fan_pwm: value.unwrap_or(0)}))) + Ok(( + input, + Ok(Command::FanSet { + fan_pwm: value.unwrap_or(0), + }), + )) }, ))(input)?; Ok((input, result)) }, - value(Ok(Command::ShowFan), end) + value(Ok(Command::ShowFan), end), ))(input) } @@ -573,8 +541,15 @@ fn fan_curve(input: &[u8]) -> IResult<&[u8], Result> { let (input, k_b) = float(input)?; let (input, _) = whitespace(input)?; let (input, k_c) = float(input)?; - if k_a.is_ok() && k_b.is_ok() && k_c.is_ok() { - Ok((input, Ok(Command::FanCurve { k_a: k_a.unwrap() as f32, k_b: k_b.unwrap() as f32, k_c: k_c.unwrap() as f32 }))) + if let (Ok(k_a), Ok(k_b), Ok(k_c)) = (k_a, k_b, k_c) { + Ok(( + input, + Ok(Command::FanCurve { + k_a: k_a as f32, + k_b: k_b as f32, + k_c: k_c as f32, + }), + )) } else { Err(nom::Err::Incomplete(Needed::Size(3))) } @@ -582,38 +557,36 @@ fn fan_curve(input: &[u8]) -> IResult<&[u8], Result> { ))(input)?; Ok((input, result)) }, - value(Err(Error::Incomplete), end) + value(Err(Error::Incomplete), end), ))(input) } fn command(input: &[u8]) -> IResult<&[u8], Result> { - alt((value(Ok(Command::Quit), tag("quit")), - load, - save, - value(Ok(Command::Reset), tag("reset")), - ipv4, - map(report, Ok), - pwm, - center_point, - pid, - steinhart_hart, - postfilter, - value(Ok(Command::Dfu), tag("dfu")), - fan, - fan_curve, - value(Ok(Command::ShowHWRev), tag("hwrev")), + alt(( + value(Ok(Command::Quit), tag("quit")), + load, + save, + value(Ok(Command::Reset), tag("reset")), + ipv4, + map(report, Ok), + pwm, + center_point, + pid, + steinhart_hart, + postfilter, + value(Ok(Command::Dfu), tag("dfu")), + fan, + fan_curve, + value(Ok(Command::ShowHWRev), tag("hwrev")), ))(input) } impl Command { pub fn parse(input: &[u8]) -> Result { match command(input) { - Ok((input_remain, result)) if input_remain.len() == 0 => - result, - Ok((input_remain, _)) => - Err(Error::UnexpectedInput(input_remain[0])), - Err(e) => - Err(e.into()), + Ok((input_remain, result)) if input_remain.is_empty() => result, + Ok((input_remain, _)) => Err(Error::UnexpectedInput(input_remain[0])), + Err(e) => Err(e.into()), } } } @@ -661,21 +634,27 @@ mod test { #[test] fn parse_ipv4() { let command = Command::parse(b"ipv4 192.168.1.26/24"); - assert_eq!(command, Ok(Command::Ipv4(Ipv4Config { - address: [192, 168, 1, 26], - mask_len: 24, - gateway: None, - }))); + assert_eq!( + command, + Ok(Command::Ipv4(Ipv4Config { + address: [192, 168, 1, 26], + mask_len: 24, + gateway: None, + })) + ); } #[test] fn parse_ipv4_and_gateway() { let command = Command::parse(b"ipv4 10.42.0.126/8 10.1.0.1"); - assert_eq!(command, Ok(Command::Ipv4(Ipv4Config { - address: [10, 42, 0, 126], - mask_len: 8, - gateway: Some([10, 1, 0, 1]), - }))); + assert_eq!( + command, + Ok(Command::Ipv4(Ipv4Config { + address: [10, 42, 0, 126], + mask_len: 8, + gateway: Some([10, 1, 0, 1]), + })) + ); } #[test] @@ -687,58 +666,71 @@ mod test { #[test] fn parse_pwm_i_set() { let command = Command::parse(b"pwm 1 i_set 16383"); - assert_eq!(command, Ok(Command::Pwm { - channel: 1, - pin: PwmPin::ISet, - value: 16383.0, - })); + assert_eq!( + command, + Ok(Command::Pwm { + channel: 1, + pin: PwmPin::ISet, + value: 16383.0, + }) + ); } #[test] fn parse_pwm_polarity() { let command = Command::parse(b"pwm 0 polarity reversed"); - assert_eq!(command, Ok(Command::PwmPolarity { - channel: 0, - polarity: Polarity::Reversed, - })); + assert_eq!( + command, + Ok(Command::PwmPolarity { + channel: 0, + polarity: Polarity::Reversed, + }) + ); } #[test] fn parse_pwm_pid() { let command = Command::parse(b"pwm 0 pid"); - assert_eq!(command, Ok(Command::PwmPid { - channel: 0, - })); + assert_eq!(command, Ok(Command::PwmPid { channel: 0 })); } #[test] fn parse_pwm_max_i_pos() { let command = Command::parse(b"pwm 0 max_i_pos 7"); - assert_eq!(command, Ok(Command::Pwm { - channel: 0, - pin: PwmPin::MaxIPos, - value: 7.0, - })); + assert_eq!( + command, + Ok(Command::Pwm { + channel: 0, + pin: PwmPin::MaxIPos, + value: 7.0, + }) + ); } #[test] fn parse_pwm_max_i_neg() { let command = Command::parse(b"pwm 0 max_i_neg 128"); - assert_eq!(command, Ok(Command::Pwm { - channel: 0, - pin: PwmPin::MaxINeg, - value: 128.0, - })); + assert_eq!( + command, + Ok(Command::Pwm { + channel: 0, + pin: PwmPin::MaxINeg, + value: 128.0, + }) + ); } #[test] fn parse_pwm_max_v() { let command = Command::parse(b"pwm 0 max_v 32768"); - assert_eq!(command, Ok(Command::Pwm { - channel: 0, - pin: PwmPin::MaxV, - value: 32768.0, - })); + assert_eq!( + command, + Ok(Command::Pwm { + channel: 0, + pin: PwmPin::MaxV, + value: 32768.0, + }) + ); } #[test] @@ -750,11 +742,14 @@ mod test { #[test] fn parse_pid_target() { let command = Command::parse(b"pid 0 target 36.5"); - assert_eq!(command, Ok(Command::Pid { - channel: 0, - parameter: PidParameter::Target, - value: 36.5, - })); + assert_eq!( + command, + Ok(Command::Pid { + channel: 0, + parameter: PidParameter::Target, + value: 36.5, + }) + ); } #[test] @@ -766,11 +761,14 @@ mod test { #[test] fn parse_steinhart_hart_set() { let command = Command::parse(b"s-h 1 t0 23.05"); - assert_eq!(command, Ok(Command::SteinhartHart { - channel: 1, - parameter: ShParameter::T0, - value: 23.05, - })); + assert_eq!( + command, + Ok(Command::SteinhartHart { + channel: 1, + parameter: ShParameter::T0, + value: 23.05, + }) + ); } #[test] @@ -782,37 +780,49 @@ mod test { #[test] fn parse_postfilter_off() { let command = Command::parse(b"postfilter 1 off"); - assert_eq!(command, Ok(Command::PostFilter { - channel: 1, - rate: None, - })); + assert_eq!( + command, + Ok(Command::PostFilter { + channel: 1, + rate: None, + }) + ); } #[test] fn parse_postfilter_rate() { let command = Command::parse(b"postfilter 0 rate 21"); - assert_eq!(command, Ok(Command::PostFilter { - channel: 0, - rate: Some(21.0), - })); + assert_eq!( + command, + Ok(Command::PostFilter { + channel: 0, + rate: Some(21.0), + }) + ); } #[test] fn parse_center_point() { let command = Command::parse(b"center 0 1.5"); - assert_eq!(command, Ok(Command::CenterPoint { - channel: 0, - center: CenterPoint::Override(1.5), - })); + assert_eq!( + command, + Ok(Command::CenterPoint { + channel: 0, + center: CenterPoint::Override(1.5), + }) + ); } #[test] fn parse_center_point_vref() { let command = Command::parse(b"center 1 vref"); - assert_eq!(command, Ok(Command::CenterPoint { - channel: 1, - center: CenterPoint::Vref, - })); + assert_eq!( + command, + Ok(Command::CenterPoint { + channel: 1, + center: CenterPoint::VRef, + }) + ); } #[test] @@ -824,7 +834,7 @@ mod test { #[test] fn parse_fan_set() { let command = Command::parse(b"fan 42"); - assert_eq!(command, Ok(Command::FanSet {fan_pwm: 42})); + assert_eq!(command, Ok(Command::FanSet { fan_pwm: 42 })); } #[test] @@ -836,11 +846,14 @@ mod test { #[test] fn parse_fcurve_set() { let command = Command::parse(b"fcurve 1.2 3.4 5.6"); - assert_eq!(command, Ok(Command::FanCurve { - k_a: 1.2, - k_b: 3.4, - k_c: 5.6 - })); + assert_eq!( + command, + Ok(Command::FanCurve { + k_a: 1.2, + k_b: 3.4, + k_c: 5.6 + }) + ); } #[test] diff --git a/src/config.rs b/src/config.rs index 65b511d..43c5bb8 100644 --- a/src/config.rs +++ b/src/config.rs @@ -1,16 +1,15 @@ -use num_traits::Zero; -use serde::{Serialize, Deserialize}; -use uom::si::{ - electric_potential::volt, - electric_current::ampere, - f64::{ElectricCurrent, ElectricPotential}, -}; use crate::{ ad7172::PostFilter, channels::Channels, command_parser::{CenterPoint, Polarity}, - pid, - steinhart_hart, + pid, steinhart_hart, +}; +use num_traits::Zero; +use serde::{Deserialize, Serialize}; +use uom::si::{ + electric_current::ampere, + electric_potential::volt, + f64::{ElectricCurrent, ElectricPotential}, }; #[derive(Clone, Debug, PartialEq, Serialize, Deserialize)] @@ -31,15 +30,17 @@ impl ChannelConfig { pub fn new(channels: &mut Channels, channel: usize) -> Self { let pwm = PwmLimits::new(channels, channel); - let adc_postfilter = channels.adc.get_postfilter(channel as u8) + let adc_postfilter = channels + .adc + .get_postfilter(channel as u8) .unwrap() .unwrap_or(PostFilter::Invalid); let state = channels.channel_state(channel); - let i_set = if state.pid_engaged { - ElectricCurrent::zero() - } else { - state.i_set + let i_set = if state.pid_engaged { + ElectricCurrent::zero() + } else { + state.i_set }; ChannelConfig { center: state.center.clone(), diff --git a/src/dfu.rs b/src/dfu.rs index 9601472..3856a67 100644 --- a/src/dfu.rs +++ b/src/dfu.rs @@ -14,7 +14,7 @@ pub unsafe fn set_dfu_trigger() { } /// Called by reset handler in lib.rs immediately after reset. -/// This function should not be called outside of reset handler as +/// This function should not be called outside of reset handler as /// bootloader expects MCU to be in reset state when called. #[cfg(target_arch = "arm")] #[pre_init] @@ -27,13 +27,13 @@ unsafe fn __pre_init() { rcc.apb2enr.modify(|_, w| w.syscfgen().set_bit()); // Bypass BOOT pins and remap bootloader to 0x00000000 - let syscfg = &*SYSCFG::ptr() ; - syscfg.memrm.write(|w| w.mem_mode().bits(0b01)); + let syscfg = &*SYSCFG::ptr(); + syscfg.memrm.write(|w| w.mem_mode().bits(0b01)); // Impose instruction and memory barriers cortex_m::asm::isb(); cortex_m::asm::dsb(); - + asm!( // Set stack pointer to bootloader location "LDR R0, =0x1FFF0000", diff --git a/src/fan_ctrl.rs b/src/fan_ctrl.rs index 2467fc1..dbc4b0a 100644 --- a/src/fan_ctrl.rs +++ b/src/fan_ctrl.rs @@ -1,25 +1,17 @@ +use crate::{channels::MAX_TEC_I, command_handler::JsonBuffer, hw_rev::HWSettings}; use num_traits::Float; use serde::Serialize; use stm32f4xx_hal::{ - pwm::{self, PwmChannels}, pac::TIM8, + pwm::{self, PwmChannels}, }; -use uom::si::{ - f64::ElectricCurrent, - electric_current::ampere, -}; -use crate::{ - hw_rev::HWSettings, - command_handler::JsonBuffer, - channels::MAX_TEC_I, -}; +use uom::si::{electric_current::ampere, f64::ElectricCurrent}; pub type FanPin = PwmChannels; const MAX_USER_FAN_PWM: f32 = 100.0; const MIN_USER_FAN_PWM: f32 = 1.0; - pub struct FanCtrl { fan: Option, fan_auto: bool, @@ -56,7 +48,9 @@ impl FanCtrl { if self.fan_auto && self.hw_settings.fan_available { let scaled_current = self.abs_max_tec_i / MAX_TEC_I.get::() as f32; // do not limit upper bound, as it will be limited in the set_pwm() - let pwm = (MAX_USER_FAN_PWM * (scaled_current * (scaled_current * self.k_a + self.k_b) + self.k_c)) as u32; + let pwm = (MAX_USER_FAN_PWM + * (scaled_current * (scaled_current * self.k_a + self.k_b) + self.k_c)) + as u32; self.set_pwm(pwm); } } @@ -89,18 +83,26 @@ impl FanCtrl { } pub fn restore_defaults(&mut self) { - self.set_curve(self.hw_settings.fan_k_a, - self.hw_settings.fan_k_b, - self.hw_settings.fan_k_c); + self.set_curve( + self.hw_settings.fan_k_a, + self.hw_settings.fan_k_b, + self.hw_settings.fan_k_c, + ); } pub fn set_pwm(&mut self, fan_pwm: u32) -> f32 { - if self.fan.is_none() || (!self.pwm_enabled && !self.enable_pwm()) { + if self.fan.is_none() || (!self.pwm_enabled && !self.enable_pwm()) { return 0f32; } let fan = self.fan.as_mut().unwrap(); - let fan_pwm = fan_pwm.min(MAX_USER_FAN_PWM as u32).max(MIN_USER_FAN_PWM as u32); - let duty = scale_number(fan_pwm as f32, self.hw_settings.min_fan_pwm, self.hw_settings.max_fan_pwm, MIN_USER_FAN_PWM, MAX_USER_FAN_PWM); + let fan_pwm = fan_pwm.clamp(MIN_USER_FAN_PWM as u32, MAX_USER_FAN_PWM as u32); + let duty = scale_number( + fan_pwm as f32, + self.hw_settings.min_fan_pwm, + self.hw_settings.max_fan_pwm, + MIN_USER_FAN_PWM, + MAX_USER_FAN_PWM, + ); let max = fan.get_max_duty(); let value = ((duty * (max as f32)) as u16).min(max); fan.set_duty(value); @@ -119,8 +121,17 @@ impl FanCtrl { if let Some(fan) = &self.fan { let duty = fan.get_duty(); let max = fan.get_max_duty(); - scale_number(duty as f32 / (max as f32), MIN_USER_FAN_PWM, MAX_USER_FAN_PWM, self.hw_settings.min_fan_pwm, self.hw_settings.max_fan_pwm).round() as u32 - } else { 0 } + scale_number( + duty as f32 / (max as f32), + MIN_USER_FAN_PWM, + MAX_USER_FAN_PWM, + self.hw_settings.min_fan_pwm, + self.hw_settings.max_fan_pwm, + ) + .round() as u32 + } else { + 0 + } } fn enable_pwm(&mut self) -> bool { @@ -136,7 +147,6 @@ impl FanCtrl { } } - fn scale_number(unscaled: f32, to_min: f32, to_max: f32, from_min: f32, from_max: f32) -> f32 { (to_max - to_min) * (unscaled - from_min) / (from_max - from_min) + to_min } diff --git a/src/flash_store.rs b/src/flash_store.rs index 473f1ea..e53d99b 100644 --- a/src/flash_store.rs +++ b/src/flash_store.rs @@ -1,9 +1,9 @@ -use log::{info, error}; +use log::{error, info}; +use sfkv::{Store, StoreBackend}; use stm32f4xx_hal::{ flash::{Error, FlashExt}, stm32::FLASH, }; -use sfkv::{Store, StoreBackend}; /// 16 KiB pub const FLASH_SECTOR_SIZE: usize = 0x4000; @@ -21,9 +21,7 @@ pub struct FlashBackend { } fn get_offset() -> usize { - unsafe { - (&_config_start as *const usize as usize) - (&_flash_start as *const usize as usize) - } + unsafe { (&_config_start as *const usize as usize) - (&_flash_start as *const usize as usize) } } impl StoreBackend for FlashBackend { @@ -40,7 +38,8 @@ impl StoreBackend for FlashBackend { } fn program(&mut self, offset: usize, payload: &[u8]) -> Result<(), Self::Error> { - self.flash.unlocked() + self.flash + .unlocked() .program(get_offset() + offset, payload.iter()) } @@ -60,7 +59,8 @@ pub fn store(flash: FLASH) -> FlashStore { Ok(_) => {} Err(e) => { error!("corrupt store, erasing. error: {:?}", e); - let _ = store.erase() + let _ = store + .erase() .map_err(|e| error!("flash erase failed: {:?}", e)); } } diff --git a/src/hw_rev.rs b/src/hw_rev.rs index ef022a1..e59fbff 100644 --- a/src/hw_rev.rs +++ b/src/hw_rev.rs @@ -1,9 +1,6 @@ use serde::Serialize; -use crate::{ - pins::HWRevPins, - command_handler::JsonBuffer, -}; +use crate::{command_handler::JsonBuffer, pins::HWRevPins}; #[derive(Serialize, Copy, Clone)] pub struct HWRev { @@ -31,13 +28,17 @@ struct HWSummary<'a> { impl HWRev { pub fn detect_hw_rev(hwrev_pins: &HWRevPins) -> Self { - let (h0, h1, h2, h3) = (hwrev_pins.hwrev0.is_high(), hwrev_pins.hwrev1.is_high(), - hwrev_pins.hwrev2.is_high(), hwrev_pins.hwrev3.is_high()); + let (h0, h1, h2, h3) = ( + hwrev_pins.hwrev0.is_high(), + hwrev_pins.hwrev1.is_high(), + hwrev_pins.hwrev2.is_high(), + hwrev_pins.hwrev3.is_high(), + ); match (h0, h1, h2, h3) { (true, true, true, false) => HWRev { major: 1, minor: 0 }, (true, false, false, false) => HWRev { major: 2, minor: 0 }, (false, true, false, false) => HWRev { major: 2, minor: 2 }, - (_, _, _, _) => HWRev { major: 0, minor: 0 } + (_, _, _, _) => HWRev { major: 0, minor: 0 }, } } @@ -70,13 +71,16 @@ impl HWRev { fan_pwm_freq_hz: 0, fan_available: false, fan_pwm_recommended: false, - } + }, } } pub fn summary(&self) -> Result { let settings = self.settings(); - let summary = HWSummary { rev: self, settings: &settings }; + let summary = HWSummary { + rev: self, + settings: &settings, + }; serde_json_core::to_vec(&summary) } -} \ No newline at end of file +} diff --git a/src/init_log.rs b/src/init_log.rs index 0381602..dbb6e26 100644 --- a/src/init_log.rs +++ b/src/init_log.rs @@ -10,17 +10,15 @@ pub fn init_log() { #[cfg(feature = "semihosting")] pub fn init_log() { + use cortex_m_log::log::{init, Logger}; + use cortex_m_log::printer::semihosting::{hio::HStdout, InterruptOk}; use log::LevelFilter; - use cortex_m_log::log::{Logger, init}; - use cortex_m_log::printer::semihosting::{InterruptOk, hio::HStdout}; static mut LOGGER: Option>> = None; let logger = Logger { inner: InterruptOk::<_>::stdout().expect("semihosting stdout"), level: LevelFilter::Info, }; - let logger = unsafe { - LOGGER.get_or_insert(logger) - }; + let logger = unsafe { LOGGER.get_or_insert(logger) }; init(logger).expect("set logger"); } diff --git a/src/leds.rs b/src/leds.rs index c03c9c5..9d5667e 100644 --- a/src/leds.rs +++ b/src/leds.rs @@ -1,6 +1,6 @@ use stm32f4xx_hal::{ gpio::{ - gpiod::{PD9, PD10, PD11}, + gpiod::{PD10, PD11, PD9}, Output, PushPull, }, hal::digital::v2::OutputPin, diff --git a/src/main.rs b/src/main.rs index 7c874e9..edc028c 100644 --- a/src/main.rs +++ b/src/main.rs @@ -8,30 +8,26 @@ use panic_halt as _; #[cfg(all(feature = "semihosting", not(test)))] use panic_semihosting as _; -use log::{error, info, warn}; use cortex_m::asm::wfi; use cortex_m_rt::entry; +use log::{error, info, warn}; +use smoltcp::{socket::TcpSocket, time::Instant, wire::EthernetAddress}; use stm32f4xx_hal::{ - hal::watchdog::{WatchdogEnable, Watchdog}, + hal::watchdog::{Watchdog, WatchdogEnable}, rcc::RccExt, stm32::{CorePeripherals, Peripherals, SCB}, - time::{U32Ext, MegaHertz}, + time::{MegaHertz, U32Ext}, watchdog::IndependentWatchdog, }; -use smoltcp::{ - time::Instant, - socket::TcpSocket, - wire::EthernetAddress, -}; mod init_log; use init_log::init_log; -mod usb; mod leds; mod pins; +mod usb; use pins::Pins; -mod ad7172; mod ad5680; +mod ad7172; mod net; mod server; use server::Server; @@ -39,18 +35,18 @@ mod session; use session::{Session, SessionInput}; mod command_parser; use command_parser::Ipv4Config; -mod timer; +mod channels; mod pid; mod steinhart_hart; -mod channels; -use channels::{CHANNELS, Channels}; +mod timer; +use channels::{Channels, CHANNELS}; mod channel; mod channel_state; mod config; use config::ChannelConfig; -mod flash_store; -mod dfu; mod command_handler; +mod dfu; +mod flash_store; use command_handler::Handler; mod fan_ctrl; use fan_ctrl::FanCtrl; @@ -73,19 +69,19 @@ fn send_line(socket: &mut TcpSocket, data: &[u8]) -> bool { // instead of sending incomplete line warn!( "TCP socket has only {}/{} needed {}", - send_free + 1, socket.send_capacity(), data.len(), + send_free + 1, + socket.send_capacity(), + data.len(), ); } else { - match socket.send_slice(&data) { + match socket.send_slice(data) { Ok(sent) if sent == data.len() => { let _ = socket.send_slice(b"\n"); // success - return true + return true; } - Ok(sent) => - warn!("sent only {}/{} bytes", sent, data.len()), - Err(e) => - error!("error sending line: {:?}", e), + Ok(sent) => warn!("sent only {}/{} bytes", sent, data.len()), + Err(e) => error!("error sending line: {:?}", e), } } // not success @@ -104,7 +100,9 @@ fn main() -> ! { cp.SCB.enable_dcache(&mut cp.CPUID); let dp = Peripherals::take().unwrap(); - let clocks = dp.RCC.constrain() + let clocks = dp + .RCC + .constrain() .cfgr .use_hse(HSE) .sysclk(168.mhz()) @@ -120,14 +118,15 @@ fn main() -> ! { timer::setup(cp.SYST, clocks); let (pins, mut leds, mut eeprom, eth_pins, usb, fan, hwrev, hw_settings) = Pins::setup( - clocks, dp.TIM1, dp.TIM3, dp.TIM8, - dp.GPIOA, dp.GPIOB, dp.GPIOC, dp.GPIOD, dp.GPIOE, dp.GPIOF, dp.GPIOG, + clocks, + (dp.TIM1, dp.TIM3, dp.TIM8), + ( + dp.GPIOA, dp.GPIOB, dp.GPIOC, dp.GPIOD, dp.GPIOE, dp.GPIOF, dp.GPIOG, + ), dp.I2C1, - dp.SPI2, dp.SPI4, dp.SPI5, + (dp.SPI2, dp.SPI4, dp.SPI5), dp.ADC1, - dp.OTG_FS_GLOBAL, - dp.OTG_FS_DEVICE, - dp.OTG_FS_PWRCLK, + (dp.OTG_FS_GLOBAL, dp.OTG_FS_DEVICE, dp.OTG_FS_PWRCLK), ); leds.r1.on(); @@ -139,14 +138,11 @@ fn main() -> ! { let mut store = flash_store::store(dp.FLASH); let mut channels = Channels::new(pins); - for c in 0..CHANNELS { - match store.read_value::(CHANNEL_CONFIG_KEY[c]) { - Ok(Some(config)) => - config.apply(&mut channels, c), - Ok(None) => - error!("flash config not found for channel {}", c), - Err(e) => - error!("unable to load config {} from flash: {:?}", c, e), + for (c, key) in CHANNEL_CONFIG_KEY.iter().enumerate().take(CHANNELS) { + match store.read_value::(key) { + Ok(Some(config)) => config.apply(&mut channels, c), + Ok(None) => error!("flash config not found for channel {}", c), + Err(e) => error!("unable to load config {} from flash: {:?}", c, e), } } @@ -159,11 +155,9 @@ fn main() -> ! { gateway: None, }; match store.read_value("ipv4") { - Ok(Some(config)) => - ipv4_config = config, + Ok(Some(config)) => ipv4_config = config, Ok(None) => {} - Err(e) => - error!("cannot read ipv4 config: {:?}", e), + Err(e) => error!("cannot read ipv4 config: {:?}", e), } // EEPROM ships with a read-only EUI-48 identifier @@ -172,102 +166,115 @@ fn main() -> ! { let hwaddr = EthernetAddress(eui48); info!("EEPROM MAC address: {}", hwaddr); - net::run(clocks, dp.ETHERNET_MAC, dp.ETHERNET_DMA, eth_pins, hwaddr, ipv4_config.clone(), |iface| { - Server::::run(iface, |server| { - leds.r1.off(); - let mut should_reset = false; + net::run( + clocks, + dp.ETHERNET_MAC, + dp.ETHERNET_DMA, + eth_pins, + hwaddr, + ipv4_config.clone(), + |iface| { + Server::::run(iface, |server| { + leds.r1.off(); + let mut should_reset = false; - loop { - let mut new_ipv4_config = None; - let instant = Instant::from_millis(i64::from(timer::now())); - channels.poll_adc(instant); + loop { + let mut new_ipv4_config = None; + let instant = Instant::from_millis(i64::from(timer::now())); + channels.poll_adc(instant); - fan_ctrl.cycle(channels.current_abs_max_tec_i()); + fan_ctrl.cycle(channels.current_abs_max_tec_i()); - if channels.pid_engaged() { - leds.g3.on(); - } else { - leds.g3.off(); - } + if channels.pid_engaged() { + leds.g3.on(); + } else { + leds.g3.off(); + } - let instant = Instant::from_millis(i64::from(timer::now())); - cortex_m::interrupt::free(net::clear_pending); - server.poll(instant) - .unwrap_or_else(|e| { + let instant = Instant::from_millis(i64::from(timer::now())); + cortex_m::interrupt::free(net::clear_pending); + server.poll(instant).unwrap_or_else(|e| { warn!("poll: {:?}", e); }); - if ! should_reset { - // TCP protocol handling - server.for_each(|mut socket, session| { - if ! socket.is_active() { - let _ = socket.listen(TCP_PORT); - session.reset(); - } else if socket.may_send() && !socket.may_recv() { - socket.close() - } else if socket.can_send() && socket.can_recv() { - match socket.recv(|buf| session.feed(buf)) { - // SessionInput::Nothing happens when the line reader parses a string of characters that is not - // followed by a newline character. Could be due to partial commands not terminated with newline, - // socket RX ring buffer wraps around, or when the command is sent as seperate TCP packets etc. - // Do nothing and feed more data to the line reader in the next loop cycle. - Ok(SessionInput::Nothing) => {} - Ok(SessionInput::Command(command)) => { - match Handler::handle_command(command, &mut socket, &mut channels, &mut store, &mut ipv4_config, &mut fan_ctrl, hwrev) { - Ok(Handler::NewIPV4(ip)) => new_ipv4_config = Some(ip), - Ok(Handler::Handled) => {}, - Ok(Handler::CloseSocket) => socket.close(), - Ok(Handler::Reset) => should_reset = true, - Err(_) => {}, + if !should_reset { + // TCP protocol handling + server.for_each(|mut socket, session| { + if !socket.is_active() { + let _ = socket.listen(TCP_PORT); + session.reset(); + } else if socket.may_send() && !socket.may_recv() { + socket.close() + } else if socket.can_send() && socket.can_recv() { + match socket.recv(|buf| session.feed(buf)) { + // SessionInput::Nothing happens when the line reader parses a string of characters that is not + // followed by a newline character. Could be due to partial commands not terminated with newline, + // socket RX ring buffer wraps around, or when the command is sent as seperate TCP packets etc. + // Do nothing and feed more data to the line reader in the next loop cycle. + Ok(SessionInput::Nothing) => {} + Ok(SessionInput::Command(command)) => { + match Handler::handle_command( + command, + &mut socket, + &mut channels, + &mut store, + &mut ipv4_config, + &mut fan_ctrl, + hwrev, + ) { + Ok(Handler::NewIPV4(ip)) => new_ipv4_config = Some(ip), + Ok(Handler::Handled) => {} + Ok(Handler::CloseSocket) => socket.close(), + Ok(Handler::Reset) => should_reset = true, + Err(_) => {} + } } + Ok(SessionInput::Error(e)) => { + error!("session input: {:?}", e); + send_line(&mut socket, b"{ \"error\": \"invalid input\" }"); + } + Err(_) => socket.close(), } - Ok(SessionInput::Error(e)) => { - error!("session input: {:?}", e); - send_line(&mut socket, b"{ \"error\": \"invalid input\" }"); - } - Err(_) => - socket.close(), } + }); + } else { + // Should reset, close all TCP sockets. + let mut any_socket_alive = false; + server.for_each(|mut socket, _| { + if socket.is_active() { + socket.abort(); + any_socket_alive = true; + } + }); + // Must let loop run for one more cycle to poll server for RST to be sent, + // this makes sure system does not reset right after socket.abort() is called. + if !any_socket_alive { + SCB::sys_reset(); } - }); - } else { - // Should reset, close all TCP sockets. - let mut any_socket_alive = false; - server.for_each(|mut socket, _| { - if socket.is_active() { - socket.abort(); - any_socket_alive = true; - } - }); - // Must let loop run for one more cycle to poll server for RST to be sent, - // this makes sure system does not reset right after socket.abort() is called. - if !any_socket_alive { - SCB::sys_reset(); - } - } + } - // Apply new IPv4 address/gateway - new_ipv4_config.take() - .map(|config| { + // Apply new IPv4 address/gateway + if let Some(config) = new_ipv4_config.take() { server.set_ipv4_config(config.clone()); ipv4_config = config; + }; + + // Update watchdog + wd.feed(); + + leds.g4.off(); + cortex_m::interrupt::free(|cs| { + if !net::is_pending(cs) { + // Wait for interrupts + // (Ethernet, SysTick, or USB) + wfi(); + } }); - - // Update watchdog - wd.feed(); - - leds.g4.off(); - cortex_m::interrupt::free(|cs| { - if !net::is_pending(cs) { - // Wait for interrupts - // (Ethernet, SysTick, or USB) - wfi(); - } - }); - leds.g4.on(); - } - }); - }); + leds.g4.on(); + } + }); + }, + ); unreachable!() } diff --git a/src/net.rs b/src/net.rs index 13ef2bf..de2bc88 100644 --- a/src/net.rs +++ b/src/net.rs @@ -1,20 +1,17 @@ //! As there is only one peripheral, supporting data structures are //! declared once and globally. -use core::cell::RefCell; -use cortex_m::interrupt::{CriticalSection, Mutex}; -use stm32f4xx_hal::{ - rcc::Clocks, - pac::{interrupt, Peripherals, ETHERNET_MAC, ETHERNET_DMA}, -}; -use smoltcp::wire::{EthernetAddress, Ipv4Address, Ipv4Cidr}; -use smoltcp::iface::{ - EthernetInterfaceBuilder, EthernetInterface, - NeighborCache, Routes, -}; -use stm32_eth::{Eth, RingEntry, RxDescriptor, TxDescriptor}; use crate::command_parser::Ipv4Config; use crate::pins::EthernetPins; +use core::cell::RefCell; +use cortex_m::interrupt::{CriticalSection, Mutex}; +use smoltcp::iface::{EthernetInterface, EthernetInterfaceBuilder, NeighborCache, Routes}; +use smoltcp::wire::{EthernetAddress, Ipv4Address, Ipv4Cidr}; +use stm32_eth::{Eth, RingEntry, RxDescriptor, TxDescriptor}; +use stm32f4xx_hal::{ + pac::{interrupt, Peripherals, ETHERNET_DMA, ETHERNET_MAC}, + rcc::Clocks, +}; /// Not on the stack so that stack can be placed in CCMRAM (which the /// ethernet peripheral cannot access) @@ -30,27 +27,27 @@ static NET_PENDING: Mutex> = Mutex::new(RefCell::new(false)); /// Run callback `f` with ethernet driver and TCP/IP stack pub fn run( clocks: Clocks, - ethernet_mac: ETHERNET_MAC, ethernet_dma: ETHERNET_DMA, + ethernet_mac: ETHERNET_MAC, + ethernet_dma: ETHERNET_DMA, eth_pins: EthernetPins, ethernet_addr: EthernetAddress, ipv4_config: Ipv4Config, - f: F + f: F, ) where F: FnOnce(EthernetInterface<&mut stm32_eth::Eth<'static, 'static>>), { - let rx_ring = unsafe { - RX_RING.get_or_insert(Default::default()) - }; - let tx_ring = unsafe { - TX_RING.get_or_insert(Default::default()) - }; + let rx_ring = unsafe { RX_RING.get_or_insert(Default::default()) }; + let tx_ring = unsafe { TX_RING.get_or_insert(Default::default()) }; // Ethernet driver let mut eth_dev = Eth::new( - ethernet_mac, ethernet_dma, - &mut rx_ring[..], &mut tx_ring[..], + ethernet_mac, + ethernet_dma, + &mut rx_ring[..], + &mut tx_ring[..], clocks, eth_pins, - ).unwrap(); + ) + .unwrap(); eth_dev.enable_interrupt(); // IP stack @@ -76,8 +73,7 @@ pub fn run( #[interrupt] fn ETH() { cortex_m::interrupt::free(|cs| { - *NET_PENDING.borrow(cs) - .borrow_mut() = true; + *NET_PENDING.borrow(cs).borrow_mut() = true; }); let p = unsafe { Peripherals::steal() }; @@ -86,15 +82,13 @@ fn ETH() { /// Has an interrupt occurred since last call to `clear_pending()`? pub fn is_pending(cs: &CriticalSection) -> bool { - *NET_PENDING.borrow(cs) - .borrow() + *NET_PENDING.borrow(cs).borrow() } /// Clear the interrupt pending flag before polling the interface for /// data. pub fn clear_pending(cs: &CriticalSection) { - *NET_PENDING.borrow(cs) - .borrow_mut() = false; + *NET_PENDING.borrow(cs).borrow_mut() = false; } /// utility for destructuring into smoltcp types diff --git a/src/pid.rs b/src/pid.rs index afc6451..e602805 100644 --- a/src/pid.rs +++ b/src/pid.rs @@ -1,4 +1,4 @@ -use serde::{Serialize, Deserialize}; +use serde::{Deserialize, Serialize}; #[derive(Clone, Debug, PartialEq, Serialize, Deserialize)] pub struct Parameters { @@ -29,38 +29,37 @@ impl Default for Parameters { #[derive(Clone)] pub struct Controller { pub parameters: Parameters, - pub target : f64, - u1 : f64, - x1 : f64, - x2 : f64, - pub y1 : f64, + pub target: f64, + u1: f64, + x1: f64, + x2: f64, + pub y1: f64, } impl Controller { pub const fn new(parameters: Parameters) -> Controller { Controller { - parameters: parameters, - target : 0.0, - u1 : 0.0, - x1 : 0.0, - x2 : 0.0, - y1 : 0.0, + parameters, + target: 0.0, + u1: 0.0, + x1: 0.0, + x2: 0.0, + y1: 0.0, } } // Based on https://hackmd.io/IACbwcOTSt6Adj3_F9bKuw PID implementation // Input x(t), target u(t), output y(t) - // y0' = y1 - ki * u0 + // y0' = y1 - ki * u0 // + x0 * (kp + ki + kd) // - x1 * (kp + 2kd) // + x2 * kd // y0 = clip(y0', ymin, ymax) pub fn update(&mut self, input: f64) -> f64 { - let mut output: f64 = self.y1 - self.target * f64::from(self.parameters.ki) - + input * f64::from(self.parameters.kp + self.parameters.ki + self.parameters.kd) - - self.x1 * f64::from(self.parameters.kp + 2.0 * self.parameters.kd) - + self.x2 * f64::from(self.parameters.kd); + + input * f64::from(self.parameters.kp + self.parameters.ki + self.parameters.kd) + - self.x1 * f64::from(self.parameters.kp + 2.0 * self.parameters.kd) + + self.x2 * f64::from(self.parameters.kd); if output < self.parameters.output_min.into() { output = self.parameters.output_min.into(); } @@ -70,7 +69,7 @@ impl Controller { self.x2 = self.x1; self.x1 = input; self.u1 = self.target; - self.y1 = output; + self.y1 = output; output } @@ -109,17 +108,17 @@ mod test { #[test] fn test_controller() { // Initial and ambient temperature - const DEFAULT: f64 = 20.0; - // Target temperature - const TARGET: f64 = 40.0; - // Control tolerance - const ERROR: f64 = 0.01; - // System response delay - const DELAY: usize = 10; + const DEFAULT: f64 = 20.0; + // Target temperature + const TARGET: f64 = 40.0; + // Control tolerance + const ERROR: f64 = 0.01; + // System response delay + const DELAY: usize = 10; // Heat lost - const LOSS: f64 = 0.05; - // Limit simulation cycle, reaching this limit before settling fails test - const CYCLE_LIMIT: u32 = 1000; + const LOSS: f64 = 0.05; + // Limit simulation cycle, reaching this limit before settling fails test + const CYCLE_LIMIT: u32 = 1000; let mut pid = Controller::new(PARAMETERS.clone()); pid.target = TARGET; diff --git a/src/pins.rs b/src/pins.rs index 3bf07fc..d5446f6 100644 --- a/src/pins.rs +++ b/src/pins.rs @@ -1,49 +1,41 @@ +use crate::{ + channel::{Channel0, Channel1}, + fan_ctrl::FanPin, + hw_rev::{HWRev, HWSettings}, + leds::Leds, +}; +use eeprom24x::{self, Eeprom24x}; +use stm32_eth::EthPins; use stm32f4xx_hal::{ adc::Adc, gpio::{ - AF5, Alternate, AlternateOD, Analog, Floating, Input, - gpioa::*, - gpiob::*, - gpioc::*, - gpioe::*, - gpiof::*, - gpiog::*, - GpioExt, - Output, PushPull, + gpioa::*, gpiob::*, gpioc::*, gpioe::*, gpiof::*, gpiog::*, Alternate, AlternateOD, Analog, + Floating, GpioExt, Input, Output, PushPull, AF5, }, hal::{self, blocking::spi::Transfer, digital::v2::OutputPin}, i2c::I2c, otg_fs::USB, - rcc::Clocks, - pwm::{self, PwmChannels}, - spi::{Spi, NoMiso, TransferModeNormal}, pac::{ - ADC1, - GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, - I2C1, - OTG_FS_GLOBAL, OTG_FS_DEVICE, OTG_FS_PWRCLK, - SPI2, SPI4, SPI5, - TIM1, TIM3, TIM8 + ADC1, GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, I2C1, OTG_FS_DEVICE, OTG_FS_GLOBAL, + OTG_FS_PWRCLK, SPI2, SPI4, SPI5, TIM1, TIM3, TIM8, }, - timer::Timer, + pwm::{self, PwmChannels}, + rcc::Clocks, + spi::{NoMiso, Spi, TransferModeNormal}, time::U32Ext, -}; -use eeprom24x::{self, Eeprom24x}; -use stm32_eth::EthPins; -use crate::{ - channel::{Channel0, Channel1}, - leds::Leds, - fan_ctrl::FanPin, - hw_rev::{HWRev, HWSettings}, + timer::Timer, }; pub type Eeprom = Eeprom24x< - I2c>, - PB9> - )>, + I2c< + I2C1, + ( + PB8>, + PB9>, + ), + >, eeprom24x::page_size::B8, - eeprom24x::addr_size::OneByte + eeprom24x::addr_size::OneByte, >; pub type EthernetPins = EthPins< @@ -54,7 +46,7 @@ pub type EthernetPins = EthPins< PB13>, PC4>, PC5>, - >; +>; pub trait ChannelPins { type DacSpi: Transfer; @@ -97,7 +89,15 @@ impl ChannelPins for Channel1 { } /// SPI peripheral used for communication with the ADC -pub type AdcSpi = Spi>, PB14>, PB15>), TransferModeNormal>; +pub type AdcSpi = Spi< + SPI2, + ( + PB10>, + PB14>, + PB15>, + ), + TransferModeNormal, +>; pub type AdcNss = PB12>; type Dac0Spi = Spi>, NoMiso, PE6>), TransferModeNormal>; type Dac1Spi = Spi>, NoMiso, PF9>), TransferModeNormal>; @@ -133,13 +133,34 @@ impl Pins { /// Setup GPIO pins and configure MCU peripherals pub fn setup( clocks: Clocks, - tim1: TIM1, tim3: TIM3, tim8: TIM8, - gpioa: GPIOA, gpiob: GPIOB, gpioc: GPIOC, gpiod: GPIOD, gpioe: GPIOE, gpiof: GPIOF, gpiog: GPIOG, + (tim1, tim3, tim8): (TIM1, TIM3, TIM8), + (gpioa, gpiob, gpioc, gpiod, gpioe, gpiof, gpiog): ( + GPIOA, + GPIOB, + GPIOC, + GPIOD, + GPIOE, + GPIOF, + GPIOG, + ), i2c1: I2C1, - spi2: SPI2, spi4: SPI4, spi5: SPI5, + (spi2, spi4, spi5): (SPI2, SPI4, SPI5), adc1: ADC1, - otg_fs_global: OTG_FS_GLOBAL, otg_fs_device: OTG_FS_DEVICE, otg_fs_pwrclk: OTG_FS_PWRCLK, - ) -> (Self, Leds, Eeprom, EthernetPins, USB, Option, HWRev, HWSettings) { + (otg_fs_global, otg_fs_device, otg_fs_pwrclk): ( + OTG_FS_GLOBAL, + OTG_FS_DEVICE, + OTG_FS_PWRCLK, + ), + ) -> ( + Self, + Leds, + Eeprom, + EthernetPins, + USB, + Option, + HWRev, + HWSettings, + ) { let gpioa = gpioa.split(); let gpiob = gpiob.split(); let gpioc = gpioc.split(); @@ -154,23 +175,29 @@ impl Pins { let pins_adc = Adc::adc1(adc1, true, Default::default()); let pwm = PwmPins::setup( - clocks, tim1, tim3, - gpioc.pc6, gpioc.pc7, - gpioe.pe9, gpioe.pe11, - gpioe.pe13, gpioe.pe14 + clocks, + (tim1, tim3), + (gpioc.pc6, gpioc.pc7), + (gpioe.pe9, gpioe.pe11), + (gpioe.pe13, gpioe.pe14), ); - let hwrev = HWRev::detect_hw_rev(&HWRevPins {hwrev0: gpiod.pd0, hwrev1: gpiod.pd1, - hwrev2: gpiod.pd2, hwrev3: gpiod.pd3}); + let hwrev = HWRev::detect_hw_rev(&HWRevPins { + hwrev0: gpiod.pd0, + hwrev1: gpiod.pd1, + hwrev2: gpiod.pd2, + hwrev3: gpiod.pd3, + }); let hw_settings = hwrev.settings(); - let (dac0_spi, dac0_sync) = Self::setup_dac0( - clocks, spi4, - gpioe.pe2, gpioe.pe4, gpioe.pe6 - ); + let (dac0_spi, dac0_sync) = Self::setup_dac0(clocks, spi4, gpioe.pe2, gpioe.pe4, gpioe.pe6); let mut shdn0 = gpioe.pe10.into_push_pull_output(); - let _ = shdn0.set_low(); - let vref0_pin = if hwrev.major > 2 {Channel0VRef::Analog(gpioa.pa0.into_analog())} else {Channel0VRef::Disabled(gpioa.pa0)}; + shdn0.set_low(); + let vref0_pin = if hwrev.major > 2 { + Channel0VRef::Analog(gpioa.pa0.into_analog()) + } else { + Channel0VRef::Disabled(gpioa.pa0) + }; let itec0_pin = gpioa.pa6.into_analog(); let dac_feedback0_pin = gpioa.pa4.into_analog(); let tec_u_meas0_pin = gpioc.pc2.into_analog(); @@ -184,13 +211,14 @@ impl Pins { tec_u_meas_pin: tec_u_meas0_pin, }; - let (dac1_spi, dac1_sync) = Self::setup_dac1( - clocks, spi5, - gpiof.pf7, gpiof.pf6, gpiof.pf9 - ); + let (dac1_spi, dac1_sync) = Self::setup_dac1(clocks, spi5, gpiof.pf7, gpiof.pf6, gpiof.pf9); let mut shdn1 = gpioe.pe15.into_push_pull_output(); - let _ = shdn1.set_low(); - let vref1_pin = if hwrev.major > 2 {Channel1VRef::Analog(gpioa.pa3.into_analog())} else {Channel1VRef::Disabled(gpioa.pa3)}; + shdn1.set_low(); + let vref1_pin = if hwrev.major > 2 { + Channel1VRef::Analog(gpioa.pa3.into_analog()) + } else { + Channel1VRef::Disabled(gpioa.pa3) + }; let itec1_pin = gpiob.pb0.into_analog(); let dac_feedback1_pin = gpioa.pa5.into_analog(); let tec_u_meas1_pin = gpioc.pc3.into_analog(); @@ -205,14 +233,19 @@ impl Pins { }; let pins = Pins { - adc_spi, adc_nss, + adc_spi, + adc_nss, pins_adc, pwm, channel0, channel1, }; - let leds = Leds::new(gpiod.pd9, gpiod.pd10.into_push_pull_output(), gpiod.pd11.into_push_pull_output()); + let leds = Leds::new( + gpiod.pd9, + gpiod.pd10.into_push_pull_output(), + gpiod.pd11.into_push_pull_output(), + ); let eeprom_scl = gpiob.pb8.into_alternate().set_open_drain(); let eeprom_sda = gpiob.pb9.into_alternate().set_open_drain(); @@ -239,8 +272,13 @@ impl Pins { }; let fan = if hw_settings.fan_available { - Some(Timer::new(tim8, &clocks).pwm(gpioc.pc9.into_alternate(), hw_settings.fan_pwm_freq_hz.hz())) - } else { None }; + Some( + Timer::new(tim8, &clocks) + .pwm(gpioc.pc9.into_alternate(), hw_settings.fan_pwm_freq_hz.hz()), + ) + } else { + None + }; (pins, leds, eeprom, eth_pins, usb, fan, hwrev, hw_settings) } @@ -252,8 +290,7 @@ impl Pins { sck: PB10, miso: PB14, mosi: PB15, - ) -> AdcSpi - { + ) -> AdcSpi { let sck = sck.into_alternate(); let miso = miso.into_alternate(); let mosi = mosi.into_alternate(); @@ -262,13 +299,16 @@ impl Pins { (sck, miso, mosi), crate::ad7172::SPI_MODE, crate::ad7172::SPI_CLOCK, - clocks + clocks, ) } fn setup_dac0( - clocks: Clocks, spi4: SPI4, - sclk: PE2, sync: PE4, sdin: PE6 + clocks: Clocks, + spi4: SPI4, + sclk: PE2, + sync: PE4, + sdin: PE6, ) -> (Dac0Spi, ::DacSync) { let sclk = sclk.into_alternate(); let sdin = sdin.into_alternate(); @@ -277,7 +317,7 @@ impl Pins { (sclk, NoMiso {}, sdin), crate::ad5680::SPI_MODE, crate::ad5680::SPI_CLOCK, - clocks + clocks, ); let sync = sync.into_push_pull_output(); @@ -285,8 +325,11 @@ impl Pins { } fn setup_dac1( - clocks: Clocks, spi5: SPI5, - sclk: PF7, sync: PF6, sdin: PF9 + clocks: Clocks, + spi5: SPI5, + sclk: PF7, + sync: PF6, + sdin: PF9, ) -> (Dac1Spi, ::DacSync) { let sclk = sclk.into_alternate(); let sdin = sdin.into_alternate(); @@ -295,7 +338,7 @@ impl Pins { (sclk, NoMiso {}, sdin), crate::ad5680::SPI_MODE, crate::ad5680::SPI_CLOCK, - clocks + clocks, ); let sync = sync.into_push_pull_output(); @@ -315,25 +358,18 @@ pub struct PwmPins { impl PwmPins { fn setup( clocks: Clocks, - tim1: TIM1, - tim3: TIM3, - max_v0: PC6, - max_v1: PC7, - max_i_pos0: PE9, - max_i_pos1: PE11, - max_i_neg0: PE13, - max_i_neg1: PE14, + (tim1, tim3): (TIM1, TIM3), + (max_v0, max_v1): (PC6, PC7), + (max_i_pos0, max_i_pos1): (PE9, PE11), + (max_i_neg0, max_i_neg1): (PE13, PE14), ) -> PwmPins { let freq = 20u32.khz(); - fn init_pwm_pin>(pin: &mut P) { + fn init_pwm_pin>(pin: &mut P) { pin.set_duty(0); pin.enable(); } - let channels = ( - max_v0.into_alternate(), - max_v1.into_alternate(), - ); + let channels = (max_v0.into_alternate(), max_v1.into_alternate()); //let (mut max_v0, mut max_v1) = pwm::tim3(tim3, channels, clocks, freq); let (mut max_v0, mut max_v1) = Timer::new(tim3, &clocks).pwm(channels, freq); init_pwm_pin(&mut max_v0); @@ -353,9 +389,12 @@ impl PwmPins { init_pwm_pin(&mut max_i_neg1); PwmPins { - max_v0, max_v1, - max_i_pos0, max_i_pos1, - max_i_neg0, max_i_neg1, + max_v0, + max_v1, + max_i_pos0, + max_i_pos1, + max_i_neg0, + max_i_neg1, } } } diff --git a/src/server.rs b/src/server.rs index 710d36f..ffb9ba8 100644 --- a/src/server.rs +++ b/src/server.rs @@ -1,25 +1,29 @@ +use crate::command_parser::Ipv4Config; +use crate::net::split_ipv4_config; use smoltcp::{ iface::EthernetInterface, - socket::{SocketSet, SocketHandle, TcpSocket, TcpSocketBuffer, SocketRef}, + socket::{SocketHandle, SocketRef, SocketSet, TcpSocket, TcpSocketBuffer}, time::Instant, wire::{IpAddress, IpCidr, Ipv4Address, Ipv4Cidr}, }; -use crate::command_parser::Ipv4Config; -use crate::net::split_ipv4_config; pub struct SocketState { handle: SocketHandle, state: S, } -impl<'a, S: Default> SocketState{ - fn new(sockets: &mut SocketSet<'a>, tcp_rx_storage: &'a mut [u8; TCP_RX_BUFFER_SIZE], tcp_tx_storage: &'a mut [u8; TCP_TX_BUFFER_SIZE]) -> SocketState { +impl<'a, S: Default> SocketState { + fn new( + sockets: &mut SocketSet<'a>, + tcp_rx_storage: &'a mut [u8; TCP_RX_BUFFER_SIZE], + tcp_tx_storage: &'a mut [u8; TCP_TX_BUFFER_SIZE], + ) -> SocketState { let tcp_rx_buffer = TcpSocketBuffer::new(&mut tcp_rx_storage[..]); let tcp_tx_buffer = TcpSocketBuffer::new(&mut tcp_tx_storage[..]); let tcp_socket = TcpSocket::new(tcp_rx_buffer, tcp_tx_buffer); SocketState:: { handle: sockets.add(tcp_socket), - state: S::default() + state: S::default(), } } } @@ -50,7 +54,7 @@ impl<'a, 'b, S: Default> Server<'a, 'b, S> { ($rx_storage:ident, $tx_storage:ident) => { let mut $rx_storage = [0; TCP_RX_BUFFER_SIZE]; let mut $tx_storage = [0; TCP_TX_BUFFER_SIZE]; - } + }; } create_rtx_storage!(tcp_rx_storage0, tcp_tx_storage0); @@ -99,15 +103,10 @@ impl<'a, 'b, S: Default> Server<'a, 'b, S> { fn set_ipv4_address(&mut self, ipv4_address: Ipv4Cidr) { self.net.update_ip_addrs(|addrs| { for addr in addrs.iter_mut() { - match addr { - IpCidr::Ipv4(_) => { - *addr = IpCidr::Ipv4(ipv4_address); - // done - break - } - _ => { - // skip - } + if let IpCidr::Ipv4(_) = addr { + *addr = IpCidr::Ipv4(ipv4_address); + // done + break; } } }); @@ -116,10 +115,9 @@ impl<'a, 'b, S: Default> Server<'a, 'b, S> { fn set_gateway(&mut self, gateway: Option) { let routes = self.net.routes_mut(); match gateway { - None => - routes.update(|routes_storage| { - routes_storage.remove(&IpCidr::new(IpAddress::v4(0, 0, 0, 0), 0)); - }), + None => routes.update(|routes_storage| { + routes_storage.remove(&IpCidr::new(IpAddress::v4(0, 0, 0, 0), 0)); + }), Some(gateway) => { routes.add_default_ipv4_route(gateway).unwrap(); } diff --git a/src/session.rs b/src/session.rs index 38b5471..0829a42 100644 --- a/src/session.rs +++ b/src/session.rs @@ -45,7 +45,8 @@ pub enum SessionInput { impl From> for SessionInput { fn from(input: Result) -> Self { - input.map(SessionInput::Command) + input + .map(SessionInput::Command) .unwrap_or_else(SessionInput::Error) } } @@ -76,12 +77,9 @@ impl Session { for (i, b) in buf.iter().enumerate() { buf_bytes = i + 1; let line = self.reader.feed(*b); - match line { - Some(line) => { - let command = Command::parse(&line); - return (buf_bytes, command.into()); - } - None => {} + if let Some(line) = line { + let command = Command::parse(line); + return (buf_bytes, command.into()); } } (buf_bytes, SessionInput::Nothing) diff --git a/src/steinhart_hart.rs b/src/steinhart_hart.rs index 87149df..667c587 100644 --- a/src/steinhart_hart.rs +++ b/src/steinhart_hart.rs @@ -1,14 +1,11 @@ use num_traits::float::Float; +use serde::{Deserialize, Serialize}; use uom::si::{ - f64::{ - ElectricalResistance, - ThermodynamicTemperature, - }, electrical_resistance::ohm, + f64::{ElectricalResistance, ThermodynamicTemperature}, ratio::ratio, thermodynamic_temperature::{degree_celsius, kelvin}, }; -use serde::{Deserialize, Serialize}; /// Steinhart-Hart equation parameters #[derive(Clone, Debug, PartialEq, Serialize, Deserialize)] diff --git a/src/timer.rs b/src/timer.rs index a9cad3d..4af0a3f 100644 --- a/src/timer.rs +++ b/src/timer.rs @@ -4,9 +4,9 @@ use cortex_m::interrupt::Mutex; use cortex_m_rt::exception; use stm32f4xx_hal::{ rcc::Clocks, - time::U32Ext, - timer::{Timer, Event as TimerEvent}, stm32::SYST, + time::U32Ext, + timer::{Event as TimerEvent, Timer}, }; /// Rate in Hz @@ -18,7 +18,6 @@ static TIMER_MS: Mutex> = Mutex::new(RefCell::new(0)); /// Setup SysTick exception pub fn setup(syst: SYST, clocks: Clocks) { - let timer = Timer::syst(syst, &clocks); let mut countdown = timer.start_count_down(TIMER_RATE.hz()); countdown.listen(TimerEvent::TimeOut); @@ -28,18 +27,13 @@ pub fn setup(syst: SYST, clocks: Clocks) { #[exception] fn SysTick() { cortex_m::interrupt::free(|cs| { - *TIMER_MS.borrow(cs) - .borrow_mut() += TIMER_DELTA; + *TIMER_MS.borrow(cs).borrow_mut() += TIMER_DELTA; }); } /// Obtain current time in milliseconds pub fn now() -> u32 { - cortex_m::interrupt::free(|cs| { - *TIMER_MS.borrow(cs) - .borrow() - .deref() - }) + cortex_m::interrupt::free(|cs| *TIMER_MS.borrow(cs).borrow().deref()) } /// block for at least `amount` milliseconds diff --git a/src/usb.rs b/src/usb.rs index 80135fb..9168731 100644 --- a/src/usb.rs +++ b/src/usb.rs @@ -1,15 +1,18 @@ -use core::{fmt::{self, Write}, mem::MaybeUninit}; +use core::{ + fmt::{self, Write}, + mem::MaybeUninit, +}; use cortex_m::interrupt::free; +use log::{Log, Metadata, Record}; use stm32f4xx_hal::{ - otg_fs::{USB, UsbBus as Bus}, + otg_fs::{UsbBus as Bus, USB}, stm32::{interrupt, Interrupt, NVIC}, }; use usb_device::{ - class_prelude::{UsbBusAllocator}, + class_prelude::UsbBusAllocator, prelude::{UsbDevice, UsbDeviceBuilder, UsbVidPid}, }; use usbd_serial::SerialPort; -use log::{Record, Log, Metadata}; static mut EP_MEMORY: [u32; 1024] = [0; 1024]; @@ -36,8 +39,8 @@ impl State { .device_class(usbd_serial::USB_CLASS_CDC) .build(); - free(|_| { - unsafe { STATE = Some(State { serial, dev }); } + free(|_| unsafe { + STATE = Some(State { serial, dev }); }); unsafe { @@ -94,8 +97,7 @@ impl Write for SerialOutput { fn write_str(&mut self, s: &str) -> core::result::Result<(), core::fmt::Error> { if let Some(ref mut state) = State::get() { for chunk in s.as_bytes().chunks(16) { - free(|_| state.serial.write(chunk)) - .map_err(|_| fmt::Error)?; + free(|_| state.serial.write(chunk)).map_err(|_| fmt::Error)?; } } Ok(())