cargo fmt

This commit is contained in:
atse 2024-01-18 16:13:55 +08:00
parent 61c8ce640e
commit 264ad3c350
26 changed files with 1110 additions and 911 deletions

View File

@ -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<SPI: Transfer<u8>, S: OutputPin> {
impl<SPI: Transfer<u8>, S: OutputPin> Dac<SPI, S> {
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<SPI: Transfer<u8>, S: OutputPin> Dac<SPI, S> {
pub fn set(&mut self, value: u32) -> Result<u32, SPI::Error> {
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)
}

View File

@ -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<SPI: Transfer<u8, Error = E>, NSS: OutputPin, E: fmt::Debug> Adc<SPI, NSS>
pub fn new(spi: SPI, mut nss: NSS) -> Result<Self, SPI::Error> {
let _ = nss.set_high();
let mut adc = Adc {
spi, nss,
spi,
nss,
checksum_mode: ChecksumMode::Off,
};
adc.reset()?;
@ -55,8 +50,7 @@ impl<SPI: Transfer<u8, Error = E>, NSS: OutputPin, E: fmt::Debug> Adc<SPI, NSS>
/// `0x00DX` for AD7172-2
pub fn identify(&mut self) -> Result<u16, SPI::Error> {
self.read_reg(&regs::Id)
.map(|id| id.id())
self.read_reg(&regs::Id).map(|id| id.id())
}
pub fn set_checksum_mode(&mut self, mode: ChecksumMode) -> Result<(), SPI::Error> {
@ -76,7 +70,10 @@ impl<SPI: Transfer<u8, Error = E>, NSS: OutputPin, E: fmt::Debug> Adc<SPI, NSS>
}
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(&regs::SetupCon { index }, |data| {
data.set_bipolar(false);
@ -106,7 +103,11 @@ impl<SPI: Transfer<u8, Error = E>, NSS: OutputPin, E: fmt::Debug> Adc<SPI, NSS>
let offset = self.read_reg(&regs::Offset { index })?.offset();
let gain = self.read_reg(&regs::Gain { index })?.gain();
let bipolar = self.read_reg(&regs::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<SPI: Transfer<u8, Error = E>, NSS: OutputPin, E: fmt::Debug> Adc<SPI, NSS>
}
pub fn get_postfilter(&mut self, index: u8) -> Result<Option<PostFilter>, SPI::Error> {
self.read_reg(&regs::FiltCon { index })
.map(|data| {
if data.enh_filt_en() {
Some(data.enh_filt())
} else {
None
}
})
self.read_reg(&regs::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<PostFilter>) -> Result<(), SPI::Error> {
self.update_reg(&regs::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<PostFilter>,
) -> Result<(), SPI::Error> {
self.update_reg(&regs::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<Option<u8>, SPI::Error> {
self.read_reg(&regs::Status)
.map(|status| {
if status.ready() {
Some(status.channel())
} else {
None
}
})
self.read_reg(&regs::Status).map(|status| {
if status.ready() {
Some(status.channel())
} else {
None
}
})
}
/// Get data
pub fn read_data(&mut self) -> Result<u32, SPI::Error> {
self.read_reg(&regs::Data)
.map(|data| data.data())
self.read_reg(&regs::Data).map(|data| data.data())
}
fn read_reg<R: regs::Register>(&mut self, reg: &R) -> Result<R::Data, SPI::Error> {
@ -175,12 +175,21 @@ impl<SPI: Transfer<u8, Error = E>, NSS: OutputPin, E: fmt::Debug> Adc<SPI, NSS>
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<R: regs::Register>(&mut self, reg: &R, reg_data: &mut R::Data) -> Result<(), SPI::Error> {
fn write_reg<R: regs::Register>(
&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 {
@ -201,7 +210,10 @@ impl<SPI: Transfer<u8, Error = E>, NSS: OutputPin, E: fmt::Debug> Adc<SPI, NSS>
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<SPI: Transfer<u8, Error = E>, NSS: OutputPin, E: fmt::Debug> Adc<SPI, NSS>
Ok(())
}
fn transfer<'w>(&mut self, addr: u8, reg_data: &'w mut [u8], checksum: Option<u8>) -> Result<Option<u8>, SPI::Error> {
fn transfer<'w>(
&mut self,
addr: u8,
reg_data: &'w mut [u8],
checksum: Option<u8>,
) -> Result<Option<u8>, SPI::Error> {
let mut addr_buf = [addr];
let _ = self.nss.set_low();
@ -234,8 +251,7 @@ impl<SPI: Transfer<u8, Error = E>, NSS: OutputPin, E: fmt::Debug> Adc<SPI, NSS>
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<SPI: Transfer<u8, Error = E>, NSS: OutputPin, E: fmt::Debug> Adc<SPI, NSS>
Err(e) => Err(e),
}
}
(Err(e), _) =>
Err(e),
(Err(e), _) => Err(e),
};
let _ = self.nss.set_high();

View File

@ -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<u8> {
match self.mode {
ChecksumMode::Off => None,
_ => Some(self.state)
_ => Some(self.state),
}
}
}

View File

@ -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-",
_ => "<INVALID>",
}.fmt(fmt)
}
.fmt(fmt)
}
}
@ -141,7 +138,8 @@ impl fmt::Display for RefSource {
Internal => "internal",
Avdd1MinusAvss => "avdd1-avss",
_ => "<INVALID>",
}.fmt(fmt)
}
.fmt(fmt)
}
}

View File

@ -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<Target=[u8]> + DerefMut {
pub trait RegisterData: Clone + Deref<Target = [u8]> + 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) {

View File

@ -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<C: ChannelPins> Channel<C> {
Channel {
state,
dac, vref_meas,
dac,
vref_meas,
shdn: pins.shdn,
vref_pin: pins.vref_pin,
itec_pin: pins.itec_pin,

View File

@ -1,22 +1,12 @@
use crate::{ad7172, command_parser::CenterPoint, pid, steinhart_hart as sh};
use smoltcp::time::{Duration, Instant};
use uom::si::{
f64::{
ElectricPotential,
ElectricalResistance,
ThermodynamicTemperature,
Time,
},
electric_potential::volt,
electrical_resistance::ohm,
f64::{ElectricPotential, ElectricalResistance, ThermodynamicTemperature, Time},
thermodynamic_temperature::degree_celsius,
time::millisecond,
};
use crate::{
ad7172,
pid,
steinhart_hart as sh,
command_parser::CenterPoint,
};
const R_INNER: f64 = 2.0 * 5100.0;
const VREF_SENS: f64 = 3.3 / 2.0;
@ -63,8 +53,7 @@ impl ChannelState {
/// Update PID state on ADC input, calculate new DAC output
pub fn update_pid(&mut self) -> Option<f64> {
let temperature = self.get_temperature()?
.get::<degree_celsius>();
let temperature = self.get_temperature()?.get::<degree_celsius>();
let pid_output = self.pid.update(temperature);
Some(pid_output)
}

View File

@ -1,26 +1,24 @@
use crate::{
ad5680, ad7172,
channel::{Channel, Channel0, Channel1},
channel_state::ChannelState,
command_handler::JsonBuffer,
command_parser::{CenterPoint, PwmPin},
pins, steinhart_hart,
};
use core::cmp::max_by;
use heapless::{consts::U2, Vec};
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},
command_handler::JsonBuffer,
pins,
steinhart_hart,
};
pub const CHANNELS: usize = 2;
const R_SENSE: f64 = 0.05;
@ -44,19 +42,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::<ampere>(0.0));
@ -97,10 +101,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.read_vref(channel),
CenterPoint::Override(center_point) =>
ElectricPotential::new::<volt>(center_point.into()),
CenterPoint::Vref => self.read_vref(channel),
CenterPoint::Override(center_point) => {
ElectricPotential::new::<volt>(center_point.into())
}
}
}
@ -120,7 +124,8 @@ impl Channels {
/// i_set DAC
fn set_dac(&mut self, channel: usize, voltage: ElectricPotential) -> ElectricPotential {
let value = ((voltage / ElectricPotential::new::<volt>(DAC_OUT_V_MAX)).get::<ratio>() * (ad5680::MAX_VALUE as f64)) as u32 ;
let value = ((voltage / ElectricPotential::new::<volt>(DAC_OUT_V_MAX)).get::<ratio>()
* (ad5680::MAX_VALUE as f64)) as u32;
match channel {
0 => self.channel0.dac.set(value).unwrap(),
1 => self.channel1.dac.set(value).unwrap(),
@ -149,7 +154,7 @@ impl Channels {
0 => {
let sample = self.pins_adc.convert(
&self.channel0.dac_feedback_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
);
let mv = self.pins_adc.sample_to_millivolts(sample);
ElectricPotential::new::<millivolt>(mv as f64)
@ -157,7 +162,7 @@ impl Channels {
1 => {
let sample = self.pins_adc.convert(
&self.channel1.dac_feedback_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
);
let mv = self.pins_adc.sample_to_millivolts(sample);
ElectricPotential::new::<millivolt>(mv as f64)
@ -166,7 +171,11 @@ impl Channels {
}
}
pub fn read_dac_feedback_until_stable(&mut self, channel: usize, tolerance: ElectricPotential) -> ElectricPotential {
pub fn read_dac_feedback_until_stable(
&mut self,
channel: usize,
tolerance: ElectricPotential,
) -> ElectricPotential {
let mut prev = self.read_dac_feedback(channel);
loop {
let current = self.read_dac_feedback(channel);
@ -182,7 +191,7 @@ impl Channels {
0 => {
let sample = self.pins_adc.convert(
&self.channel0.itec_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
);
let mv = self.pins_adc.sample_to_millivolts(sample);
ElectricPotential::new::<millivolt>(mv as f64)
@ -190,7 +199,7 @@ impl Channels {
1 => {
let sample = self.pins_adc.convert(
&self.channel1.itec_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
);
let mv = self.pins_adc.sample_to_millivolts(sample);
ElectricPotential::new::<millivolt>(mv as f64)
@ -205,7 +214,7 @@ impl Channels {
0 => {
let sample = self.pins_adc.convert(
&self.channel0.vref_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
);
let mv = self.pins_adc.sample_to_millivolts(sample);
ElectricPotential::new::<millivolt>(mv as f64)
@ -213,7 +222,7 @@ impl Channels {
1 => {
let sample = self.pins_adc.convert(
&self.channel1.vref_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
);
let mv = self.pins_adc.sample_to_millivolts(sample);
ElectricPotential::new::<millivolt>(mv as f64)
@ -227,7 +236,7 @@ impl Channels {
0 => {
let sample = self.pins_adc.convert(
&self.channel0.tec_u_meas_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
);
let mv = self.pins_adc.sample_to_millivolts(sample);
ElectricPotential::new::<millivolt>(mv as f64)
@ -235,7 +244,7 @@ impl Channels {
1 => {
let sample = self.pins_adc.convert(
&self.channel1.tec_u_meas_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
);
let mv = self.pins_adc.sample_to_millivolts(sample);
ElectricPotential::new::<millivolt>(mv as f64)
@ -248,18 +257,18 @@ 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::<volt>(0.0);
@ -283,7 +292,8 @@ impl Channels {
_ => unreachable!(),
}
let dac_feedback = self.read_dac_feedback_until_stable(channel, ElectricPotential::new::<volt>(0.001));
let dac_feedback = self
.read_dac_feedback_until_stable(channel, ElectricPotential::new::<volt>(0.001));
let error = target_voltage - dac_feedback;
if error < ElectricPotential::new::<volt>(0.0) {
break;
@ -291,7 +301,8 @@ impl Channels {
best_error = error;
start_value = prev_value;
let vref = (value as f64 / ad5680::MAX_VALUE as f64) * ElectricPotential::new::<volt>(DAC_OUT_V_MAX);
let vref = (value as f64 / ad5680::MAX_VALUE as f64)
* ElectricPotential::new::<volt>(DAC_OUT_V_MAX);
match channel {
0 => self.channel0.vref_meas = vref,
1 => self.channel1.vref_meas = vref,
@ -326,28 +337,20 @@ impl Channels {
}
fn get_pwm(&self, channel: usize, pin: PwmPin) -> f64 {
fn get<P: hal::PwmPin<Duty=u16>>(pin: &P) -> f64 {
fn get<P: hal::PwmPin<Duty = u16>>(pin: &P) -> f64 {
let duty = pin.get_duty();
let max = pin.get_max_duty();
duty as f64 / (max as f64)
}
match (channel, pin) {
(_, PwmPin::ISet) =>
panic!("i_set is no pwm pin"),
(0, PwmPin::MaxIPos) =>
get(&self.pwm.max_i_pos0),
(0, PwmPin::MaxINeg) =>
get(&self.pwm.max_i_neg0),
(0, PwmPin::MaxV) =>
get(&self.pwm.max_v0),
(1, PwmPin::MaxIPos) =>
get(&self.pwm.max_i_pos1),
(1, PwmPin::MaxINeg) =>
get(&self.pwm.max_i_neg1),
(1, PwmPin::MaxV) =>
get(&self.pwm.max_v1),
_ =>
unreachable!(),
(_, PwmPin::ISet) => panic!("i_set is no pwm pin"),
(0, PwmPin::MaxIPos) => get(&self.pwm.max_i_pos0),
(0, PwmPin::MaxINeg) => get(&self.pwm.max_i_neg0),
(0, PwmPin::MaxV) => get(&self.pwm.max_v0),
(1, PwmPin::MaxIPos) => get(&self.pwm.max_i_pos1),
(1, PwmPin::MaxINeg) => get(&self.pwm.max_i_neg1),
(1, PwmPin::MaxV) => get(&self.pwm.max_v1),
_ => unreachable!(),
}
}
@ -380,47 +383,51 @@ impl Channels {
}
fn set_pwm(&mut self, channel: usize, pin: PwmPin, duty: f64) -> f64 {
fn set<P: hal::PwmPin<Duty=u16>>(pin: &mut P, duty: f64) -> f64 {
fn set<P: hal::PwmPin<Duty = u16>>(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::<volt>(3.3);
let duty = (max_v / max).get::<ratio>();
let duty = self.set_pwm(channel, PwmPin::MaxV, duty);
(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::<ampere>(3.0);
let duty = (max_i_pos / max).get::<ratio>();
let duty = self.set_pwm(channel, PwmPin::MaxIPos, duty);
(duty * max, 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::<ampere>(3.0);
let duty = (max_i_neg / max).get::<ratio>();
let duty = self.set_pwm(channel, PwmPin::MaxINeg, duty);
@ -440,7 +447,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::<degree_celsius>()),
pid_engaged: state.pid_engaged,
i_set,
@ -498,7 +506,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 }
}
@ -516,7 +527,9 @@ impl Channels {
SteinhartHartSummary { channel, params }
}
pub fn steinhart_hart_summaries_json(&mut self) -> Result<JsonBuffer, serde_json_core::ser::Error> {
pub fn steinhart_hart_summaries_json(
&mut self,
) -> Result<JsonBuffer, serde_json_core::ser::Error> {
let mut summaries = Vec::<_, U2>::new();
for channel in 0..CHANNELS {
let _ = summaries.push(self.steinhart_hart_summary(channel));
@ -525,9 +538,11 @@ impl Channels {
}
pub fn current_abs_max_tec_i(&mut self) -> f64 {
max_by(self.get_tec_i(0).abs().get::<ampere>(),
self.get_tec_i(1).abs().get::<ampere>(),
|a, b| a.partial_cmp(b).unwrap_or(core::cmp::Ordering::Equal))
max_by(
self.get_tec_i(0).abs().get::<ampere>(),
self.get_tec_i(1).abs().get::<ampere>(),
|a, b| a.partial_cmp(b).unwrap_or(core::cmp::Ordering::Equal),
)
}
}
@ -558,10 +573,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),
}
}
}

View File

@ -1,45 +1,28 @@
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
},
ad7172,
CHANNEL_CONFIG_KEY,
channels::{
Channels,
CHANNELS
channels::{Channels, CHANNELS},
command_parser::{
CenterPoint, Command, Ipv4Config, PidParameter, PwmPin, ShParameter, ShowCommand,
},
config::ChannelConfig,
dfu,
flash_store::FlashStore,
session::Session,
FanCtrl,
hw_rev::HWRev,
net,
session::Session,
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)]
@ -54,7 +37,7 @@ pub enum Handler {
pub enum Error {
ReportError,
PostFilterRateError,
FlashError
FlashError,
}
pub type JsonBuffer = Vec<u8, U1024>;
@ -66,19 +49,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) {
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 +69,6 @@ fn send_line(socket: &mut TcpSocket, data: &[u8]) -> bool {
}
impl Handler {
fn reporting(socket: &mut TcpSocket) -> Result<Handler, Error> {
send_line(socket, b"{}");
Ok(Handler::Handled)
@ -139,7 +121,10 @@ impl Handler {
Ok(Handler::Handled)
}
fn show_steinhart_hart(socket: &mut TcpSocket, channels: &mut Channels) -> Result<Handler, Error> {
fn show_steinhart_hart(
socket: &mut TcpSocket,
channels: &mut Channels,
) -> Result<Handler, Error> {
match channels.steinhart_hart_summaries_json() {
Ok(buf) => {
send_line(socket, &buf);
@ -153,7 +138,7 @@ impl Handler {
Ok(Handler::Handled)
}
fn show_post_filter (socket: &mut TcpSocket, channels: &mut Channels) -> Result<Handler, Error> {
fn show_post_filter(socket: &mut TcpSocket, channels: &mut Channels) -> Result<Handler, Error> {
match channels.postfilter_summaries_json() {
Ok(buf) => {
send_line(socket, &buf);
@ -167,7 +152,7 @@ impl Handler {
Ok(Handler::Handled)
}
fn show_ipv4 (socket: &mut TcpSocket, ipv4_config: &mut Ipv4Config) -> Result<Handler, Error> {
fn show_ipv4(socket: &mut TcpSocket, ipv4_config: &mut Ipv4Config) -> Result<Handler, Error> {
let (cidr, gateway) = net::split_ipv4_config(ipv4_config.clone());
let _ = write!(socket, "{{\"addr\":\"{}\"", cidr);
gateway.map(|gateway| write!(socket, ",\"gateway\":\"{}\"", gateway));
@ -175,13 +160,23 @@ impl Handler {
Ok(Handler::Handled)
}
fn engage_pid (socket: &mut TcpSocket, channels: &mut Channels, channel: usize) -> Result<Handler, Error> {
fn engage_pid(
socket: &mut TcpSocket,
channels: &mut Channels,
channel: usize,
) -> Result<Handler, Error> {
channels.channel_state(channel).pid_engaged = true;
send_line(socket, b"{}");
Ok(Handler::Handled)
}
fn set_pwm (socket: &mut TcpSocket, channels: &mut Channels, channel: usize, pin: PwmPin, value: f64) -> Result<Handler, Error> {
fn set_pwm(
socket: &mut TcpSocket,
channels: &mut Channels,
channel: usize,
pin: PwmPin,
value: f64,
) -> Result<Handler, Error> {
match pin {
PwmPin::ISet => {
channels.channel_state(channel).pid_engaged = false;
@ -206,7 +201,12 @@ impl Handler {
Ok(Handler::Handled)
}
fn set_center_point(socket: &mut TcpSocket, channels: &mut Channels, channel: usize, center: CenterPoint) -> Result<Handler, Error> {
fn set_center_point(
socket: &mut TcpSocket,
channels: &mut Channels,
channel: usize,
center: CenterPoint,
) -> Result<Handler, Error> {
let i_tec = channels.get_i(channel);
let state = channels.channel_state(channel);
state.center = center;
@ -217,28 +217,34 @@ impl Handler {
Ok(Handler::Handled)
}
fn set_pid (socket: &mut TcpSocket, channels: &mut Channels, channel: usize, parameter: PidParameter, value: f64) -> Result<Handler, Error> {
fn set_pid(
socket: &mut TcpSocket,
channels: &mut Channels,
channel: usize,
parameter: PidParameter,
value: f64,
) -> Result<Handler, Error> {
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<Handler, Error> {
fn set_steinhart_hart(
socket: &mut TcpSocket,
channels: &mut Channels,
channel: usize,
parameter: ShParameter,
value: f64,
) -> Result<Handler, Error> {
let sh = &mut channels.channel_state(channel).sh;
use super::command_parser::ShParameter::*;
match parameter {
@ -250,29 +256,49 @@ impl Handler {
Ok(Handler::Handled)
}
fn reset_post_filter (socket: &mut TcpSocket, channels: &mut Channels, channel: usize) -> Result<Handler, Error> {
fn reset_post_filter(
socket: &mut TcpSocket,
channels: &mut Channels,
channel: usize,
) -> Result<Handler, Error> {
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<Handler, Error> {
fn set_post_filter(
socket: &mut TcpSocket,
channels: &mut Channels,
channel: usize,
rate: f32,
) -> Result<Handler, Error> {
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\"}}");
send_line(
socket,
b"{{\"error\": \"unable to choose postfilter rate\"}}",
);
return Err(Error::PostFilterRateError);
}
}
Ok(Handler::Handled)
}
fn load_channel (socket: &mut TcpSocket, channels: &mut Channels, store: &mut FlashStore, channel: Option<usize>) -> Result<Handler, Error> {
fn load_channel(
socket: &mut TcpSocket,
channels: &mut Channels,
store: &mut FlashStore,
channel: Option<usize>,
) -> Result<Handler, Error> {
for c in 0..CHANNELS {
if channel.is_none() || channel == Some(c) {
match store.read_value::<ChannelConfig>(CHANNEL_CONFIG_KEY[c]) {
@ -295,7 +321,12 @@ impl Handler {
Ok(Handler::Handled)
}
fn save_channel (socket: &mut TcpSocket, channels: &mut Channels, channel: Option<usize>, store: &mut FlashStore) -> Result<Handler, Error> {
fn save_channel(
socket: &mut TcpSocket,
channels: &mut Channels,
channel: Option<usize>,
store: &mut FlashStore,
) -> Result<Handler, Error> {
for c in 0..CHANNELS {
let mut store_value_buf = [0u8; 256];
if channel.is_none() || channel == Some(c) {
@ -315,7 +346,11 @@ impl Handler {
Ok(Handler::Handled)
}
fn set_ipv4 (socket: &mut TcpSocket, store: &mut FlashStore, config: Ipv4Config) -> Result<Handler, Error> {
fn set_ipv4(
socket: &mut TcpSocket,
store: &mut FlashStore,
config: Ipv4Config,
) -> Result<Handler, Error> {
let _ = store
.write_value("ipv4", &config, [0; 16])
.map_err(|e| error!("unable to save ipv4 config to flash: {:?}", e));
@ -324,7 +359,7 @@ impl Handler {
Ok(Handler::NewIPV4(new_ipv4_config.unwrap()))
}
fn reset (channels: &mut Channels) -> Result<Handler, Error> {
fn reset(channels: &mut Channels) -> Result<Handler, Error> {
for i in 0..CHANNELS {
channels.power_down(i);
}
@ -332,7 +367,7 @@ impl Handler {
Ok(Handler::Reset)
}
fn dfu (channels: &mut Channels) -> Result<Handler, Error> {
fn dfu(channels: &mut Channels) -> Result<Handler, Error> {
for i in 0..CHANNELS {
channels.power_down(i);
}
@ -343,9 +378,16 @@ impl Handler {
Ok(Handler::Reset)
}
fn set_fan(socket: &mut TcpSocket, fan_pwm: u32, fan_ctrl: &mut FanCtrl) -> Result<Handler, Error> {
fn set_fan(
socket: &mut TcpSocket,
fan_pwm: u32,
fan_ctrl: &mut FanCtrl,
) -> Result<Handler, Error> {
if !fan_ctrl.fan_available() {
send_line(socket, b"{ \"warning\": \"this thermostat doesn't have fan!\" }");
send_line(
socket,
b"{ \"warning\": \"this thermostat doesn't have fan!\" }",
);
return Ok(Handler::Handled);
}
fan_ctrl.set_auto_mode(false);
@ -374,7 +416,10 @@ impl Handler {
fn fan_auto(socket: &mut TcpSocket, fan_ctrl: &mut FanCtrl) -> Result<Handler, Error> {
if !fan_ctrl.fan_available() {
send_line(socket, b"{ \"warning\": \"this thermostat doesn't have fan!\" }");
send_line(
socket,
b"{ \"warning\": \"this thermostat doesn't have fan!\" }",
);
return Ok(Handler::Handled);
}
fan_ctrl.set_auto_mode(true);
@ -386,7 +431,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<Handler, Error> {
fn fan_curve(
socket: &mut TcpSocket,
fan_ctrl: &mut FanCtrl,
k_a: f32,
k_b: f32,
k_c: f32,
) -> Result<Handler, Error> {
fan_ctrl.set_curve(k_a, k_b, k_c);
send_line(socket, b"{}");
Ok(Handler::Handled)
@ -412,35 +463,68 @@ impl Handler {
}
}
pub fn handle_command(command: Command, socket: &mut TcpSocket, channels: &mut Channels, session: &Session, store: &mut FlashStore, ipv4_config: &mut Ipv4Config, fan_ctrl: &mut FanCtrl, hwrev: HWRev) -> Result<Self, Error> {
pub fn handle_command(
command: Command,
socket: &mut TcpSocket,
channels: &mut Channels,
session: &Session,
store: &mut FlashStore,
ipv4_config: &mut Ipv4Config,
fan_ctrl: &mut FanCtrl,
hwrev: HWRev,
) -> Result<Self, Error> {
match command {
Command::Quit => Ok(Handler::CloseSocket),
Command::Reporting(_reporting) => Handler::reporting(socket),
Command::Show(ShowCommand::Reporting) => Handler::show_report_mode(socket, session),
Command::Reporting(_reporting) => Handler::reporting(socket),
Command::Show(ShowCommand::Reporting) => Handler::show_report_mode(socket, session),
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::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::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),
}
}
}
}

View File

@ -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<nom::Err<(&'t [u8], ErrorKind)>> 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<ParseFloatError> 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),
}
}
}
@ -180,7 +175,7 @@ pub enum Command {
},
Dfu,
FanSet {
fan_pwm: u32
fan_pwm: u32,
},
FanAuto,
ShowFan,
@ -194,12 +189,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], ()> {
@ -207,36 +197,27 @@ fn whitespace(input: &[u8]) -> IResult<&[u8], ()> {
}
fn unsigned(input: &[u8]) -> IResult<&[u8], Result<u32, Error>> {
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| u32::from_str_radix(digits, 10).map_err(|e| e.into()));
(input, result)
})
}
fn float(input: &[u8]) -> IResult<&[u8], Result<f64, Error>> {
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 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))
}
fn off_on(input: &[u8]) -> IResult<&[u8], bool> {
alt((value(false, tag("off")),
value(true, tag("on"))
))(input)
alt((value(false, tag("off")), value(true, tag("on"))))(input)
}
fn channel(input: &[u8]) -> IResult<&[u8], usize> {
@ -255,65 +236,41 @@ fn report(input: &[u8]) -> IResult<&[u8], Command> {
preceded(
whitespace,
// `report mode <on | off>` - Switch repoting mode
map(off_on, Command::Reporting)
map(off_on, Command::Reporting),
),
// `report mode` - Show current reporting state
value(Command::Show(ShowCommand::Reporting), end)
))
)),
value(Command::Show(ShowCommand::Reporting), end),
)),
),
),
// `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<f64, Error>|
result.map(|value| (pin, value));
let result_with_pin =
|pin: PwmPin| move |result: Result<f64, Error>| 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
@ -336,17 +293,22 @@ fn pwm(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
|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)
}
@ -355,36 +317,39 @@ fn center_point(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
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> <parameter> <value>`
fn pid_parameter(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
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))
}
@ -392,11 +357,8 @@ fn pid_parameter(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
fn pid(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
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)
}
@ -404,15 +366,18 @@ fn pid(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
fn steinhart_hart_parameter(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
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))
}
@ -420,42 +385,38 @@ fn steinhart_hart_parameter(input: &[u8]) -> IResult<&[u8], Result<Command, Erro
fn steinhart_hart(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
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<Command, Error>> {
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)
}
@ -468,7 +429,7 @@ fn load(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
let (input, _) = end(input)?;
Ok((input, Some(channel)))
},
value(None, end)
value(None, end),
))(input)?;
let result = Ok(Command::Load { channel });
@ -484,7 +445,7 @@ fn save(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
let (input, _) = end(input)?;
Ok((input, Some(channel)))
},
value(None, end)
value(None, end),
))(input)?;
let result = Ok(Command::Save { channel });
@ -546,12 +507,17 @@ fn fan(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
},
|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)
}
@ -572,7 +538,14 @@ fn fan_curve(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
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 })))
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,
}),
))
} else {
Err(nom::Err::Incomplete(Needed::Size(3)))
}
@ -580,38 +553,36 @@ fn fan_curve(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
))(input)?;
Ok((input, result))
},
value(Err(Error::Incomplete), end)
value(Err(Error::Incomplete), end),
))(input)
}
fn command(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
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<Self, Error> {
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.len() == 0 => result,
Ok((input_remain, _)) => Err(Error::UnexpectedInput(input_remain[0])),
Err(e) => Err(e.into()),
}
}
}
@ -659,21 +630,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]
@ -703,49 +680,59 @@ 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_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]
@ -757,11 +744,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]
@ -773,11 +763,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]
@ -789,37 +782,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]
@ -831,7 +836,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]
@ -843,11 +848,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]

View File

@ -1,15 +1,11 @@
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,
pid,
steinhart_hart,
ad7172::PostFilter, channels::Channels, command_parser::CenterPoint, pid, steinhart_hart,
};
use serde::{Deserialize, Serialize};
use uom::si::{
electric_current::ampere,
electric_potential::volt,
f64::{ElectricCurrent, ElectricPotential},
};
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
@ -28,7 +24,9 @@ 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);

View File

@ -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",

View File

@ -1,14 +1,11 @@
use num_traits::Float;
use serde::Serialize;
use stm32f4xx_hal::{
pwm::{self, PwmChannels},
pac::TIM8,
pwm::{self, PwmChannels},
};
use crate::{
hw_rev::HWSettings,
command_handler::JsonBuffer,
};
use crate::{command_handler::JsonBuffer, hw_rev::HWSettings};
pub type FanPin = PwmChannels<TIM8, pwm::C4>;
@ -18,7 +15,6 @@ const MAX_TEC_I: f32 = 3.0;
const MAX_USER_FAN_PWM: f32 = 100.0;
const MIN_USER_FAN_PWM: f32 = 1.0;
pub struct FanCtrl {
fan: Option<FanPin>,
fan_auto: bool,
@ -55,7 +51,9 @@ impl FanCtrl {
if self.fan_auto && self.hw_settings.fan_available {
let scaled_current = self.abs_max_tec_i / MAX_TEC_I;
// 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);
}
}
@ -88,18 +86,28 @@ 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
.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 max = fan.get_max_duty();
let value = ((duty * (max as f32)) as u16).min(max);
fan.set_duty(value);
@ -118,8 +126,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 {
@ -135,7 +152,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
}

View File

@ -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));
}
}

View File

@ -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<JsonBuffer, serde_json_core::ser::Error> {
let settings = self.settings();
let summary = HWSummary { rev: self, settings: &settings };
let summary = HWSummary {
rev: self,
settings: &settings,
};
serde_json_core::to_vec(&summary)
}
}
}

View File

@ -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<Logger<InterruptOk<HStdout>>> = 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");
}

View File

@ -1,6 +1,6 @@
use stm32f4xx_hal::{
gpio::{
gpiod::{PD9, PD10, PD11},
gpiod::{PD10, PD11, PD9},
Output, PushPull,
},
hal::digital::v2::OutputPin,

View File

@ -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) {
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,10 +118,21 @@ 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,
@ -141,12 +150,9 @@ fn main() -> ! {
let mut channels = Channels::new(pins);
for c in 0..CHANNELS {
match store.read_value::<ChannelConfig>(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),
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 +165,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,118 +176,131 @@ 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::<Session>::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::<Session>::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()));
let updated_channel = channels.poll_adc(instant);
if let Some(channel) = updated_channel {
server.for_each(|_, session| session.set_report_pending(channel.into()));
}
loop {
let mut new_ipv4_config = None;
let instant = Instant::from_millis(i64::from(timer::now()));
let updated_channel = channels.poll_adc(instant);
if let Some(channel) = updated_channel {
server.for_each(|_, session| session.set_report_pending(channel.into()));
}
fan_ctrl.cycle(channels.current_abs_max_tec_i() as f32);
fan_ctrl.cycle(channels.current_abs_max_tec_i() as f32);
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, session, &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,
session,
&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(),
}
} else if socket.can_send() {
if let Some(channel) = session.is_report_pending() {
match channels.reports_json() {
Ok(buf) => {
send_line(&mut socket, &buf[..]);
session.mark_report_sent(channel);
Ok(SessionInput::Error(e)) => {
error!("session input: {:?}", e);
send_line(&mut socket, b"{ \"error\": \"invalid input\" }");
}
Err(e) => {
error!("unable to serialize report: {:?}", e);
Err(_) => socket.close(),
}
} else if socket.can_send() {
if let Some(channel) = session.is_report_pending() {
match channels.reports_json() {
Ok(buf) => {
send_line(&mut socket, &buf[..]);
session.mark_report_sent(channel);
}
Err(e) => {
error!("unable to serialize report: {:?}", e);
}
}
}
}
});
} 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
new_ipv4_config.take().map(|config| {
server.set_ipv4_config(config.clone());
ipv4_config = config;
});
// Update watchdog
wd.feed();
// 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.off();
cortex_m::interrupt::free(|cs| {
if !net::is_pending(cs) {
// Wait for interrupts
// (Ethernet, SysTick, or USB)
wfi();
}
});
leds.g4.on();
}
});
},
);
unreachable!()
}

View File

@ -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<RefCell<bool>> = Mutex::new(RefCell::new(false));
/// Run callback `f` with ethernet driver and TCP/IP stack
pub fn run<F>(
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<F>(
#[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

View File

@ -1,4 +1,4 @@
use serde::{Serialize, Deserialize};
use serde::{Deserialize, Serialize};
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
pub struct Parameters {
@ -29,40 +29,39 @@ 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,
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
// + kp * (u0 - u1)
// 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)
+ f64::from(self.parameters.kp) * (self.target - self.u1);
+ 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)
+ f64::from(self.parameters.kp) * (self.target - self.u1);
if output < self.parameters.output_min.into() {
output = self.parameters.output_min.into();
}
@ -72,7 +71,7 @@ impl Controller {
self.x2 = self.x1;
self.x1 = input;
self.u1 = self.target;
self.y1 = output;
self.y1 = output;
output
}
@ -111,17 +110,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;

View File

@ -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<I2C1, (
PB8<AlternateOD<{ stm32f4xx_hal::gpio::AF4 }>>,
PB9<AlternateOD<{ stm32f4xx_hal::gpio::AF4 }>>
)>,
I2c<
I2C1,
(
PB8<AlternateOD<{ stm32f4xx_hal::gpio::AF4 }>>,
PB9<AlternateOD<{ stm32f4xx_hal::gpio::AF4 }>>,
),
>,
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<Input<Floating>>,
PC4<Input<Floating>>,
PC5<Input<Floating>>,
>;
>;
pub trait ChannelPins {
type DacSpi: Transfer<u8>;
@ -87,7 +79,15 @@ impl ChannelPins for Channel1 {
}
/// SPI peripheral used for communication with the ADC
pub type AdcSpi = Spi<SPI2, (PB10<Alternate<AF5>>, PB14<Alternate<AF5>>, PB15<Alternate<AF5>>), TransferModeNormal>;
pub type AdcSpi = Spi<
SPI2,
(
PB10<Alternate<AF5>>,
PB14<Alternate<AF5>>,
PB15<Alternate<AF5>>,
),
TransferModeNormal,
>;
pub type AdcNss = PB12<Output<PushPull>>;
type Dac0Spi = Spi<SPI4, (PE2<Alternate<AF5>>, NoMiso, PE6<Alternate<AF5>>), TransferModeNormal>;
type Dac1Spi = Spi<SPI5, (PF7<Alternate<AF5>>, NoMiso, PF9<Alternate<AF5>>), TransferModeNormal>;
@ -123,13 +123,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: TIM1,
tim3: TIM3,
tim8: TIM8,
gpioa: GPIOA,
gpiob: GPIOB,
gpioc: GPIOC,
gpiod: GPIOD,
gpioe: GPIOE,
gpiof: GPIOF,
gpiog: GPIOG,
i2c1: I2C1,
spi2: SPI2, spi4: SPI4, spi5: SPI5,
spi2: SPI2,
spi4: SPI4,
spi5: 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<FanPin>, HWRev, HWSettings) {
otg_fs_global: OTG_FS_GLOBAL,
otg_fs_device: OTG_FS_DEVICE,
otg_fs_pwrclk: OTG_FS_PWRCLK,
) -> (
Self,
Leds,
Eeprom,
EthernetPins,
USB,
Option<FanPin>,
HWRev,
HWSettings,
) {
let gpioa = gpioa.split();
let gpiob = gpiob.split();
let gpioc = gpioc.split();
@ -144,16 +165,10 @@ 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 (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 = gpioa.pa0.into_analog();
@ -170,10 +185,7 @@ 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 = gpioa.pa3.into_analog();
@ -191,18 +203,27 @@ impl Pins {
};
let pins = Pins {
adc_spi, adc_nss,
adc_spi,
adc_nss,
pins_adc,
pwm,
channel0,
channel1,
};
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 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();
@ -229,8 +250,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)
}
@ -242,8 +268,7 @@ impl Pins {
sck: PB10<M1>,
miso: PB14<M2>,
mosi: PB15<M3>,
) -> AdcSpi
{
) -> AdcSpi {
let sck = sck.into_alternate();
let miso = miso.into_alternate();
let mosi = mosi.into_alternate();
@ -252,13 +277,16 @@ impl Pins {
(sck, miso, mosi),
crate::ad7172::SPI_MODE,
crate::ad7172::SPI_CLOCK,
clocks
clocks,
)
}
fn setup_dac0<M1, M2, M3>(
clocks: Clocks, spi4: SPI4,
sclk: PE2<M1>, sync: PE4<M2>, sdin: PE6<M3>
clocks: Clocks,
spi4: SPI4,
sclk: PE2<M1>,
sync: PE4<M2>,
sdin: PE6<M3>,
) -> (Dac0Spi, <Channel0 as ChannelPins>::DacSync) {
let sclk = sclk.into_alternate();
let sdin = sdin.into_alternate();
@ -267,7 +295,7 @@ impl Pins {
(sclk, NoMiso {}, sdin),
crate::ad5680::SPI_MODE,
crate::ad5680::SPI_CLOCK,
clocks
clocks,
);
let sync = sync.into_push_pull_output();
@ -275,8 +303,11 @@ impl Pins {
}
fn setup_dac1<M1, M2, M3>(
clocks: Clocks, spi5: SPI5,
sclk: PF7<M1>, sync: PF6<M2>, sdin: PF9<M3>
clocks: Clocks,
spi5: SPI5,
sclk: PF7<M1>,
sync: PF6<M2>,
sdin: PF9<M3>,
) -> (Dac1Spi, <Channel1 as ChannelPins>::DacSync) {
let sclk = sclk.into_alternate();
let sdin = sdin.into_alternate();
@ -285,7 +316,7 @@ impl Pins {
(sclk, NoMiso {}, sdin),
crate::ad5680::SPI_MODE,
crate::ad5680::SPI_CLOCK,
clocks
clocks,
);
let sync = sync.into_push_pull_output();
@ -316,14 +347,11 @@ impl PwmPins {
) -> PwmPins {
let freq = 20u32.khz();
fn init_pwm_pin<P: hal::PwmPin<Duty=u16>>(pin: &mut P) {
fn init_pwm_pin<P: hal::PwmPin<Duty = u16>>(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);
@ -343,9 +371,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,
}
}
}

View File

@ -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<S> {
handle: SocketHandle,
state: S,
}
impl<'a, S: Default> SocketState<S>{
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<S> {
impl<'a, S: Default> SocketState<S> {
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<S> {
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::<S> {
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);
@ -103,7 +107,7 @@ impl<'a, 'b, S: Default> Server<'a, 'b, S> {
IpCidr::Ipv4(_) => {
*addr = IpCidr::Ipv4(ipv4_address);
// done
break
break;
}
_ => {
// skip
@ -116,10 +120,9 @@ impl<'a, 'b, S: Default> Server<'a, 'b, S> {
fn set_gateway(&mut self, gateway: Option<Ipv4Address>) {
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();
}

View File

@ -1,5 +1,5 @@
use super::command_parser::{Command, Error as ParserError};
use super::channels::CHANNELS;
use super::command_parser::{Command, Error as ParserError};
const MAX_LINE_LEN: usize = 64;
@ -46,7 +46,8 @@ pub enum SessionInput {
impl From<Result<Command, ParserError>> for SessionInput {
fn from(input: Result<Command, ParserError>) -> Self {
input.map(SessionInput::Command)
input
.map(SessionInput::Command)
.unwrap_or_else(SessionInput::Error)
}
}
@ -89,16 +90,15 @@ impl Session {
}
pub fn is_report_pending(&self) -> Option<usize> {
if ! self.reporting {
if !self.reporting {
None
} else {
self.report_pending.iter()
.enumerate()
.fold(None, |result, (channel, report_pending)| {
result.or_else(|| {
if *report_pending { Some(channel) } else { None }
})
})
self.report_pending.iter().enumerate().fold(
None,
|result, (channel, report_pending)| {
result.or_else(|| if *report_pending { Some(channel) } else { None })
},
)
}
}

View File

@ -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)]

View File

@ -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<RefCell<u32>> = 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

View File

@ -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(())