Merge remote-tracking branch 'origin/master' into rj/itcm

* origin/master: (34 commits)
  Simplifying unit conversions
  Cleaning up conversion + comments
  Addressing review feedback
  Update src/hardware/dac.rs
  Renaming AdcSample -> AdcCode
  Updating float conversion
  Adding adc/dac code conversion utilities
  Simplifying settings lock
  Updating after review
  Updating delay
  Fixing merge
  Formatting
  Updating dependencies
  Fixing clippy
  Finalizing merge
  Merging lockin app functions
  Fixing system timer
  Fixing build, formatting
  Adding documentation
  Renaming files
  ...
master
Robert Jördens 2021-05-10 17:00:57 +02:00
commit 66184ca089
15 changed files with 836 additions and 168 deletions

16
Cargo.lock generated
View File

@ -429,7 +429,7 @@ dependencies = [
[[package]]
name = "minimq"
version = "0.2.0"
source = "git+https://github.com/quartiq/minimq.git?rev=b3f364d#b3f364d55dea35da6572f78ddb91c87bfbb453bf"
source = "git+https://github.com/quartiq/minimq.git?rev=d2ec3e8#d2ec3e8351fa403ea96defd98c0b4410cbaa18a4"
dependencies = [
"bit_field",
"embedded-nal",
@ -705,6 +705,16 @@ dependencies = [
"syn",
]
[[package]]
name = "shared-bus"
version = "0.2.2"
source = "registry+https://github.com/rust-lang/crates.io-index"
checksum = "78b60428415b23ed3f0e3abc776e10e548cf2cbb4288e73d5d181a02b5a90b95"
dependencies = [
"cortex-m 0.6.7",
"embedded-hal",
]
[[package]]
name = "smoltcp"
version = "0.7.1"
@ -719,7 +729,7 @@ dependencies = [
[[package]]
name = "smoltcp-nal"
version = "0.1.0"
source = "git+https://github.com/quartiq/smoltcp-nal.git?rev=8468f11#8468f11abacd7aba82454e6904df19c1d1ab91bb"
source = "git+https://github.com/quartiq/smoltcp-nal.git?rev=4a1711c#4a1711c54cdf79f5ee8c1c99a1e8984f5944270c"
dependencies = [
"embedded-nal",
"heapless 0.6.1",
@ -751,6 +761,8 @@ dependencies = [
"panic-semihosting",
"paste",
"serde",
"serde-json-core",
"shared-bus",
"smoltcp-nal",
"stm32h7xx-hal",
]

View File

@ -45,6 +45,8 @@ dsp = { path = "dsp" }
ad9959 = { path = "ad9959" }
generic-array = "0.14"
miniconf = "0.1.0"
shared-bus = {version = "0.2.2", features = ["cortex-m"] }
serde-json-core = "0.3"
[dependencies.mcp23017]
git = "https://github.com/mrd0ll4r/mcp23017.git"
@ -67,11 +69,11 @@ rev = "c6f2b28"
[dependencies.smoltcp-nal]
git = "https://github.com/quartiq/smoltcp-nal.git"
rev = "8468f11"
rev = "4a1711c"
[dependencies.minimq]
git = "https://github.com/quartiq/minimq.git"
rev = "b3f364d"
rev = "d2ec3e8"
[features]
semihosting = ["panic-semihosting", "cortex-m-log/semihosting"]

View File

@ -9,11 +9,11 @@ use serde::Deserialize;
use dsp::iir;
use hardware::{
Adc0Input, Adc1Input, AfeGain, Dac0Output, Dac1Output, DigitalInput1,
InputPin, AFE0, AFE1,
Adc0Input, Adc1Input, AdcCode, AfeGain, Dac0Output, Dac1Output, DacCode,
DigitalInput0, DigitalInput1, InputPin, SystemTimer, AFE0, AFE1,
};
use net::{Action, MqttInterface};
use net::{NetworkUsers, Telemetry, TelemetryBuffer, UpdateState};
const SCALE: f32 = i16::MAX as _;
@ -26,6 +26,7 @@ pub struct Settings {
iir_ch: [[iir::IIR; IIR_CASCADE_LENGTH]; 2],
allow_hold: bool,
force_hold: bool,
telemetry_period: u16,
}
impl Default for Settings {
@ -43,42 +44,44 @@ impl Default for Settings {
allow_hold: false,
// Force suppress filter output updates.
force_hold: false,
// The default telemetry period in seconds.
telemetry_period: 10,
}
}
}
#[rtic::app(device = stm32h7xx_hal::stm32, peripherals = true, monotonic = rtic::cyccnt::CYCCNT)]
#[rtic::app(device = stm32h7xx_hal::stm32, peripherals = true, monotonic = stabilizer::hardware::SystemTimer)]
const APP: () = {
struct Resources {
afes: (AFE0, AFE1),
digital_input1: DigitalInput1,
digital_inputs: (DigitalInput0, DigitalInput1),
adcs: (Adc0Input, Adc1Input),
dacs: (Dac0Output, Dac1Output),
mqtt: MqttInterface<Settings>,
network: NetworkUsers<Settings, Telemetry>,
settings: Settings,
telemetry: TelemetryBuffer,
#[init([[[0.; 5]; IIR_CASCADE_LENGTH]; 2])]
iir_state: [[iir::Vec5; IIR_CASCADE_LENGTH]; 2],
settings: Settings,
}
#[init(spawn=[settings_update])]
#[init(spawn=[telemetry, settings_update])]
fn init(c: init::Context) -> init::LateResources {
// Configure the microcontroller
let (mut stabilizer, _pounder) = hardware::setup(c.core, c.device);
let mqtt = MqttInterface::new(
let network = NetworkUsers::new(
stabilizer.net.stack,
"",
&net::get_device_prefix(
env!("CARGO_BIN_NAME"),
stabilizer.net.mac_address,
),
stabilizer.net.phy,
stabilizer.cycle_counter,
env!("CARGO_BIN_NAME"),
stabilizer.net.mac_address,
);
// Spawn a settings update for default settings.
c.spawn.settings_update().unwrap();
c.spawn.telemetry().unwrap();
// Enable ADC/DAC events
stabilizer.adcs.0.start();
@ -93,8 +96,9 @@ const APP: () = {
afes: stabilizer.afes,
adcs: stabilizer.adcs,
dacs: stabilizer.dacs,
mqtt,
digital_input1: stabilizer.digital_inputs.1,
network,
digital_inputs: stabilizer.digital_inputs,
telemetry: net::TelemetryBuffer::default(),
settings: Settings::default(),
}
}
@ -115,7 +119,7 @@ const APP: () = {
///
/// Because the ADC and DAC operate at the same rate, these two constraints actually implement
/// the same time bounds, meeting one also means the other is also met.
#[task(binds=DMA1_STR4, resources=[adcs, digital_input1, dacs, iir_state, settings], priority=2)]
#[task(binds=DMA1_STR4, resources=[adcs, digital_inputs, dacs, iir_state, settings, telemetry], priority=2)]
#[inline(never)]
#[link_section = ".itcm.process"]
fn process(c: process::Context) {
@ -129,9 +133,13 @@ const APP: () = {
c.resources.dacs.1.acquire_buffer(),
];
let digital_inputs = [
c.resources.digital_inputs.0.is_high().unwrap(),
c.resources.digital_inputs.1.is_high().unwrap(),
];
let hold = c.resources.settings.force_hold
|| (c.resources.digital_input1.is_high().unwrap()
&& c.resources.settings.allow_hold);
|| (digital_inputs[1] && c.resources.settings.allow_hold);
for channel in 0..adc_samples.len() {
for sample in 0..adc_samples[0].len() {
@ -147,29 +155,34 @@ const APP: () = {
// The truncation introduces 1/2 LSB distortion.
let y = unsafe { y.to_int_unchecked::<i16>() };
// Convert to DAC code
dac_samples[channel][sample] = y as u16 ^ 0x8000;
dac_samples[channel][sample] = DacCode::from(y).0;
}
}
// Update telemetry measurements.
c.resources.telemetry.adcs =
[AdcCode(adc_samples[0][0]), AdcCode(adc_samples[1][0])];
c.resources.telemetry.dacs =
[DacCode(dac_samples[0][0]), DacCode(dac_samples[1][0])];
c.resources.telemetry.digital_inputs = digital_inputs;
}
#[idle(resources=[mqtt], spawn=[settings_update])]
#[idle(resources=[network], spawn=[settings_update])]
fn idle(mut c: idle::Context) -> ! {
loop {
match c.resources.mqtt.lock(|mqtt| mqtt.update()) {
Some(Action::Sleep) => cortex_m::asm::wfi(),
Some(Action::UpdateSettings) => {
c.spawn.settings_update().unwrap()
}
_ => {}
match c.resources.network.lock(|net| net.update()) {
UpdateState::Updated => c.spawn.settings_update().unwrap(),
UpdateState::NoChange => cortex_m::asm::wfi(),
}
}
}
#[task(priority = 1, resources=[mqtt, afes, settings])]
#[task(priority = 1, resources=[network, afes, settings])]
fn settings_update(mut c: settings_update::Context) {
let settings = c.resources.mqtt.settings();
// Update the IIR channels.
let settings = c.resources.network.miniconf.settings();
c.resources.settings.lock(|current| *current = *settings);
// Update AFEs
@ -177,6 +190,30 @@ const APP: () = {
c.resources.afes.1.set_gain(settings.afe[1]);
}
#[task(priority = 1, resources=[network, settings, telemetry], schedule=[telemetry])]
fn telemetry(mut c: telemetry::Context) {
let telemetry: TelemetryBuffer =
c.resources.telemetry.lock(|telemetry| *telemetry);
let (gains, telemetry_period) = c
.resources
.settings
.lock(|settings| (settings.afe, settings.telemetry_period));
c.resources
.network
.telemetry
.publish(&telemetry.finalize(gains[0], gains[1]));
// Schedule the telemetry task in the future.
c.schedule
.telemetry(
c.scheduled
+ SystemTimer::ticks_from_secs(telemetry_period as u32),
)
.unwrap();
}
#[task(binds = ETH, priority = 1)]
fn eth(_: eth::Context) {
unsafe { stm32h7xx_hal::ethernet::interrupt_handler() }

View File

@ -2,6 +2,7 @@
#![no_std]
#![no_main]
use embedded_hal::digital::v2::InputPin;
use generic_array::typenum::U4;
use serde::Deserialize;
@ -11,12 +12,13 @@ use dsp::{Accu, Complex, ComplexExt, Lockin, RPLL};
use stabilizer::net;
use stabilizer::hardware::{
design_parameters, setup, Adc0Input, Adc1Input, AfeGain, Dac0Output,
Dac1Output, InputStamper, AFE0, AFE1,
design_parameters, setup, Adc0Input, Adc1Input, AdcCode, AfeGain,
Dac0Output, Dac1Output, DacCode, DigitalInput0, DigitalInput1,
InputStamper, SystemTimer, AFE0, AFE1,
};
use miniconf::Miniconf;
use stabilizer::net::{Action, MqttInterface};
use net::{NetworkUsers, Telemetry, TelemetryBuffer, UpdateState};
// A constant sinusoid to send on the DAC output.
// Full-scale gives a +/- 10.24V amplitude waveform. Scale it down to give +/- 1V.
@ -54,6 +56,7 @@ pub struct Settings {
lockin_phase: i32,
output_conf: [Conf; 2],
telemetry_period: u16,
}
impl Default for Settings {
@ -70,38 +73,39 @@ impl Default for Settings {
lockin_phase: 0, // Demodulation LO phase offset
output_conf: [Conf::InPhase, Conf::Quadrature],
// The default telemetry period in seconds.
telemetry_period: 10,
}
}
}
#[rtic::app(device = stm32h7xx_hal::stm32, peripherals = true, monotonic = rtic::cyccnt::CYCCNT)]
#[rtic::app(device = stm32h7xx_hal::stm32, peripherals = true, monotonic = stabilizer::hardware::SystemTimer)]
const APP: () = {
struct Resources {
afes: (AFE0, AFE1),
adcs: (Adc0Input, Adc1Input),
dacs: (Dac0Output, Dac1Output),
mqtt: MqttInterface<Settings>,
network: NetworkUsers<Settings, Telemetry>,
settings: Settings,
telemetry: TelemetryBuffer,
digital_inputs: (DigitalInput0, DigitalInput1),
timestamper: InputStamper,
pll: RPLL,
lockin: Lockin<U4>,
}
#[init(spawn=[settings_update])]
#[init(spawn=[settings_update, telemetry])]
fn init(c: init::Context) -> init::LateResources {
// Configure the microcontroller
let (mut stabilizer, _pounder) = setup(c.core, c.device);
let mqtt = MqttInterface::new(
let network = NetworkUsers::new(
stabilizer.net.stack,
"",
&net::get_device_prefix(
env!("CARGO_BIN_NAME"),
stabilizer.net.mac_address,
),
stabilizer.net.phy,
stabilizer.cycle_counter,
env!("CARGO_BIN_NAME"),
stabilizer.net.mac_address,
);
let settings = Settings::default();
@ -111,8 +115,9 @@ const APP: () = {
+ design_parameters::SAMPLE_BUFFER_SIZE_LOG2,
);
// Spawn a settings update for default settings.
// Spawn a settings and telemetry update for default settings.
c.spawn.settings_update().unwrap();
c.spawn.telemetry().unwrap();
// Enable ADC/DAC events
stabilizer.adcs.0.start();
@ -133,8 +138,10 @@ const APP: () = {
afes: stabilizer.afes,
adcs: stabilizer.adcs,
dacs: stabilizer.dacs,
mqtt,
network,
digital_inputs: stabilizer.digital_inputs,
timestamper: stabilizer.timestamper,
telemetry: net::TelemetryBuffer::default(),
settings,
@ -150,7 +157,9 @@ const APP: () = {
/// This is an implementation of a externally (DI0) referenced PLL lockin on the ADC0 signal.
/// It outputs either I/Q or power/phase on DAC0/DAC1. Data is normalized to full scale.
/// PLL bandwidth, filter bandwidth, slope, and x/y or power/phase post-filters are available.
#[task(binds=DMA1_STR4, resources=[adcs, dacs, lockin, timestamper, pll, settings], priority=2)]
#[task(binds=DMA1_STR4, resources=[adcs, dacs, lockin, timestamper, pll, settings, telemetry], priority=2)]
#[inline(never)]
#[link_section = ".itcm.process"]
fn process(c: process::Context) {
let adc_samples = [
c.resources.adcs.0.acquire_buffer(),
@ -226,27 +235,31 @@ const APP: () = {
Conf::Modulation => DAC_SEQUENCE[i] as i32,
};
*sample = value as u16 ^ 0x8000;
*sample = DacCode::from(value as i16).0;
}
}
// Update telemetry measurements.
c.resources.telemetry.adcs =
[AdcCode(adc_samples[0][0]), AdcCode(adc_samples[1][0])];
c.resources.telemetry.dacs =
[DacCode(dac_samples[0][0]), DacCode(dac_samples[1][0])];
}
#[idle(resources=[mqtt], spawn=[settings_update])]
#[idle(resources=[network], spawn=[settings_update])]
fn idle(mut c: idle::Context) -> ! {
loop {
match c.resources.mqtt.lock(|mqtt| mqtt.update()) {
Some(Action::Sleep) => cortex_m::asm::wfi(),
Some(Action::UpdateSettings) => {
c.spawn.settings_update().unwrap()
}
_ => {}
match c.resources.network.lock(|net| net.update()) {
UpdateState::Updated => c.spawn.settings_update().unwrap(),
UpdateState::NoChange => cortex_m::asm::wfi(),
}
}
}
#[task(priority = 1, resources=[mqtt, settings, afes])]
#[task(priority = 1, resources=[network, settings, afes])]
fn settings_update(mut c: settings_update::Context) {
let settings = c.resources.mqtt.settings();
let settings = c.resources.network.miniconf.settings();
c.resources.afes.0.set_gain(settings.afe[0]);
c.resources.afes.1.set_gain(settings.afe[1]);
@ -254,6 +267,35 @@ const APP: () = {
c.resources.settings.lock(|current| *current = *settings);
}
#[task(priority = 1, resources=[network, digital_inputs, settings, telemetry], schedule=[telemetry])]
fn telemetry(mut c: telemetry::Context) {
let mut telemetry: TelemetryBuffer =
c.resources.telemetry.lock(|telemetry| *telemetry);
telemetry.digital_inputs = [
c.resources.digital_inputs.0.is_high().unwrap(),
c.resources.digital_inputs.1.is_high().unwrap(),
];
let (gains, telemetry_period) = c
.resources
.settings
.lock(|settings| (settings.afe, settings.telemetry_period));
c.resources
.network
.telemetry
.publish(&telemetry.finalize(gains[0], gains[1]));
// Schedule the telemetry task in the future.
c.schedule
.telemetry(
c.scheduled
+ SystemTimer::ticks_from_secs(telemetry_period as u32),
)
.unwrap();
}
#[task(binds = ETH, priority = 1)]
fn eth(_: eth::Context) {
unsafe { stm32h7xx_hal::ethernet::interrupt_handler() }

View File

@ -84,6 +84,24 @@ use hal::dma::{
MemoryToPeripheral, PeripheralToMemory, Transfer,
};
/// A type representing an ADC sample.
#[derive(Copy, Clone)]
pub struct AdcCode(pub u16);
impl Into<f32> for AdcCode {
/// Convert raw ADC codes to/from voltage levels.
///
/// # Note
/// This does not account for the programmable gain amplifier at the signal input.
fn into(self) -> f32 {
// The ADC has a differential input with a range of +/- 4.096 V and 16-bit resolution.
// The gain into the two inputs is 1/5.
let adc_volts_per_lsb = 5.0 / 2.0 * 4.096 / (1u16 << 15) as f32;
(self.0 as i16) as f32 * adc_volts_per_lsb
}
}
// The following data is written by the timer ADC sample trigger into the SPI CR1 to start the
// transfer. Data in AXI SRAM is not initialized on boot, so the contents are random. This value is
// initialized during setup.

View File

@ -20,6 +20,18 @@ pub struct ProgrammableGainAmplifier<A0, A1> {
a1: A1,
}
impl Gain {
/// Get the AFE gain as a numerical value.
pub fn as_multiplier(self) -> f32 {
match self {
Gain::G1 => 1.0,
Gain::G2 => 2.0,
Gain::G5 => 5.0,
Gain::G10 => 10.0,
}
}
}
impl TryFrom<u8> for Gain {
type Error = ();

View File

@ -7,25 +7,30 @@ use stm32h7xx_hal::{
prelude::*,
};
const NUM_SOCKETS: usize = 4;
use heapless::{consts, Vec};
use smoltcp_nal::smoltcp;
use embedded_hal::digital::v2::{InputPin, OutputPin};
use super::{
adc, afe, cycle_counter::CycleCounter, dac, design_parameters,
digital_input_stamper, eeprom, pounder, timers, DdsOutput, DigitalInput0,
DigitalInput1, EthernetPhy, NetworkStack, AFE0, AFE1,
digital_input_stamper, eeprom, pounder, system_timer, timers, DdsOutput,
DigitalInput0, DigitalInput1, EthernetPhy, NetworkStack, AFE0, AFE1,
};
pub struct NetStorage {
pub ip_addrs: [smoltcp::wire::IpCidr; 1],
pub sockets: [Option<smoltcp::socket::SocketSetItem<'static>>; 2],
// Note: There is an additional socket set item required for the DHCP socket.
pub sockets:
[Option<smoltcp::socket::SocketSetItem<'static>>; NUM_SOCKETS + 1],
pub socket_storage: [SocketStorage; NUM_SOCKETS],
pub neighbor_cache:
[Option<(smoltcp::wire::IpAddress, smoltcp::iface::Neighbor)>; 8],
pub routes_cache:
[Option<(smoltcp::wire::IpCidr, smoltcp::iface::Route)>; 8],
pub tx_storage: [u8; 4096],
pub rx_storage: [u8; 4096],
pub dhcp_rx_metadata: [smoltcp::socket::RawPacketMetadata; 1],
pub dhcp_tx_metadata: [smoltcp::socket::RawPacketMetadata; 1],
@ -33,6 +38,21 @@ pub struct NetStorage {
pub dhcp_rx_storage: [u8; 600],
}
#[derive(Copy, Clone)]
pub struct SocketStorage {
rx_storage: [u8; 1024],
tx_storage: [u8; 1024],
}
impl SocketStorage {
const fn new() -> Self {
Self {
rx_storage: [0; 1024],
tx_storage: [0; 1024],
}
}
}
impl NetStorage {
pub fn new() -> Self {
NetStorage {
@ -42,9 +62,8 @@ impl NetStorage {
)],
neighbor_cache: [None; 8],
routes_cache: [None; 8],
sockets: [None, None],
tx_storage: [0; 4096],
rx_storage: [0; 4096],
sockets: [None, None, None, None, None],
socket_storage: [SocketStorage::new(); NUM_SOCKETS],
dhcp_tx_storage: [0; 600],
dhcp_rx_storage: [0; 600],
dhcp_rx_metadata: [smoltcp::socket::RawPacketMetadata::EMPTY; 1],
@ -98,7 +117,7 @@ static mut DES_RING: ethernet::DesRing = ethernet::DesRing::new();
/// `Some(devices)` if pounder is detected, where `devices` is a `PounderDevices` structure
/// containing all of the pounder hardware interfaces in a disabled state.
pub fn setup(
mut core: rtic::export::Peripherals,
mut core: rtic::Peripherals,
device: stm32h7xx_hal::stm32::Peripherals,
) -> (StabilizerDevices, Option<PounderDevices>) {
let pwr = device.PWR.constrain();
@ -141,7 +160,18 @@ pub fn setup(
init_log(logger).unwrap();
}
let mut delay = hal::delay::Delay::new(core.SYST, ccdr.clocks);
// Set up the system timer for RTIC scheduling.
{
let tim15 =
device
.TIM15
.timer(10.khz(), ccdr.peripheral.TIM15, &ccdr.clocks);
system_timer::SystemTimer::initialize(tim15);
}
let mut delay = asm_delay::AsmDelay::new(asm_delay::bitrate::Hertz(
ccdr.clocks.c_ck().0,
));
let gpioa = device.GPIOA.split(ccdr.peripheral.GPIOA);
let gpiob = device.GPIOB.split(ccdr.peripheral.GPIOB);
@ -562,19 +592,25 @@ pub fn setup(
let mut sockets =
smoltcp::socket::SocketSet::new(&mut store.sockets[..]);
let tcp_socket = {
let rx_buffer = smoltcp::socket::TcpSocketBuffer::new(
&mut store.rx_storage[..],
);
let tx_buffer = smoltcp::socket::TcpSocketBuffer::new(
&mut store.tx_storage[..],
);
let mut handles: Vec<smoltcp::socket::SocketHandle, consts::U64> =
Vec::new();
for storage in store.socket_storage.iter_mut() {
let tcp_socket = {
let rx_buffer = smoltcp::socket::TcpSocketBuffer::new(
&mut storage.rx_storage[..],
);
let tx_buffer = smoltcp::socket::TcpSocketBuffer::new(
&mut storage.tx_storage[..],
);
smoltcp::socket::TcpSocket::new(rx_buffer, tx_buffer)
};
smoltcp::socket::TcpSocket::new(rx_buffer, tx_buffer)
};
let handle = sockets.add(tcp_socket);
let handle = sockets.add(tcp_socket);
(sockets, [handle])
handles.push(handle).unwrap();
}
(sockets, handles)
};
let dhcp_client = {

View File

@ -69,6 +69,28 @@ use hal::dma::{
static mut DAC_BUF: [[[u16; SAMPLE_BUFFER_SIZE]; 3]; 2] =
[[[0; SAMPLE_BUFFER_SIZE]; 3]; 2];
/// Custom type for referencing DAC output codes.
/// The internal integer is the raw code written to the DAC output register.
#[derive(Copy, Clone)]
pub struct DacCode(pub u16);
impl Into<f32> for DacCode {
fn into(self) -> f32 {
// The DAC output range in bipolar mode (including the external output op-amp) is +/- 4.096
// V with 16-bit resolution. The anti-aliasing filter has an additional gain of 2.5.
let dac_volts_per_lsb = 4.096 * 2.5 / (1u16 << 15) as f32;
(self.0 as i16).wrapping_add(i16::MIN) as f32 * dac_volts_per_lsb
}
}
impl From<i16> for DacCode {
/// Encode signed 16-bit values into DAC offset binary for a bipolar output configuration.
fn from(value: i16) -> Self {
Self(value.wrapping_add(i16::MIN) as u16)
}
}
macro_rules! dac_output {
($name:ident, $index:literal, $data_stream:ident,
$spi:ident, $trigger_channel:ident, $dma_req:ident) => {

View File

@ -16,14 +16,16 @@ pub mod design_parameters;
mod digital_input_stamper;
mod eeprom;
pub mod pounder;
mod system_timer;
mod timers;
pub use adc::{Adc0Input, Adc1Input};
pub use adc::{Adc0Input, Adc1Input, AdcCode};
pub use afe::Gain as AfeGain;
pub use cycle_counter::CycleCounter;
pub use dac::{Dac0Output, Dac1Output};
pub use dac::{Dac0Output, Dac1Output, DacCode};
pub use digital_input_stamper::InputStamper;
pub use pounder::DdsOutput;
pub use system_timer::SystemTimer;
// Type alias for the analog front-end (AFE) for ADC0.
pub type AFE0 = afe::ProgrammableGainAmplifier<

View File

@ -0,0 +1,115 @@
///! System timer used for RTIC scheduling
///!
///! # Design
///! The SystemTimer is an RTIC monotonic timer that can be used for scheduling tasks in RTIC.
///! This timer is used in place of the cycle counter to allow the timer to tick at a slower rate
///! than the CPU clock. This allows for longer scheduling periods with less resolution. This is
///! needed for infrequent (e.g. multiple second) telemetry periods.
///!
///! # Limitations
///! This implementation relies on sufficient timer polling to not miss timer counter overflows. If
///! the timer is not polled often enough, it's possible that an overflow would be missed and time
///! would "halt" for a shore period of time. This could be fixed in the future by instead
///! listening for the overflow interrupt instead of polling the overflow state.
use hal::prelude::*;
use stm32h7xx_hal as hal;
// A global buffer indicating how many times the internal counter has overflowed.
static mut OVERFLOWS: u32 = 0;
/// System timer used for implementing RTIC scheduling.
///
/// # Note
/// The system timer must be initialized before being used.
pub struct SystemTimer {}
impl SystemTimer {
/// Initialize the system timer.
///
/// # Args
/// * `timer` - The hardware timer used for implementing the RTIC monotonic.
pub fn initialize(mut timer: hal::timer::Timer<hal::device::TIM15>) {
timer.pause();
// Have the system timer operate at a tick rate of 10KHz (100uS per tick). With this
// configuration and a 65535 period, we get an overflow once every 6.5 seconds.
timer.set_tick_freq(10.khz());
timer.apply_freq();
timer.resume();
}
/// Convert a provided number of seconds into timer ticks.
pub fn ticks_from_secs(secs: u32) -> i32 {
(secs * 10_000) as i32
}
}
impl rtic::Monotonic for SystemTimer {
// Instants are stored in 32-bit signed integers. With a 10KHz tick rate, this means an
// instant can store up to ~59 hours of time before overflowing.
type Instant = i32;
fn ratio() -> rtic::Fraction {
rtic::Fraction {
// At 10KHz with a 400MHz CPU clock, the CPU clock runs 40,000 times faster than
// the system timer.
numerator: 40_000,
denominator: 1,
}
}
/// Get the current time instant.
///
/// # Note
/// The time will overflow into -59 hours after the first 59 hours. This time value is intended
/// for use in calculating time delta, and should not be used for timestamping purposes due to
/// roll-over.
fn now() -> i32 {
// Note(unsafe): Multiple interrupt contexts have access to the underlying timer, so care
// is taken when reading and modifying register values.
let regs = unsafe { &*hal::device::TIM15::ptr() };
cortex_m::interrupt::free(|_cs| {
loop {
// Checking for overflows of the current counter must be performed atomically. Any
// other task that is accessing the current time could potentially race for the
// registers. Note that this is only required for writing to global state (e.g. timer
// registers and overflow counter)
// Check for overflows and clear the overflow bit atomically. This must be done in
// a critical section to prevent race conditions on the status register.
if regs.sr.read().uif().bit_is_set() {
regs.sr.modify(|_, w| w.uif().clear_bit());
unsafe {
OVERFLOWS += 1;
}
}
let current_value = regs.cnt.read().bits();
// Check that an overflow didn't occur since we just cleared the overflow bit. If
// it did, loop around and retry.
if regs.sr.read().uif().bit_is_clear() {
// Note(unsafe): We are in a critical section, so it is safe to read the
// global variable.
return unsafe {
((OVERFLOWS << 16) + current_value) as i32
};
}
}
})
}
/// Reset the timer count.
unsafe fn reset() {
// Note: The timer must be safely configured in `SystemTimer::initialize()`.
let regs = &*hal::device::TIM15::ptr();
OVERFLOWS = 0;
regs.cnt.reset();
}
/// Get a timestamp correlating to zero time.
fn zero() -> i32 {
0
}
}

View File

@ -1,27 +1,33 @@
use crate::hardware::{
design_parameters::MQTT_BROKER, CycleCounter, EthernetPhy, NetworkStack,
};
///! Stabilizer Run-time Settings Client
///!
///! # Design
///! Stabilizer allows for settings to be configured at run-time via MQTT using miniconf.
///! Settings are written in serialized JSON form to the settings path associated with the setting.
///!
///! # Limitations
///! The MQTT client logs failures to subscribe to the settings topic, but does not re-attempt to
///connect to it when errors occur.
///!
///! Respones to settings updates are sent without quality-of-service guarantees, so there's no
///! guarantee that the requestee will be informed that settings have been applied.
use heapless::{consts, String};
use super::{Action, MqttMessage, SettingsResponse};
use super::{MqttMessage, NetworkReference, SettingsResponse, UpdateState};
use crate::hardware::design_parameters::MQTT_BROKER;
/// MQTT settings interface.
pub struct MqttInterface<S>
pub struct MiniconfClient<S>
where
S: miniconf::Miniconf + Default + Clone,
{
default_response_topic: String<consts::U128>,
mqtt: minimq::MqttClient<minimq::consts::U256, NetworkStack>,
mqtt: minimq::MqttClient<minimq::consts::U256, NetworkReference>,
settings: S,
clock: CycleCounter,
phy: EthernetPhy,
network_was_reset: bool,
subscribed: bool,
settings_prefix: String<consts::U64>,
}
impl<S> MqttInterface<S>
impl<S> MiniconfClient<S>
where
S: miniconf::Miniconf + Default + Clone,
{
@ -31,15 +37,7 @@ where
/// * `stack` - The network stack to use for communication.
/// * `client_id` - The ID of the MQTT client. May be an empty string for auto-assigning.
/// * `prefix` - The MQTT device prefix to use for this device.
/// * `phy` - The PHY driver for querying the link state.
/// * `clock` - The clock to utilize for querying the current system time.
pub fn new(
stack: NetworkStack,
client_id: &str,
prefix: &str,
phy: EthernetPhy,
clock: CycleCounter,
) -> Self {
pub fn new(stack: NetworkReference, client_id: &str, prefix: &str) -> Self {
let mqtt =
minimq::MqttClient::new(MQTT_BROKER.into(), client_id, stack)
.unwrap();
@ -54,10 +52,7 @@ where
mqtt,
settings: S::default(),
settings_prefix,
clock,
phy,
default_response_topic: response_topic,
network_was_reset: false,
subscribed: false,
}
}
@ -66,31 +61,7 @@ where
///
/// # Returns
/// An option containing an action that should be completed as a result of network servicing.
pub fn update(&mut self) -> Option<Action> {
// First, service the network stack to process any inbound and outbound traffic.
let sleep = match self.mqtt.network_stack.poll(self.clock.current_ms())
{
Ok(updated) => !updated,
Err(err) => {
log::info!("Network error: {:?}", err);
false
}
};
// If the PHY indicates there's no more ethernet link, reset the DHCP server in the network
// stack.
match self.phy.poll_link() {
true => self.network_was_reset = false,
// Only reset the network stack once per link reconnection. This prevents us from
// sending an excessive number of DHCP requests.
false if !self.network_was_reset => {
self.network_was_reset = true;
self.mqtt.network_stack.handle_link_reset();
}
_ => {}
};
pub fn update(&mut self) -> UpdateState {
let mqtt_connected = match self.mqtt.is_connected() {
Ok(connected) => connected,
Err(minimq::Error::Network(
@ -167,30 +138,24 @@ where
.ok();
}) {
// If settings updated,
Ok(_) => {
if update {
Some(Action::UpdateSettings)
} else if sleep {
Some(Action::Sleep)
} else {
None
}
}
Err(minimq::Error::Disconnected) => {
Ok(_) if update => UpdateState::Updated,
Ok(_) => UpdateState::NoChange,
Err(minimq::Error::SessionReset) => {
self.subscribed = false;
None
UpdateState::NoChange
}
Err(minimq::Error::Network(
smoltcp_nal::NetworkError::NoIpAddress,
)) => None,
)) => UpdateState::NoChange,
Err(error) => {
log::info!("Unexpected error: {:?}", error);
None
UpdateState::NoChange
}
}
}
/// Get the current settings from miniconf.
pub fn settings(&self) -> &S {
&self.settings
}

View File

@ -6,21 +6,129 @@
///! streaming over raw UDP/TCP sockets. This module encompasses the main processing routines
///! related to Stabilizer networking operations.
use heapless::{consts, String};
use miniconf::Miniconf;
use serde::Serialize;
use core::fmt::Write;
mod messages;
mod mqtt_interface;
mod miniconf_client;
mod network_processor;
mod shared;
mod telemetry;
use crate::hardware::{CycleCounter, EthernetPhy, NetworkStack};
use messages::{MqttMessage, SettingsResponse};
pub use mqtt_interface::MqttInterface;
/// Potential actions for firmware to take.
pub enum Action {
/// Indicates that firmware can sleep for the next event.
Sleep,
pub use miniconf_client::MiniconfClient;
pub use network_processor::NetworkProcessor;
pub use shared::NetworkManager;
pub use telemetry::{Telemetry, TelemetryBuffer, TelemetryClient};
/// Indicates that settings have updated and firmware needs to propogate changes.
UpdateSettings,
pub type NetworkReference = shared::NetworkStackProxy<'static, NetworkStack>;
#[derive(Copy, Clone, PartialEq)]
pub enum UpdateState {
NoChange,
Updated,
}
/// A structure of Stabilizer's default network users.
pub struct NetworkUsers<S: Default + Clone + Miniconf, T: Serialize> {
pub miniconf: MiniconfClient<S>,
pub processor: NetworkProcessor,
pub telemetry: TelemetryClient<T>,
}
impl<S, T> NetworkUsers<S, T>
where
S: Default + Clone + Miniconf,
T: Serialize,
{
/// Construct Stabilizer's default network users.
///
/// # Args
/// * `stack` - The network stack that will be used to share with all network users.
/// * `phy` - The ethernet PHY connecting the network.
/// * `cycle_counter` - The clock used for measuring time in the network.
/// * `app` - The name of the application.
/// * `mac` - The MAC address of the network.
///
/// # Returns
/// A new struct of network users.
pub fn new(
stack: NetworkStack,
phy: EthernetPhy,
cycle_counter: CycleCounter,
app: &str,
mac: smoltcp_nal::smoltcp::wire::EthernetAddress,
) -> Self {
let stack_manager =
cortex_m::singleton!(: NetworkManager = NetworkManager::new(stack))
.unwrap();
let processor = NetworkProcessor::new(
stack_manager.acquire_stack(),
phy,
cycle_counter,
);
let prefix = get_device_prefix(app, mac);
let settings = MiniconfClient::new(
stack_manager.acquire_stack(),
&get_client_id(app, "settings", mac),
&prefix,
);
let telemetry = TelemetryClient::new(
stack_manager.acquire_stack(),
&get_client_id(app, "tlm", mac),
&prefix,
);
NetworkUsers {
miniconf: settings,
processor,
telemetry,
}
}
/// Update and process all of the network users state.
///
/// # Returns
/// An indication if any of the network users indicated a state change.
pub fn update(&mut self) -> UpdateState {
// Poll for incoming data.
let poll_result = self.processor.update();
// Update the MQTT clients.
self.telemetry.update();
match self.miniconf.update() {
UpdateState::Updated => UpdateState::Updated,
UpdateState::NoChange => poll_result,
}
}
}
/// Get an MQTT client ID for a client.
///
/// # Args
/// * `app` - The name of the application
/// * `client` - The unique tag of the client
/// * `mac` - The MAC address of the device.
///
/// # Returns
/// A client ID that may be used for MQTT client identification.
fn get_client_id(
app: &str,
client: &str,
mac: smoltcp_nal::smoltcp::wire::EthernetAddress,
) -> String<consts::U64> {
let mut identifier = String::new();
write!(&mut identifier, "{}-{}-{}", app, mac, client).unwrap();
identifier
}
/// Get the MQTT prefix of a device.
@ -35,26 +143,10 @@ pub fn get_device_prefix(
app: &str,
mac: smoltcp_nal::smoltcp::wire::EthernetAddress,
) -> String<consts::U128> {
let mac_string = {
let mut mac_string: String<consts::U32> = String::new();
let mac = mac.as_bytes();
// Note(unwrap): 32-bytes is guaranteed to be valid for any mac address, as the address has
// a fixed length.
write!(
&mut mac_string,
"{:02x}-{:02x}-{:02x}-{:02x}-{:02x}-{:02x}",
mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]
)
.unwrap();
mac_string
};
// Note(unwrap): The mac address + binary name must be short enough to fit into this string. If
// they are defined too long, this will panic and the device will fail to boot.
let mut prefix: String<consts::U128> = String::new();
write!(&mut prefix, "dt/sinara/{}/{}", app, mac_string).unwrap();
write!(&mut prefix, "dt/sinara/{}/{}", app, mac).unwrap();
prefix
}

View File

@ -0,0 +1,77 @@
///! Task to process network hardware.
///!
///! # Design
///! The network processir is a small taks to regularly process incoming data over ethernet, handle
///! the ethernet PHY state, and reset the network as appropriate.
use super::{NetworkReference, UpdateState};
use crate::hardware::{CycleCounter, EthernetPhy};
/// Processor for managing network hardware.
pub struct NetworkProcessor {
stack: NetworkReference,
phy: EthernetPhy,
clock: CycleCounter,
network_was_reset: bool,
}
impl NetworkProcessor {
/// Construct a new network processor.
///
/// # Args
/// * `stack` - A reference to the shared network stack
/// * `phy` - The ethernet PHY used for the network.
/// * `clock` - The clock used for providing time to the network.
///
/// # Returns
/// The newly constructed processor.
pub fn new(
stack: NetworkReference,
phy: EthernetPhy,
clock: CycleCounter,
) -> Self {
Self {
stack,
phy,
clock,
network_was_reset: false,
}
}
/// Process and update the state of the network.
///
/// # Note
/// This function should be called regularly before other network tasks to update the state of
/// all relevant network sockets.
///
/// # Returns
/// An update state corresponding with any changes in the underlying network.
pub fn update(&mut self) -> UpdateState {
// Service the network stack to process any inbound and outbound traffic.
let now = self.clock.current_ms();
let result = match self.stack.lock(|stack| stack.poll(now)) {
Ok(true) => UpdateState::Updated,
Ok(false) => UpdateState::NoChange,
Err(err) => {
log::info!("Network error: {:?}", err);
UpdateState::Updated
}
};
// If the PHY indicates there's no more ethernet link, reset the DHCP server in the network
// stack.
match self.phy.poll_link() {
true => self.network_was_reset = false,
// Only reset the network stack once per link reconnection. This prevents us from
// sending an excessive number of DHCP requests.
false if !self.network_was_reset => {
self.network_was_reset = true;
self.stack.lock(|stack| stack.handle_link_reset());
}
_ => {}
};
result
}
}

91
src/net/shared.rs Normal file
View File

@ -0,0 +1,91 @@
///! Network Stack Sharing Utilities
///!
///! # Design
///! This module provides a mechanism for sharing a single network stack safely between drivers
///that may or may not execute in multiple contexts. The design copies that of `shared-bus`.
///!
///! Specifically, the network stack is stored in a global static singleton and proxies to the
///! underlying stack are handed out. The proxies provide an identical API for the
///! `embedded_nal::TcpStack` stack trait, so they can be provided direclty to drivers that require
///! a network stack.
///!
///! In order to ensure that pre-emption does not occur while accessing the same network stack from
///! multiple interrupt contexts, the proxy uses an atomic boolean check - if the flag indicates the
///! stack is in use, the proxy will generate a panic. The actual synchronization mechanism (mutex)
///! leverages RTIC resource allocation. All devices that use the underlying network stack must be
///! placed in a single RTIC resource, which will cause RTIC to prevent contention for the
///! underlying network stack.
use minimq::embedded_nal;
use shared_bus::{AtomicCheckMutex, BusMutex};
use crate::hardware::NetworkStack;
/// A manager for a shared network stack.
pub struct NetworkManager {
mutex: AtomicCheckMutex<NetworkStack>,
}
/// A basic proxy that references a shared network stack.
pub struct NetworkStackProxy<'a, S> {
mutex: &'a AtomicCheckMutex<S>,
}
impl<'a, S> NetworkStackProxy<'a, S> {
/// Using the proxy, access the underlying network stack directly.
///
/// # Args
/// * `f` - A closure which will be provided the network stack as an argument.
///
/// # Returns
/// Any value returned by the provided closure
pub fn lock<R, F: FnOnce(&mut S) -> R>(&mut self, f: F) -> R {
self.mutex.lock(|stack| f(stack))
}
}
// A simple forwarding macro taken from the `embedded-nal` to forward the embedded-nal API into the
// proxy structure.
macro_rules! forward {
($func:ident($($v:ident: $IT:ty),*) -> $T:ty) => {
fn $func(&self, $($v: $IT),*) -> $T {
self.mutex.lock(|stack| stack.$func($($v),*))
}
}
}
// Implement a TCP stack for the proxy if the underlying network stack implements it.
impl<'a, S> embedded_nal::TcpStack for NetworkStackProxy<'a, S>
where
S: embedded_nal::TcpStack,
{
type TcpSocket = S::TcpSocket;
type Error = S::Error;
forward! {open(mode: embedded_nal::Mode) -> Result<S::TcpSocket, S::Error>}
forward! {connect(socket: S::TcpSocket, remote: embedded_nal::SocketAddr) -> Result<S::TcpSocket, S::Error>}
forward! {is_connected(socket: &S::TcpSocket) -> Result<bool, S::Error>}
forward! {write(socket: &mut S::TcpSocket, buffer: &[u8]) -> embedded_nal::nb::Result<usize, S::Error>}
forward! {read(socket: &mut S::TcpSocket, buffer: &mut [u8]) -> embedded_nal::nb::Result<usize, S::Error>}
forward! {close(socket: S::TcpSocket) -> Result<(), S::Error>}
}
impl NetworkManager {
/// Construct a new manager for a shared network stack
///
/// # Args
/// * `stack` - The network stack that is being shared.
pub fn new(stack: NetworkStack) -> Self {
Self {
mutex: AtomicCheckMutex::create(stack),
}
}
/// Acquire a proxy to the shared network stack.
///
/// # Returns
/// A proxy that can be used in place of the network stack. Note the requirements of
/// concurrency listed in the description of this file for usage.
pub fn acquire_stack(&'_ self) -> NetworkStackProxy<'_, NetworkStack> {
NetworkStackProxy { mutex: &self.mutex }
}
}

145
src/net/telemetry.rs Normal file
View File

@ -0,0 +1,145 @@
///! Stabilizer Telemetry Capabilities
///!
///! # Design
///! Telemetry is reported regularly using an MQTT client. All telemetry is reported in SI units
///! using standard JSON format.
///!
///! In order to report ADC/DAC codes generated during the DSP routines, a telemetry buffer is
///! employed to track the latest codes. Converting these codes to SI units would result in
///! repetitive and unnecessary calculations within the DSP routine, slowing it down and limiting
///! sampling frequency. Instead, the raw codes are stored and the telemetry is generated as
///! required immediately before transmission. This ensures that any slower computation required
///! for unit conversion can be off-loaded to lower priority tasks.
use heapless::{consts, String, Vec};
use minimq::QoS;
use serde::Serialize;
use super::NetworkReference;
use crate::hardware::{
design_parameters::MQTT_BROKER, AdcCode, AfeGain, DacCode,
};
/// The telemetry client for reporting telemetry data over MQTT.
pub struct TelemetryClient<T: Serialize> {
mqtt: minimq::MqttClient<minimq::consts::U256, NetworkReference>,
telemetry_topic: String<consts::U128>,
_telemetry: core::marker::PhantomData<T>,
}
/// The telemetry buffer is used for storing sample values during execution.
///
/// # Note
/// These values can be converted to SI units immediately before reporting to save processing time.
/// This allows for the DSP process to continually update the values without incurring significant
/// run-time overhead during conversion to SI units.
#[derive(Copy, Clone)]
pub struct TelemetryBuffer {
/// The latest input sample on ADC0/ADC1.
pub adcs: [AdcCode; 2],
/// The latest output code on DAC0/DAC1.
pub dacs: [DacCode; 2],
/// The latest digital input states during processing.
pub digital_inputs: [bool; 2],
}
/// The telemetry structure is data that is ultimately reported as telemetry over MQTT.
///
/// # Note
/// This structure should be generated on-demand by the buffer when required to minimize conversion
/// overhead.
#[derive(Serialize)]
pub struct Telemetry {
adcs: [f32; 2],
dacs: [f32; 2],
digital_inputs: [bool; 2],
}
impl Default for TelemetryBuffer {
fn default() -> Self {
Self {
adcs: [AdcCode(0), AdcCode(0)],
dacs: [DacCode(0), DacCode(0)],
digital_inputs: [false, false],
}
}
}
impl TelemetryBuffer {
/// Convert the telemetry buffer to finalized, SI-unit telemetry for reporting.
///
/// # Args
/// * `afe0` - The current AFE configuration for channel 0.
/// * `afe1` - The current AFE configuration for channel 1.
///
/// # Returns
/// The finalized telemetry structure that can be serialized and reported.
pub fn finalize(self, afe0: AfeGain, afe1: AfeGain) -> Telemetry {
let in0_volts = Into::<f32>::into(self.adcs[0]) / afe0.as_multiplier();
let in1_volts = Into::<f32>::into(self.adcs[1]) / afe1.as_multiplier();
Telemetry {
adcs: [in0_volts, in1_volts],
dacs: [self.dacs[0].into(), self.dacs[1].into()],
digital_inputs: self.digital_inputs,
}
}
}
impl<T: Serialize> TelemetryClient<T> {
/// Construct a new telemetry client.
///
/// # Args
/// * `stack` - A reference to the (shared) underlying network stack.
/// * `client_id` - The MQTT client ID of the telemetry client.
/// * `prefix` - The device prefix to use for MQTT telemetry reporting.
///
/// # Returns
/// A new telemetry client.
pub fn new(stack: NetworkReference, client_id: &str, prefix: &str) -> Self {
let mqtt =
minimq::MqttClient::new(MQTT_BROKER.into(), client_id, stack)
.unwrap();
let mut telemetry_topic: String<consts::U128> = String::from(prefix);
telemetry_topic.push_str("/telemetry").unwrap();
Self {
mqtt,
telemetry_topic,
_telemetry: core::marker::PhantomData::default(),
}
}
/// Publish telemetry over MQTT
///
/// # Note
/// Telemetry is reported in a "best-effort" fashion. Failure to transmit telemetry will cause
/// it to be silently dropped.
///
/// # Args
/// * `telemetry` - The telemetry to report
pub fn publish(&mut self, telemetry: &T) {
let telemetry: Vec<u8, consts::U256> =
serde_json_core::to_vec(telemetry).unwrap();
self.mqtt
.publish(&self.telemetry_topic, &telemetry, QoS::AtMostOnce, &[])
.ok();
}
/// Update the telemetry client
///
/// # Note
/// This function is provided to force the underlying MQTT state machine to process incoming
/// and outgoing messages. Without this, the client will never connect to the broker. This
/// should be called regularly.
pub fn update(&mut self) {
match self.mqtt.poll(|_client, _topic, _message, _properties| {}) {
Err(minimq::Error::Network(
smoltcp_nal::NetworkError::NoIpAddress,
)) => {}
Err(error) => log::info!("Unexpected error: {:?}", error),
_ => {}
}
}
}