Compare commits

...

3 Commits

Author SHA1 Message Date
linuswck 4526536a48 Ignore packets of 0 bytes size 2024-03-01 11:31:06 +08:00
linuswck f488786e1c Use DMA to read Tec_I & Tec_V
- Remove the single conversion polling time with DMA
2024-03-01 11:31:01 +08:00
linuswck 3528d8a68f Update Python Test Scripts 2024-02-28 13:33:51 +08:00
8 changed files with 206 additions and 78 deletions

View File

@ -20,7 +20,11 @@ dfu_cmd = {
ld_cmd = {
"laser_diode_cmd": "SetI",
"data_f64": 0.0,
"data_f32": 0.0,
}
tec_clear_alarm = {
"thermostat_cmd": "ClearAlarm",
}
tec_power_down = {
@ -29,47 +33,47 @@ tec_power_down = {
tec_set_sh_t0_cmd = {
"thermostat_cmd": "SetShT0",
"data_f64": 25.0,
"data_f32": 25.0,
}
tec_set_sh_r0_cmd = {
"thermostat_cmd": "SetShR0",
"data_f64": 10.0 * 1000,
"data_f32": 10.0 * 1000,
}
tec_set_sh_beta_cmd = {
"thermostat_cmd": "SetShBeta",
"data_f64": 3900.0,
"data_f32": 3900.0,
}
tec_set_temperature_setpoint_cmd = {
"thermostat_cmd": "SetTemperatureSetpoint",
"data_f64": 25.0,
"data_f32": 30.0,
}
tec_set_pid_kp_cmd = {
"thermostat_cmd": "SetPidKp",
"data_f64": 0.10889684439011593
"data_f32": 0.14398316474562461
}
tec_set_pid_ki_cmd = {
"thermostat_cmd": "SetPidKi",
"data_f64": 0.0038377132059211646
"data_f32": 0.004117762308816449
}
tec_set_pid_kd_cmd = {
"thermostat_cmd": "SetPidKd",
"data_f64": 0.22294449514406328
"data_f32": 0.36324599631515664
}
tec_set_pid_out_min_cmd = {
"thermostat_cmd": "SetPidOutMin",
"data_f64": -1.0,
"data_f32": -1.0,
}
tec_set_pid_out_max_cmd = {
"thermostat_cmd": "SetPidOutMax",
"data_f64": 1.0,
"data_f32": 1.0,
}
tec_power_up = {
@ -80,8 +84,21 @@ tec_pid_engage = {
"thermostat_cmd": "SetPidEngage",
}
tec_get_tec_status = {
"thermostat_cmd": "GetTecStatus",
kirdy_get_status_report = {
"device_cmd": "GetStatusReport",
}
kirdy_report_mode_cmd = {
"device_cmd": "SetActiveReportMode",
"data_bool": True,
}
temp_adc_config = {
"thermostat_cmd": "ConfigTempAdcFilter",
"temp_adc_filter": {
"filter_type": "Sinc5Sinc1With50hz60HzRejection",
"sinc5sinc1postfilter": "F16SPS"
}
}
def send_cmd(input, socket):
@ -89,15 +106,20 @@ def send_cmd(input, socket):
# Give some time for Kirdy to process the cmd
time.sleep(0.5)
def read_cmd(input, socket):
socket.send(bytes(json.dumps(input), "UTF-8"))
data = socket.recv(1024).decode('utf8')
return json.loads(data)
def poll_status_report(socket):
while True:
data = socket.recv(1024).decode('utf8')
try:
json_data = json.loads(data)
break
except json.decoder.JSONDecodeError:
pass
return json_data
s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
def signal_handler(sig, frame):
ld_cmd["data_f64"] = 0.0
ld_cmd["data_f32"] = 0.0
send_cmd(ld_cmd, s)
send_cmd(tec_power_down, s)
s.close()
@ -116,10 +138,12 @@ with socket.socket(socket.AF_INET, socket.SOCK_STREAM) as s:
send_cmd(tec_set_pid_kp_cmd, s)
send_cmd(tec_set_pid_ki_cmd, s)
send_cmd(tec_set_pid_kd_cmd, s)
send_cmd(tec_clear_alarm, s)
send_cmd(temp_adc_config, s)
send_cmd(tec_pid_engage, s)
send_cmd(tec_power_up, s)
send_cmd(kirdy_report_mode_cmd, s)
while True:
tec_status = read_cmd(tec_get_tec_status, s)
print(f"Ts: {tec_status['ts']} | Temperature: {tec_status['temperature'] - 273.15}")
s.close()
status_report = poll_status_report(s)
print(f"Ts: {status_report['ts']} | Temperature: {status_report['tec']['temperature'] - 273.15}")

View File

@ -227,6 +227,10 @@ tec_power_down = {
"thermostat_cmd": "PowerDown",
}
kirdy_get_status_report = {
"device_cmd": "GetStatusReport",
}
tec_get_tec_status = {
"thermostat_cmd": "GetTecStatus",
}
@ -236,8 +240,7 @@ tec_pid_dis_engage = {
}
tec_set_i_out = {
"thermostat_cmd": "SetTecIOut",
"data_f64": 0.0,
"tec_set_i": 0.0,
}
# Kirdy IP and Port Number
@ -284,21 +287,22 @@ def main():
send_cmd(tec_power_up, s)
while True:
tec_status = read_cmd(tec_get_tec_status, s)
status_report = read_cmd(kirdy_get_status_report, s)
temperature = tec_status["temperature"] - 273.15
ts = tec_status['ts']
temperature = status_report["tec"]["temperature"] - 273.15
print(temperature)
ts = status_report['ts']
if (tuner.run(temperature, ts / 1000.0)):
break
tuner_out = tuner.output()
tec_set_i_out["data_f64"] = float(tuner_out * 1000.0)
tec_set_i_out["tec_set_i"] = float(tuner_out * 1000.0)
send_cmd(tec_set_i_out, s)
tec_set_i_out["data_f64"] = 0.0
tec_set_i_out["tec_set_i"] = 0.0
send_cmd(tec_power_down, s)
s.close()

View File

@ -63,7 +63,7 @@ pub fn bootup(
usb::State::setup(usb);
debug!("Setting up TEC");
let tec_driver = MAX1968::new(max1968_phy, perif.ADC1);
let tec_driver = MAX1968::new(max1968_phy, perif.ADC1, perif.ADC2, perif.DMA2);
let mut thermostat = Thermostat::new(tec_driver, ad7172_phy);
thermostat.setup();
thermostat.power_up();
@ -72,7 +72,7 @@ pub fn bootup(
debug!("Setting up Laser Driver");
let current_source = LdCtrl::new(current_source_phy);
let mut laser = LdDrive::new(current_source, perif.ADC2, perif.TIM2.counter(&clocks), pd_mon_phy);
let mut laser = LdDrive::new(current_source, perif.ADC3, perif.TIM2.counter(&clocks), pd_mon_phy);
laser.setup();
laser.ld_open();
laser.ld_set_i(ElectricCurrent::new::<ampere>(0.0));

View File

@ -1,6 +1,6 @@
use miniconf::Tree;
use stm32f4xx_hal::timer::CounterUs;
use stm32f4xx_hal::pac::{ADC2, TIM2};
use stm32f4xx_hal::pac::{ADC3, TIM2};
use uom::si::electric_current::ampere;
use uom::si::power::milliwatt;
use crate::laser_diode::ld_ctrl::{LdCtrl, Impedance};
@ -85,7 +85,7 @@ pub struct LdDrive{
}
impl LdDrive{
pub fn new(current_source: LdCtrl, pins_adc: ADC2, tim2: CounterUs<TIM2>, phy: ld_pwr_exc_protector::LdPwrExcProtectorPhy)-> Self {
pub fn new(current_source: LdCtrl, pins_adc: ADC3, tim2: CounterUs<TIM2>, phy: ld_pwr_exc_protector::LdPwrExcProtectorPhy)-> Self {
LdPwrExcProtector::setup(pins_adc, phy);
LdCurrentOutCtrlTimer::setup(tim2);

View File

@ -1,7 +1,7 @@
use stm32f4xx_hal::pac;
use stm32f4xx_hal::rcc::Enable;
use stm32f4xx_hal::{
pac::{ADC2, NVIC},
pac::{ADC3, NVIC},
gpio::{Analog, Output, PushPull, gpioa::PA3, gpiod::PD9},
interrupt,
};
@ -45,7 +45,7 @@ impl Default for Status {
}
pub struct LdPwrExcProtector {
pac: ADC2,
pac: ADC3,
phy: LdPwrExcProtectorPhy,
alarm_status: Status,
calibrated_vdda: u32,
@ -55,13 +55,13 @@ impl LdPwrExcProtector {
/// ADC Analog Watchdog is configured to guard a single regular Adc channel on Pd Mon Pin.
/// ADC is configured to start continuous conversion without using DMA immediately.
/// Interrupt is disabled by default.
pub fn setup(pac_adc: ADC2, mut phy: LdPwrExcProtectorPhy){
pub fn setup(pac_adc: ADC3, mut phy: LdPwrExcProtectorPhy){
unsafe {
// All ADCs share the same reset interface.
// NOTE(unsafe) this reference will only be used for atomic writes with no side effects.
let rcc = &(*pac::RCC::ptr());
// Enable the ADC2 Clock
pac::ADC2::enable(rcc);
// Enable the ADC3 Clock
pac::ADC3::enable(rcc);
// Enable ADC Interrupt
NVIC::unmask(interrupt::ADC);
}

View File

@ -13,7 +13,7 @@ use device::{boot::bootup, log_setup, sys_timer};
use uom::fmt::DisplayStyle::Abbreviation;
use uom::si::electric_potential::volt;
use uom::si::electric_current::{ampere, milliampere};
use uom::si::f64::{ElectricPotential, ElectricCurrent};
use uom::si::f32::{ElectricPotential, ElectricCurrent};
use stm32f4xx_hal::pac::SCB;
// If RTT is used, print panic info through RTT
@ -89,10 +89,12 @@ fn main() -> ! {
if !should_reset {
let mut eth_is_pending = false;
let mut has_temp_reading = false;
laser.poll_and_update_output_current();
if thermostat.poll_adc() {
has_temp_reading = true;
thermostat.update_pid();
if thermostat.get_temp_mon_status().over_temp_alarm {
laser.power_down();
@ -100,17 +102,17 @@ fn main() -> ! {
thermostat.power_down();
}
info!("curr_dac_vfb: {:?}", volt_fmt.with(thermostat.get_dac_vfb()));
info!("curr_vref: {:?}", volt_fmt.with(thermostat.get_vref()));
info!("curr_tec_i: {:?}", amp_fmt.with(thermostat.get_tec_i()));
info!("curr_tec_v: {:?}", volt_fmt.with(thermostat.get_tec_v()));
// info!("curr_dac_vfb: {:?}", volt_fmt.with(thermostat.get_dac_vfb()));
// info!("curr_vref: {:?}", volt_fmt.with(thermostat.get_vref()));
// info!("curr_tec_i: {:?}", amp_fmt.with(thermostat.get_tec_i()));
// info!("curr_tec_v: {:?}", volt_fmt.with(thermostat.get_tec_v()));
info!("curr_ld_drive_cuurent: {:?}", milli_amp_fmt.with(laser.get_ld_drive_current()));
// info!("curr_ld_drive_cuurent: {:?}", milli_amp_fmt.with(laser.get_ld_drive_current()));
info!("pd_mon_v: {:?}", volt_fmt.with(laser.pd_mon_status().v));
info!("power_excursion: {:?}", laser.pd_mon_status().pwr_excursion);
// info!("pd_mon_v: {:?}", volt_fmt.with(laser.pd_mon_status().v));
// info!("power_excursion: {:?}", laser.pd_mon_status().pwr_excursion);
info!("Termination Status: {:?}", laser.get_term_status());
// info!("Termination Status: {:?}", laser.get_term_status());
if net::net::eth_is_socket_active() {
if device_settings.report_readings {
@ -134,10 +136,16 @@ fn main() -> ! {
net::net::clear_pending(cs);
});
let bytes = net::net::eth_recv(&mut ETH_DATA_BUFFER);
debug!("Number of bytes recv: {:?}", bytes);
(laser, thermostat, should_reset, device_settings) = net::cmd_handler::execute_cmd(&mut ETH_DATA_BUFFER, bytes, laser, thermostat, device_settings);
if bytes != 0 {
info!("Ts: {:?}", sys_timer::now());
debug!("Number of bytes recv: {:?}", bytes);
(laser, thermostat, should_reset, device_settings) = net::cmd_handler::execute_cmd(&mut ETH_DATA_BUFFER, bytes, laser, thermostat, device_settings);
}
}
}
if has_temp_reading {
thermostat.start_tec_readings_conversion();
}
}
else {
device_settings.report_readings = false;

View File

@ -1,16 +1,15 @@
use core::u16;
use crate::thermostat::ad5680;
use fugit::KilohertzU32;
use stm32_eth::stm32::{ADC2, DMA2};
use stm32f4xx_hal::{
adc::{
config::{self, AdcConfig},
Adc,
},
adc::{config::{self, AdcConfig}, Adc},
dma::{config::DmaConfig, PeripheralToMemory, Stream2, StreamsTuple, Transfer as DMA_Transfer},
gpio::{gpioa::*, gpiob::*, gpioc::*, Alternate, Analog, Output, PushPull},
hal::{self, blocking::spi::Transfer, digital::v2::OutputPin},
pac::{ADC1, SPI1, TIM4},
spi::{NoMiso, Spi, TransferModeNormal},
timer::pwm::PwmChannel,
timer::pwm::PwmChannel
};
use uom::si::{
@ -77,9 +76,9 @@ type DacSpi = Spi<SPI1, (PB3<Alternate<5>>, NoMiso, PB5<Alternate<5>>), Transfer
type DacSync = PB4<Output<PushPull>>;
pub struct MAX1968 {
// settings
pub phy: MAX1968Phy<Channel0>,
pub pins_adc: Adc<ADC1>,
pub dma_adc: DMA_Transfer<Stream2<DMA2>, 1, Adc<ADC2>, PeripheralToMemory, &'static mut [u16; 16]>,
}
pub enum PwmPinsEnum {
@ -88,6 +87,7 @@ pub enum PwmPinsEnum {
MaxNegI,
}
#[allow(unused)]
pub enum AdcReadTarget {
VREF,
DacVfb,
@ -111,21 +111,96 @@ impl<C: ChannelPins> MAX1968Phy<C> {
}
}
static mut ADC2_FIRST_BUFFER : [u16; 16] = [0; 16];
static mut ADC2_LOCAL_BUFFER : [u16; 16] = [0; 16];
impl MAX1968 {
pub fn new(phy_ch0: MAX1968Phy<Channel0>, adc1: ADC1) -> Self {
let config = AdcConfig::default()
pub fn new(phy_ch0: MAX1968Phy<Channel0>, adc1: ADC1, adc2: ADC2, dma2: DMA2) -> Self {
let adc_config = AdcConfig::default()
.clock(config::Clock::Pclk2_div_8)
.default_sample_time(config::SampleTime::Cycles_480);
// Do not set reset RCCs as it causes other ADCs' clock to be disabled
let mut pins_adc = Adc::adc1(adc1, false, config);
pins_adc.calibrate();
let mut pins_adc1 = Adc::adc1(adc1, false, adc_config);
pins_adc1.calibrate();
let adc_config = AdcConfig::default()
.clock(config::Clock::Pclk2_div_8)
.default_sample_time(config::SampleTime::Cycles_480)
.dma(config::Dma::Continuous)
.scan(config::Scan::Enabled)
.reference_voltage(pins_adc1.reference_voltage());
let dma_config = DmaConfig::default()
.transfer_complete_interrupt(true)
.memory_increment(true)
.double_buffer(false);
let mut pins_adc2 = Adc::adc2(adc2, false, adc_config);
pins_adc2.configure_channel(&phy_ch0.itec_pin, config::Sequence::One, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.vtec_pin, config::Sequence::Two, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.itec_pin, config::Sequence::Three, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.vtec_pin, config::Sequence::Four, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.itec_pin, config::Sequence::Five, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.vtec_pin, config::Sequence::Six, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.itec_pin, config::Sequence::Seven, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.vtec_pin, config::Sequence::Eight, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.itec_pin, config::Sequence::Nine, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.vtec_pin, config::Sequence::Ten, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.itec_pin, config::Sequence::Eleven, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.vtec_pin, config::Sequence::Twelve, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.itec_pin, config::Sequence::Thirteen, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.vtec_pin, config::Sequence::Fourteen, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.itec_pin, config::Sequence::Fifteen, config::SampleTime::Cycles_480);
pins_adc2.configure_channel(&phy_ch0.vtec_pin, config::Sequence::Sixteen, config::SampleTime::Cycles_480);
let dma = StreamsTuple::new(dma2);
let dma_adc : DMA_Transfer<Stream2<DMA2>, 1, Adc<ADC2>, PeripheralToMemory, &'static mut [u16; 16]>;
unsafe {
dma_adc = DMA_Transfer::init_peripheral_to_memory(dma.2, pins_adc2, &mut ADC2_FIRST_BUFFER, None, dma_config);
}
MAX1968 {
phy: phy_ch0,
pins_adc: pins_adc,
pins_adc: pins_adc1,
dma_adc: dma_adc,
}
}
pub fn dma_adc_start_conversion(&mut self){
self.dma_adc.clear_interrupts();
self.dma_adc.start(|adc| {
adc.clear_end_of_conversion_flag();
adc.start_conversion();
});
}
pub fn get_tec_readings(&mut self) -> (ElectricPotential, ElectricPotential) {
self.dma_adc.clear_interrupts();
let buffer: &[u16; 16];
unsafe{
(buffer, _) = self.dma_adc
.next_transfer(&mut ADC2_LOCAL_BUFFER)
.unwrap();
}
let sample_to_millivolts = self.dma_adc.peripheral().make_sample_to_millivolts();
let mut itec: u16 = 0;
for data in buffer.into_iter().step_by(2){
itec += *data;
}
itec = itec >> 3;
let mut vtec: u16 = 0;
for data in buffer.into_iter().skip(1).step_by(2){
vtec += *data;
}
vtec = vtec >> 3;
unsafe {
ADC2_LOCAL_BUFFER = *buffer;
}
(ElectricPotential::new::<millivolt>(sample_to_millivolts(vtec) as f32), ElectricPotential::new::<millivolt>(sample_to_millivolts(itec) as f32))
}
// Return the calibrated VDDA Voltage
// Can be used to set reference voltage for other ADC
pub fn get_calibrated_vdda(&mut self) -> u32 {

View File

@ -1,4 +1,4 @@
use core::f64::NAN;
use core::f32::NAN;
use core::marker::PhantomData;
use crate::sys_timer;
use crate::thermostat::ad5680;
@ -34,6 +34,7 @@ pub struct TecSettings {
pub max_i_pos_set: ElectricCurrent,
pub max_i_neg_set: ElectricCurrent,
pub i_set: ElectricCurrent,
pub vref: ElectricPotential,
}
impl TecSettings{
@ -96,6 +97,7 @@ impl Default for TecSettings {
max_i_pos_set: ElectricCurrent::new::<ampere>(1.0),
max_i_neg_set: ElectricCurrent::new::<ampere>(1.0),
i_set: ElectricCurrent::new::<ampere>(0.0),
vref: ElectricPotential::new::<volt>(1.5),
}
}
}
@ -133,6 +135,13 @@ impl Thermostat{
self.pid_ctrl_ch0.set_adc_calibration(t_adc_ch0_cal) ;
}
/// start_tec_readings_conversion() should not be called before the current
/// DMA request is serviced or the conversion process will be restarted
/// Thus, no new readings is available when you call get_tec_readings() fn
pub fn start_tec_readings_conversion(&mut self){
self.max1968.dma_adc_start_conversion();
}
fn tec_setup(&mut self) {
self.power_down();
@ -232,23 +241,31 @@ impl Thermostat{
self.tec_settings.max_i_neg_set
}
pub fn get_dac_vfb(&mut self) -> ElectricPotential {
ElectricPotential::new::<volt>(NAN)
// self.max1968.adc_read(AdcReadTarget::DacVfb, 16)
#[allow(unused)]
fn get_dac_vfb(&mut self) -> ElectricPotential {
self.max1968.adc_read(AdcReadTarget::DacVfb, 16)
}
pub fn get_vref(&mut self) -> ElectricPotential {
// ElectricPotential::new::<volt>(NAN)
self.max1968.adc_read(AdcReadTarget::VREF, 1)
#[allow(unused)]
fn get_vref(&mut self) -> ElectricPotential {
self.max1968.adc_read(AdcReadTarget::VREF, 16)
}
#[allow(unused)]
pub fn get_tec_i(&mut self) -> ElectricCurrent {
let vref = self.get_vref();
(self.max1968.adc_read(AdcReadTarget::ITec, 1) - vref) / ElectricalResistance::new::<ohm>(0.4)
let vref = self.max1968.adc_read(AdcReadTarget::VREF, 16);
(self.max1968.adc_read(AdcReadTarget::ITec, 16) - vref) / ElectricalResistance::new::<ohm>(0.4)
}
#[allow(unused)]
pub fn get_tec_v(&mut self) -> ElectricPotential {
(self.max1968.adc_read(AdcReadTarget::VTec, 1) - TecSettings::TEC_VSEC_BIAS_V) * 4.0
(self.max1968.adc_read(AdcReadTarget::VTec, 16) - TecSettings::TEC_VSEC_BIAS_V) * 4.0
}
pub fn get_tec_readings(&mut self) -> (ElectricPotential, ElectricCurrent) {
let vref = self.tec_settings.vref;
let (vtec, itec) = self.max1968.get_tec_readings();
((vtec - TecSettings::TEC_VSEC_BIAS_V) * 4.0, (itec - vref) / ElectricalResistance::new::<ohm>(0.4))
}
/// Calibrates the DAC output to match vref of the MAX driver to reduce zero-current offset of the MAX driver output.
@ -293,6 +310,7 @@ impl Thermostat{
prev_value = value;
}
}
self.tec_settings.vref = target_voltage;
}
pub fn set_pid_engaged(&mut self, val: bool) {
@ -304,14 +322,14 @@ impl Thermostat{
}
pub fn get_status_report(&mut self) -> StatusReport {
let (tec_v, tec_i) = self.get_tec_readings();
StatusReport {
pid_engaged: self.get_pid_engaged(),
temp_mon_status: self.temp_mon.get_status(),
temperature: self.pid_ctrl_ch0.get_temperature(),
i_set: self.tec_settings.i_set,
tec_i: self.get_tec_i(),
tec_v: self.get_tec_v(),
tec_vref: self.get_vref(),
tec_i: tec_i,
tec_v: tec_v,
}
}
@ -424,7 +442,6 @@ pub struct StatusReport {
i_set: ElectricCurrent,
tec_i: ElectricCurrent,
tec_v: ElectricPotential,
tec_vref: ElectricPotential,
}
#[derive(Deserialize, Serialize, Copy, Clone, Debug, Tree)]