Compare commits

..

1 Commits

Author SHA1 Message Date
atse c5674343a1 README: Document interval key in reports 2024-08-16 13:37:48 +08:00
30 changed files with 1230 additions and 1380 deletions

3
.gitignore vendored
View File

@ -1,5 +1,2 @@
target/
result
*.bin
__pycache__/

View File

@ -23,7 +23,7 @@ cargo build --release
The resulting ELF file will be located under `target/thumbv7em-none-eabihf/release/thermostat`.
Alternatively, you can install the Rust toolchain without Nix using rustup; see the `rust` variable in `flake.nix` to determine which Rust version to use.
Alternatively, you can install the Rust toolchain without Nix using rustup; see the Rust manifest file pulled in `flake.nix` to determine which Rust version to use.
## Debugging
@ -84,7 +84,9 @@ invalidate the first line of input.
### Reading ADC input
ADC input data is provided in reports. Query for the latest report with the command `report`. See the *Reports* section below.
Set report mode to `on` for a continuous stream of input data.
The scope of this setting is per TCP session.
### TCP commands
@ -92,41 +94,42 @@ ADC input data is provided in reports. Query for the latest report with the comm
Send commands as simple text string terminated by `\n`. Responses are
formatted as line-delimited JSON.
| Syntax | Function |
|------------------------------------------- |-------------------------------------------------------------------------------|
| `report` | Show latest report of channel parameters (see *Reports* section) |
| `pwm` | Show current PWM settings |
| `pwm <0/1> max_i_pos <amp>` | Set maximum positive output current, clamped to [0, 2] |
| `pwm <0/1> max_i_neg <amp>` | Set maximum negative output current, clamped to [0, 2] |
| `pwm <0/1> max_v <volt>` | Set maximum output voltage, clamped to [0, 4] |
| `pwm <0/1> i_set <amp>` | Disengage PID, set fixed output current, clamped to [-2, 2] |
| `pwm <0/1> polarity <normal/reversed>` | Set output current polarity, with 'normal' being the front panel polarity |
| `pwm <0/1> pid` | Let output current to be controlled by the PID |
| `center <0/1> <volt>` | Set the MAX1968 0A-centerpoint to the specified fixed voltage |
| `center <0/1> vref` | Set the MAX1968 0A-centerpoint to measure from VREF |
| `pid` | Show PID configuration |
| `pid <0/1> target <deg_celsius>` | Set the PID controller target temperature |
| `pid <0/1> kp <value>` | Set proportional gain |
| `pid <0/1> ki <value>` | Set integral gain |
| `pid <0/1> kd <value>` | Set differential gain |
| `pid <0/1> output_min <amp>` | Set mininum output |
| `pid <0/1> output_max <amp>` | Set maximum output |
| `s-h` | Show Steinhart-Hart equation parameters |
| `s-h <0/1> <t0/b/r0> <value>` | Set Steinhart-Hart parameter for a channel |
| `postfilter` | Show postfilter settings |
| `postfilter <0/1> off` | Disable postfilter |
| `postfilter <0/1> rate <rate>` | Set postfilter output data rate |
| `load [0/1]` | Restore configuration for channel all/0/1 from flash |
| `save [0/1]` | Save configuration for channel all/0/1 to flash |
| `reset` | Reset the device |
| `dfu` | Reset device and enters USB device firmware update (DFU) mode |
| `ipv4 <X.X.X.X/L> [Y.Y.Y.Y]` | Configure IPv4 address, netmask length, and optional default gateway |
| `fan` | Show current fan settings and sensors' measurements |
| `fan <value>` | Set fan power with values from 1 to 100 |
| `fan auto` | Enable automatic fan speed control |
| `fcurve <a> <b> <c>` | Set fan controller curve coefficients (see *Fan control* section) |
| `fcurve default` | Set fan controller curve coefficients to defaults (see *Fan control* section) |
| `hwrev` | Show hardware revision, and settings related to it |
| Syntax | Function |
|----------------------------------|-------------------------------------------------------------------------------|
| `report` | Show current input |
| `report mode` | Show current report mode |
| `report mode <off/on>` | Set report mode |
| `pwm` | Show current PWM settings |
| `pwm <0/1> max_i_pos <amp>` | Set maximum positive output current |
| `pwm <0/1> max_i_neg <amp>` | Set maximum negative output current |
| `pwm <0/1> max_v <volt>` | Set maximum output voltage |
| `pwm <0/1> i_set <amp>` | Disengage PID, set fixed output current |
| `pwm <0/1> pid` | Let output current to be controlled by the PID |
| `center <0/1> <volt>` | Set the MAX1968 0A-centerpoint to the specified fixed voltage |
| `center <0/1> vref` | Set the MAX1968 0A-centerpoint to measure from VREF |
| `pid` | Show PID configuration |
| `pid <0/1> target <deg_celsius>` | Set the PID controller target temperature |
| `pid <0/1> kp <value>` | Set proportional gain |
| `pid <0/1> ki <value>` | Set integral gain |
| `pid <0/1> kd <value>` | Set differential gain |
| `pid <0/1> output_min <amp>` | Set mininum output |
| `pid <0/1> output_max <amp>` | Set maximum output |
| `s-h` | Show Steinhart-Hart equation parameters |
| `s-h <0/1> <t0/b/r0> <value>` | Set Steinhart-Hart parameter for a channel |
| `postfilter` | Show postfilter settings |
| `postfilter <0/1> off` | Disable postfilter |
| `postfilter <0/1> rate <rate>` | Set postfilter output data rate |
| `load [0/1]` | Restore configuration for channel all/0/1 from flash |
| `save [0/1]` | Save configuration for channel all/0/1 to flash |
| `reset` | Reset the device |
| `dfu` | Reset device and enters USB device firmware update (DFU) mode |
| `ipv4 <X.X.X.X/L> [Y.Y.Y.Y]` | Configure IPv4 address, netmask length, and optional default gateway |
| `fan` | Show current fan settings and sensors' measurements |
| `fan <value>` | Set fan power with values from 1 to 100 |
| `fan auto` | Enable automatic fan speed control |
| `fcurve <a> <b> <c>` | Set fan controller curve coefficients (see *Fan control* section) |
| `fcurve default` | Set fan controller curve coefficients to defaults (see *Fan control* section) |
| `hwrev` | Show hardware revision, and settings related to it |
## USB
@ -183,13 +186,11 @@ postfilter rate can be tuned with the `postfilter` command.
When using a TEC module with the Thermostat, the Thermostat expects the thermal load (where the thermistor is located) to cool down with a positive software current set point, and heat up with a negative current set point.
If the Thermostat is used for temperature control with the Sinara 5432 DAC "Zotino", and is connected via an IDC cable, the TEC polarity may need to be reversed with the `pwm <ch> polarity reversed` TCP command.
Testing heat flow direction with a low set current is recommended before installation of the TEC module.
### Limits
Each MAX1968 TEC driver has analog/PWM inputs for setting
Each of the MAX1968 TEC driver has analog/PWM inputs for setting
output limits.
Use the `pwm` command to see current settings and maximum values.
@ -218,7 +219,7 @@ pwm 0 max_i_pos 3
### Open-loop mode
To manually control TEC output current, set a fixed output current with
To manually control TEC output current, omit the limit parameter of
the `pwm` command. Doing so will disengage the PID control for that
channel.
@ -250,7 +251,8 @@ pwm 0 pid
## Reports
Use the bare `report` command to obtain a single report. Reports are JSON objects
Use the bare `report` command to obtain a single report. Enable
continuous reporting with `report mode on`. Reports are JSON objects
with the following keys.
| Key | Unit | Description |
@ -270,7 +272,7 @@ with the following keys.
| `tec_u_meas` | Volts | Measurement of the voltage across the TEC |
| `pid_output` | Amperes | PID control output |
Note: Prior to Thermostat hardware revision v2.2.4, the voltage and current readouts `i_tec` and `tec_i` are noisy without the hardware fix shown in [this PR](https://git.m-labs.hk/M-Labs/thermostat/pulls/105).
Note: With Thermostat v2 and below, the voltage and current readouts `i_tec` and `tec_i` are noisy without the hardware fix shown in [this PR][https://git.m-labs.hk/M-Labs/thermostat/pulls/105].
## PID Tuning

View File

@ -63,7 +63,7 @@
name = "thermostat-dev-shell";
packages = with pkgs; [
rust llvm
openocd dfu-util rlwrap
openocd dfu-util
] ++ (with python3Packages; [
numpy matplotlib
]);

View File

@ -1,7 +1,6 @@
import socket
import json
import logging
import time
class CommandError(Exception):
pass
@ -16,7 +15,7 @@ class Client:
pwm_report = self.get_pwm()
for pwm_channel in pwm_report:
for limit in ["max_i_neg", "max_i_pos", "max_v"]:
if pwm_channel[limit] == 0.0:
if pwm_channel[limit]["value"] == 0.0:
logging.warning("`{}` limit is set to zero on channel {}".format(limit, pwm_channel["channel"]))
def _read_line(self):
@ -53,18 +52,16 @@ class Client:
Example::
[{'channel': 0,
'center': 'vref',
'i_set': -0.02002179650216762,
'max_i_neg': 2.0,
'max_v': 3.988,
'max_i_pos': 2.0,
'polarity': 'normal',
'i_set': {'max': 2.9802790335151985, 'value': -0.02002179650216762},
'max_i_neg': {'max': 3.0, 'value': 3.0},
'max_v': {'max': 5.988, 'value': 5.988},
'max_i_pos': {'max': 3.0, 'value': 3.0}},
{'channel': 1,
'center': 'vref',
'i_set': -0.02002179650216762,
'max_i_neg': 2.0,
'max_v': 3.988,
'max_i_pos': 2.0}
'polarity': 'normal',
'i_set': {'max': 2.9802790335151985, 'value': -0.02002179650216762},
'max_i_neg': {'max': 3.0, 'value': 3.0},
'max_v': {'max': 5.988, 'value': 5.988},
'max_i_pos': {'max': 3.0, 'value': 3.0}}
]
"""
return self._get_conf("pwm")
@ -129,8 +126,9 @@ class Client:
'tec_u_meas': 2.5340000000000003,
'pid_output': 2.067581958092247}
"""
self._command("report mode", "on")
while True:
self._socket.sendall("report\n".encode('utf-8'))
line = self._read_line()
if not line:
break
@ -138,7 +136,6 @@ class Client:
yield json.loads(line)
except json.decoder.JSONDecodeError:
pass
time.sleep(0.05)
def set_param(self, topic, channel, field="", value=""):
"""Set configuration parameters

View File

@ -1,9 +1,12 @@
use crate::timer::sleep;
use stm32f4xx_hal::{
hal::{blocking::spi::Transfer, digital::v2::OutputPin},
spi,
hal::{
blocking::spi::Transfer,
digital::v2::OutputPin,
},
time::MegaHertz,
spi,
};
use crate::timer::sleep;
/// SPI Mode 1
pub const SPI_MODE: spi::Mode = spi::Mode {
@ -24,8 +27,11 @@ 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> {
@ -41,7 +47,11 @@ 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,12 +1,18 @@
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::{electric_potential::volt, f64::ElectricPotential};
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,
};
/// AD7172-2 implementation
///
@ -21,8 +27,7 @@ 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()?;
@ -50,7 +55,8 @@ 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> {
@ -70,10 +76,7 @@ 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);
@ -103,11 +106,7 @@ 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> {
@ -120,43 +119,44 @@ 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,21 +175,12 @@ 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 {
@ -199,7 +190,7 @@ impl<SPI: Transfer<u8, Error = E>, NSS: OutputPin, E: fmt::Debug> Adc<SPI, NSS>
ChecksumMode::Crc => ChecksumMode::Crc,
});
checksum.feed(&[address]);
checksum.feed(reg_data);
checksum.feed(&reg_data);
let checksum_out = checksum.result();
let mut data = reg_data.clone();
@ -210,10 +201,7 @@ 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);
}
}
@ -237,12 +225,7 @@ impl<SPI: Transfer<u8, Error = E>, NSS: OutputPin, E: fmt::Debug> Adc<SPI, NSS>
Ok(())
}
fn transfer(
&mut self,
addr: u8,
reg_data: &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();
@ -251,7 +234,8 @@ 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) {
@ -259,7 +243,8 @@ 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,10 +1,13 @@
use core::fmt;
use num_traits::float::Float;
use serde::{Deserialize, Serialize};
use stm32f4xx_hal::{spi, time::MegaHertz};
use serde::{Serialize, Deserialize};
use stm32f4xx_hal::{
time::MegaHertz,
spi,
};
mod checksum;
pub mod regs;
mod checksum;
pub use checksum::ChecksumMode;
mod adc;
pub use adc::*;
@ -19,6 +22,7 @@ pub const SPI_CLOCK: MegaHertz = MegaHertz(2);
pub const MAX_VALUE: u32 = 0xFF_FFFF;
#[derive(Clone, Copy, Debug)]
#[repr(u8)]
pub enum Mode {
@ -101,8 +105,7 @@ impl fmt::Display for Input {
RefPos => "ref+",
RefNeg => "ref-",
_ => "<INVALID>",
}
.fmt(fmt)
}.fmt(fmt)
}
}
@ -138,8 +141,7 @@ impl fmt::Display for RefSource {
Internal => "internal",
Avdd1MinusAvss => "avdd1-avss",
_ => "<INVALID>",
}
.fmt(fmt)
}.fmt(fmt)
}
}

View File

@ -1,6 +1,6 @@
use bit_field::BitField;
use byteorder::{BigEndian, ByteOrder};
use core::ops::{Deref, DerefMut};
use byteorder::{BigEndian, ByteOrder};
use bit_field::BitField;
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,9 +49,7 @@ 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 {
@ -78,7 +76,7 @@ macro_rules! def_reg {
}
}
}
};
}
}
macro_rules! reg_bit {
@ -148,7 +146,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");
@ -161,21 +159,9 @@ 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");
}
@ -188,19 +174,15 @@ 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);
@ -218,7 +200,8 @@ 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)]
@ -227,66 +210,27 @@ 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");
}
@ -294,7 +238,9 @@ 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) {
@ -308,7 +254,9 @@ 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,10 +1,14 @@
use crate::{
ad5680, ad7172,
channel_state::ChannelState,
pins::{ChannelPinSet, ChannelPins},
};
use stm32f4xx_hal::hal::digital::v2::OutputPin;
use uom::si::{electric_potential::volt, f64::ElectricPotential};
use uom::si::{
f64::ElectricPotential,
electric_potential::volt,
};
use crate::{
ad5680,
ad7172,
channel_state::ChannelState,
pins::{ChannelPins, ChannelPinSet},
};
/// Marker type for the first channel
pub struct Channel0;
@ -36,8 +40,7 @@ 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,20 +1,24 @@
use crate::{
ad7172,
command_parser::{CenterPoint, Polarity},
config::PwmLimits,
pid, steinhart_hart as sh,
};
use smoltcp::time::{Duration, Instant};
use uom::si::{
electric_current::ampere,
electric_potential::volt,
electrical_resistance::ohm,
f64::{
ElectricCurrent, ElectricPotential, ElectricalResistance, ThermodynamicTemperature, Time,
ElectricPotential,
ElectricCurrent,
ElectricalResistance,
ThermodynamicTemperature,
Time,
},
electric_potential::volt,
electric_current::ampere,
electrical_resistance::ohm,
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;
@ -28,11 +32,9 @@ pub struct ChannelState {
pub center: CenterPoint,
pub dac_value: ElectricPotential,
pub i_set: ElectricCurrent,
pub pwm_limits: PwmLimits,
pub pid_engaged: bool,
pub pid: pid::Controller,
pub sh: sh::Parameters,
pub polarity: Polarity,
}
impl ChannelState {
@ -43,18 +45,12 @@ impl ChannelState {
adc_time: Instant::from_secs(0),
// default: 10 Hz
adc_interval: Duration::from_millis(100),
center: CenterPoint::VRef,
center: CenterPoint::Vref,
dac_value: ElectricPotential::new::<volt>(0.0),
i_set: ElectricCurrent::new::<ampere>(0.0),
pwm_limits: PwmLimits {
max_v: 0.0,
max_i_pos: 0.0,
max_i_neg: 0.0,
},
pid_engaged: false,
pid: pid::Controller::new(pid::Parameters::default()),
sh: sh::Parameters::default(),
polarity: Polarity::Normal,
}
}
@ -71,7 +67,8 @@ 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,13 +1,3 @@
use crate::timer::sleep;
use crate::{
ad5680, ad7172,
channel::{Channel, Channel0, Channel1},
channel_state::ChannelState,
command_handler::JsonBuffer,
command_parser::{CenterPoint, Polarity, PwmPin},
pins::{self, Channel0VRef, Channel1VRef},
steinhart_hart,
};
use core::marker::PhantomData;
use heapless::{consts::U2, Vec};
use num_traits::Zero;
@ -15,16 +5,26 @@ use serde::{Serialize, Serializer};
use smoltcp::time::Instant;
use stm32f4xx_hal::hal;
use uom::si::{
electric_current::ampere,
electric_potential::{millivolt, volt},
electrical_resistance::ohm,
f64::{ElectricCurrent, ElectricPotential, ElectricalResistance, Time},
electric_potential::{millivolt, volt},
electric_current::ampere,
electrical_resistance::ohm,
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::{self, Channel0VRef, Channel1VRef},
steinhart_hart,
};
pub enum PinsAdcReadTarget {
VRef,
VREF,
DacVfb,
ITec,
VTec,
@ -44,11 +44,7 @@ pub const MAX_TEC_V: ElectricPotential = ElectricPotential {
units: PhantomData,
value: 4.0,
};
const MAX_TEC_I_DUTY_TO_CURRENT_RATE: ElectricCurrent = ElectricCurrent {
dimension: PhantomData,
units: PhantomData,
value: 1.0 / (10.0 * R_SENSE / 3.3),
};
// DAC chip outputs 0-5v, which is then passed through a resistor dividor to provide 0-3v range
const DAC_OUT_V_MAX: ElectricPotential = ElectricPotential {
dimension: PhantomData,
@ -72,25 +68,19 @@ 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));
@ -131,10 +121,10 @@ impl Channels {
/// calculate the TEC i_set centerpoint
pub fn get_center(&mut self, channel: usize) -> ElectricPotential {
match self.channel_state(channel).center {
CenterPoint::VRef => self.adc_read(channel, PinsAdcReadTarget::VRef, 8),
CenterPoint::Override(center_point) => {
ElectricPotential::new::<volt>(center_point.into())
}
CenterPoint::Vref =>
self.adc_read(channel, PinsAdcReadTarget::VREF, 8),
CenterPoint::Override(center_point) =>
ElectricPotential::new::<volt>(center_point.into()),
}
}
@ -151,7 +141,7 @@ impl Channels {
/// i_set DAC
fn set_dac(&mut self, channel: usize, voltage: ElectricPotential) -> ElectricPotential {
let value = ((voltage / DAC_OUT_V_MAX).get::<ratio>() * (ad5680::MAX_VALUE as f64)) as u32;
let value = ((voltage / 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(),
@ -163,71 +153,64 @@ impl Channels {
pub fn set_i(&mut self, channel: usize, i_set: ElectricCurrent) -> ElectricCurrent {
let i_set = i_set.min(MAX_TEC_I).max(-MAX_TEC_I);
self.channel_state(channel).i_set = i_set;
let negate = match self.channel_state(channel).polarity {
Polarity::Normal => 1.0,
Polarity::Reversed => -1.0,
};
let vref_meas = match channel {
let vref_meas = match channel.into() {
0 => self.channel0.vref_meas,
1 => self.channel1.vref_meas,
_ => unreachable!(),
};
let center_point = vref_meas;
let r_sense = ElectricalResistance::new::<ohm>(R_SENSE);
let voltage = negate * i_set * 10.0 * r_sense + center_point;
let voltage = i_set * 10.0 * r_sense + center_point;
let voltage = self.set_dac(channel, voltage);
negate * (voltage - center_point) / (10.0 * r_sense)
let i_set = (voltage - center_point) / (10.0 * r_sense);
self.channel_state(channel).i_set = i_set;
i_set
}
/// AN4073: ADC Reading Dispersion can be reduced through Averaging
pub fn adc_read(
&mut self,
channel: usize,
adc_read_target: PinsAdcReadTarget,
avg_pt: u16,
) -> ElectricPotential {
pub fn adc_read(&mut self, channel: usize, adc_read_target: PinsAdcReadTarget, avg_pt: u16) -> ElectricPotential {
let mut sample: u32 = 0;
match channel {
0 => {
sample = match adc_read_target {
PinsAdcReadTarget::VRef => match &self.channel0.vref_pin {
Channel0VRef::Analog(vref_pin) => {
for _ in (0..avg_pt).rev() {
sample += self.pins_adc.convert(
vref_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
) as u32;
}
sample / avg_pt as u32
PinsAdcReadTarget::VREF => {
match &self.channel0.vref_pin {
Channel0VRef::Analog(vref_pin) => {
for _ in (0..avg_pt).rev() {
sample += self
.pins_adc
.convert(vref_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480)
as u32;
}
sample / avg_pt as u32
},
Channel0VRef::Disabled(_) => {2048 as u32}
}
Channel0VRef::Disabled(_) => 2048_u32,
},
}
PinsAdcReadTarget::DacVfb => {
for _ in (0..avg_pt).rev() {
sample += self.pins_adc.convert(
&self.channel0.dac_feedback_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
) as u32;
sample += self
.pins_adc
.convert(&self.channel0.dac_feedback_pin,stm32f4xx_hal::adc::config::SampleTime::Cycles_480)
as u32;
}
sample / avg_pt as u32
}
PinsAdcReadTarget::ITec => {
for _ in (0..avg_pt).rev() {
sample += self.pins_adc.convert(
&self.channel0.itec_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
) as u32;
sample += self
.pins_adc
.convert(&self.channel0.itec_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480)
as u32;
}
sample / avg_pt as u32
}
PinsAdcReadTarget::VTec => {
for _ in (0..avg_pt).rev() {
sample += self.pins_adc.convert(
&self.channel0.tec_u_meas_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
) as u32;
sample += self
.pins_adc
.convert(&self.channel0.tec_u_meas_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480)
as u32;
}
sample / avg_pt as u32
}
@ -237,42 +220,44 @@ impl Channels {
}
1 => {
sample = match adc_read_target {
PinsAdcReadTarget::VRef => match &self.channel1.vref_pin {
Channel1VRef::Analog(vref_pin) => {
for _ in (0..avg_pt).rev() {
sample += self.pins_adc.convert(
vref_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
) as u32;
}
sample / avg_pt as u32
PinsAdcReadTarget::VREF => {
match &self.channel1.vref_pin {
Channel1VRef::Analog(vref_pin) => {
for _ in (0..avg_pt).rev() {
sample += self
.pins_adc
.convert(vref_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480)
as u32;
}
sample / avg_pt as u32
},
Channel1VRef::Disabled(_) => {2048 as u32}
}
Channel1VRef::Disabled(_) => 2048_u32,
},
}
PinsAdcReadTarget::DacVfb => {
for _ in (0..avg_pt).rev() {
sample += self.pins_adc.convert(
&self.channel1.dac_feedback_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
) as u32;
sample += self
.pins_adc
.convert(&self.channel1.dac_feedback_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480)
as u32;
}
sample / avg_pt as u32
}
PinsAdcReadTarget::ITec => {
for _ in (0..avg_pt).rev() {
sample += self.pins_adc.convert(
&self.channel1.itec_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
) as u32;
sample += self
.pins_adc
.convert(&self.channel1.itec_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480)
as u32;
}
sample / avg_pt as u32
}
PinsAdcReadTarget::VTec => {
for _ in (0..avg_pt).rev() {
sample += self.pins_adc.convert(
&self.channel1.tec_u_meas_pin,
stm32f4xx_hal::adc::config::SampleTime::Cycles_480,
) as u32;
sample += self
.pins_adc
.convert(&self.channel1.tec_u_meas_pin, stm32f4xx_hal::adc::config::SampleTime::Cycles_480)
as u32;
}
sample / avg_pt as u32
}
@ -280,7 +265,18 @@ impl Channels {
let mv = self.pins_adc.sample_to_millivolts(sample as u16);
ElectricPotential::new::<millivolt>(mv as f64)
}
_ => unreachable!(),
_ => unreachable!()
}
}
pub fn read_dac_feedback_until_stable(&mut self, channel: usize, tolerance: ElectricPotential) -> ElectricPotential {
let mut prev = self.adc_read(channel, PinsAdcReadTarget::DacVfb, 1);
loop {
let current = self.adc_read(channel, PinsAdcReadTarget::DacVfb, 1);
if (current - prev).abs() < tolerance {
return current;
}
prev = current;
}
}
@ -288,29 +284,30 @@ 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);
for _ in 0..samples {
target_voltage += self.get_center(channel);
target_voltage = target_voltage + self.get_center(channel);
}
target_voltage /= samples as f64;
target_voltage = target_voltage / samples as f64;
let mut start_value = 1;
let mut best_error = ElectricPotential::new::<volt>(100.0);
for step in (5..18).rev() {
for step in (0..18).rev() {
let mut prev_value = start_value;
for value in (start_value..=ad5680::MAX_VALUE).step_by(1 << step) {
match channel {
0 => {
@ -321,15 +318,14 @@ impl Channels {
}
_ => unreachable!(),
}
sleep(10);
let dac_feedback = self.adc_read(channel, PinsAdcReadTarget::DacVfb, 64);
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;
} else if error < best_error {
best_error = error;
start_value = value;
start_value = prev_value;
let vref = (value as f64 / ad5680::MAX_VALUE as f64) * DAC_OUT_V_MAX;
match channel {
@ -338,6 +334,8 @@ impl Channels {
_ => unreachable!(),
}
}
prev_value = value;
}
}
@ -363,110 +361,106 @@ impl Channels {
}
}
pub fn get_max_v(&mut self, channel: usize) -> ElectricPotential {
ElectricPotential::new::<volt>(self.channel_state(channel).pwm_limits.max_v)
fn get_pwm(&self, channel: usize, pin: PwmPin) -> 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!(),
}
}
pub fn get_max_i_pos(&mut self, channel: usize) -> ElectricCurrent {
ElectricCurrent::new::<ampere>(self.channel_state(channel).pwm_limits.max_i_pos)
pub fn get_max_v(&mut self, channel: usize) -> (ElectricPotential, ElectricPotential) {
let max = 4.0 * ElectricPotential::new::<volt>(3.3);
let duty = self.get_pwm(channel, PwmPin::MaxV);
(duty * max, MAX_TEC_V)
}
pub fn get_max_i_neg(&mut self, channel: usize) -> ElectricCurrent {
ElectricCurrent::new::<ampere>(self.channel_state(channel).pwm_limits.max_i_neg)
pub fn get_max_i_pos(&mut self, channel: usize) -> (ElectricCurrent, ElectricCurrent) {
let max = ElectricCurrent::new::<ampere>(3.0);
let duty = self.get_pwm(channel, PwmPin::MaxIPos);
(duty * max, MAX_TEC_I)
}
pub fn get_max_i_neg(&mut self, channel: usize) -> (ElectricCurrent, ElectricCurrent) {
let max = ElectricCurrent::new::<ampere>(3.0);
let duty = self.get_pwm(channel, PwmPin::MaxINeg);
(duty * max, MAX_TEC_I)
}
// Get current passing through TEC
pub fn get_tec_i(&mut self, channel: usize) -> ElectricCurrent {
let tec_i = (self.adc_read(channel, PinsAdcReadTarget::ITec, 16)
- self.adc_read(channel, PinsAdcReadTarget::VRef, 16))
/ ElectricalResistance::new::<ohm>(0.4);
match self.channel_state(channel).polarity {
Polarity::Normal => tec_i,
Polarity::Reversed => -tec_i,
}
(self.adc_read(channel, PinsAdcReadTarget::ITec, 16) - self.adc_read(channel, PinsAdcReadTarget::VREF, 16)) / ElectricalResistance::new::<ohm>(0.4)
}
// Get voltage across TEC
pub fn get_tec_v(&mut self, channel: usize) -> ElectricPotential {
(self.adc_read(channel, PinsAdcReadTarget::VTec, 16) - ElectricPotential::new::<volt>(1.5))
* 4.0
(self.adc_read(channel, PinsAdcReadTarget::VTec, 16) - ElectricPotential::new::<volt>(1.5)) * 4.0
}
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 max_v = max_v.min(MAX_TEC_V).max(ElectricPotential::zero());
let duty = (max_v / max).get::<ratio>();
let duty = (max_v.min(MAX_TEC_V).max(ElectricPotential::zero()) / max).get::<ratio>();
let duty = self.set_pwm(channel, PwmPin::MaxV, duty);
self.channel_state(channel).pwm_limits.max_v = max_v.get::<volt>();
(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 max_i_pos = max_i_pos.min(MAX_TEC_I).max(ElectricCurrent::zero());
let duty = (max_i_pos / MAX_TEC_I_DUTY_TO_CURRENT_RATE).get::<ratio>();
let duty = match self.channel_state(channel).polarity {
Polarity::Normal => self.set_pwm(channel, PwmPin::MaxIPos, duty),
Polarity::Reversed => self.set_pwm(channel, PwmPin::MaxINeg, duty),
};
self.channel_state(channel).pwm_limits.max_i_pos = max_i_pos.get::<ampere>();
(duty * MAX_TEC_I_DUTY_TO_CURRENT_RATE, max)
let duty = (max_i_pos.min(MAX_TEC_I).max(ElectricCurrent::zero()) / 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 max_i_neg = max_i_neg.min(MAX_TEC_I).max(ElectricCurrent::zero());
let duty = (max_i_neg / MAX_TEC_I_DUTY_TO_CURRENT_RATE).get::<ratio>();
let duty = match self.channel_state(channel).polarity {
Polarity::Normal => self.set_pwm(channel, PwmPin::MaxINeg, duty),
Polarity::Reversed => self.set_pwm(channel, PwmPin::MaxIPos, duty),
};
self.channel_state(channel).pwm_limits.max_i_neg = max_i_neg.get::<ampere>();
(duty * MAX_TEC_I_DUTY_TO_CURRENT_RATE, max)
}
pub fn set_polarity(&mut self, channel: usize, polarity: Polarity) {
if self.channel_state(channel).polarity != polarity {
let i_set = self.channel_state(channel).i_set;
let max_i_pos = self.get_max_i_pos(channel);
let max_i_neg = self.get_max_i_neg(channel);
self.channel_state(channel).polarity = polarity;
self.set_i(channel, i_set);
self.set_max_i_pos(channel, max_i_pos);
self.set_max_i_neg(channel, max_i_neg);
}
let duty = (max_i_neg.min(MAX_TEC_I).max(ElectricCurrent::zero()) / max).get::<ratio>();
let duty = self.set_pwm(channel, PwmPin::MaxINeg, duty);
(duty * max, max)
}
fn report(&mut self, channel: usize) -> Report {
@ -482,8 +476,7 @@ 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,
@ -525,11 +518,10 @@ impl Channels {
PwmSummary {
channel,
center: CenterPointJson(self.channel_state(channel).center.clone()),
i_set: self.get_i(channel),
max_v: self.get_max_v(channel),
max_i_pos: self.get_max_i_pos(channel),
max_i_neg: self.get_max_i_neg(channel),
polarity: PolarityJson(self.channel_state(channel).polarity.clone()),
i_set: (self.get_i(channel), MAX_TEC_I).into(),
max_v: self.get_max_v(channel).into(),
max_i_pos: self.get_max_i_pos(channel).into(),
max_i_neg: self.get_max_i_neg(channel).into(),
}
}
@ -542,10 +534,7 @@ 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 }
}
@ -563,9 +552,7 @@ 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));
@ -608,24 +595,23 @@ 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),
}
}
}
pub struct PolarityJson(Polarity);
#[derive(Serialize)]
pub struct PwmSummaryField<T: Serialize> {
value: T,
max: T,
}
// used in JSON encoding, not for config
impl Serialize for PolarityJson {
fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error>
where
S: Serializer,
{
serializer.serialize_str(match self.0 {
Polarity::Normal => "normal",
Polarity::Reversed => "reversed",
})
impl<T: Serialize> From<(T, T)> for PwmSummaryField<T> {
fn from((value, max): (T, T)) -> Self {
PwmSummaryField { value, max }
}
}
@ -633,11 +619,10 @@ impl Serialize for PolarityJson {
pub struct PwmSummary {
channel: usize,
center: CenterPointJson,
i_set: ElectricCurrent,
max_v: ElectricPotential,
max_i_pos: ElectricCurrent,
max_i_neg: ElectricCurrent,
polarity: PolarityJson,
i_set: PwmSummaryField<ElectricCurrent>,
max_v: PwmSummaryField<ElectricPotential>,
max_i_pos: PwmSummaryField<ElectricCurrent>,
max_i_neg: PwmSummaryField<ElectricCurrent>,
}
#[derive(Serialize)]

View File

@ -1,26 +1,45 @@
use smoltcp::socket::TcpSocket;
use log::{error, warn};
use core::fmt::Write;
use heapless::{consts::U1024, Vec};
use super::{
ad7172,
channels::{Channels, CHANNELS},
net,
command_parser::{
CenterPoint, Command, Ipv4Config, PidParameter, Polarity, PwmPin, ShParameter, ShowCommand,
Ipv4Config,
Command,
ShowCommand,
CenterPoint,
PidParameter,
PwmPin,
ShParameter
},
ad7172,
CHANNEL_CONFIG_KEY,
channels::{
Channels,
CHANNELS
},
config::ChannelConfig,
dfu,
flash_store::FlashStore,
session::Session,
FanCtrl,
hw_rev::HWRev,
net, FanCtrl, CHANNEL_CONFIG_KEY,
};
use core::fmt::Write;
use heapless::{consts::U1024, Vec};
use log::{error, warn};
use smoltcp::socket::TcpSocket;
use uom::si::{
electric_current::ampere,
electric_potential::volt,
electrical_resistance::ohm,
f64::{ElectricCurrent, ElectricPotential, ElectricalResistance, ThermodynamicTemperature},
thermodynamic_temperature::degree_celsius,
use uom::{
si::{
f64::{
ElectricCurrent,
ElectricPotential,
ElectricalResistance,
ThermodynamicTemperature,
},
electric_current::ampere,
electric_potential::volt,
electrical_resistance::ohm,
thermodynamic_temperature::degree_celsius,
},
};
#[derive(Debug, Clone, PartialEq)]
@ -33,9 +52,9 @@ pub enum Handler {
#[derive(Clone, Debug, PartialEq)]
pub enum Error {
Report,
PostFilterRate,
Flash,
ReportError,
PostFilterRateError,
FlashError
}
pub type JsonBuffer = Vec<u8, U1024>;
@ -47,19 +66,19 @@ fn send_line(socket: &mut TcpSocket, data: &[u8]) -> bool {
// instead of sending incomplete line
warn!(
"TCP socket has only {}/{} needed {}",
send_free + 1,
socket.send_capacity(),
data.len(),
send_free + 1, socket.send_capacity(), data.len(),
);
} else {
match socket.send_slice(data) {
match socket.send_slice(&data) {
Ok(sent) if sent == data.len() => {
let _ = socket.send_slice(b"\n");
// success
return true;
return true
}
Ok(sent) => warn!("sent only {}/{} bytes", sent, data.len()),
Err(e) => error!("error sending line: {:?}", e),
Ok(sent) =>
warn!("sent only {}/{} bytes", sent, data.len()),
Err(e) =>
error!("error sending line: {:?}", e),
}
}
// not success
@ -67,6 +86,17 @@ 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)
}
fn show_report_mode(socket: &mut TcpSocket, session: &Session) -> Result<Handler, Error> {
let _ = writeln!(socket, "{{ \"report\": {:?} }}", session.reporting());
Ok(Handler::Handled)
}
fn show_report(socket: &mut TcpSocket, channels: &mut Channels) -> Result<Handler, Error> {
match channels.reports_json() {
Ok(buf) => {
@ -75,7 +105,7 @@ impl Handler {
Err(e) => {
error!("unable to serialize report: {:?}", e);
let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e);
return Err(Error::Report);
return Err(Error::ReportError);
}
}
Ok(Handler::Handled)
@ -89,7 +119,7 @@ impl Handler {
Err(e) => {
error!("unable to serialize pid summary: {:?}", e);
let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e);
return Err(Error::Report);
return Err(Error::ReportError);
}
}
Ok(Handler::Handled)
@ -103,16 +133,13 @@ impl Handler {
Err(e) => {
error!("unable to serialize pwm summary: {:?}", e);
let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e);
return Err(Error::Report);
return Err(Error::ReportError);
}
}
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);
@ -120,13 +147,13 @@ impl Handler {
Err(e) => {
error!("unable to serialize steinhart-hart summaries: {:?}", e);
let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e);
return Err(Error::Report);
return Err(Error::ReportError);
}
}
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);
@ -134,13 +161,13 @@ impl Handler {
Err(e) => {
error!("unable to serialize postfilter summary: {:?}", e);
let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e);
return Err(Error::Report);
return Err(Error::ReportError);
}
}
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));
@ -148,34 +175,13 @@ 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_polarity(
socket: &mut TcpSocket,
channels: &mut Channels,
channel: usize,
polarity: Polarity,
) -> Result<Handler, Error> {
channels.set_polarity(channel, polarity);
send_line(socket, b"{}");
Ok(Handler::Handled)
}
fn set_pwm(
socket: &mut TcpSocket,
channels: &mut Channels,
channel: usize,
pin: PwmPin,
value: f64,
) -> Result<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;
@ -200,12 +206,7 @@ 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_set = channels.get_i(channel);
let state = channels.channel_state(channel);
state.center = center;
@ -216,34 +217,28 @@ 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 {
@ -255,52 +250,32 @@ 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\"}}",
);
return Err(Error::PostFilterRate);
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> {
for (c, key) in CHANNEL_CONFIG_KEY.iter().enumerate().take(CHANNELS) {
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>(key) {
match store.read_value::<ChannelConfig>(CHANNEL_CONFIG_KEY[c]) {
Ok(Some(config)) => {
config.apply(channels, c);
send_line(socket, b"{}");
@ -312,7 +287,7 @@ impl Handler {
Err(e) => {
error!("unable to load config from flash: {:?}", e);
let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e);
return Err(Error::Flash);
return Err(Error::FlashError);
}
}
}
@ -320,24 +295,19 @@ impl Handler {
Ok(Handler::Handled)
}
fn save_channel(
socket: &mut TcpSocket,
channels: &mut Channels,
channel: Option<usize>,
store: &mut FlashStore,
) -> Result<Handler, Error> {
for (c, key) in CHANNEL_CONFIG_KEY.iter().enumerate().take(CHANNELS) {
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) {
let config = ChannelConfig::new(channels, c);
match store.write_value(key, &config, &mut store_value_buf) {
match store.write_value(CHANNEL_CONFIG_KEY[c], &config, &mut store_value_buf) {
Ok(()) => {
send_line(socket, b"{}");
}
Err(e) => {
error!("unable to save channel {} config to flash: {:?}", c, e);
let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e);
return Err(Error::Flash);
return Err(Error::FlashError);
}
}
}
@ -345,11 +315,7 @@ 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));
@ -358,7 +324,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);
}
@ -366,7 +332,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);
}
@ -377,16 +343,9 @@ 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 a fan!\" }",
);
send_line(socket, b"{ \"warning\": \"this thermostat doesn't have a fan!\" }");
return Ok(Handler::Handled);
}
fan_ctrl.set_auto_mode(false);
@ -408,17 +367,14 @@ impl Handler {
Err(e) => {
error!("unable to serialize fan summary: {:?}", e);
let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e);
Err(Error::Report)
Err(Error::ReportError)
}
}
}
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 a fan!\" }",
);
send_line(socket, b"{ \"warning\": \"this thermostat doesn't have a fan!\" }");
return Ok(Handler::Handled);
}
fan_ctrl.set_auto_mode(true);
@ -430,13 +386,7 @@ 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)
@ -457,73 +407,40 @@ impl Handler {
Err(e) => {
error!("unable to serialize HWRev summary: {:?}", e);
let _ = writeln!(socket, "{{\"error\":\"{:?}\"}}", e);
Err(Error::Report)
Err(Error::ReportError)
}
}
}
pub fn handle_command(
command: Command,
socket: &mut TcpSocket,
channels: &mut Channels,
store: &mut FlashStore,
ipv4_config: &mut Ipv4Config,
fan_ctrl: &mut FanCtrl,
hwrev: HWRev,
) -> Result<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::Show(ShowCommand::Input) => Handler::show_report(socket, channels),
Command::Show(ShowCommand::Pid) => Handler::show_pid(socket, channels),
Command::Show(ShowCommand::Pwm) => Handler::show_pwm(socket, channels),
Command::Show(ShowCommand::SteinhartHart) => {
Handler::show_steinhart_hart(socket, channels)
}
Command::Show(ShowCommand::SteinhartHart) => Handler::show_steinhart_hart(socket, channels),
Command::Show(ShowCommand::PostFilter) => Handler::show_post_filter(socket, channels),
Command::Show(ShowCommand::Ipv4) => Handler::show_ipv4(socket, ipv4_config),
Command::PwmPid { channel } => Handler::engage_pid(socket, channels, channel),
Command::PwmPolarity { channel, polarity } => {
Handler::set_polarity(socket, channels, channel, polarity)
}
Command::Pwm {
channel,
pin,
value,
} => Handler::set_pwm(socket, channels, channel, pin, value),
Command::CenterPoint { channel, center } => {
Handler::set_center_point(socket, channels, channel, center)
}
Command::Pid {
channel,
parameter,
value,
} => Handler::set_pid(socket, channels, channel, parameter, value),
Command::SteinhartHart {
channel,
parameter,
value,
} => Handler::set_steinhart_hart(socket, channels, channel, parameter, value),
Command::PostFilter {
channel,
rate: None,
} => Handler::reset_post_filter(socket, channels, channel),
Command::PostFilter {
channel,
rate: Some(rate),
} => Handler::set_post_filter(socket, channels, channel, rate),
Command::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,20 +2,19 @@ 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::{
complete::{char, one_of},
is_digit,
},
character::{is_digit, complete::{char, one_of}},
combinator::{complete, map, opt, value},
error::ErrorKind,
multi::{fold_many0, fold_many1},
sequence::preceded,
IResult, Needed,
multi::{fold_many0, fold_many1},
error::ErrorKind,
Needed,
};
use num_traits::{Num, ParseFloatError};
use serde::{Deserialize, Serialize};
use serde::{Serialize, Deserialize};
#[derive(Clone, Debug, PartialEq)]
pub enum Error {
@ -31,9 +30,12 @@ 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),
}
}
}
@ -59,7 +61,8 @@ 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)
@ -76,7 +79,9 @@ 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)
}
}
}
}
@ -91,6 +96,7 @@ pub struct Ipv4Config {
#[derive(Debug, Clone, PartialEq)]
pub enum ShowCommand {
Input,
Reporting,
Pwm,
Pid,
SteinhartHart,
@ -126,16 +132,10 @@ pub enum PwmPin {
#[derive(Debug, Clone, PartialEq, Serialize, Deserialize)]
pub enum CenterPoint {
VRef,
Vref,
Override(f32),
}
#[derive(Debug, Clone, PartialEq, Serialize, Deserialize)]
pub enum Polarity {
Normal,
Reversed,
}
#[derive(Debug, Clone, PartialEq)]
pub enum Command {
Quit,
@ -148,6 +148,7 @@ pub enum Command {
Reset,
Ipv4(Ipv4Config),
Show(ShowCommand),
Reporting(bool),
/// PWM parameter setting
Pwm {
channel: usize,
@ -158,10 +159,6 @@ pub enum Command {
PwmPid {
channel: usize,
},
PwmPolarity {
channel: usize,
polarity: Polarity,
},
CenterPoint {
channel: usize,
center: CenterPoint,
@ -183,7 +180,7 @@ pub enum Command {
},
Dfu,
FanSet {
fan_pwm: u32,
fan_pwm: u32
},
FanAuto,
ShowFan,
@ -197,7 +194,12 @@ 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], ()> {
@ -205,25 +207,38 @@ 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| digits.parse::<u32>().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 == b'.')(input)?;
let result = from_utf8(digits)
let (input, digits) = take_while1(|c| is_digit(c) || c == '.' as u8)(input)?;
let result =
from_utf8(digits)
.map_err(|e| e.into())
.and_then(|digits| f64::from_str_radix(digits, 10).map_err(|e| e.into()))
.and_then(|digits| f64::from_str_radix(digits, 10)
.map_err(|e| e.into())
)
.map(|result: f64| if negative { -result } else { result });
Ok((input, result))
}
fn off_on(input: &[u8]) -> IResult<&[u8], bool> {
alt((value(false, tag("off")),
value(true, tag("on"))
))(input)
}
fn channel(input: &[u8]) -> IResult<&[u8], usize> {
map(one_of("01"), |c| (c as usize) - ('0' as usize))(input)
}
@ -231,33 +246,74 @@ fn channel(input: &[u8]) -> IResult<&[u8], usize> {
fn report(input: &[u8]) -> IResult<&[u8], Command> {
preceded(
tag("report"),
// `report` - Report once
value(Command::Show(ShowCommand::Input), end),
alt((
preceded(
whitespace,
preceded(
tag("mode"),
alt((
preceded(
whitespace,
// `report mode <on | off>` - Switch repoting mode
map(off_on, Command::Reporting)
),
// `report mode` - Show current reporting state
value(Command::Show(ShowCommand::Reporting), end)
))
)),
// `report` - Report once
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
@ -265,19 +321,6 @@ fn pwm_pid(input: &[u8]) -> IResult<&[u8], ()> {
value((), tag("pid"))(input)
}
fn pwm_polarity(input: &[u8]) -> IResult<&[u8], Polarity> {
preceded(
tag("polarity"),
preceded(
whitespace,
alt((
value(Polarity::Normal, tag("normal")),
value(Polarity::Reversed, tag("reversed")),
)),
),
)(input)
}
fn pwm(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
let (input, _) = tag("pwm")(input)?;
alt((
@ -290,29 +333,20 @@ fn pwm(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
let (input, ()) = pwm_pid(input)?;
Ok((input, Ok(Command::PwmPid { channel })))
},
|input| {
let (input, polarity) = pwm_polarity(input)?;
Ok((input, Ok(Command::PwmPolarity { channel, polarity })))
},
|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)
}
@ -321,39 +355,36 @@ 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))
}
@ -361,8 +392,11 @@ 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)
}
@ -370,18 +404,15 @@ 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))
}
@ -389,38 +420,42 @@ 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)
}
@ -433,7 +468,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 });
@ -449,7 +484,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 });
@ -511,17 +546,12 @@ 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)
}
@ -541,15 +571,8 @@ fn fan_curve(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
let (input, k_b) = float(input)?;
let (input, _) = whitespace(input)?;
let (input, k_c) = float(input)?;
if let (Ok(k_a), Ok(k_b), Ok(k_c)) = (k_a, k_b, k_c) {
Ok((
input,
Ok(Command::FanCurve {
k_a: k_a as f32,
k_b: k_b as f32,
k_c: k_c as f32,
}),
))
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 })))
} else {
Err(nom::Err::Incomplete(Needed::Size(3)))
}
@ -557,36 +580,38 @@ 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.is_empty() => 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()),
}
}
}
@ -634,27 +659,21 @@ 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]
@ -664,73 +683,69 @@ 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,
})
);
fn parse_report_mode() {
let command = Command::parse(b"report mode");
assert_eq!(command, Ok(Command::Show(ShowCommand::Reporting)));
}
#[test]
fn parse_pwm_polarity() {
let command = Command::parse(b"pwm 0 polarity reversed");
assert_eq!(
command,
Ok(Command::PwmPolarity {
channel: 0,
polarity: Polarity::Reversed,
})
);
fn parse_report_mode_on() {
let command = Command::parse(b"report mode on");
assert_eq!(command, Ok(Command::Reporting(true)));
}
#[test]
fn parse_report_mode_off() {
let command = Command::parse(b"report mode off");
assert_eq!(command, Ok(Command::Reporting(false)));
}
#[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,
}));
}
#[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]
@ -742,14 +757,11 @@ 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]
@ -761,14 +773,11 @@ 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]
@ -780,49 +789,37 @@ 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]
@ -834,7 +831,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]
@ -846,14 +843,11 @@ 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,16 @@
use num_traits::Zero;
use serde::{Serialize, Deserialize};
use uom::si::{
electric_potential::volt,
electric_current::ampere,
f64::{ElectricCurrent, ElectricPotential},
};
use crate::{
ad7172::PostFilter,
channels::Channels,
command_parser::{CenterPoint, Polarity},
pid, steinhart_hart,
};
use num_traits::Zero;
use serde::{Deserialize, Serialize};
use uom::si::{
electric_current::ampere,
electric_potential::volt,
f64::{ElectricCurrent, ElectricPotential},
command_parser::CenterPoint,
pid,
steinhart_hart,
};
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
@ -19,7 +20,6 @@ pub struct ChannelConfig {
pid_target: f32,
pid_engaged: bool,
i_set: ElectricCurrent,
polarity: Polarity,
sh: steinhart_hart::Parameters,
pwm: PwmLimits,
/// uses variant `PostFilter::Invalid` instead of `None` to save space
@ -30,25 +30,22 @@ impl ChannelConfig {
pub fn new(channels: &mut Channels, channel: usize) -> Self {
let pwm = PwmLimits::new(channels, channel);
let adc_postfilter = channels
.adc
.get_postfilter(channel as u8)
let adc_postfilter = channels.adc.get_postfilter(channel as u8)
.unwrap()
.unwrap_or(PostFilter::Invalid);
let state = channels.channel_state(channel);
let i_set = if state.pid_engaged {
ElectricCurrent::zero()
} else {
state.i_set
let i_set = if state.pid_engaged {
ElectricCurrent::zero()
} else {
state.i_set
};
ChannelConfig {
center: state.center.clone(),
pid: state.pid.parameters.clone(),
pid_target: state.pid.target as f32,
pid_engaged: state.pid_engaged,
i_set,
polarity: state.polarity.clone(),
i_set: i_set,
sh: state.sh.clone(),
pwm,
adc_postfilter,
@ -71,22 +68,21 @@ impl ChannelConfig {
};
let _ = channels.adc.set_postfilter(channel as u8, adc_postfilter);
let _ = channels.set_i(channel, self.i_set);
channels.set_polarity(channel, self.polarity.clone());
}
}
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
pub struct PwmLimits {
pub max_v: f64,
pub max_i_pos: f64,
pub max_i_neg: f64,
struct PwmLimits {
max_v: f64,
max_i_pos: f64,
max_i_neg: f64,
}
impl PwmLimits {
pub fn new(channels: &mut Channels, channel: usize) -> Self {
let max_v = channels.get_max_v(channel);
let max_i_pos = channels.get_max_i_pos(channel);
let max_i_neg = channels.get_max_i_neg(channel);
let (max_v, _) = channels.get_max_v(channel);
let (max_i_pos, _) = channels.get_max_i_pos(channel);
let (max_i_neg, _) = channels.get_max_i_neg(channel);
PwmLimits {
max_v: max_v.get::<volt>(),
max_i_pos: max_i_pos.get::<ampere>(),

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,17 +1,25 @@
use crate::{channels::MAX_TEC_I, command_handler::JsonBuffer, hw_rev::HWSettings};
use num_traits::Float;
use serde::Serialize;
use stm32f4xx_hal::{
pac::TIM8,
pwm::{self, PwmChannels},
pac::TIM8,
};
use uom::si::{
f64::ElectricCurrent,
electric_current::ampere,
};
use crate::{
hw_rev::HWSettings,
command_handler::JsonBuffer,
channels::MAX_TEC_I,
};
use uom::si::{electric_current::ampere, f64::ElectricCurrent};
pub type FanPin = PwmChannels<TIM8, pwm::C4>;
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,
@ -48,9 +56,7 @@ impl FanCtrl {
if self.fan_auto && self.hw_settings.fan_available {
let scaled_current = self.abs_max_tec_i / MAX_TEC_I.get::<ampere>() as f32;
// do not limit upper bound, as it will be limited in the set_pwm()
let pwm = (MAX_USER_FAN_PWM
* (scaled_current * (scaled_current * self.k_a + self.k_b) + self.k_c))
as u32;
let pwm = (MAX_USER_FAN_PWM * (scaled_current * (scaled_current * self.k_a + self.k_b) + self.k_c)) as u32;
self.set_pwm(pwm);
}
}
@ -83,26 +89,18 @@ 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.clamp(MIN_USER_FAN_PWM as u32, MAX_USER_FAN_PWM as u32);
let duty = scale_number(
fan_pwm as f32,
self.hw_settings.min_fan_pwm,
self.hw_settings.max_fan_pwm,
MIN_USER_FAN_PWM,
MAX_USER_FAN_PWM,
);
let 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);
@ -121,17 +119,8 @@ 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 {
@ -147,6 +136,7 @@ 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::{error, info};
use sfkv::{Store, StoreBackend};
use log::{info, error};
use stm32f4xx_hal::{
flash::{Error, FlashExt},
stm32::FLASH,
};
use sfkv::{Store, StoreBackend};
/// 16 KiB
pub const FLASH_SECTOR_SIZE: usize = 0x4000;
@ -21,7 +21,9 @@ 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 {
@ -38,8 +40,7 @@ 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())
}
@ -59,8 +60,7 @@ 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,6 +1,9 @@
use serde::Serialize;
use crate::{command_handler::JsonBuffer, pins::HWRevPins};
use crate::{
pins::HWRevPins,
command_handler::JsonBuffer,
};
#[derive(Serialize, Copy, Clone)]
pub struct HWRev {
@ -28,17 +31,13 @@ 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 }
}
}
@ -71,16 +70,13 @@ 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,15 +10,17 @@ 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::{PD10, PD11, PD9},
gpiod::{PD9, PD10, PD11},
Output, PushPull,
},
hal::digital::v2::OutputPin,

View File

@ -8,26 +8,30 @@ 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::{Watchdog, WatchdogEnable},
hal::watchdog::{WatchdogEnable, Watchdog},
rcc::RccExt,
stm32::{CorePeripherals, Peripherals, SCB},
time::{MegaHertz, U32Ext},
time::{U32Ext, MegaHertz},
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 ad5680;
mod ad7172;
mod ad5680;
mod net;
mod server;
use server::Server;
@ -35,18 +39,18 @@ mod session;
use session::{Session, SessionInput};
mod command_parser;
use command_parser::Ipv4Config;
mod channels;
mod timer;
mod pid;
mod steinhart_hart;
mod timer;
use channels::{Channels, CHANNELS};
mod channels;
use channels::{CHANNELS, Channels};
mod channel;
mod channel_state;
mod config;
use config::ChannelConfig;
mod command_handler;
mod dfu;
mod flash_store;
mod dfu;
mod command_handler;
use command_handler::Handler;
mod fan_ctrl;
use fan_ctrl::FanCtrl;
@ -69,19 +73,19 @@ fn send_line(socket: &mut TcpSocket, data: &[u8]) -> bool {
// instead of sending incomplete line
warn!(
"TCP socket has only {}/{} needed {}",
send_free + 1,
socket.send_capacity(),
data.len(),
send_free + 1, socket.send_capacity(), data.len(),
);
} else {
match socket.send_slice(data) {
match socket.send_slice(&data) {
Ok(sent) if sent == data.len() => {
let _ = socket.send_slice(b"\n");
// success
return true;
return true
}
Ok(sent) => warn!("sent only {}/{} bytes", sent, data.len()),
Err(e) => error!("error sending line: {:?}", e),
Ok(sent) =>
warn!("sent only {}/{} bytes", sent, data.len()),
Err(e) =>
error!("error sending line: {:?}", e),
}
}
// not success
@ -100,9 +104,7 @@ 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())
@ -118,15 +120,14 @@ fn main() -> ! {
timer::setup(cp.SYST, clocks);
let (pins, mut leds, mut eeprom, eth_pins, usb, fan, hwrev, hw_settings) = Pins::setup(
clocks,
(dp.TIM1, dp.TIM3, dp.TIM8),
(
dp.GPIOA, dp.GPIOB, dp.GPIOC, dp.GPIOD, dp.GPIOE, dp.GPIOF, dp.GPIOG,
),
clocks, dp.TIM1, dp.TIM3, dp.TIM8,
dp.GPIOA, dp.GPIOB, dp.GPIOC, dp.GPIOD, dp.GPIOE, dp.GPIOF, dp.GPIOG,
dp.I2C1,
(dp.SPI2, dp.SPI4, dp.SPI5),
dp.SPI2, dp.SPI4, dp.SPI5,
dp.ADC1,
(dp.OTG_FS_GLOBAL, dp.OTG_FS_DEVICE, dp.OTG_FS_PWRCLK),
dp.OTG_FS_GLOBAL,
dp.OTG_FS_DEVICE,
dp.OTG_FS_PWRCLK,
);
leds.r1.on();
@ -138,11 +139,14 @@ fn main() -> ! {
let mut store = flash_store::store(dp.FLASH);
let mut channels = Channels::new(pins);
for (c, key) in CHANNEL_CONFIG_KEY.iter().enumerate().take(CHANNELS) {
match store.read_value::<ChannelConfig>(key) {
Ok(Some(config)) => config.apply(&mut channels, c),
Ok(None) => error!("flash config not found for channel {}", c),
Err(e) => error!("unable to load config {} from flash: {:?}", c, e),
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),
}
}
@ -155,9 +159,11 @@ 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
@ -166,115 +172,118 @@ 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()));
channels.poll_adc(instant);
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());
fan_ctrl.cycle(channels.current_abs_max_tec_i());
if channels.pid_engaged() {
leds.g3.on();
} else {
leds.g3.off();
}
if channels.pid_engaged() {
leds.g3.on();
} else {
leds.g3.off();
}
let instant = Instant::from_millis(i64::from(timer::now()));
cortex_m::interrupt::free(net::clear_pending);
server.poll(instant).unwrap_or_else(|e| {
let instant = Instant::from_millis(i64::from(timer::now()));
cortex_m::interrupt::free(net::clear_pending);
server.poll(instant)
.unwrap_or_else(|e| {
warn!("poll: {:?}", e);
});
if !should_reset {
// TCP protocol handling
server.for_each(|mut socket, session| {
if !socket.is_active() {
let _ = socket.listen(TCP_PORT);
session.reset();
} else if socket.may_send() && !socket.may_recv() {
socket.close()
} else if socket.can_send() && socket.can_recv() {
match socket.recv(|buf| session.feed(buf)) {
// SessionInput::Nothing happens when the line reader parses a string of characters that is not
// followed by a newline character. Could be due to partial commands not terminated with newline,
// socket RX ring buffer wraps around, or when the command is sent as seperate TCP packets etc.
// Do nothing and feed more data to the line reader in the next loop cycle.
Ok(SessionInput::Nothing) => {}
Ok(SessionInput::Command(command)) => {
match Handler::handle_command(
command,
&mut socket,
&mut channels,
&mut store,
&mut ipv4_config,
&mut fan_ctrl,
hwrev,
) {
Ok(Handler::NewIPV4(ip)) => new_ipv4_config = Some(ip),
Ok(Handler::Handled) => {}
Ok(Handler::CloseSocket) => socket.close(),
Ok(Handler::Reset) => should_reset = true,
Err(_) => {}
}
if ! should_reset {
// TCP protocol handling
server.for_each(|mut socket, session| {
if ! socket.is_active() {
let _ = socket.listen(TCP_PORT);
session.reset();
} else if socket.may_send() && !socket.may_recv() {
socket.close()
} else if socket.can_send() && socket.can_recv() {
match socket.recv(|buf| session.feed(buf)) {
// SessionInput::Nothing happens when the line reader parses a string of characters that is not
// followed by a newline character. Could be due to partial commands not terminated with newline,
// socket RX ring buffer wraps around, or when the command is sent as seperate TCP packets etc.
// Do nothing and feed more data to the line reader in the next loop cycle.
Ok(SessionInput::Nothing) => {}
Ok(SessionInput::Command(command)) => {
match Handler::handle_command(command, &mut socket, &mut channels, 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\" }");
}
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);
}
Err(e) => {
error!("unable to serialize report: {:?}", e);
}
Err(_) => socket.close(),
}
}
});
} else {
// Should reset, close all TCP sockets.
let mut any_socket_alive = false;
server.for_each(|mut socket, _| {
if socket.is_active() {
socket.abort();
any_socket_alive = true;
}
});
// Must let loop run for one more cycle to poll server for RST to be sent,
// this makes sure system does not reset right after socket.abort() is called.
if !any_socket_alive {
SCB::sys_reset();
}
}
// Apply new IPv4 address/gateway
if let Some(config) = new_ipv4_config.take() {
server.set_ipv4_config(config.clone());
ipv4_config = config;
};
// Update watchdog
wd.feed();
leds.g4.off();
cortex_m::interrupt::free(|cs| {
if !net::is_pending(cs) {
// Wait for interrupts
// (Ethernet, SysTick, or USB)
wfi();
}
});
leds.g4.on();
} 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| {
server.set_ipv4_config(config.clone());
ipv4_config = config;
});
// Update watchdog
wd.feed();
leds.g4.off();
cortex_m::interrupt::free(|cs| {
if !net::is_pending(cs) {
// Wait for interrupts
// (Ethernet, SysTick, or USB)
wfi();
}
});
leds.g4.on();
}
});
});
unreachable!()
}

View File

@ -1,17 +1,20 @@
//! As there is only one peripheral, supporting data structures are
//! declared once and globally.
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,
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;
/// Not on the stack so that stack can be placed in CCMRAM (which the
/// ethernet peripheral cannot access)
@ -27,27 +30,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
@ -73,7 +76,8 @@ 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() };
@ -82,13 +86,15 @@ 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::{Deserialize, Serialize};
use serde::{Serialize, Deserialize};
#[derive(Clone, Debug, PartialEq, Serialize, Deserialize)]
pub struct Parameters {
@ -29,37 +29,38 @@ 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,
target: 0.0,
u1: 0.0,
x1: 0.0,
x2: 0.0,
y1: 0.0,
parameters: parameters,
target : 0.0,
u1 : 0.0,
x1 : 0.0,
x2 : 0.0,
y1 : 0.0,
}
}
// Based on https://hackmd.io/IACbwcOTSt6Adj3_F9bKuw PID implementation
// Input x(t), target u(t), output y(t)
// y0' = y1 - ki * u0
// y0' = y1 - ki * u0
// + x0 * (kp + ki + kd)
// - x1 * (kp + 2kd)
// + x2 * kd
// y0 = clip(y0', ymin, ymax)
pub fn update(&mut self, input: f64) -> f64 {
let mut output: f64 = self.y1 - self.target * f64::from(self.parameters.ki)
+ input * f64::from(self.parameters.kp + self.parameters.ki + self.parameters.kd)
- self.x1 * f64::from(self.parameters.kp + 2.0 * self.parameters.kd)
+ self.x2 * f64::from(self.parameters.kd);
+ input * f64::from(self.parameters.kp + self.parameters.ki + self.parameters.kd)
- self.x1 * f64::from(self.parameters.kp + 2.0 * self.parameters.kd)
+ self.x2 * f64::from(self.parameters.kd);
if output < self.parameters.output_min.into() {
output = self.parameters.output_min.into();
}
@ -69,7 +70,7 @@ impl Controller {
self.x2 = self.x1;
self.x1 = input;
self.u1 = self.target;
self.y1 = output;
self.y1 = output;
output
}
@ -108,17 +109,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,41 +1,49 @@
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::{
gpioa::*, gpiob::*, gpioc::*, gpioe::*, gpiof::*, gpiog::*, Alternate, AlternateOD, Analog,
Floating, GpioExt, Input, Output, PushPull, AF5,
AF5, Alternate, AlternateOD, Analog, Floating, Input,
gpioa::*,
gpiob::*,
gpioc::*,
gpioe::*,
gpiof::*,
gpiog::*,
GpioExt,
Output, PushPull,
},
hal::{self, blocking::spi::Transfer, digital::v2::OutputPin},
i2c::I2c,
otg_fs::USB,
pac::{
ADC1, GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, I2C1, OTG_FS_DEVICE, OTG_FS_GLOBAL,
OTG_FS_PWRCLK, SPI2, SPI4, SPI5, TIM1, TIM3, TIM8,
},
pwm::{self, PwmChannels},
rcc::Clocks,
spi::{NoMiso, Spi, TransferModeNormal},
time::U32Ext,
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
},
timer::Timer,
time::U32Ext,
};
use eeprom24x::{self, Eeprom24x};
use stm32_eth::EthPins;
use crate::{
channel::{Channel0, Channel1},
leds::Leds,
fan_ctrl::FanPin,
hw_rev::{HWRev, HWSettings},
};
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<
@ -46,7 +54,7 @@ pub type EthernetPins = EthPins<
PB13<Input<Floating>>,
PC4<Input<Floating>>,
PC5<Input<Floating>>,
>;
>;
pub trait ChannelPins {
type DacSpi: Transfer<u8>;
@ -89,15 +97,7 @@ 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>;
@ -133,34 +133,13 @@ impl Pins {
/// Setup GPIO pins and configure MCU peripherals
pub fn setup(
clocks: Clocks,
(tim1, tim3, tim8): (TIM1, TIM3, TIM8),
(gpioa, gpiob, gpioc, gpiod, gpioe, gpiof, gpiog): (
GPIOA,
GPIOB,
GPIOC,
GPIOD,
GPIOE,
GPIOF,
GPIOG,
),
tim1: TIM1, tim3: TIM3, tim8: TIM8,
gpioa: GPIOA, gpiob: GPIOB, gpioc: GPIOC, gpiod: GPIOD, gpioe: GPIOE, gpiof: GPIOF, gpiog: GPIOG,
i2c1: I2C1,
(spi2, spi4, spi5): (SPI2, SPI4, SPI5),
spi2: SPI2, spi4: SPI4, spi5: SPI5,
adc1: ADC1,
(otg_fs_global, otg_fs_device, otg_fs_pwrclk): (
OTG_FS_GLOBAL,
OTG_FS_DEVICE,
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();
@ -175,29 +154,23 @@ impl Pins {
let pins_adc = Adc::adc1(adc1, true, Default::default());
let pwm = PwmPins::setup(
clocks,
(tim1, tim3),
(gpioc.pc6, gpioc.pc7),
(gpioe.pe9, gpioe.pe11),
(gpioe.pe13, gpioe.pe14),
clocks, tim1, tim3,
gpioc.pc6, gpioc.pc7,
gpioe.pe9, gpioe.pe11,
gpioe.pe13, gpioe.pe14
);
let hwrev = HWRev::detect_hw_rev(&HWRevPins {
hwrev0: gpiod.pd0,
hwrev1: gpiod.pd1,
hwrev2: gpiod.pd2,
hwrev3: gpiod.pd3,
});
let hwrev = HWRev::detect_hw_rev(&HWRevPins {hwrev0: gpiod.pd0, hwrev1: gpiod.pd1,
hwrev2: gpiod.pd2, hwrev3: gpiod.pd3});
let hw_settings = hwrev.settings();
let (dac0_spi, dac0_sync) = Self::setup_dac0(clocks, spi4, gpioe.pe2, gpioe.pe4, gpioe.pe6);
let (dac0_spi, dac0_sync) = Self::setup_dac0(
clocks, spi4,
gpioe.pe2, gpioe.pe4, gpioe.pe6
);
let mut shdn0 = gpioe.pe10.into_push_pull_output();
shdn0.set_low();
let vref0_pin = if hwrev.major > 2 {
Channel0VRef::Analog(gpioa.pa0.into_analog())
} else {
Channel0VRef::Disabled(gpioa.pa0)
};
let _ = shdn0.set_low();
let vref0_pin = if hwrev.major > 2 {Channel0VRef::Analog(gpioa.pa0.into_analog())} else {Channel0VRef::Disabled(gpioa.pa0)};
let itec0_pin = gpioa.pa6.into_analog();
let dac_feedback0_pin = gpioa.pa4.into_analog();
let tec_u_meas0_pin = gpioc.pc2.into_analog();
@ -211,14 +184,13 @@ 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();
shdn1.set_low();
let vref1_pin = if hwrev.major > 2 {
Channel1VRef::Analog(gpioa.pa3.into_analog())
} else {
Channel1VRef::Disabled(gpioa.pa3)
};
let _ = shdn1.set_low();
let vref1_pin = if hwrev.major > 2 {Channel1VRef::Analog(gpioa.pa3.into_analog())} else {Channel1VRef::Disabled(gpioa.pa3)};
let itec1_pin = gpiob.pb0.into_analog();
let dac_feedback1_pin = gpioa.pa5.into_analog();
let tec_u_meas1_pin = gpioc.pc3.into_analog();
@ -233,19 +205,14 @@ impl Pins {
};
let pins = Pins {
adc_spi,
adc_nss,
adc_spi, adc_nss,
pins_adc,
pwm,
channel0,
channel1,
};
let leds = Leds::new(
gpiod.pd9,
gpiod.pd10.into_push_pull_output(),
gpiod.pd11.into_push_pull_output(),
);
let leds = Leds::new(gpiod.pd9, gpiod.pd10.into_push_pull_output(), gpiod.pd11.into_push_pull_output());
let eeprom_scl = gpiob.pb8.into_alternate().set_open_drain();
let eeprom_sda = gpiob.pb9.into_alternate().set_open_drain();
@ -272,13 +239,8 @@ 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)
}
@ -290,7 +252,8 @@ 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();
@ -299,16 +262,13 @@ 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();
@ -317,7 +277,7 @@ impl Pins {
(sclk, NoMiso {}, sdin),
crate::ad5680::SPI_MODE,
crate::ad5680::SPI_CLOCK,
clocks,
clocks
);
let sync = sync.into_push_pull_output();
@ -325,11 +285,8 @@ 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();
@ -338,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();
@ -358,18 +315,25 @@ pub struct PwmPins {
impl PwmPins {
fn setup<M1, M2, M3, M4, M5, M6>(
clocks: Clocks,
(tim1, tim3): (TIM1, TIM3),
(max_v0, max_v1): (PC6<M1>, PC7<M2>),
(max_i_pos0, max_i_pos1): (PE9<M3>, PE11<M4>),
(max_i_neg0, max_i_neg1): (PE13<M5>, PE14<M6>),
tim1: TIM1,
tim3: TIM3,
max_v0: PC6<M1>,
max_v1: PC7<M2>,
max_i_pos0: PE9<M3>,
max_i_pos1: PE11<M4>,
max_i_neg0: PE13<M5>,
max_i_neg1: PE14<M6>,
) -> 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);
@ -389,12 +353,9 @@ 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,29 +1,25 @@
use crate::command_parser::Ipv4Config;
use crate::net::split_ipv4_config;
use smoltcp::{
iface::EthernetInterface,
socket::{SocketHandle, SocketRef, SocketSet, TcpSocket, TcpSocketBuffer},
socket::{SocketSet, SocketHandle, TcpSocket, TcpSocketBuffer, SocketRef},
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()
}
}
}
@ -54,7 +50,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,10 +99,15 @@ impl<'a, 'b, S: Default> Server<'a, 'b, S> {
fn set_ipv4_address(&mut self, ipv4_address: Ipv4Cidr) {
self.net.update_ip_addrs(|addrs| {
for addr in addrs.iter_mut() {
if let IpCidr::Ipv4(_) = addr {
*addr = IpCidr::Ipv4(ipv4_address);
// done
break;
match addr {
IpCidr::Ipv4(_) => {
*addr = IpCidr::Ipv4(ipv4_address);
// done
break
}
_ => {
// skip
}
}
}
});
@ -115,9 +116,10 @@ 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,4 +1,5 @@
use super::command_parser::{Command, Error as ParserError};
use super::channels::CHANNELS;
const MAX_LINE_LEN: usize = 64;
@ -45,14 +46,15 @@ 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)
}
}
pub struct Session {
reader: LineReader,
reporting: bool,
report_pending: [bool; CHANNELS],
}
impl Default for Session {
@ -65,11 +67,43 @@ impl Session {
pub fn new() -> Self {
Session {
reader: LineReader::new(),
reporting: false,
report_pending: [false; CHANNELS],
}
}
pub fn reset(&mut self) {
self.reader = LineReader::new();
self.reporting = false;
self.report_pending = [false; CHANNELS];
}
pub fn reporting(&self) -> bool {
self.reporting
}
pub fn set_report_pending(&mut self, channel: usize) {
if self.reporting {
self.report_pending[channel] = true;
}
}
pub fn is_report_pending(&self) -> Option<usize> {
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 }
})
})
}
}
pub fn mark_report_sent(&mut self, channel: usize) {
self.report_pending[channel] = false;
}
pub fn feed(&mut self, buf: &[u8]) -> (usize, SessionInput) {
@ -77,9 +111,18 @@ impl Session {
for (i, b) in buf.iter().enumerate() {
buf_bytes = i + 1;
let line = self.reader.feed(*b);
if let Some(line) = line {
let command = Command::parse(line);
return (buf_bytes, command.into());
match line {
Some(line) => {
let command = Command::parse(&line);
match command {
Ok(Command::Reporting(reporting)) => {
self.reporting = reporting;
}
_ => {}
}
return (buf_bytes, command.into());
}
None => {}
}
}
(buf_bytes, SessionInput::Nothing)

View File

@ -1,11 +1,14 @@
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,
stm32::SYST,
time::U32Ext,
timer::{Event as TimerEvent, Timer},
timer::{Timer, Event as TimerEvent},
stm32::SYST,
};
/// Rate in Hz
@ -18,6 +18,7 @@ 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);
@ -27,13 +28,18 @@ 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,18 +1,15 @@
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::{UsbBus as Bus, USB},
otg_fs::{USB, UsbBus as Bus},
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];
@ -39,8 +36,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 {
@ -97,7 +94,8 @@ 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(())