Appendix B: Function Block Reference
AutoCore provides standard function blocks inspired by IEC 61131-3. Import them from autocore_std::fb.
RTrig — Rising Edge Detector
Detects false to true transitions. Equivalent to R_TRIG in IEC 61131-3.
#![allow(unused)]
fn main() {
use autocore_std::fb::RTrig;
let mut trig = RTrig::new();
trig.call(false); // returns false
trig.call(true); // returns true (rising edge detected)
trig.call(true); // returns false (no transition)
trig.call(false); // returns false
trig.call(true); // returns true (another rising edge)
}
FTrig — Falling Edge Detector
Detects true to false transitions. Equivalent to F_TRIG in IEC 61131-3.
#![allow(unused)]
fn main() {
use autocore_std::fb::FTrig;
let mut trig = FTrig::new();
trig.call(true); // returns false
trig.call(false); // returns true (falling edge detected)
trig.call(false); // returns false (no transition)
trig.call(true); // returns false
trig.call(false); // returns true (another falling edge)
}
Blink — Simple Oscillator
Toggles its output on and off at a fixed frequency (0.5 seconds on, 0.5 seconds off) while the input is true.
#![allow(unused)]
fn main() {
use autocore_std::fb::Blink;
let mut blink = Blink::new();
// Oscillates automatically while input is true
let q = blink.call(true); // Goes true immediately
// After 500ms... q becomes false
// After 1000ms... q becomes true
// Reset and output false
let q = blink.call(false);
}
Ton — Timer On Delay
Output becomes true after input has been true for the specified duration. Equivalent to TON in IEC 61131-3.
#![allow(unused)]
fn main() {
use autocore_std::fb::Ton;
use std::time::Duration;
let mut timer = Ton::new();
// In process_tick:
let done = timer.call(input_signal, Duration::from_secs(5));
// done = true after input_signal has been true for 5 seconds continuously
// timer.et = elapsed time
// timer.q = same as the return value (done)
// If input_signal becomes false at any time, the timer resets
}
Fields:
| Field | Type | Description |
|---|---|---|
q | bool | Output — true when timer has elapsed |
et | Duration | Elapsed time since input became true |
BitResetOnDelay — Auto-Reset Timer
Sets output to false after a delay. Useful for pulse outputs.
#![allow(unused)]
fn main() {
use autocore_std::fb::BitResetOnDelay;
use std::time::Duration;
let mut reset = BitResetOnDelay::new(Duration::from_millis(500));
// When you set the bit to true, it automatically resets to false after 500ms
reset.set(); // Output becomes true
// ... 500ms later, in process_tick ...
reset.call(); // Call every cycle to update
// reset.q becomes false after the delay
}
RunningAverage — Online Averaging
Computes a running average of values.
#![allow(unused)]
fn main() {
use autocore_std::fb::RunningAverage;
let mut avg = RunningAverage::new();
avg.add(10.0);
avg.add(20.0);
avg.add(30.0);
let mean = avg.average(); // 20.0
let count = avg.count(); // 3
avg.reset(); // Start over
}
Shutdown — System Shutdown Controller
Initiates or cancels a full system shutdown via IPC. The server delays the actual power-off by 15 seconds, giving the control program (or a human operator) time to cancel. All methods are non-blocking — the block tracks the IPC transaction internally and updates its output flags each scan cycle.
#![allow(unused)]
fn main() {
use autocore_std::fb::Shutdown;
struct MyProgram {
shutdown: Shutdown,
shutdown_trigger: RTrig,
cancel_trigger: RTrig,
}
impl MyProgram {
fn new() -> Self {
Self {
shutdown: Shutdown::new(),
shutdown_trigger: RTrig::new(),
cancel_trigger: RTrig::new(),
}
}
}
}
In process_tick:
#![allow(unused)]
fn main() {
// Always call once per cycle to poll for server responses
self.shutdown.call(ctx.client);
// Initiate shutdown on rising edge of a button
if self.shutdown_trigger.call(ctx.gm.shutdown_button) {
self.shutdown.initiate(ctx.client);
}
// Cancel shutdown on rising edge of an abort button
if self.cancel_trigger.call(ctx.gm.abort_button) {
self.shutdown.cancel(ctx.client);
}
// React to results
if self.shutdown.done {
log::info!("Server confirmed the command");
}
if self.shutdown.error {
log::error!("Shutdown error: {}", self.shutdown.error_message);
}
}
Methods:
| Method | Signature | Description |
|---|---|---|
new | () -> Self | Create in idle state |
call | (&mut self, client: &mut CommandClient) | Poll for response — call every scan cycle |
initiate | (&mut self, client: &mut CommandClient) | Send system.full_shutdown. No-op while busy. |
cancel | (&mut self, client: &mut CommandClient) | Send system.cancel_full_shutdown. No-op while busy. |
is_initiating | (&self) -> bool | A shutdown initiation is pending |
is_cancelling | (&self) -> bool | A shutdown cancellation is pending |
Output fields:
| Field | Type | Description |
|---|---|---|
busy | bool | true while waiting for the server to respond |
done | bool | true for one cycle after the server confirms the command |
error | bool | true for one cycle after the server returns an error |
error_message | String | Error description from the server (empty when no error) |
Server broadcasts: When a shutdown is scheduled, the server sends system.shutdown_pending to all connected clients. If cancelled, it sends system.shutdown_cancelled. After the 15-second delay elapses, it sends system.shutdown_executing just before powering off.
Typical flow:
Cycle 1: initiate() → busy=true
Cycle 2: call() → (waiting for response)
Cycle 3: call() → done=true, busy=false (server accepted)
... 15 seconds pass on the server ...
Server powers off the PC
Cancellation flow:
Cycle 1: initiate() → busy=true
Cycle 2: call() → done=true (shutdown scheduled)
Cycle 3: call() → done cleared
Cycle 4: cancel() → busy=true
Cycle 5: call() → done=true (shutdown cancelled)
ni::DaqCapture — NI DAQ Triggered Capture
Manages the full lifecycle of a triggered DAQ capture: arm the trigger, wait for the hardware event, and retrieve the captured data. All communication is via IPC commands to the autocore-ni module — the control program does not need to interact with capture shared memory directly.
#![allow(unused)]
fn main() {
use autocore_std::fb::ni::DaqCapture;
use autocore_std::fb::RTrig;
struct MyProgram {
daq: DaqCapture,
arm_trigger: RTrig,
}
impl MyProgram {
fn new() -> Self {
Self {
daq: DaqCapture::new("ni.impact"), // matches the DAQ name in NI config
arm_trigger: RTrig::new(),
}
}
}
}
In process_tick:
#![allow(unused)]
fn main() {
// Call every cycle with the execute signal and a timeout (ms).
// Rising edge on the first argument triggers a new capture sequence.
self.daq.call(ctx.gm.arm_request, 5000, ctx.client);
// Check results
if self.daq.error {
log::error!("Capture error: {}", self.daq.error_message);
}
if !self.daq.busy && !self.daq.error {
if let Some(data) = &self.daq.data {
// Capture complete — process the data
log::info!(
"Captured {} channels, {} samples/ch at {} Hz",
data.channel_count, data.actual_samples, data.sample_rate,
);
// Access channel data: data.channels[ch_idx][sample_idx]
let ch0_peak = data.channels[0].iter().cloned().fold(f64::MIN, f64::max);
log::info!("Channel 0 peak: {:.2}", ch0_peak);
// Trigger point is at sample index data.pre_trigger_samples
let trigger_sample = data.pre_trigger_samples;
log::info!("Trigger at sample {}", trigger_sample);
}
}
}
Constructor:
| Method | Signature | Description |
|---|---|---|
new | (daq_fqdn: &str) -> Self | Create a new capture FB. daq_fqdn is the FQDN prefix for the DAQ, e.g. "ni.impact". |
Call signature:
#![allow(unused)]
fn main() {
pub fn call(&mut self, execute: bool, timeout_ms: u32, client: &mut CommandClient)
}
Call once per cycle. A rising edge on execute starts a new capture sequence. The FB internally handles edge detection, arming, polling for completion, reading the data, and timeout tracking.
Output fields:
| Field | Type | Description |
|---|---|---|
busy | bool | true from the rising edge of execute until capture completes or an error/timeout occurs |
active | bool | true while the DAQ is armed and waiting for the hardware trigger event |
error | bool | true when an error or timeout occurs. Stays true until the next rising edge of execute. |
error_message | String | Error description (empty when no error) |
data | Option<CaptureData> | Some(...) after a successful capture, None otherwise |
CaptureData fields:
| Field | Type | Description |
|---|---|---|
channels | Vec<Vec<f64>> | Sample data per channel. channels[ch_idx][sample_idx]. |
channel_count | usize | Number of channels in the capture |
capture_length | usize | Configured post-trigger samples per channel |
pre_trigger_samples | usize | Configured pre-trigger samples per channel |
actual_samples | usize | Total samples per channel actually written (pre + post) |
sample_rate | f64 | Sample rate in Hz |
timestamp_ns | u64 | UNIX timestamp (nanoseconds) of the trigger event |
sequence | u64 | Monotonically increasing capture sequence number |
State machine:
Idle ──(rising edge on execute)──> Arming (busy=true)
Arming ──(arm confirmed)────────> Waiting (active=true)
Waiting ──(data ready)──────────> Reading Data
Waiting ──(timeout)─────────────> Idle (error=true)
Reading Data ──(data received)──> Idle (data=Some(...))
Reading Data ──(error)──────────> Idle (error=true)
IPC commands used internally: <daq_fqdn>.arm, <daq_fqdn>.capture_status, <daq_fqdn>.read_capture. These are handled by the autocore-ni module.
Complete example — impact test with force plate:
#![allow(unused)]
fn main() {
use autocore_std::{ControlProgram, TickContext};
use autocore_std::fb::ni::DaqCapture;
use crate::gm::GlobalMemory;
pub struct ImpactTest {
daq: DaqCapture,
peak_force: f64,
}
impl ImpactTest {
pub fn new() -> Self {
Self {
daq: DaqCapture::new("ni.impact"),
peak_force: 0.0,
}
}
}
impl ControlProgram for ImpactTest {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
// Arm on rising edge of the HMI button, 10 second timeout
self.daq.call(ctx.gm.arm_request, 10000, ctx.client);
// Write status to HMI
ctx.gm.capture_busy = self.daq.busy;
ctx.gm.capture_active = self.daq.active;
ctx.gm.capture_error = self.daq.error;
// Process completed capture
if !self.daq.busy && !self.daq.error {
if let Some(data) = &self.daq.data {
// Sum all force channels to get total force per sample
let num_samples = data.actual_samples;
let mut total_force = vec![0.0f64; num_samples];
for ch in &data.channels {
for (i, &v) in ch.iter().enumerate() {
total_force[i] += v;
}
}
// Find peak total force
self.peak_force = total_force.iter().cloned().fold(f64::MIN, f64::max);
ctx.gm.peak_force = self.peak_force;
log::info!("Impact captured: peak force = {:.1} N", self.peak_force);
}
}
}
}
}
beckhoff::El3356 — Beckhoff EL3356 Strain-Gauge Terminal
Function block for the Beckhoff EL3356 single-channel strain-gauge evaluation terminal (and pin-compatible variants). Handles three things:
- Peak tracking — maintains a running largest-magnitude
peak_loadthat resets on tare orreset_peak(). - Tare — pulses the terminal’s tare output bit high for 100 ms and zeros the peak.
- Load-cell calibration — writes the three SDO parameters the EL3356 needs to scale raw bridge readings into engineering units (sensitivity, full-scale load, scale factor).
All IPC traffic is non-blocking. The FB owns an internal SdoClient scoped to the EtherCAT device name you pass to new().
Project.json prerequisites
Before writing a control program, project.json must declare five GM variables linked to the EL3356’s PDOs. Using a logical prefix of impact:
"variables": {
"impact_load": { "type": "f32", "link": "ethercat.EL3356_0.load", "description": "Scaled load (N)" },
"impact_load_steady": { "type": "bool", "link": "ethercat.EL3356_0.load_steady", "description": "Steady-state flag" },
"impact_load_error": { "type": "bool", "link": "ethercat.EL3356_0.load_error", "description": "Bridge error bit" },
"impact_load_overrange": { "type": "bool", "link": "ethercat.EL3356_0.load_overrange", "description": "Overrange flag" },
"impact_tare": { "type": "bool", "link": "ethercat.EL3356_0.tare", "description": "Tare command output" }
}
The {prefix}_* naming convention is required — the el3356_view! macro derives all five field names by concatenation. Replace impact with any prefix you like (e.g. load_cell, fz_sensor) and use that same identifier when invoking the macro. See Chapter 8 — Analog Input Terminals for the EtherCAT-side hardware configuration that produces these FQDNs.
Basic usage
#![allow(unused)]
fn main() {
use autocore_std::{ControlProgram, TickContext};
use autocore_std::fb::beckhoff::El3356;
use autocore_std::fb::RTrig;
use autocore_std::el3356_view;
use crate::gm::GlobalMemory;
pub struct LoadCellDemo {
load_cell: El3356,
manual_tare_edge: RTrig,
}
impl LoadCellDemo {
pub fn new() -> Self {
Self {
load_cell: El3356::new("EL3356_0"), // ethercat device name
manual_tare_edge: RTrig::new(),
}
}
}
impl ControlProgram for LoadCellDemo {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
// Rising edge on an HMI button tares the load cell
if self.manual_tare_edge.call(ctx.gm.manual_tare) {
self.load_cell.tare();
}
// Build the view from the linked GM fields and run the FB
let mut view = el3356_view!(ctx.gm, impact);
self.load_cell.tick(&mut view, ctx.client);
// Expose peak to the HMI
ctx.gm.impact_peak_load = self.load_cell.peak_load;
}
}
}
tick() must be called every scan — it’s what actually writes the tare bit to view.tare, updates peak_load, and advances any in-flight SDO sequence.
Constructor
| Method | Signature | Description |
|---|---|---|
new | (device: &str) -> Self | Create a new FB scoped to an EtherCAT device name (matches the devices[].name entry in the ethercat config — e.g. "EL3356_0"). |
Methods
Lifecycle & tare
| Method | Signature | Non-blocking | Description |
|---|---|---|---|
tick | (&mut self, view: &mut El3356View, client: &mut CommandClient) | yes | Call every scan. Updates peak_load from view.load, releases the 100 ms tare pulse, and progresses any active SDO sequence. |
tare | (&mut self) | yes | Start a 100 ms pulse on view.tare and zero peak_load. Subsequent tick() calls hold view.tare high until the window expires, then clear it. Calling tare() while a pulse is already active restarts the window. |
reset_peak | (&mut self) | yes | Zero peak_load. No IPC. |
reset | (&mut self) | yes | Full reset: clear error, cancel in-flight SDO, release tare pulse, discard last sdo_read result. Does not zero peak_load or configured_* fields. |
clear_error | (&mut self) | yes | Clear error and error_message. |
Calibration (three-step SDO sequences on 0x8000)
| Method | Signature | Non-blocking | Description |
|---|---|---|---|
configure | (&mut self, client: &mut CommandClient, full_scale_load: f32, sensitivity_mv_v: f32, scale_factor: f32) | yes | Start a three-step SDO write sequence to subs 0x23, 0x24, 0x27. Sets busy=true. No-op (warning logged) if already busy. Clears error at start. |
read_configuration | (&mut self, client: &mut CommandClient) | yes | Start a three-step SDO read sequence that pulls mV/V, full-scale, and scale factor from the terminal’s non-volatile memory and populates the configured_* fields. Sets busy=true. No-op if already busy. Clears error and resets all three configured_* fields to None at the start. |
Filter / ADC mode configuration
These write to sub-indices of 0x8000 via the generic sdo_write machinery — each sets busy=true; wait for it to clear (or is_error()) before issuing the next. All are no-op (with a warning log) if called while busy.
| Method | Signature | Writes sub | Description |
|---|---|---|---|
set_mode0_filter_enabled | (&mut self, client, enable: bool) | 0x01 | Enable/disable the software filter in Mode 0 (10.5 kSps, high-precision). Default TRUE. |
set_mode1_filter_enabled | (&mut self, client, enable: bool) | 0x02 | Enable/disable the software filter in Mode 1 (105.5 kSps, fast). Default TRUE. |
set_mode0_averager_enabled | (&mut self, client, enable: bool) | 0x03 | Enable/disable the 4-sample hardware averager in Mode 0 (~0.14 ms added latency). Default TRUE. |
set_mode1_averager_enabled | (&mut self, client, enable: bool) | 0x05 | Enable/disable the 4-sample hardware averager in Mode 1 (~0.014 ms added latency). Default TRUE. |
set_mode0_filter | (&mut self, client, filter: El3356Filters) | 0x11 | Select the Mode 0 software filter. See El3356Filters. |
set_mode1_filter | (&mut self, client, filter: El3356Filters) | 0x12 | Select the Mode 1 software filter. |
Low-level / accessors
| Method | Signature | Non-blocking | Description |
|---|---|---|---|
sdo_write | (&mut self, client, index: u16, sub_index: u8, value: serde_json::Value) | yes | Write an arbitrary SDO. Runs through the FB’s busy/state machine (sets busy=true). Does not touch the configured_* calibration fields — orthogonal to configure(). |
sdo_read | (&mut self, client, index: u16, sub_index: u8) | yes | Read an arbitrary SDO. Response lands in the internal result buffer; retrieve via result() / result_as_* once busy clears. Also does not touch configured_*. |
is_busy | (&self) -> bool | — | Same as reading the busy field directly. |
is_error | (&self) -> bool | — | Same as reading the error field directly. |
result | (&self) -> serde_json::Value | — | Full response payload from the last sdo_read — the object with value, value_hex, size, raw_bytes, etc. Prefer the typed accessors for scalar reads. |
result_as_f64 | (&self) -> Option<f64> | — | value field of the last sdo_read, coerced to f64. None before any read. |
result_as_i64 | (&self) -> Option<i64> | — | value field as i64. For REAL32 SDOs this returns the raw u32 bit pattern; use result_as_f32 instead. |
result_as_f32 | (&self) -> Option<f32> | — | value field reinterpreted as IEEE-754 REAL32 via f32::from_bits. Correct accessor for REAL32 SDOs such as the EL3356’s calibration parameters. |
Output fields
| Field | Type | Description |
|---|---|---|
peak_load | f32 | Largest absolute load seen since the last tare or reset_peak(). The signed value at the peak is stored. |
busy | bool | true during a configure() or read_configuration() sequence. |
error | bool | Sticky — set on any SDO failure. Cleared by clear_error() or the start of the next configure() / read_configuration() call. |
error_message | String | Description of the most recent error (empty when none). |
configured_mv_v | Option<f32> | Current sensitivity (sub 0x23) — set by a successful configure() or read_configuration(). Reset to None at the start of each such call. |
configured_full_scale_load | Option<f32> | Current full-scale load (sub 0x24). Same lifecycle as configured_mv_v. |
configured_scale_factor | Option<f32> | Current scale factor (sub 0x27). Same lifecycle as configured_mv_v. |
Configure state machine
configure() writes three SDOs in sequence. Each transition happens on a subsequent tick() after the IPC response lands:
Idle ──(configure called)───> WritingMvV (busy=true, writes sub 0x23)
WritingMvV ──(OK)───────────> WritingFullScale (writes sub 0x24)
WritingMvV ──(Err/Timeout)──> Idle (error=true, busy=false)
WritingFullScale ──(OK)─────> WritingScaleFactor (writes sub 0x27)
WritingFullScale ──(Err)────> Idle (error=true, busy=false)
WritingScaleFactor ──(OK)───> Idle (busy=false, all three configured_* set)
WritingScaleFactor ──(Err)──> Idle (error=true, busy=false)
SDO timeout is 3 seconds per write.
Read-configuration state machine
read_configuration() reads the same three SDOs. The response payload’s
value field is the IEEE-754 REAL32 bit pattern as a u32, which the FB
converts back to f32 via f32::from_bits before populating the
configured_* field.
Idle ──(read_configuration called)─> ReadingMvV (busy=true, reads sub 0x23)
ReadingMvV ──(OK)─────────────────> ReadingFullScale (reads sub 0x24)
ReadingMvV ──(Err/Timeout/parse)──> Idle (error=true, busy=false)
ReadingFullScale ──(OK)───────────> ReadingScaleFactor (reads sub 0x27)
ReadingFullScale ──(Err)──────────> Idle (error=true, busy=false)
ReadingScaleFactor ──(OK)─────────> Idle (busy=false, all three configured_* set)
ReadingScaleFactor ──(Err)────────> Idle (error=true, busy=false)
A partial failure leaves all three configured_* fields at None — after a
failed read the control program should treat the device’s parameters as
unknown, not trust the fields that did come back before the failure.
SDO timeout is 3 seconds per read.
Verifying non-volatile parameters at startup
The EL3356 stores sensitivity, full-scale, and scale factor in non-volatile memory, so a just-powered-up card carries whatever was last written — not necessarily what the current control program expects. The canonical startup pattern is: read, compare against expected, re-configure only if they don’t match.
use autocore_std::{ControlProgram, TickContext};
use autocore_std::fb::beckhoff::El3356;
use autocore_std::el3356_view;
use crate::gm::GlobalMemory;
const EXPECTED_FULL_SCALE: f32 = 1_000.0;
const EXPECTED_MV_V: f32 = 2.0;
const EXPECTED_SCALE: f32 = 100_000.0;
#[derive(PartialEq)]
enum StartupPhase { ReadPending, Check, Writing, Ready, Failed }
pub struct ImpactStation {
load_cell: El3356,
phase: StartupPhase,
}
impl ImpactStation {
pub fn new() -> Self {
Self {
load_cell: El3356::new("EL3356_0"),
phase: StartupPhase::ReadPending,
}
}
}
impl ControlProgram for ImpactStation {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
// Always tick the FB (peak tracking, tare pulse, SDO progress).
let mut view = el3356_view!(ctx.gm, impact);
self.load_cell.tick(&mut view, ctx.client);
match self.phase {
StartupPhase::ReadPending => {
if !self.load_cell.busy {
self.load_cell.read_configuration(ctx.client);
self.phase = StartupPhase::Check;
}
}
StartupPhase::Check => {
if self.load_cell.error {
log::error!("Load cell config read failed: {}", self.load_cell.error_message);
self.phase = StartupPhase::Failed;
} else if !self.load_cell.busy {
let ok = self.load_cell.configured_mv_v == Some(EXPECTED_MV_V)
&& self.load_cell.configured_full_scale_load == Some(EXPECTED_FULL_SCALE)
&& self.load_cell.configured_scale_factor == Some(EXPECTED_SCALE);
if ok {
log::info!("Load cell already calibrated correctly — no write needed");
self.phase = StartupPhase::Ready;
} else {
log::warn!(
"Load cell parameters differ from expected (got mV/V={:?}, full_scale={:?}, scale={:?}) — rewriting",
self.load_cell.configured_mv_v,
self.load_cell.configured_full_scale_load,
self.load_cell.configured_scale_factor,
);
self.load_cell.configure(
ctx.client, EXPECTED_FULL_SCALE, EXPECTED_MV_V, EXPECTED_SCALE,
);
self.phase = StartupPhase::Writing;
}
}
}
StartupPhase::Writing => {
if self.load_cell.error {
log::error!("Load cell configure failed: {}", self.load_cell.error_message);
self.phase = StartupPhase::Failed;
} else if !self.load_cell.busy {
self.phase = StartupPhase::Ready;
}
}
StartupPhase::Ready | StartupPhase::Failed => {
// Normal operation below — see the main usage example.
}
}
ctx.gm.impact_peak_load = self.load_cell.peak_load;
ctx.gm.impact_calibrated = self.phase == StartupPhase::Ready;
ctx.gm.impact_startup_error = self.phase == StartupPhase::Failed;
}
}
This verify-then-write pattern avoids unnecessary EEPROM wear on the EL3356 — writes only happen when the stored values actually differ from the expected calibration.
The el3356_view! macro
let mut view = el3356_view!(ctx.gm, impact);
Expands to an El3356View with references to ctx.gm.impact_tare, ctx.gm.impact_load, ctx.gm.impact_load_steady, ctx.gm.impact_load_error, and ctx.gm.impact_load_overrange. Use a different prefix per terminal when you have multiple — each call to the macro produces a fresh view bound to that prefix’s fields.
El3356View fields
| Field | Type | Direction | Description |
|---|---|---|---|
tare | &mut bool | output | Tare command bit. Written by tick(). |
load | &f32 | input | Scaled load value from the terminal. |
load_steady | &bool | input | Steady-state indicator. true when the signal has been stable within the configured band. |
load_error | &bool | input | General error flag. |
load_overrange | &bool | input | Signal exceeds configured range. |
El3356Filters enum
Passed to [set_mode0_filter] and [set_mode1_filter]. Selects which software filter runs on the ADC output before the process value is published. The enum is #[repr(u16)] so the discriminant matches the CoE register layout exactly.
| Variant | Register value | Cutoff | ~Step-response latency | Typical use |
|---|---|---|---|---|
FIR50Hz | 0 | 50 Hz notch | ~13 ms | Suppress 50 Hz mains hum |
FIR60Hz | 1 | 60 Hz notch | ~16 ms | Suppress 60 Hz mains hum |
IIR1 | 2 | ~2000 Hz | ~0.3 ms | Very fast tracking, minimal smoothing |
IIR2 | 3 | ~500 Hz | ~0.8 ms | Light smoothing |
IIR3 | 4 | ~125 Hz | ~3.5 ms | Fast machinery tracking |
IIR4 | 5 | ~30 Hz | ~14 ms | Moderate mechanical vibration rejection |
IIR5 | 6 | ~8 Hz | ~56 ms | Slower processes |
IIR6 | 7 | ~2 Hz | ~225 ms | Heavy smoothing, mostly static loads |
IIR7 | 8 | ~0.5 Hz | ~900 ms | Very heavy smoothing |
IIR8 | 9 | ~0.1 Hz | ~3600 ms | Maximum damping, fully static measurement |
DynamicIIR | 10 | variable | ~0.3 ms – ~3600 ms | Auto-switches between IIR1 and IIR8 based on signal change rate — good for dosing/filling (fast track + static precision) |
PDOFilterFrequency | 11 | variable | depends | FIR notch with PDO-driven frequency (0.1 Hz to 200 Hz); use for vibration suppression at a known, variable frequency |
Filter chain — why both averager and software filter
The EL3356’s signal path is:
Raw ADC → Hardware 4-sample averager → Software filter (FIR/IIR) → PDO
They attack different noise types. The hardware averager is the optimal tool for random Gaussian “white” noise (electrical interference in the sensor wires) and adds almost no latency — ~0.14 ms in Mode 0, ~0.014 ms in Mode 1. Leave it on in almost every case.
The software filters target specific lower-frequency phenomena: FIR notches kill mains hum (50/60 Hz), IIR low-pass filters damp mechanical vibration (hopper swing, force-plate ring-out, etc.).
Running both is the right default. The averager clips random spikes before they reach the IIR filter — important because IIR filters “ring” on sharp spikes, causing an exponential tail that skews readings. With the averager feeding the IIR a clean baseline, you can often drop to a weaker, faster IIR level (IIR3 instead of IIR5) and save tens to hundreds of milliseconds of total latency while still rejecting the mechanical noise you care about.
Mode 0 vs Mode 1
The EL3356 has two ADC modes selected by the Sample Mode bit of the Control Word:
| Mode | ADC rate | Hardware latency | Typical filter pairing | Typical use |
|---|---|---|---|---|
| 0 — High Precision (default) | 10.5 kSps | ~7.2 ms | Strong IIR (IIR5–IIR8) | Static weighing, high-accuracy calm readings |
| 1 — High Speed | 105.5 kSps | ~0.72 ms | Weak or off (IIR1, or filter disabled) | Impact capture, high-speed dosing, fast transients |
set_mode0_filter and set_mode1_filter configure each mode independently, so you can have both pre-loaded and switch between them in-flight via the Control Word without a reconfigure round-trip.
Complete example — calibrate at startup, then run
The typical workflow: configure the load cell once when the system comes up, then run the main process loop. Use a simple state flag to sequence startup before normal operation.
use autocore_std::{ControlProgram, TickContext};
use autocore_std::fb::beckhoff::El3356;
use autocore_std::fb::RTrig;
use autocore_std::el3356_view;
use crate::gm::GlobalMemory;
pub struct ImpactStation {
load_cell: El3356,
configured: bool,
tare_edge: RTrig,
}
impl ImpactStation {
pub fn new() -> Self {
Self {
load_cell: El3356::new("EL3356_0"),
configured: false,
tare_edge: RTrig::new(),
}
}
}
impl ControlProgram for ImpactStation {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
// 1. One-shot calibration on first tick
if !self.configured && !self.load_cell.busy {
self.load_cell.configure(
ctx.client,
/* full_scale_load */ 1_000.0, // N (sensor rating)
/* sensitivity */ 2.0, // mV/V (sensor datasheet)
/* scale_factor */ 100_000.0, // EL3356 default
);
self.configured = true;
}
// 2. Normal operation: manual tare from HMI, tick the FB
if self.tare_edge.call(ctx.gm.manual_tare) {
self.load_cell.tare();
}
let mut view = el3356_view!(ctx.gm, impact);
self.load_cell.tick(&mut view, ctx.client);
// 3. Publish state
ctx.gm.impact_peak_load = self.load_cell.peak_load;
ctx.gm.impact_calibrated = self.load_cell.configured_mv_v.is_some();
ctx.gm.impact_calibration_err = self.load_cell.error;
if self.load_cell.error {
log::warn!("Load cell: {}", self.load_cell.error_message);
// Optional: retry on next tick by flipping `configured` back to false
// after clear_error(), or require operator acknowledgement.
}
}
}
Auto-tare after calibration
If you want the terminal to re-zero automatically as soon as calibration completes, watch the configured_scale_factor field for a transition from None to Some(_):
let was_configured = self.load_cell.configured_scale_factor.is_some();
// ... call self.load_cell.tick() ...
let now_configured = self.load_cell.configured_scale_factor.is_some();
if !was_configured && now_configured {
self.load_cell.tare(); // fire once on the completion edge
}
Multiple load cells
Each terminal gets its own FB instance, view prefix, and SDO client. Their calls are independent — SDO sequences can run in parallel:
pub struct DualStation {
fx: El3356, // station 1
fy: El3356, // station 2
}
impl DualStation {
pub fn new() -> Self {
Self {
fx: El3356::new("EL3356_0"),
fy: El3356::new("EL3356_1"),
}
}
}
impl ControlProgram for DualStation {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
let mut fx_view = el3356_view!(ctx.gm, fx);
let mut fy_view = el3356_view!(ctx.gm, fy);
self.fx.tick(&mut fx_view, ctx.client);
self.fy.tick(&mut fy_view, ctx.client);
}
}
Porting notes for TwinCAT users
If you’re migrating from a TwinCAT-style EL3356 FB, here’s the direct mapping:
| TwinCAT concept | Rust equivalent |
|---|---|
AT %I* inputs (fLoad, bLoadSteady, bLoadError, bLoadOverrange) | &T fields on El3356View |
AT %Q* output (bTare) | &mut bool on El3356View |
nCommandCode / nStatusCode handshake | Method calls (.tare(), .configure()) + pub busy: bool field |
rtTare / ftTare edge triggers on a manual-tare button | RTrig from autocore_std::fb, invoked on the HMI field; call .tare() on the rising edge |
writeMvV(... bExecute := bWriteSdo) | First step of configure() — writes 0x8000:0x23 internally |
writeFullLoad(... ) | Second step of configure() — 0x8000:0x24 |
writeScale(..., SCALE_FACTOR, ...) | Third step of configure() — 0x8000:0x27. Pass the scale factor as the third arg. |
CASE state.index OF ... T#100MS TON for tare pulse timing | Internal to the FB — tick() clears the tare bit automatically 100 ms after tare() is called. |
stEL3356.fPeakLoad := fLoad peak update | Automatic at the top of every tick(). |
There is no equivalent to the PLC’s E_LoadCellCommand enum; you call the Rust methods directly. There’s also no status-ack round-trip — busy simply reflects whether an operation is in progress, and control programs poll it from their own state machines.
Motion
Import motion function blocks from autocore_std::motion.
SeekProbe — Jog to Sensor
Jogs an axis in the negative direction until a sensor triggers, then halts. The axis must be enabled and at a position > 0 before executing.
Jog velocity, acceleration, and deceleration are taken from the axis configuration (jog_speed, jog_accel, jog_decel).
use autocore_std::motion::{AxisConfig, SeekProbe};
use crate::gm::AxisLift;
struct MyProgram {
lift_axis: AxisLift,
seek_ball: SeekProbe,
}
impl MyProgram {
fn new() -> Self {
let config = AxisConfig::new(12_800).with_user_scale(100.0);
Self {
lift_axis: AxisLift::new(config),
seek_ball: SeekProbe::new(),
}
}
}
In process_tick:
// Read feedback
self.lift_axis.sync(&ctx.gm);
// Outer State Machine logic
match self.state {
State::StartSeek => {
self.seek_ball.start();
self.state = State::WaitSeek;
}
State::WaitSeek => {
// Run the seek probe state machine
self.seek_ball.tick(&mut self.lift_axis, ctx.gm.ball_sensor);
if self.seek_ball.done {
log::info!("Probe found at position {:.3}", self.lift_axis.position());
self.state = State::Done;
} else if self.seek_ball.is_error() {
log::error!("Seek failed: code={}", self.seek_ball.error_code());
self.state = State::Error;
}
}
}
// Write outputs
self.lift_axis.tick(&mut ctx.gm, &mut ctx.client);
Methods:
| Method | Signature | Description |
|---|---|---|
new | () -> Self | Create in idle state |
start | (&mut self) | Start the seek operation on the next tick |
tick | (&mut self, handle: &mut impl AxisHandle, sensor: bool) | Execute one scan cycle. |
reset | (&mut self, handle: &mut impl AxisHandle) | Halt axis immediately and return FB to idle state |
is_busy | (&self) -> bool | true while seek operation is in progress |
is_error | (&self) -> bool | true if an error occurred during the seek |
error_code | (&self) -> i32 | Returns the error code from the state machine |
Output fields:
| Field | Type | Description |
|---|---|---|
done | bool | true for one cycle when the probe is found and axis has stopped |
error | bool | true when an error occurs |
state | StateMachine | Internal state machine with index, error_code, error_message |
Error codes:
| Code | Meaning |
|---|---|
| 1 | Abort/Reset called while motion was active |
| 100 | Axis position is not > 0 at start |
| 120 | Axis error or control disabled during motion |
| 200 | Axis reported error when stopping |
State diagram:
┌──────────┐ execute ↑ ┌────────────┐ position>0 ┌────────────────┐
│ 10: Idle │──────────►│ 100: Start │────────────►│ 120: Jogging │
└──────────┘ └────────────┘ │ (negative) │
▲ │ pos<=0 └───────┬────────┘
│ ▼ sensor │ │ axis error
│ error_code=100 ▼ ▼
│ ┌────────────────┐
│◄──── done=true ◄─────────────────────────│ 200: Stopping │
│◄──── error=true ◄────────────────────────│ │
│ └────────────────┘
│◄──── error=true ◄── 250: Motion Error
Complete example — ball detect on a linear slide:
use autocore_std::{ControlProgram, TickContext};
use autocore_std::motion::{AxisConfig, SeekProbe};
use crate::gm::{GlobalMemory, Slide};
pub struct BallDetect {
drive: Slide,
seek: SeekProbe,
}
impl BallDetect {
pub fn new() -> Self {
let config = AxisConfig::new(12_800)
.with_user_scale(100.0); // mm per rev
Self {
drive: Slide::new(config),
seek: SeekProbe::new(),
}
}
}
impl ControlProgram for BallDetect {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
self.drive.sync(&ctx.gm);
self.seek.call(
&mut self.drive.axis,
&mut self.drive.snapshot,
ctx.gm.start_button,
ctx.gm.proximity_sensor,
);
ctx.gm.seek_busy = self.seek.is_busy();
if self.seek.done {
ctx.gm.probe_position = self.drive.position();
log::info!("Ball detected at {:.3} mm", self.drive.position());
}
if self.seek.error {
ctx.gm.error_code = self.seek.state.error_code;
log::error!("Seek error {}: {}",
self.seek.state.error_code,
self.seek.state.error_message);
}
// Abort on E-stop
if ctx.gm.estop {
self.seek.abort(&mut self.drive.axis, &mut self.drive.snapshot);
}
self.drive.tick(&mut ctx.gm, &mut ctx.client);
}
}
PressureControl — Closed-loop force control
A closed-loop PID pressure/force controller for Profile Position (PP) axes.
This function block uses an Exponential Moving Average (EMA) filter to smooth incoming load cell data. It calculates a PID output which is clamped to a safe maximum step size and issued as a small, incremental absolute target to the drive every cycle. It is designed to safely apply a consistent load to a material at high tick rates (1-3ms).
use autocore_std::motion::{PressureControl, PressureControlConfig};
Configuration:
The controller requires a PressureControlConfig struct to dictate tuning and safety bounds:
| Field | Type | Default | Description |
|---|---|---|---|
kp | f64 | 0.0 | Proportional gain. |
ki | f64 | 0.0 | Integral gain. |
kd | f64 | 0.0 | Derivative gain. |
feed_forward | f64 | 0.0 | Feed forward value added directly to the output. |
max_step | f64 | 0.005 | Maximum allowed position delta (in user units) per call/tick. Critical safety limit to prevent crushing. |
max_integral | f64 | 100.0 | Maximum accumulated integral windup. |
filter_alpha | f64 | 0.5 | EMA filter coefficient (0.0 to 1.0). 1.0 = No filtering (raw data), 0.1 = Heavy filtering. |
invert_direction | bool | false | Set to true if moving the axis negative increases compression (e.g., a downward Z-axis). |
tolerance | f64 | 1.0 | Acceptable load error window to be considered “in tolerance” (e.g., +/- 2.0 lbs). |
settling_time | f64 | 0.1 | How long the load must remain within tolerance before reporting in_tolerance = true. |
Execution:
You must call the function block every tick while active. On the rising edge of execute, it will engage the PID loop. On the falling edge, it will automatically halt the axis and reset its internal state.
pub fn call(
&mut self,
axis: &mut impl AxisHandle,
execute: bool,
target_load: f64,
current_load: f64,
config: &PressureControlConfig,
dt: f64,
)
Output fields:
| Field | Type | Description |
|---|---|---|
active | bool | true when the block is actively executing and controlling the axis. |
in_tolerance | bool | true when the current load has been within config.tolerance for at least config.settling_time seconds. |
error | bool | true if a fault occurred (e.g., axis error). Check state.error_code. |
state | StateMachine | Internal state machine for operation sequencing and error reporting. |
Example:
use autocore_std::{ControlProgram, TickContext};
use autocore_std::motion::{AxisConfig, PressureControl, PressureControlConfig};
use crate::gm::{GlobalMemory, PressAxis};
pub struct MyPressProgram {
drive: PressAxis,
pressure_fb: PressureControl,
config: PressureControlConfig,
}
impl MyPressProgram {
pub fn new() -> Self {
Self {
drive: PressAxis::new(AxisConfig::new(10_000)),
pressure_fb: PressureControl::new(),
config: PressureControlConfig {
kp: 0.05,
filter_alpha: 0.1, // Smooth noisy load cell
invert_direction: true, // Z-axis presses down (negative)
max_step: 0.002, // Never move more than 0.002 units per ms
tolerance: 2.5,
settling_time: 0.5,
..Default::default()
},
}
}
}
impl ControlProgram for MyPressProgram {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
self.drive.sync(&ctx.gm);
// dt is the cycle time in seconds (e.g., 0.001 for 1ms tick)
let dt = ctx.cycle_time_us as f64 / 1_000_000.0;
self.pressure_fb.call(
&mut self.drive.axis,
ctx.gm.engage_press, // execute
ctx.gm.target_pressure,
ctx.gm.load_cell_value,
&self.config,
dt,
);
ctx.gm.press_active = self.pressure_fb.active;
ctx.gm.press_in_tolerance = self.pressure_fb.in_tolerance;
if self.pressure_fb.error {
log::error!("Press fault: {}", self.pressure_fb.state.error_message);
ctx.gm.engage_press = false; // Reset command
}
self.drive.tick(&mut ctx.gm, &mut ctx.client);
}
}
MoveToLoad — Move until load is reached
Moves an axis towards a target load (e.g., from a load cell) and stops as quickly as possible once the edge of that load is reached. It does not average the input, making it highly responsive for edge detection.
- If
current_load > target_load, it moves in the negative direction. - If
current_load < target_load, it moves in the positive direction.
It accepts a position_limit safety envelope and a hysteresis value (minimum 1.0) to prevent premature stopping from noise spikes.
use autocore_std::motion::MoveToLoad;
Execution:
You must call the function block every tick while active. On the rising edge of execute, it will determine the direction and issue a move. On the falling edge, it will automatically halt the axis and reset its internal state.
pub fn call(
&mut self,
axis: &mut impl AxisHandle,
execute: bool,
target_load: f64,
current_load: f64,
position_limit: f64,
hysteresis: f64,
)
Output fields:
| Field | Type | Description |
|---|---|---|
done | bool | true when the target load edge has been reached and the axis has halted. |
active | bool | true when the block is actively executing motion. |
error | bool | true if a fault occurred (e.g., reached position limit, axis error). Check state.error_code. |
state | StateMachine | Internal state machine for operation sequencing and error reporting. |
Error codes:
| Code | Meaning |
|---|---|
| 1 | Abort called |
| 110 | Axis already past position limit before starting |
| 120 | Axis is in an error state |
| 150 | Reached position limit without hitting target load |
Example:
use autocore_std::{ControlProgram, TickContext};
use autocore_std::motion::{AxisConfig, MoveToLoad};
use crate::gm::{GlobalMemory, PressAxis};
pub struct MyPressProgram {
drive: PressAxis,
move_to_load_fb: MoveToLoad,
}
impl MyPressProgram {
pub fn new() -> Self {
Self {
drive: PressAxis::new(AxisConfig::new(10_000)),
move_to_load_fb: MoveToLoad::new(),
}
}
}
impl ControlProgram for MyPressProgram {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
self.drive.sync(&ctx.gm);
self.move_to_load_fb.call(
&mut self.drive.axis,
ctx.gm.start_move, // execute
-50.0, // target_load (50 lbs compression)
ctx.gm.load_cell, // current_load
-10.0, // position_limit (never move past -10.0)
2.0, // hysteresis
);
if self.move_to_load_fb.done {
log::info!("Load edge reached!");
ctx.gm.start_move = false;
}
if self.move_to_load_fb.error {
log::error!("Move to load failed: {}", self.move_to_load_fb.state.error_message);
ctx.gm.start_move = false;
}
self.drive.tick(&mut ctx.gm, &mut ctx.client);
}
}
Banner
Import Banner device helpers from autocore_std::banner::wls15.
Wls15RunMode — WLS15P IO-Link Light Strip
Controls a Banner WLS15P multi-color light strip via IO-Link. Each output field corresponds to a PDO byte that should be linked to the device’s IO-Link process data. Use the preset methods for common animations, or set the fields directly for full control.
use autocore_std::banner::wls15::{Wls15RunMode, Color, ColorIntensity, Speed};
let mut light = Wls15RunMode::new();
// Solid green
light.steady(Color::Green, ColorIntensity::High);
// Red alert — scrolls out from center
light.alert(Color::Red, ColorIntensity::High, Speed::Medium);
// Knight Rider scanner effect
light.knight_rider(Color::Red);
// Breathing pulse
light.pulse(Color::Blue, ColorIntensity::High, Speed::Slow);
// Rainbow spectrum
light.spectrum(Speed::Fast);
// Turn off
light.off();
Preset methods:
| Method | Signature | Description |
|---|---|---|
new | () -> Self | Create with all outputs at zero (off) |
off | (&mut self) | Turn the light off |
steady | (&mut self, color, intensity) | Solid single color |
flash | (&mut self, color, intensity, speed) | Single color flashing |
alert | (&mut self, color, intensity, speed) | Center-scroll alert pattern |
knight_rider | (&mut self, color) | Bouncing scanner with tail |
pulse | (&mut self, color, intensity, speed) | Smooth breathing effect |
spectrum | (&mut self, speed) | Rainbow sweep across the strip |
PDO output fields (all u8):
| Field | Type | Description |
|---|---|---|
animation | u8 | Animation mode (see Animation enum) |
color1 | u8 | Primary color (see Color enum) |
color1_intensity | u8 | Primary color intensity (see ColorIntensity enum) |
color2 | u8 | Secondary color |
color2_intensity | u8 | Secondary color intensity |
speed | u8 | Animation speed (see Speed enum) |
pulse_pattern | u8 | Pulse pattern (see PulsePattern enum) |
scroll_bounce_style | u8 | Scroll/bounce style (see ScrollStyle enum) |
percent_width_color1 | u8 | Color 1 width percentage (0-100) |
direction | u8 | Direction: 0=Up, 1=Down |
Enums:
All enums are #[repr(u8)] and map directly to hardware PDO values.
| Enum | Values |
|---|---|
Animation | Off(0), Steady(1), Flash(2), TwoColorFlash(3), TwoColorShift(4), EndsSteady(5), EndsFlash(6), Scroll(7), CenterScroll(8), Bounce(9), CenterBounce(10), IntensitySweep(11), TwoColorSweep(12), Spectrum(13), SingleEndSteady(14), SingleEndFlash(15) |
Color | Green(0), Red(1), Orange(2), Amber(3), Yellow(4), LimeGreen(5), SpringGreen(6), Cyan(7), SkyBlue(8), Blue(9), Violet(10), Magenta(11), Rose(12), DaylightWhite(13), Custom1(14), Custom2(15), IncandescentWhite(16), WarmWhite(17), FluorescentWhite(18), NeutralWhite(19), CoolWhite(20) |
ColorIntensity | High(0), Low(1), Medium(2), Off(3), Custom(4) |
Speed | Medium(0), Fast(1), Slow(2), CustomFlashRate(3) |
PulsePattern | Normal(0), Strobe(1), ThreePulse(2), Sos(3), Random(4) |
ScrollStyle | Solid(0), Tail(1), Ripple(2) |
Direction | Up(0), Down(1) |
Complete example — machine status indicator:
use autocore_std::{ControlProgram, TickContext};
use autocore_std::banner::wls15::{Wls15RunMode, Color, ColorIntensity, Speed};
use crate::gm::GlobalMemory;
pub struct StatusLight {
light: Wls15RunMode,
}
impl StatusLight {
pub fn new() -> Self {
Self { light: Wls15RunMode::new() }
}
}
impl ControlProgram for StatusLight {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
if ctx.gm.fault_active {
self.light.alert(Color::Red, ColorIntensity::High, Speed::Fast);
} else if ctx.gm.cycle_running {
self.light.steady(Color::Green, ColorIntensity::High);
} else if ctx.gm.waiting_for_part {
self.light.pulse(Color::Yellow, ColorIntensity::High, Speed::Slow);
} else {
self.light.off();
}
// Write PDO outputs to global memory
ctx.gm.wls15_animation = self.light.animation;
ctx.gm.wls15_color1 = self.light.color1;
ctx.gm.wls15_color1_intensity = self.light.color1_intensity;
ctx.gm.wls15_color2 = self.light.color2;
ctx.gm.wls15_color2_intensity = self.light.color2_intensity;
ctx.gm.wls15_speed = self.light.speed;
ctx.gm.wls15_pulse_pattern = self.light.pulse_pattern;
ctx.gm.wls15_scroll_bounce_style = self.light.scroll_bounce_style;
ctx.gm.wls15_percent_width = self.light.percent_width_color1;
ctx.gm.wls15_direction = self.light.direction;
}
}
Wls15Digital — WLS15P Two-Wire Digital Control
Controls a Banner WLS15P using two digital outputs (Q1, Q2) for simple color selection with optional blinking. No IO-Link required — connect two wires directly to the light strip inputs.
use autocore_std::banner::wls15::Wls15Digital;
use std::time::Duration;
let mut light = Wls15Digital::new();
// Set colors
light.green(); // Q1=false, Q2=true
light.red(); // Q1=true, Q2=false
light.blue(); // Q1=true, Q2=true
light.off(); // Q1=false, Q2=false
// Enable blinking at 500ms interval
light.blink_on(Duration::from_millis(500));
light.call(); // must call every scan cycle
// Disable blinking
light.blink_off();
Color mapping:
| Q1 | Q2 | Color |
|---|---|---|
false | false | Off |
true | false | Red |
false | true | Green |
true | true | Blue |
Methods:
| Method | Signature | Description |
|---|---|---|
new | () -> Self | Create with outputs off, no blink |
off | (&mut self) | Set color to off |
red | (&mut self) | Set color to red |
green | (&mut self) | Set color to green |
blue | (&mut self) | Set color to blue |
blink_on | (&mut self, interval: Duration) | Enable blinking at the specified interval |
blink_off | (&mut self) | Disable blinking — outputs follow color directly |
call | (&mut self) | Update outputs — call every scan cycle |
Output fields:
| Field | Type | Description |
|---|---|---|
q1 | bool | Digital output 1 — connect to light strip channel 1 |
q2 | bool | Digital output 2 — connect to light strip channel 2 |
Complete example — error blinker:
use autocore_std::{ControlProgram, TickContext};
use autocore_std::banner::wls15::Wls15Digital;
use std::time::Duration;
use crate::gm::GlobalMemory;
pub struct ErrorBlinker {
light: Wls15Digital,
}
impl ErrorBlinker {
pub fn new() -> Self {
Self { light: Wls15Digital::new() }
}
}
impl ControlProgram for ErrorBlinker {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
if ctx.gm.fault_active {
self.light.red();
self.light.blink_on(Duration::from_millis(250));
} else if ctx.gm.cycle_running {
self.light.green();
self.light.blink_off();
} else {
self.light.off();
self.light.blink_off();
}
self.light.call();
// Write outputs to global memory (mapped to digital outputs)
ctx.gm.light_q1 = self.light.q1;
ctx.gm.light_q2 = self.light.q2;
}
}
EtherCAT
Import EtherCAT helpers from autocore_std::ethercat.
SdoClient — Non-Blocking SDO Access
Provides an ergonomic, handle-based interface for runtime SDO (Service Data Object) operations over CoE (CANopen over EtherCAT). Create one per device, issue reads/writes from your control loop, and check results by handle on subsequent ticks.
Use SdoClient for runtime SDO access — reading diagnostic registers, changing operating parameters on the fly, or any CoE transfer that happens after the cyclic loop is running. For SDOs that must be applied before the cyclic loop starts (e.g. setting modes_of_operation), use the startup_sdo array in project.json instead.
use autocore_std::ethercat::{SdoClient, SdoResult};
use serde_json::json;
use std::time::Duration;
let mut sdo = SdoClient::new("ClearPath_0");
// Issue an SDO write (from process_tick):
let tid = sdo.write(ctx.client, 0x6060, 0, json!(1));
// Check result on subsequent ticks:
match sdo.result(ctx.client, tid, Duration::from_secs(3)) {
SdoResult::Pending => { /* keep waiting */ }
SdoResult::Ok(_) => { log::info!("SDO write confirmed"); }
SdoResult::Err(e) => { log::error!("SDO error: {}", e); }
SdoResult::Timeout => { log::error!("SDO timed out"); }
}
Methods:
| Method | Signature | Description |
|---|---|---|
new | (device: &str) -> Self | Create a client scoped to a device (e.g. "ClearPath_0") |
write | (&mut self, client, index: u16, sub_index: u8, value: Value) -> u32 | Issue SDO write; returns transaction handle |
read | (&mut self, client, index: u16, sub_index: u8) -> u32 | Issue SDO read; returns transaction handle |
result | (&mut self, client, tid: u32, timeout: Duration) -> SdoResult | Check result of in-flight request |
drain_stale | (&mut self, client, timeout: Duration) | Remove requests pending longer than timeout |
pending_count | (&self) -> usize | Number of in-flight SDO requests |
SdoResult variants:
| Variant | Description |
|---|---|
Pending | No response yet — check again next tick |
Ok(Value) | Success; contains the read value or null for writes |
Err(String) | Server/EtherCAT error with message (e.g. "SDO abort: 0x06090011") |
Timeout | No response within caller-specified deadline |
IPC topics used internally:
| Operation | Topic | Payload |
|---|---|---|
| Write | ethercat.{device}.sdo_write | {"index": "0x6060", "sub": 0, "value": 1} |
| Read | ethercat.{device}.sdo_read | {"index": "0x6064", "sub": 0} |
Complete example — runtime parameter change with state machine:
use autocore_std::{ControlProgram, TickContext};
use autocore_std::ethercat::{SdoClient, SdoResult};
use autocore_std::fb::StateMachine;
use serde_json::json;
use std::time::Duration;
use crate::gm::GlobalMemory;
pub struct ConfigWriter {
sm: StateMachine,
sdo: SdoClient,
write_tid: Option<u32>,
}
impl ConfigWriter {
pub fn new() -> Self {
Self {
sm: StateMachine::new(),
sdo: SdoClient::new("ClearPath_0"),
write_tid: None,
}
}
}
impl ControlProgram for ConfigWriter {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
self.sm.call();
match self.sm.index {
10 => {
// Send SDO write: set modes_of_operation to Profile Position (1)
self.write_tid = Some(
self.sdo.write(ctx.client, 0x6060, 0, json!(1))
);
self.sm.index = 20;
}
20 => {
// Wait for response
let tid = self.write_tid.unwrap();
match self.sdo.result(ctx.client, tid, Duration::from_secs(3)) {
SdoResult::Pending => {}
SdoResult::Ok(_) => {
log::info!("modes_of_operation set to PP");
self.sm.index = 30;
}
SdoResult::Err(e) => {
log::error!("SDO write failed: {}", e);
self.sm.set_error(1, "SDO write failed");
}
SdoResult::Timeout => {
log::error!("SDO write timed out");
self.sm.set_error(2, "SDO timeout");
}
}
}
30 => {
// Done — continue with normal operation
}
_ => {}
}
}
}
DriveHandle — CiA 402 Servo Drive Interface
A generated per-drive struct that bundles the Axis state machine with a Cia402PpSnapshot (an owned copy of the CiA 402 PDO fields). Works with any CiA 402 servo drive (Teknic, Yaskawa, Beckhoff, etc.).
When you add an axis entry with "type": "pp" to the axes array in the ethercat config, the code generator creates a DriveHandle struct named after the axis (e.g., ClearPath0, Servo1). Use sync() to read feedback, issue commands, then tick() to advance the state machine and write outputs:
use crate::gm::{GlobalMemory, ClearPath0};
// In your program struct:
drive: ClearPath0,
// In process_tick:
self.drive.sync(&ctx.gm);
// Issue commands
self.drive.enable();
self.drive.move_absolute(100.0, 50.0, 100.0, 100.0);
// Check status
if !self.drive.is_busy() {
log::info!("Move complete, position: {:.1}", self.drive.position());
}
// Advance state machine and write outputs
self.drive.tick(&mut ctx.gm, &mut ctx.client);
Command methods:
| Method | Description |
|---|---|
enable() | Start the enable sequence (Axis handles CiA 402 transitions) |
disable() | Disable the drive |
move_absolute(target, vel, accel, decel) | Absolute move in user units |
move_relative(distance, vel, accel, decel) | Relative move in user units |
halt() | Decelerate to stop |
home(method) | Start homing with the given HomingMethod |
reset_faults() | Clear drive faults |
set_position(user_units) | Set current position as the given value |
set_software_max_limit(user_units) | Set positive software limit |
set_software_min_limit(user_units) | Set negative software limit |
sdo_write(client, index, sub_index, value) | Write an SDO to the drive |
sdo_read(client, index, sub_index) -> u32 | Start an SDO read (returns transaction ID) |
sdo_result(client, tid) -> SdoResult | Check result of a previous SDO read |
Status methods:
| Method | Returns | Description |
|---|---|---|
position() | f64 | Current position in user units |
raw_position() | i64 | Current position in encoder counts |
speed() | f64 | Current speed in user units/s (absolute) |
is_busy() | bool | Any operation in progress |
is_error() | bool | Drive fault or operation error |
error_code() | u32 | Drive error code |
error_message() | &str | Human-readable error description |
motor_on() | bool | Drive in Operation Enabled state |
in_motion() | bool | Move specifically in progress |
moving_positive() | bool | Velocity is positive |
moving_negative() | bool | Velocity is negative |
at_max_limit() | bool | At positive software limit |
at_min_limit() | bool | At negative software limit |
at_positive_limit_switch() | bool | Positive hardware limit active |
at_negative_limit_switch() | bool | Negative hardware limit active |
home_sensor() | bool | Home sensor active |
Public fields:
| Field | Type | Description |
|---|---|---|
axis | Axis | The underlying axis state machine (for advanced use with SeekProbe, etc.) |
snapshot | Cia402PpSnapshot | The PDO snapshot (for advanced low-level access) |
Multiple axes: Because the DriveHandle owns its data by value (no references into GlobalMemory), you can use multiple axes without borrow conflicts:
self.lift.sync(&ctx.gm);
self.centering.sync(&ctx.gm);
if !self.lift.is_busy() {
self.lift.move_absolute(100.0, 50.0, 100.0, 100.0);
}
self.lift.tick(&mut ctx.gm, &mut ctx.client);
self.centering.tick(&mut ctx.gm, &mut ctx.client);
Homing with Axis:
The DriveHandle’s home() method delegates to the Axis struct, which handles the full homing sequence: SDO writes for method/speed/acceleration, mode switching, triggering, and home offset capture. This is the recommended approach.
There are two categories of homing method (see HomingMethod enum):
- Integrated methods (
IntegratedLimitSwitchNeg,HardStopPos,CurrentPosition, etc.) delegate to the drive’s built-in CiA 402 homing mode. TheAxiswrites SDO 0x6098 (method), 0x6099 (speeds), 0x609A (acceleration), then triggers the drive’s internal homing. - Software methods (
LimitSwitchNegPnp,HomeSensorPosPnp, etc.) are implemented by theAxisitself. It puts the drive in Profile Position mode and monitors sensor signals. When the sensor triggers, the axis halts and captures the home position. Specify your sensor variables inoptionsin the axis config:
"axes": [{
"name": "Servo1",
"link": "MyDrive_1",
"type": "pp",
"options": {
"positive_limit": "ls_servo1_pos",
"negative_limit": "ls_servo1_neg"
}
}]
The generated sync() method automatically copies the named GlobalMemory variables into the snapshot each tick. Available options fields:
| Field | Type | Default | Description |
|---|---|---|---|
positive_limit | string | — | GlobalMemory bool for positive limit switch |
negative_limit | string | — | GlobalMemory bool for negative limit switch |
home_sensor | string | — | GlobalMemory bool for home reference sensor |
error_code | string | — | GlobalMemory u16 for drive error code |
invert_direction | bool | false | Negate position targets and feedback (reverses motor direction in software) |
Inverting direction: Some drives don’t support reversing the counting direction internally. Set "invert_direction": true to flip the sign of all position targets (absolute and relative) and all position/speed feedback. The control program sees the axis moving in the logical positive direction even though the motor counts negative. Limit switches, homing, and software limits all respect the inversion automatically — no code changes needed.
Auto-publishing axis status to GlobalMemory:
Add an outputs block to the axis config to automatically write axis status values to GlobalMemory each tick. This eliminates manual ctx.gm.my_var = self.drive.position() boilerplate:
{
"name": "Lift",
"link": "ClearPath_2",
"type": "pp",
"options": { ... },
"outputs": {
"position": "lift_position",
"speed": "lift_speed",
"is_busy": "lift_busy",
"is_error": "lift_error",
"error_message": "lift_error_msg",
"motor_on": "lift_motor_on"
}
}
Only list the fields you need. The generated tick() writes them after advancing the axis state machine. Available output fields:
| Field | GM type | Description |
|---|---|---|
position | f64 | Position in user units |
raw_position | i64 | Position in encoder counts |
speed | f64 | Speed in user units/s |
is_busy | bool | Any operation in progress |
is_error | bool | Fault or error occurred |
error_code | u32/i32 | Drive error code |
error_message | string | Error description |
motor_on | bool | Drive enabled |
in_motion | bool | Move in progress |
moving_positive | bool | Moving in positive direction |
moving_negative | bool | Moving in negative direction |
at_max_limit | bool | At positive software limit |
at_min_limit | bool | At negative software limit |
at_positive_limit_switch | bool | Positive hardware limit active |
at_negative_limit_switch | bool | Negative hardware limit active |
home_sensor | bool | Home sensor active |
The referenced GM variables must exist in your project’s variables section with compatible types.
If homing_speed and homing_accel are both 0 (default), the SDO writes for speed/accel are skipped — useful when those parameters are pre-configured via startup_sdo in project.json.
HomingMethod variants:
| Variant | Kind | Description |
|---|---|---|
HardStopPos | Integrated | Hard stop positive direction (torque foldback) |
HardStopNeg | Integrated | Hard stop negative direction |
IntegratedLimitSwitchPos | Integrated | Drive’s positive limit switch (CiA 402 code 18) |
IntegratedLimitSwitchNeg | Integrated | Drive’s negative limit switch (CiA 402 code 17) |
IntegratedHomeSensorPosRt | Integrated | Drive’s home sensor, positive, rising edge |
IntegratedHomeSensorNegRt | Integrated | Drive’s home sensor, negative, rising edge |
CurrentPosition | Integrated | Set current position as home (no movement) |
Integrated(i8) | Integrated | Arbitrary CiA 402 code (vendor-specific) |
LimitSwitchPosPnp | Software | Move positive, home on positive limit (PNP: true = detected) |
LimitSwitchNegPnp | Software | Move negative, home on negative limit (PNP: true = detected) |
LimitSwitchPosNpn | Software | Move positive, home on positive limit (NPN: false = detected) |
LimitSwitchNegNpn | Software | Move negative, home on negative limit (NPN: false = detected) |
HomeSensorPosPnp | Software | Move positive, home on home sensor (PNP: true = detected) |
HomeSensorNegPnp | Software | Move negative, home on home sensor (PNP: true = detected) |
HomeSensorPosNpn | Software | Move positive, home on home sensor (NPN: false = detected) |
HomeSensorNegNpn | Software | Move negative, home on home sensor (NPN: false = detected) |
Complete example — home to limit switch then move to position:
use autocore_std::{ControlProgram, TickContext};
use autocore_std::motion::{AxisConfig, HomingMethod};
use crate::gm::{GlobalMemory, Servo1};
#[derive(Debug, Clone, Copy, PartialEq)]
enum Step {
Home,
WaitHomed,
Enable,
WaitEnabled,
MoveToWork,
WaitMove,
Done,
Reset,
WaitReset,
}
pub struct HomeThenMove {
drive: Servo1,
step: Step,
}
impl HomeThenMove {
pub fn new() -> Self {
let mut config = AxisConfig::new(12_800)
.with_user_scale(100.0); // 100 mm per rev
config.homing_speed = 25.0; // mm/s
config.homing_accel = 100.0; // mm/s²
Self {
drive: Servo1::new(config),
step: Step::Home,
}
}
}
impl ControlProgram for HomeThenMove {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
// sync() copies TxPDO feedback AND sensor inputs (from axis options) automatically
self.drive.sync(&ctx.gm);
match self.step {
Step::Home => {
// Home to the negative limit switch (rising edge trigger).
// The Axis will jog negative and stop when negative_limit goes true.
self.drive.home(HomingMethod::LimitSwitchNegPnp);
log::info!("Homing: seeking negative limit switch");
self.step = Step::WaitHomed;
}
Step::WaitHomed => {
if !self.drive.is_busy() {
if !self.drive.is_error() {
log::info!("Homed at {:.1} mm", self.drive.position());
self.step = Step::Enable;
} else {
log::error!("Homing failed: {}", self.drive.error_message());
self.step = Step::Reset;
}
}
}
Step::Enable => {
self.drive.enable();
self.step = Step::WaitEnabled;
}
Step::WaitEnabled => {
if !self.drive.is_busy() {
if self.drive.motor_on() {
self.step = Step::MoveToWork;
} else {
log::error!("Enable failed: {}", self.drive.error_message());
self.step = Step::Reset;
}
}
}
Step::MoveToWork => {
// Move to 50 mm at 100 mm/s, 200 mm/s² accel and decel
self.drive.move_absolute(50.0, 100.0, 200.0, 200.0);
log::info!("Moving to work position");
self.step = Step::WaitMove;
}
Step::WaitMove => {
if !self.drive.is_busy() {
if !self.drive.is_error() {
log::info!("At work position: {:.1} mm", self.drive.position());
self.step = Step::Done;
} else {
log::error!("Move failed: {}", self.drive.error_message());
self.step = Step::Reset;
}
}
}
Step::Done => {
// Ready for application logic
}
Step::Reset => {
self.drive.reset_faults();
self.step = Step::WaitReset;
}
self.drive.tick(&mut ctx.gm, &mut ctx.client);
}
}
Integrations
Function blocks for integrating with external AutoCore modules and the core server services via IPC.
DAQ Capture (ni::DaqCapture)
Manages the lifecycle of a triggered NI DAQ capture: arms the trigger, waits for the capture to complete, and retrieves the captured data — all via IPC commands to the autocore-ni module.
use autocore_std::fb::ni::DaqCapture;
struct MyProgram {
daq: DaqCapture,
}
impl MyProgram {
fn new() -> Self {
Self {
daq: DaqCapture::new("ni.impact"),
}
}
}
In process_tick:
match self.state {
State::StartCapture => {
self.daq.start(ctx.client);
self.state = State::WaitCapture;
}
State::WaitCapture => {
// Poll DAQ with a 5000ms timeout
self.daq.tick(5000, ctx.client);
if !self.daq.is_busy() {
if self.daq.is_error() {
log::error!("DAQ failed: {}", self.daq.error_message);
} else if let Some(data) = &self.daq.data {
log::info!("Captured {} samples!", data.actual_samples);
}
self.state = State::Idle;
}
}
}
Methods:
| Method | Signature | Description |
|---|---|---|
new | (daq_fqdn: &str) -> Self | Creates the FB to command the specified module (e.g. "ni.impact") |
start | (&mut self, client: &mut CommandClient) | Send the arm command to the DAQ on the next tick |
tick | (&mut self, timeout_ms: u32, client: &mut CommandClient) | Execute one scan cycle. Handles async IPC polling. |
reset | (&mut self) | Cancel the FB and return to idle state |
is_busy | (&self) -> bool | true while arming, waiting, or reading data |
is_error | (&self) -> bool | true if an error occurred during the capture |
Data Object (CaptureData):
When a capture succeeds, self.data will contain a populated CaptureData struct featuring:
channels: Vec<Vec<f64>>: The raw samples.channels[channel_index][sample_index].channel_count: usizeactual_samples: usizesample_rate: f64
Datastore & MemoryStore
Function blocks for asynchronous storage operations across the IPC bridge. These blocks make it trivial to persist configurations, logs, or giant raw data arrays generated by DAQ or Vision systems without blocking the high-speed real-time loop.
DataStoreRead & DataStoreWrite (datastore::*)
Reads and writes JSON payloads to the persistent Datastore asynchronously.
use autocore_std::fb::datastore::{DataStoreRead, DataStoreWrite};
use serde_json::json;
// Start a read
self.ds_read.start("calibration.json", ctx.client);
// Start a write (creates directories if missing)
self.ds_write.start("captures/trace_1.json", json!({"data": 123}), json!({"create_dirs": true}), ctx.client);
In process_tick:
self.ds_read.tick(5000, ctx.client);
if self.ds_read.done {
if let Some(val) = self.ds_read.data.take() {
// Handle read JSON Value
}
self.ds_read.reset();
} else if self.ds_read.is_error() {
log::error!("Read failed: {}", self.ds_read.error_message);
self.ds_read.reset();
}
MemoryStoreRead & MemoryStoreWrite (memorystore::*)
Reads and writes JSON payloads to the volatile MemoryStore asynchronously via IPC. The API exactly mirrors Datastore FBs.
use autocore_std::fb::memorystore::{MemoryStoreRead, MemoryStoreWrite};
use serde_json::json;
// Start a read/write to the MemoryStore key "config.camera"
self.mem_write.start("config.camera", json!({"exposure": 100}), ctx.client);
self.mem_read.start("config.camera", ctx.client);
Results System
Test Manager (*TestManager)
Specific Test Manager function blocks are automatically generated by codegen.rs based on the test_definitions in project.json. They provide a high-level, type-safe interface for logging test cycles and managing test state.
// Example usage of a generated 'ImpactTestManager'
match self.state {
State::BeginTest => {
self.test_manager.start_test("my_project_123", ctx.client);
self.state = State::WaitCycle;
}
State::CycleComplete => {
// Source-linked fields (like gm.peak_load) are auto-fetched!
self.test_manager.add_cycle("PASS".to_string(), ctx);
}
}
Methods:
| Method | Signature | Description |
|---|---|---|
new | () -> Self | Create a new manager instance |
start_test | (&mut self, project_id: &str, client: &mut CommandClient) | Start a new test sequence |
add_cycle | (&mut self, manual_fields..., ctx: &mut TickContext) | Log a cycle. Manual fields are those without a source in project.json |
update_results | (&mut self, results_fields..., ctx: &mut TickContext) | Update test-wide aggregate results |
add_raw_data | (&mut self, name: &str, data: Value, ctx: &mut TickContext) | Link heavy raw arrays to the current cycle |
tick | (&mut self, client: &mut CommandClient) | Execute one scan cycle to handle IPC comms |