Make hwrev to be settings provider

Signed-off-by: Egor Savkin <es@m-labs.hk>
This commit is contained in:
Egor Savkin 2023-03-21 17:33:22 +08:00
parent 2c9436a0b3
commit afdab2f025
7 changed files with 126 additions and 83 deletions

View File

@ -129,7 +129,7 @@ formatted as line-delimited JSON.
| `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 |
| `hwrev` | Show hardware revision, and settings related to it |
## USB

View File

@ -347,12 +347,16 @@ impl Handler {
}
fn set_fan(socket: &mut TcpSocket, fan_pwm: u32, fan_ctrl: &mut FanCtrl) -> Result<Handler, Error> {
if !fan_ctrl.fan_available() {
send_line(socket, b"{ \"warning\": \"this thermostat doesn't have fan!\" }");
return Ok(Handler::Handled);
}
fan_ctrl.set_auto_mode(false);
fan_ctrl.set_pwm(fan_pwm);
if fan_ctrl.is_default_auto() {
if fan_ctrl.fan_pwm_recommended() {
send_line(socket, b"{}");
} else {
send_line(socket, b"{ \"warning\": \"this fan doesn't have full PWM support. Use it on your own risk!\" }");
send_line(socket, b"{ \"warning\": \"this fan doesn't have full PWM support. Use it at your own risk!\" }");
}
Ok(Handler::Handled)
}
@ -372,11 +376,15 @@ impl Handler {
}
fn fan_auto(socket: &mut TcpSocket, fan_ctrl: &mut FanCtrl) -> Result<Handler, Error> {
if !fan_ctrl.fan_available() {
send_line(socket, b"{ \"warning\": \"this thermostat doesn't have fan!\" }");
return Ok(Handler::Handled);
}
fan_ctrl.set_auto_mode(true);
if fan_ctrl.is_default_auto() {
if fan_ctrl.fan_pwm_recommended() {
send_line(socket, b"{}");
} else {
send_line(socket, b"{ \"warning\": \"this fan doesn't have full PWM support. Use it on your own risk!\" }");
send_line(socket, b"{ \"warning\": \"this fan doesn't have full PWM support. Use it at your own risk!\" }");
}
Ok(Handler::Handled)
}

View File

@ -549,7 +549,6 @@ fn fan(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
Ok((input, Ok(Command::FanSet { fan_pwm: value.unwrap_or(0)})))
},
))(input)?;
let (input, _) = end(input)?;
Ok((input, result))
},
value(Ok(Command::ShowFan), end)
@ -572,7 +571,6 @@ 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)?;
let (input, _) = end(input)?;
if k_a.is_ok() && k_b.is_ok() && k_c.is_ok() {
Ok((input, Ok(Command::FanCurve { k_a: k_a.unwrap() as f32, k_b: k_b.unwrap() as f32, k_c: k_c.unwrap() as f32 })))
} else {
@ -580,7 +578,6 @@ fn fan_curve(input: &[u8]) -> IResult<&[u8], Result<Command, Error>> {
}
},
))(input)?;
let (input, _) = end(input)?;
Ok((input, result))
},
value(Err(Error::Incomplete), end)

View File

@ -6,7 +6,7 @@ use stm32f4xx_hal::{
};
use crate::{
hw_rev::HWRev,
hw_rev::HWSettings,
command_handler::JsonBuffer,
};
@ -17,43 +17,32 @@ const MAX_TEC_I: f32 = 3.0;
const MAX_USER_FAN_PWM: f32 = 100.0;
const MIN_USER_FAN_PWM: f32 = 1.0;
const MAX_FAN_PWM: f32 = 1.0;
// below this value motor's autostart feature may fail
const MIN_FAN_PWM: f32 = 0.04;
const DEFAULT_K_A: f32 = 1.0;
const DEFAULT_K_B: f32 = 0.0;
const DEFAULT_K_C: f32 = 0.0;
pub struct FanCtrl {
fan: FanPin,
fan: Option<FanPin>,
fan_auto: bool,
available: bool,
default_auto: bool,
pwm_enabled: bool,
k_a: f32,
k_b: f32,
k_c: f32,
abs_max_tec_i: f32,
hw_settings: HWSettings,
}
impl FanCtrl {
pub fn new(fan: FanPin, hwrev: HWRev) -> Self {
let available = hwrev.fan_available();
let default_auto = hwrev.fan_default_auto();
pub fn new(fan: Option<FanPin>, hw_settings: HWSettings) -> Self {
let mut fan_ctrl = FanCtrl {
fan,
available,
// do not enable auto mode by default,
// but allow to turn it on on user's own risk
default_auto,
fan_auto: default_auto,
// but allow to turn it at the user's own risk
fan_auto: hw_settings.fan_pwm_recommended,
pwm_enabled: false,
k_a: DEFAULT_K_A,
k_b: DEFAULT_K_B,
k_c: DEFAULT_K_C,
k_a: hw_settings.fan_k_a,
k_b: hw_settings.fan_k_b,
k_c: hw_settings.fan_k_c,
abs_max_tec_i: 0f32,
hw_settings,
};
if fan_ctrl.fan_auto {
fan_ctrl.enable_pwm();
@ -63,11 +52,16 @@ impl FanCtrl {
pub fn cycle(&mut self, abs_max_tec_i: f32) {
self.abs_max_tec_i = abs_max_tec_i;
self.adjust_speed();
if self.fan_auto && self.hw_settings.fan_available {
let scaled_current = self.abs_max_tec_i / MAX_TEC_I;
// do not limit upper bound, as it will be limited in the set_pwm()
let pwm = (MAX_USER_FAN_PWM * (scaled_current * (scaled_current * self.k_a + self.k_b) + self.k_c)) as u32;
self.set_pwm(pwm);
}
}
pub fn summary(&mut self) -> Result<JsonBuffer, serde_json_core::ser::Error> {
if self.available {
if self.hw_settings.fan_available {
let summary = FanSummary {
fan_pwm: self.get_pwm(),
abs_max_tec_i: self.abs_max_tec_i,
@ -83,15 +77,6 @@ impl FanCtrl {
}
}
pub fn adjust_speed(&mut self) {
if self.fan_auto && self.available {
let scaled_current = self.abs_max_tec_i / MAX_TEC_I;
// do not limit upper bound, as it will be limited in the set_pwm()
let pwm = (MAX_USER_FAN_PWM * (scaled_current * (scaled_current * self.k_a + self.k_b) + self.k_c)) as u32;
self.set_pwm(pwm);
}
}
pub fn set_auto_mode(&mut self, fan_auto: bool) {
self.fan_auto = fan_auto;
}
@ -103,44 +88,58 @@ impl FanCtrl {
}
pub fn restore_defaults(&mut self) {
self.set_curve(DEFAULT_K_A, DEFAULT_K_B, DEFAULT_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.pwm_enabled {
self.enable_pwm()
if self.fan.is_none() || (!self.pwm_enabled && !self.enable_pwm()) {
return 0f32;
}
let fan = self.fan.as_mut().unwrap();
let fan_pwm = fan_pwm.min(MAX_USER_FAN_PWM as u32).max(MIN_USER_FAN_PWM as u32);
let duty = Self::scale_number(fan_pwm as f32, MIN_FAN_PWM, MAX_FAN_PWM, MIN_USER_FAN_PWM, MAX_USER_FAN_PWM);
let max = self.fan.get_max_duty();
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);
self.fan.set_duty(value);
fan.set_duty(value);
value as f32 / (max as f32)
}
pub fn is_default_auto(&self) -> bool {
self.default_auto
pub fn fan_pwm_recommended(&self) -> bool {
self.hw_settings.fan_pwm_recommended
}
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
pub fn fan_available(&self) -> bool {
self.hw_settings.fan_available
}
fn get_pwm(&self) -> u32 {
let duty = self.fan.get_duty();
let max = self.fan.get_max_duty();
Self::scale_number(duty as f32 / (max as f32), MIN_USER_FAN_PWM, MAX_USER_FAN_PWM, MIN_FAN_PWM, MAX_FAN_PWM).round() as u32
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 }
}
fn enable_pwm(&mut self) {
if self.available {
self.fan.set_duty(0);
self.fan.enable();
fn enable_pwm(&mut self) -> bool {
if self.fan.is_some() && self.hw_settings.fan_available {
let fan = self.fan.as_mut().unwrap();
fan.set_duty(0);
fan.enable();
self.pwm_enabled = true;
true
} else {
false
}
}
}
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
}
#[derive(Serialize)]
pub struct FanSummary {
fan_pwm: u32,

View File

@ -2,7 +2,7 @@ use serde::Serialize;
use crate::{
pins::HWRevPins,
command_handler::JsonBuffer
command_handler::JsonBuffer,
};
#[derive(Serialize, Copy, Clone)]
@ -11,6 +11,23 @@ pub struct HWRev {
pub minor: u8,
}
#[derive(Serialize, Clone)]
pub struct HWSettings {
pub fan_k_a: f32,
pub fan_k_b: f32,
pub fan_k_c: f32,
pub min_fan_pwm: f32,
pub max_fan_pwm: f32,
pub fan_pwm_freq_hz: u32,
pub fan_available: bool,
pub fan_pwm_recommended: bool,
}
#[derive(Serialize, Clone)]
struct HWSummary<'a> {
rev: &'a HWRev,
settings: &'a HWSettings,
}
impl HWRev {
pub fn detect_hw_rev(hwrev_pins: &HWRevPins) -> Self {
@ -24,18 +41,42 @@ impl HWRev {
}
}
pub fn fan_available(&self) -> bool {
self.major == 2 && self.minor == 2
}
pub fn fan_default_auto(&self) -> bool {
pub fn settings(&self) -> HWSettings {
match (self.major, self.minor) {
(2, 2) => HWSettings {
fan_k_a: 1.0,
fan_k_b: 0.0,
fan_k_c: 0.0,
// below this value motor's autostart feature may fail,
// according to internal experiments
min_fan_pwm: 0.04,
max_fan_pwm: 1.0,
// According to `SUNON DC Brushless Fan & Blower(255-E)` catalogue p.36-37
// model MF35101V1-1000U-G99 doesn't have a PWM wire, but we'll follow their others models'
// recommended frequency, as it is said by the Thermostat's schematics that we can
// use PWM, but not stated at which frequency
fan_pwm_freq_hz: 25_000,
fan_available: true,
// see https://github.com/sinara-hw/Thermostat/issues/115 and
// https://git.m-labs.hk/M-Labs/thermostat/issues/69#issuecomment-6464 for explanation
self.fan_available() && self.minor != 2
fan_pwm_recommended: false,
},
(_, _) => HWSettings {
fan_k_a: 0.0,
fan_k_b: 0.0,
fan_k_c: 0.0,
min_fan_pwm: 0.0,
max_fan_pwm: 0.0,
fan_pwm_freq_hz: 0,
fan_available: false,
fan_pwm_recommended: false,
}
}
}
pub fn summary(&self) -> Result<JsonBuffer, serde_json_core::ser::Error> {
serde_json_core::to_vec(&self)
let settings = self.settings();
let summary = HWSummary { rev: self, settings: &settings };
serde_json_core::to_vec(&summary)
}
}

View File

@ -56,7 +56,6 @@ use command_handler::Handler;
mod fan_ctrl;
use fan_ctrl::FanCtrl;
mod hw_rev;
use hw_rev::HWRev;
const HSE: MegaHertz = MegaHertz(8);
#[cfg(not(feature = "semihosting"))]
@ -121,7 +120,7 @@ fn main() -> ! {
timer::setup(cp.SYST, clocks);
let (pins, mut leds, mut eeprom, eth_pins, usb, fan) = Pins::setup(
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,
dp.I2C1,
@ -140,8 +139,6 @@ fn main() -> ! {
let mut store = flash_store::store(dp.FLASH);
let hwrev = HWRev::detect_hw_rev(&pins.hwrev);
let mut channels = Channels::new(pins);
for c in 0..CHANNELS {
match store.read_value::<ChannelConfig>(CHANNEL_CONFIG_KEY[c]) {
@ -154,7 +151,7 @@ fn main() -> ! {
}
}
let mut fan_ctrl = FanCtrl::new(fan, hwrev);
let mut fan_ctrl = FanCtrl::new(fan, hw_settings);
// default net config:
let mut ipv4_config = Ipv4Config {

View File

@ -33,7 +33,8 @@ use stm32_eth::EthPins;
use crate::{
channel::{Channel0, Channel1},
leds::Leds,
fan_ctrl::FanPin
fan_ctrl::FanPin,
hw_rev::{HWRev, HWSettings},
};
pub type Eeprom = Eeprom24x<
@ -116,7 +117,6 @@ pub struct Pins {
pub pwm: PwmPins,
pub channel0: ChannelPinSet<Channel0>,
pub channel1: ChannelPinSet<Channel1>,
pub hwrev: HWRevPins
}
impl Pins {
@ -129,7 +129,7 @@ impl Pins {
spi2: SPI2, spi4: SPI4, spi5: SPI5,
adc1: ADC1,
otg_fs_global: OTG_FS_GLOBAL, otg_fs_device: OTG_FS_DEVICE, otg_fs_pwrclk: OTG_FS_PWRCLK,
) -> (Self, Leds, Eeprom, EthernetPins, USB, FanPin) {
) -> (Self, Leds, Eeprom, EthernetPins, USB, Option<FanPin>, HWRev, HWSettings) {
let gpioa = gpioa.split();
let gpiob = gpiob.split();
let gpioc = gpioc.split();
@ -196,10 +196,12 @@ impl Pins {
pwm,
channel0,
channel1,
hwrev: HWRevPins {hwrev0: gpiod.pd0, hwrev1: gpiod.pd1,
hwrev2: gpiod.pd2, hwrev3: gpiod.pd3}
};
let hwrev = HWRev::detect_hw_rev(&HWRevPins {hwrev0: gpiod.pd0, hwrev1: gpiod.pd1,
hwrev2: gpiod.pd2, hwrev3: gpiod.pd3});
let hw_settings = hwrev.settings();
let leds = Leds::new(gpiod.pd9, gpiod.pd10.into_push_pull_output(), gpiod.pd11.into_push_pull_output());
let eeprom_scl = gpiob.pb8.into_alternate().set_open_drain();
@ -226,12 +228,11 @@ impl Pins {
hclk: clocks.hclk(),
};
// According to `SUNON DC Brushless Fan & Blower(255-E)` catalogue p.36-37
// model MF35101V1-1000U-G99 doesn't have a PWM wire, so it is advised to have
// higher frequency to have less audible noise.
let fan = Timer::new(tim8, &clocks).pwm(gpioc.pc9.into_alternate(), 25u32.khz());
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 };
(pins, leds, eeprom, eth_pins, usb, fan)
(pins, leds, eeprom, eth_pins, usb, fan, hwrev, hw_settings)
}
/// Configure the GPIO pins for SPI operation, and initialize SPI