Remove all tacho/status related logic

Signed-off-by: Egor Savkin <es@m-labs.hk>
This commit is contained in:
Egor Savkin 2023-01-05 13:05:22 +08:00
parent 33070abd81
commit a645bfb6e8
5 changed files with 22 additions and 174 deletions

View File

@ -125,9 +125,10 @@ formatted as line-delimited JSON.
| `dfu` | Reset device and enters USB device firmware update (DFU) mode | | `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 | | `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` | Show current fan settings and sensors' measurements |
| `fan <value>` | Set fan power with values from 0 to 100, where 0 is auto mode | | `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 <a> <b> <c>` | Set fan controller curve coefficients (see *Fan control* section) |
| `fcurve-restore` | Set fan controller curve coefficients to defaults (see *Fan control* section) | | `fcurve default` | Set fan controller curve coefficients to defaults (see *Fan control* section) |
## USB ## USB
@ -277,13 +278,11 @@ The thermostat implements a PID control loop for each of the TEC channels, more
## Fan control ## Fan control
Fan control is available for the thermostat revisions with integrated fan system. For this purpose four commands are available: Fan control is available for the thermostat revisions with integrated fan system. For this purpose four commands are available:
1. `fan` - show fan stats: `fan_pwm`, `tacho`, `abs_max_tec_i`, `auto_mode`. Please note that `tacho` shows *approximate* value, which 1. `fan` - show fan stats: `fan_pwm`, `abs_max_tec_i`, `auto_mode`, `k_a`, `k_b`, `k_c`.
linearly correlates with the actual fan speed. 2. `fan auto` - enable auto speed controller mode, which correlates with the square of the TEC's current.
2. `fan <value>` - set the fan power with the value from `0` to `100`. Since there is no hardware way to disable the fan, 3. `fan <value>` - set the fan power with the value from `1` to `100` and disable auto mode. There is no way to disable the fan.
`0` value is used for enabling automatic fan control mode, which correlates with the square of the TEC's current.
Values from `1` to `100` are used for setting the power from minimum to maximum respectively.
Please note that power doesn't correlate with the actual speed linearly. Please note that power doesn't correlate with the actual speed linearly.
3. `fcurve <a> <b> <c>` - set coefficients of the controlling curve `a*x^2 + b*x + c`, where `x` is `abs_max_tec_i/MAX_TEC_I`, 4. `fcurve <a> <b> <c>` - set coefficients of the controlling curve `a*x^2 + b*x + c`, where `x` is `abs_max_tec_i/MAX_TEC_I`,
i.e. receives values from 0 to 1 linearly tied to the maximum current. The controlling curve should produce values from 0 to 1, i.e. receives values from 0 to 1 linearly tied to the maximum current. The controlling curve should produce values from 0 to 1,
as below and beyond values would be substituted by 0 and 1 respectively. as below and beyond values would be substituted by 0 and 1 respectively.
4. `fcurve-restore` - restore fan settings to defaults: `auto = true, a = 1.0, b = 0.0, c = 0.00`. 5. `fcurve default` - restore fan curve settings to defaults: `a = 1.0, b = 0.0, c = 0.0`.

View File

@ -342,7 +342,7 @@ impl Handler {
Ok(Handler::Reset) Ok(Handler::Reset)
} }
fn 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> {
fan_ctrl.set_auto_mode(false); fan_ctrl.set_auto_mode(false);
fan_ctrl.set_pwm(fan_pwm); fan_ctrl.set_pwm(fan_pwm);
send_line(socket, b"{}"); send_line(socket, b"{}");
@ -404,7 +404,7 @@ impl Handler {
Command::Ipv4(config) => Handler::set_ipv4(socket, store, config), Command::Ipv4(config) => Handler::set_ipv4(socket, store, config),
Command::Reset => Handler::reset(&mut fan_ctrl.channels), Command::Reset => Handler::reset(&mut fan_ctrl.channels),
Command::Dfu => Handler::dfu(&mut fan_ctrl.channels), Command::Dfu => Handler::dfu(&mut fan_ctrl.channels),
Command::FanSet {fan_pwm} => Handler::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::ShowFan => Handler::show_fan(socket, fan_ctrl),
Command::FanAuto => Handler::fan_auto(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),

View File

@ -2,23 +2,14 @@ use serde::Serialize;
use stm32f4xx_hal::{ use stm32f4xx_hal::{
pwm::{self, PwmChannels}, pwm::{self, PwmChannels},
pac::TIM8, pac::TIM8,
gpio::{
Floating, Input, ExtiPin,
gpioc::PC8, Edge,
},
stm32::EXTI,
syscfg::{SysCfg},
}; };
use smoltcp::time::Instant;
use crate::{ use crate::{
pins::HWRevPins, pins::HWRevPins,
channels::{Channels, JsonBuffer}, channels::{Channels, JsonBuffer},
timer
}; };
pub type FanPin = PwmChannels<TIM8, pwm::C4>; pub type FanPin = PwmChannels<TIM8, pwm::C4>;
pub type TachoPin = PC8<Input<Floating>>;
// as stated in the schematics // as stated in the schematics
const MAX_TEC_I: f64 = 3.0; const MAX_TEC_I: f64 = 3.0;
@ -26,27 +17,13 @@ const MAX_TEC_I: f64 = 3.0;
const MAX_USER_FAN_PWM: f64 = 100.0; const MAX_USER_FAN_PWM: f64 = 100.0;
const MIN_USER_FAN_PWM: f64 = 1.0; const MIN_USER_FAN_PWM: f64 = 1.0;
const MAX_FAN_PWM: f64 = 1.0; const MAX_FAN_PWM: f64 = 1.0;
// below this value, motor pulse signal is too weak to be registered by tachometer // below this value, motor pulse signal is too weak
const MIN_FAN_PWM: f64 = 0.05; const MIN_FAN_PWM: f64 = 0.05;
const TACHO_MEASURE_MS: i64 = 2500;
// by default up to 2 cycles are skipped on changes in PWM output,
// and the halt threshold will help detect the failure during these skipped cycles
const TACHO_HALT_THRESHOLD: u32 = 250;
const TACHO_SKIP_CYCLES: u8 = 2;
const DEFAULT_K_A: f64 = 1.0; const DEFAULT_K_A: f64 = 1.0;
const DEFAULT_K_B: f64 = 0.0; const DEFAULT_K_B: f64 = 0.0;
const DEFAULT_K_C: f64 = 0.0; const DEFAULT_K_C: f64 = 0.0;
// This regression is from 6% to 25% lower than values registered in the experiments.
// Actual values would be better estimated by logarithmic regression, but that would require more
// runtime computation, and wouldn't give significant correlation difference
// (0.996 for log and 0.966 for quadratic regression).
const TACHO_REGRESSION_A: f64 = -0.04135128436;
const TACHO_REGRESSION_B: f64 = 6.23015531;
const TACHO_REGRESSION_C: f64 = 403.6833577;
#[derive(Serialize, Copy, Clone)] #[derive(Serialize, Copy, Clone)]
pub struct HWRev { pub struct HWRev {
@ -54,83 +31,46 @@ pub struct HWRev {
pub minor: u8, pub minor: u8,
} }
#[derive(Serialize, Clone, Copy, PartialEq)]
pub enum FanStatus {
OK,
NotAvailable,
TooSlow,
Halted
}
struct TachoCtrl {
tacho: TachoPin,
tacho_cnt: u32,
tacho_value: Option<u32>,
prev_epoch: i64,
}
pub struct FanCtrl { pub struct FanCtrl {
fan: FanPin, fan: FanPin,
tacho: TachoCtrl,
fan_auto: bool, fan_auto: bool,
available: bool, available: bool,
k_a: f64, k_a: f64,
k_b: f64, k_b: f64,
k_c: f64, k_c: f64,
pub channels: Channels, pub channels: Channels,
last_status: FanStatus,
skip_cycles: u8,
} }
impl FanCtrl { impl FanCtrl {
pub fn new(mut fan: FanPin, tacho: TachoPin, channels: Channels, exti: &mut EXTI, syscfg: &mut SysCfg) -> Self { pub fn new(mut fan: FanPin, channels: Channels) -> Self {
let available = channels.hwrev.fan_available(); let available = channels.hwrev.fan_available();
let mut tacho_ctrl = TachoCtrl::new(tacho);
if available { if available {
fan.set_duty(0); fan.set_duty(0);
fan.enable(); fan.enable();
tacho_ctrl.init(exti, syscfg);
} }
FanCtrl { FanCtrl {
fan, fan,
tacho: tacho_ctrl,
available, available,
fan_auto: true, fan_auto: true,
k_a: DEFAULT_K_A, k_a: DEFAULT_K_A,
k_b: DEFAULT_K_B, k_b: DEFAULT_K_B,
k_c: DEFAULT_K_C, k_c: DEFAULT_K_C,
channels, channels,
last_status: if available { FanStatus::OK } else { FanStatus::NotAvailable },
skip_cycles: 0
} }
} }
pub fn cycle(&mut self) -> Result<(), FanStatus> { pub fn cycle(&mut self) {
if self.available {
if self.tacho.cycle() {
self.skip_cycles >>= 1;
}
}
self.adjust_speed(); self.adjust_speed();
let diagnose = self.diagnose();
if (self.skip_cycles == 0 || diagnose == FanStatus::Halted) && diagnose != self.last_status {
self.last_status = diagnose;
Err(diagnose)
} else {
Ok(())
}
} }
pub fn summary(&mut self) -> Result<JsonBuffer, serde_json_core::ser::Error> { pub fn summary(&mut self) -> Result<JsonBuffer, serde_json_core::ser::Error> {
if self.available { if self.available {
let summary = FanSummary { let summary = FanSummary {
fan_pwm: self.get_pwm(), fan_pwm: self.get_pwm(),
tacho: self.tacho.get(),
abs_max_tec_i: self.channels.current_abs_max_tec_i(), abs_max_tec_i: self.channels.current_abs_max_tec_i(),
auto_mode: self.fan_auto, auto_mode: self.fan_auto,
status: self.diagnose(),
k_a: self.k_a, k_a: self.k_a,
k_b: self.k_b, k_b: self.k_b,
k_c: self.k_c, k_c: self.k_c,
@ -165,15 +105,11 @@ impl FanCtrl {
#[inline] #[inline]
pub fn restore_defaults(&mut self) { pub fn restore_defaults(&mut self) {
self.set_auto_mode(true);
self.set_curve(DEFAULT_K_A, DEFAULT_K_B, DEFAULT_K_C); self.set_curve(DEFAULT_K_A, DEFAULT_K_B, DEFAULT_K_C);
} }
pub fn set_pwm(&mut self, fan_pwm: u32) -> f64 { pub fn set_pwm(&mut self, fan_pwm: u32) -> f64 {
let fan_pwm = fan_pwm.min(MAX_USER_FAN_PWM as u32).max(MIN_USER_FAN_PWM as u32); let fan_pwm = fan_pwm.min(MAX_USER_FAN_PWM as u32).max(MIN_USER_FAN_PWM as u32);
self.skip_cycles = if (self.tacho.get() as f64) <= Self::threshold_for_pwm(fan_pwm as f64) {
TACHO_SKIP_CYCLES
} else { self.skip_cycles };
let duty = Self::scale_number(fan_pwm as f64, MIN_FAN_PWM, MAX_FAN_PWM, MIN_USER_FAN_PWM, MAX_USER_FAN_PWM); let duty = Self::scale_number(fan_pwm as f64, MIN_FAN_PWM, MAX_FAN_PWM, MIN_USER_FAN_PWM, MAX_USER_FAN_PWM);
let max = self.fan.get_max_duty(); let max = self.fan.get_max_duty();
let value = ((duty * (max as f64)) as u16).min(max); let value = ((duty * (max as f64)) as u16).min(max);
@ -181,31 +117,11 @@ impl FanCtrl {
value as f64 / (max as f64) value as f64 / (max as f64)
} }
#[inline]
fn threshold_for_pwm(fan_pwm: f64) -> f64 {
(TACHO_REGRESSION_A * fan_pwm + TACHO_REGRESSION_B) * fan_pwm + TACHO_REGRESSION_C
}
#[inline] #[inline]
fn scale_number(unscaled: f64, to_min: f64, to_max: f64, from_min: f64, from_max: f64) -> f64 { fn scale_number(unscaled: f64, to_min: f64, to_max: f64, from_min: f64, from_max: f64) -> f64 {
(to_max - to_min) * (unscaled - from_min) / (from_max - from_min) + to_min (to_max - to_min) * (unscaled - from_min) / (from_max - from_min) + to_min
} }
fn diagnose(&mut self) -> FanStatus {
if !self.available {
return FanStatus::NotAvailable;
}
let threshold = Self::threshold_for_pwm(self.get_pwm() as f64) as u32;
let tacho = self.tacho.get();
if tacho >= threshold {
FanStatus::OK
} else if tacho >= TACHO_HALT_THRESHOLD {
FanStatus::TooSlow
} else {
FanStatus::Halted
}
}
fn get_pwm(&self) -> u32 { fn get_pwm(&self) -> u32 {
let duty = self.fan.get_duty(); let duty = self.fan.get_duty();
let max = self.fan.get_max_duty(); let max = self.fan.get_max_duty();
@ -213,53 +129,6 @@ impl FanCtrl {
} }
} }
impl TachoCtrl {
fn new(tacho: TachoPin) -> Self {
TachoCtrl {
tacho,
tacho_cnt: 0,
tacho_value: None,
prev_epoch: 0,
}
}
fn init(&mut self, exti: &mut EXTI, syscfg: &mut SysCfg) {
// These lines do not cause NVIC to run the ISR,
// since the interrupt is masked in the cortex_m::peripheral::NVIC.
// Also using interrupt-related workaround is the best
// option for the current version of stm32f4xx-hal,
// since tying the IC's PC8 with the PWM's PC9 to the same TIM8 is not supported.
// The possible solution would be to update the library to >=v0.14.*,
// and use its Timer's counter functionality.
self.tacho.make_interrupt_source(syscfg);
self.tacho.trigger_on_edge(exti, Edge::Rising);
self.tacho.enable_interrupt(exti);
}
// returns whether the epoch elapsed
fn cycle(&mut self) -> bool {
let tacho_input = self.tacho.check_interrupt();
if tacho_input {
self.tacho.clear_interrupt_pending_bit();
self.tacho_cnt += 1;
}
let instant = Instant::from_millis(i64::from(timer::now()));
if instant.millis - self.prev_epoch >= TACHO_MEASURE_MS {
self.tacho_value = Some(self.tacho_cnt);
self.tacho_cnt = 0;
self.prev_epoch = instant.millis;
true
} else {
false
}
}
fn get(&self) -> u32 {
self.tacho_value.unwrap_or(u32::MAX)
}
}
impl HWRev { impl HWRev {
pub fn detect_hw_rev(hwrev_pins: &HWRevPins) -> Self { pub fn detect_hw_rev(hwrev_pins: &HWRevPins) -> Self {
let (h0, h1, h2, h3) = (hwrev_pins.hwrev0.is_high(), hwrev_pins.hwrev1.is_high(), let (h0, h1, h2, h3) = (hwrev_pins.hwrev0.is_high(), hwrev_pins.hwrev1.is_high(),
@ -280,26 +149,13 @@ impl HWRev {
#[derive(Serialize)] #[derive(Serialize)]
pub struct FanSummary { pub struct FanSummary {
fan_pwm: u32, fan_pwm: u32,
tacho: u32,
abs_max_tec_i: f64, abs_max_tec_i: f64,
auto_mode: bool, auto_mode: bool,
status: FanStatus,
k_a: f64, k_a: f64,
k_b: f64, k_b: f64,
k_c: f64, k_c: f64,
} }
impl FanStatus {
pub fn fmt_u8(&self) -> &'static [u8] {
match *self {
FanStatus::OK => "Fan is OK".as_bytes(),
FanStatus::NotAvailable => "Fan is not available".as_bytes(),
FanStatus::TooSlow => "Fan is too slow".as_bytes(),
FanStatus::Halted => "Fan is halted".as_bytes(),
}
}
}
#[cfg(test)] #[cfg(test)]
mod test { mod test {
use super::*; use super::*;

View File

@ -18,7 +18,6 @@ use stm32f4xx_hal::{
stm32::{CorePeripherals, Peripherals, SCB}, stm32::{CorePeripherals, Peripherals, SCB},
time::{U32Ext, MegaHertz}, time::{U32Ext, MegaHertz},
watchdog::IndependentWatchdog, watchdog::IndependentWatchdog,
syscfg::SysCfgExt
}; };
use smoltcp::{ use smoltcp::{
time::Instant, time::Instant,
@ -104,7 +103,7 @@ fn main() -> ! {
cp.SCB.enable_icache(); cp.SCB.enable_icache();
cp.SCB.enable_dcache(&mut cp.CPUID); cp.SCB.enable_dcache(&mut cp.CPUID);
let mut dp = Peripherals::take().unwrap(); let dp = Peripherals::take().unwrap();
let clocks = dp.RCC.constrain() let clocks = dp.RCC.constrain()
.cfgr .cfgr
.use_hse(HSE) .use_hse(HSE)
@ -120,7 +119,7 @@ fn main() -> ! {
timer::setup(cp.SYST, clocks); timer::setup(cp.SYST, clocks);
let (pins, mut leds, mut eeprom, eth_pins, usb, fan, tacho) = Pins::setup( let (pins, mut leds, mut eeprom, eth_pins, usb, fan) = Pins::setup(
clocks, dp.TIM1, dp.TIM3, dp.TIM8, clocks, dp.TIM1, dp.TIM3, dp.TIM8,
dp.GPIOA, dp.GPIOB, dp.GPIOC, dp.GPIOD, dp.GPIOE, dp.GPIOF, dp.GPIOG, dp.GPIOA, dp.GPIOB, dp.GPIOC, dp.GPIOD, dp.GPIOE, dp.GPIOF, dp.GPIOG,
dp.I2C1, dp.I2C1,
@ -151,7 +150,7 @@ fn main() -> ! {
} }
} }
let mut fan_ctrl = FanCtrl::new(fan, tacho, channels, &mut dp.EXTI, &mut dp.SYSCFG.constrain()); let mut fan_ctrl = FanCtrl::new(fan, channels);
// default net config: // default net config:
let mut ipv4_config = Ipv4Config { let mut ipv4_config = Ipv4Config {
@ -186,7 +185,7 @@ fn main() -> ! {
server.for_each(|_, session| session.set_report_pending(channel.into())); server.for_each(|_, session| session.set_report_pending(channel.into()));
} }
let fan_status = fan_ctrl.cycle(); fan_ctrl.cycle();
let instant = Instant::from_millis(i64::from(timer::now())); let instant = Instant::from_millis(i64::from(timer::now()));
cortex_m::interrupt::free(net::clear_pending); cortex_m::interrupt::free(net::clear_pending);
@ -239,12 +238,6 @@ fn main() -> ! {
} }
} }
} }
match fan_status {
Ok(_) => {}
Err(status) => {
send_line(&mut socket, status.fmt_u8());
}
};
} }
}); });
} else { } else {

View File

@ -33,7 +33,7 @@ use stm32_eth::EthPins;
use crate::{ use crate::{
channel::{Channel0, Channel1}, channel::{Channel0, Channel1},
leds::Leds, leds::Leds,
fan_ctrl::{TachoPin, FanPin} fan_ctrl::FanPin
}; };
const PWM_FREQ: KiloHertz = KiloHertz(20u32); const PWM_FREQ: KiloHertz = KiloHertz(20u32);
@ -131,7 +131,7 @@ impl Pins {
spi2: SPI2, spi4: SPI4, spi5: SPI5, spi2: SPI2, spi4: SPI4, spi5: SPI5,
adc1: ADC1, adc1: ADC1,
otg_fs_global: OTG_FS_GLOBAL, otg_fs_device: OTG_FS_DEVICE, otg_fs_pwrclk: OTG_FS_PWRCLK, otg_fs_global: OTG_FS_GLOBAL, otg_fs_device: OTG_FS_DEVICE, otg_fs_pwrclk: OTG_FS_PWRCLK,
) -> (Self, Leds, Eeprom, EthernetPins, USB, FanPin, TachoPin) { ) -> (Self, Leds, Eeprom, EthernetPins, USB, FanPin) {
let gpioa = gpioa.split(); let gpioa = gpioa.split();
let gpiob = gpiob.split(); let gpiob = gpiob.split();
let gpioc = gpioc.split(); let gpioc = gpioc.split();
@ -228,9 +228,9 @@ impl Pins {
hclk: clocks.hclk(), hclk: clocks.hclk(),
}; };
let fan = Timer::new(tim8, &clocks).pwm(gpioc.pc9.into_alternate(), 20u32.khz()); let fan = Timer::new(tim8, &clocks).pwm(gpioc.pc9.into_alternate(), PWM_FREQ);
(pins, leds, eeprom, eth_pins, usb, fan, gpioc.pc8) (pins, leds, eeprom, eth_pins, usb, fan)
} }
/// Configure the GPIO pins for SPI operation, and initialize SPI /// Configure the GPIO pins for SPI operation, and initialize SPI
@ -342,7 +342,7 @@ impl PwmPins {
PwmPins { PwmPins {
max_v0, max_v1, max_v0, max_v1,
max_i_pos0, max_i_pos1, max_i_pos0, max_i_pos1,
max_i_neg0, max_i_neg1 max_i_neg0, max_i_neg1,
} }
} }
} }