Hardware Integration: EtherCAT
EtherCAT Overview
EtherCAT is a high-performance fieldbus commonly used for servo drives, digital I/O modules, and analog I/O. If you have used EtherCAT with TwinCAT or acontis, the concepts are the same — slaves are scanned on an Ethernet interface, PDOs (Process Data Objects) are exchanged cyclically, and SDOs (Service Data Objects) are used for acyclic configuration.
In AutoCore, the autocore-ethercat module handles the EtherCAT master. It:
- Scans and configures slaves on startup
- Exchanges PDO data cyclically (synchronized with the server tick)
- Maps all PDO entries into shared memory variables
Configuring EtherCAT Slaves
EtherCAT slaves are configured in the modules.ethercat.config.slaves array in project.json. Each slave needs:
- A name (used to build variable FQDNs)
- A position on the bus (0 = first slave)
- A device_id (vendor ID, product code, revision)
- Sync managers with PDO mappings
Here is a simple example with a Beckhoff EK1100 coupler and an EL1008 8-channel digital input module:
{
"modules": {
"ethercat": {
"enabled": true,
"args": ["service"],
"config": {
"interface_name": "eth0",
"auto_activate": true,
"runtime_settings": {
"cycle_time_us": 5000,
"priority": 99
},
"slaves": [
{
"name": "EK1100",
"position": 0,
"device_id": {
"vendor_id": 2,
"product_code": 72100946,
"revision_number": 1114112
}
},
{
"name": "DI_8CH",
"position": 1,
"device_id": {
"vendor_id": 2,
"product_code": 66084946,
"revision_number": 1048576
},
"sync_managers": [
{
"direction": "Inputs",
"index": 0,
"pdos": [
{
"name": "Channel 1-8",
"entries": [
{ "index": "0x6000", "sub": 1, "name": "Input 1", "type": "BIT", "bits": 1 },
{ "index": "0x6010", "sub": 1, "name": "Input 2", "type": "BIT", "bits": 1 },
{ "index": "0x6020", "sub": 1, "name": "Input 3", "type": "BIT", "bits": 1 },
{ "index": "0x6030", "sub": 1, "name": "Input 4", "type": "BIT", "bits": 1 },
{ "index": "0x6040", "sub": 1, "name": "Input 5", "type": "BIT", "bits": 1 },
{ "index": "0x6050", "sub": 1, "name": "Input 6", "type": "BIT", "bits": 1 },
{ "index": "0x6060", "sub": 1, "name": "Input 7", "type": "BIT", "bits": 1 },
{ "index": "0x6070", "sub": 1, "name": "Input 8", "type": "BIT", "bits": 1 }
]
}
]
}
]
}
]
}
}
},
"variables": {
"di_input_1": { "type": "bool", "link": "ethercat.di_8ch.channel_1_8.input_1" },
"di_input_2": { "type": "bool", "link": "ethercat.di_8ch.channel_1_8.input_2" },
"di_input_3": { "type": "bool", "link": "ethercat.di_8ch.channel_1_8.input_3" },
"di_input_4": { "type": "bool", "link": "ethercat.di_8ch.channel_1_8.input_4" },
"di_input_5": { "type": "bool", "link": "ethercat.di_8ch.channel_1_8.input_5" },
"di_input_6": { "type": "bool", "link": "ethercat.di_8ch.channel_1_8.input_6" },
"di_input_7": { "type": "bool", "link": "ethercat.di_8ch.channel_1_8.input_7" },
"di_input_8": { "type": "bool", "link": "ethercat.di_8ch.channel_1_8.input_8" }
}
}
Finding device IDs: The vendor ID, product code, and revision number come from the EtherCAT slave’s ESI (EtherCAT Slave Information) file. You can find these in the device manufacturer’s documentation, or by running
ethercat slaveson a system with the IgH EtherCAT master installed.
Digital I/O Example
Using the EtherCAT digital input module above, here is a control program that reads the inputs and uses them:
#![allow(unused)]
fn main() {
use autocore_std::{ControlProgram, TickContext};
use autocore_std::fb::RTrig;
use crate::gm::GlobalMemory;
pub struct MyControlProgram {
start_trig: RTrig,
stop_trig: RTrig,
running: bool,
}
impl MyControlProgram {
pub fn new() -> Self {
Self {
start_trig: RTrig::new(),
stop_trig: RTrig::new(),
running: false,
}
}
}
impl ControlProgram for MyControlProgram {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
// Input 1 = Start button, Input 2 = Stop button
if self.start_trig.call(ctx.gm.di_input_1) {
log::info!("Start button pressed");
self.running = true;
}
if self.stop_trig.call(ctx.gm.di_input_2) {
log::info!("Stop button pressed");
self.running = false;
}
// Input 3 = Emergency stop (normally closed, active low)
if !ctx.gm.di_input_3 {
self.running = false;
}
// Input 4 = Part sensor
// Input 5 = Home position sensor
// etc.
}
}
}
Analog Input Terminals (Strain Gauge / Load Cell)
Beckhoff EL3356 (and pin-compatible variants) measure a resistive bridge — typically a strain-gauge load cell — and expose the scaled result plus status bits over PDO. The EL3356 FB in autocore-std handles peak tracking, tare pulse timing, and SDO-based sensor calibration; this section covers just the EtherCAT-side setup needed to feed it.
Process image and GM variables
Each EL3356 slave produces four inputs and consumes one output. Map them to five GM variables using the {prefix}_* naming convention — the logical prefix (impact in the example below) is what you’ll pass to the el3356_view! macro in the control program.
{
"modules": {
"ethercat": {
"config": {
"devices": [
{
"name": "EL3356_0",
"product_code": "0x0d1c3052",
"vendor_id": "0x00000002",
"position": 3
}
]
}
}
},
"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" },
"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 FQDN on each link must match what the EL3356’s ESI file names its PDO entries — run ethercat> scan --project_file <path> against a live bus to populate the correct product code, vendor ID, and PDO FQDNs automatically; then copy them into your variable declarations.
Calibration parameters
The terminal needs three numbers to turn raw bridge readings into engineering units:
| What | SDO | Source |
|---|---|---|
| Sensitivity (mV/V) | 0x8000:0x23 | From the load cell’s calibration certificate |
| Full-scale load | 0x8000:0x24 | From the load cell’s datasheet (same units as load) |
| Scale factor | 0x8000:0x27 | EL3356 default is 100000.0; leave this unless the EL3356 manual calls for a different value for your setup |
You have two ways to apply these:
- At runtime from the control program — the recommended path. Call
El3356::configure(client, full_scale, mv_v, scale_factor)during startup. This handles the three SDO writes and reports success/failure via the FB’sbusy/errorfields. See the EL3356 FB reference. - As startup SDOs — add entries to the device’s
startup_sdoarray inproject.jsonso the ethercat module applies them before the cyclic loop starts. Use this when the values are known to be stable across deployments (e.g. a machine with a permanently mounted sensor).
Runtime configuration is preferred when the sensor can be swapped out in the field (different load cells → different mV/V). The FB stores the last-written values in configured_mv_v, configured_full_scale_load, and configured_scale_factor so the HMI can verify that calibration completed.
Minimal control program
#![allow(unused)]
fn main() {
use autocore_std::{ControlProgram, TickContext};
use autocore_std::fb::beckhoff::El3356;
use autocore_std::el3356_view;
use crate::gm::GlobalMemory;
pub struct MyProgram {
load_cell: El3356,
initialised: bool,
}
impl MyProgram {
pub fn new() -> Self {
Self {
load_cell: El3356::new("EL3356_0"),
initialised: false,
}
}
}
impl ControlProgram for MyProgram {
type Memory = GlobalMemory;
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
if !self.initialised && !self.load_cell.busy {
self.load_cell.configure(ctx.client, 1_000.0, 2.0, 100_000.0);
self.initialised = true;
}
let mut view = el3356_view!(ctx.gm, impact);
self.load_cell.tick(&mut view, ctx.client);
ctx.gm.impact_peak_load = self.load_cell.peak_load;
}
}
}
See Appendix B for the full FB API, state machine, multi-terminal setup, and TwinCAT-to-Rust porting notes.
Motion Control with CiA 402 Drives
Many EtherCAT servo drives follow the CiA 402 device profile, which defines standard PDO objects for:
- Control word (0x6040): Commands to the drive (enable, start, stop, fault reset)
- Status word (0x6041): Drive state feedback
- Target position (0x607A): Position command
- Position actual (0x6064): Encoder feedback
- Profile velocity (0x6081): Speed limit for profile moves
- Profile acceleration (0x6083): Acceleration ramp
- Profile deceleration (0x6084): Deceleration ramp
AutoCore provides the Axis helper from autocore-std that wraps the CiA 402 state machine, giving you high-level methods like home(), enable(), move_absolute(), and reset_faults().
When you add an axis entry to the axes array in the ethercat config with "type": "pp" (Profile Position mode), the code generator creates a DriveHandle struct in gm.rs (e.g., Lift). This struct bundles the Axis state machine with a vendor-neutral Cia402PpSnapshot — an owned copy of the CiA 402 PDO fields. Because the snapshot owns its data by value (no references), you can use multiple axes simultaneously without borrow conflicts.
The workflow in each tick is:
sync()— copies TxPDO feedback from shared memory into the snapshot- Issue commands —
enable(),move_absolute(),home(), etc. tick()— advances the axis state machine and writes RxPDO outputs back to shared memory
Full Example: CiA 402 Servo (Teknic ClearPath)
This complete example walks through configuring a Teknic ClearPath servo for Profile Position mode and writing a control program that homes and moves back and forth. The same pattern works with any CiA 402 drive.
Step 1: Scan and configure the drive
With the drive powered on and connected, load device definitions and scan the bus from the autocore console:
ethercat> load
ethercat> scan --project_file ./project.json
The scan creates a project.json with a default configuration for each slave. The ClearPath will default to Cyclic Synchronous Position mode — we need to switch it to Profile Position.
List available profiles:
ethercat> configure --action list_profiles --device ClearPath_0
You should see “Profile position mode (PP)” in the list.
Select the PP profile and add the startup SDO:
ethercat> configure --action select_profile --device ClearPath_0 --profile "Profile position mode (PP)"
ethercat> configure --action add_startup --device ClearPath_0 --index 0x6060 --sub 0 --value 0x01 --comment "Motion Mode"
Verify:
ethercat> configure --action show --device ClearPath_0
Verify you see RxPDO 5 / TxPDO 5 with Profile Velocity, Profile Acceleration, and Profile Deceleration in the output entries.
Step 2: Add axis definition
Edit project.json and add an axes array to the ethercat config (alongside slaves). This tells the code generator to create a DriveHandle for this drive:
"config": {
"axes": [
{
"name": "Lift",
"link": "ClearPath_0",
"type": "pp",
"options": {
"positive_limit": "ls_clearpath_pos",
"negative_limit": "ls_clearpath_neg",
"error_code": "clearpath_0_txpdo_5_error_code",
"maximum_pos_limit": "lift_max_position_limit",
"minimum_pos_limit": "lift_min_position_limit"
},
"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"
}
}
],
"slaves": [...]
}
-
name— your axis name, used to generate the DriveHandle struct (e.g.,"Lift"generatesLift). Choose a name that describes the axis function, not the hardware. -
link— the slave name this axis is bound to (must match a slave in theslavesarray). If you swap the motor to a different drive, changelink— the control program doesn’t need to change. -
options— sensor wiring, diagnostics, and motion settings (all optional):Field Type Default Description positive_limitstring — GlobalMemory bool for positive limit switch negative_limitstring — GlobalMemory bool for negative limit switch home_sensorstring — GlobalMemory bool for home reference sensor error_codestring — GlobalMemory u16 for drive error code maximum_pos_limitstring — GlobalMemory numeric (f32/f64/int) variable supplying a dynamic maximum software position limit, in user units minimum_pos_limitstring — GlobalMemory numeric variable supplying a dynamic minimum software position limit, in user units invert_directionbool falseNegate position targets and feedback (reverses motor direction in software) Software position limits (
maximum_pos_limit/minimum_pos_limit). When set, the named GM variable is read every tick and used as a software envelope for the axis. Two protections apply:- Move rejection. Any
move_absoluteormove_relativewhose target would land outside the range is rejected before any PDO is touched, and the axis enters its error state. A move away from a violated limit is always allowed so you can recover. - In-flight quick-stop. If the actual position passes a limit while the axis is moving toward it, control word bit 8 (halt) is asserted and the op is marked in error — the same mechanism used for hardware limit switches.
Because the limits live in GlobalMemory, operators can tune them at runtime (web console, recipe loads, nonvolatile init) without rebuilding. If the same axis also has static limits set in
AxisConfig(enable_max_position_limit/max_position_limitand the correspondingminpair), both sources are evaluated and the most restrictive value wins — the dynamic limit cannot widen a static envelope, only tighten it. Omitting the option leaves the snapshot field atNoneand falls back to the static config (or to no limit at all).Software limits only protect once the axis is homed —
position_actualis meaningless before homing — so wire these alongside your homing routine. - Move rejection. Any
-
outputs— axis status values published to GlobalMemory each tick (all optional, omit any you don’t need):Field GM type Description positionf64Position in user units raw_positioni64Position in encoder counts speedf64Speed in user units/s is_busyboolAny operation in progress is_errorboolFault or error occurred error_codeu32/i32Drive error code error_messagestringError description motor_onboolDrive enabled in_motionboolMove in progress moving_positiveboolMoving in positive direction moving_negativeboolMoving in negative direction at_max_limitboolAt positive software limit at_min_limitboolAt negative software limit at_positive_limit_switchboolPositive hardware limit active at_negative_limit_switchboolNegative hardware limit active home_sensorboolHome sensor active The generated
tick()method writes these values after advancing the axis state machine.Tip: Auto-Generation You do not need to manually create these variables in your
project.jsonfile. Simply define your desired variable names in theoutputsandoptionsblocks, then run theethercat.generate_variablescommand. AutoCore will automatically scan your axes and scaffold all missing variables into your project with the correct data types.
Step 3: Generate variables, sync, and build
# Generate the missing variables defined in the axes output/options blocks
acctl ethercat.generate_variables
acctl sync # push project.json to server, regenerate gm.rs
acctl push control --start # build and deploy the control program
Step 4: Write the control program
control/src/program.rs:
#![allow(unused)]
fn main() {
use autocore_std::motion::{AxisConfig, HomingMethod};
use autocore_std::{ControlProgram, TickContext};
use crate::gm::{GlobalMemory, Lift};
#[derive(Debug, Clone, Copy, PartialEq)]
enum Step {
Home,
WaitHomed,
Enable,
WaitEnabled,
MoveCW,
WaitCW,
MoveCCW,
WaitCCW,
Reset,
WaitReset,
}
pub struct MyControlProgram {
drive: Lift,
step: Step,
}
impl MyControlProgram {
pub fn new() -> Self {
// Configure the axis: 12,800 encoder counts per revolution, display in degrees
let config = AxisConfig::new(12_800)
.with_user_scale(360.0);
Self {
drive: Lift::new(config),
step: Step::Home,
}
}
}
impl ControlProgram for MyControlProgram {
type Memory = GlobalMemory;
fn initialize(&mut self, _mem: &mut Self::Memory) {
log::info!("ClearPath reversing program started");
}
fn process_tick(&mut self, ctx: &mut TickContext<Self::Memory>) {
// Read feedback from shared memory
self.drive.sync(&ctx.gm);
// Application state machine
match self.step {
Step::Home => {
self.drive.home(HomingMethod::CurrentPosition);
log::info!("Homing: setting current position as 0 degrees");
self.step = Step::WaitHomed;
}
Step::WaitHomed => {
if !self.drive.is_busy() {
if !self.drive.is_error() {
log::info!("Homed at {:.1} degrees", 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::MoveCW;
} else {
log::error!("Enable failed: {}", self.drive.error_message());
self.step = Step::Reset;
}
}
}
Step::MoveCW => {
// Move to 45 degrees at 90 deg/s, 180 deg/s² accel and decel
self.drive.move_absolute(45.0, 90.0, 180.0, 180.0);
log::info!("Moving CW to 45 degrees");
self.step = Step::WaitCW;
}
Step::WaitCW => {
if !self.drive.is_busy() {
if !self.drive.is_error() {
log::info!("CW move complete at {:.1} degrees", self.drive.position());
self.step = Step::MoveCCW;
} else {
log::error!("CW move failed: {}", self.drive.error_message());
self.step = Step::Reset;
}
}
}
Step::MoveCCW => {
self.drive.move_absolute(0.0, 90.0, 180.0, 180.0);
log::info!("Moving CCW to 0 degrees");
self.step = Step::WaitCCW;
}
Step::WaitCCW => {
if !self.drive.is_busy() {
if !self.drive.is_error() {
log::info!("CCW move complete at {:.1} degrees", self.drive.position());
self.step = Step::MoveCW; // Repeat
} else {
log::error!("CCW move failed: {}", self.drive.error_message());
self.step = Step::Reset;
}
}
}
Step::Reset => {
self.drive.reset_faults();
self.step = Step::WaitReset;
}
Step::WaitReset => {
if !self.drive.is_busy() {
self.step = Step::Enable;
}
}
}
// Advance state machine and write outputs back to shared memory
self.drive.tick(&mut ctx.gm, &mut ctx.client);
}
}
}
Key points:
Liftis a DriveHandle auto-generated ingm.rs. It bundles theAxisstate machine with aCia402PpSnapshotthat holds PDO field copies by value. Fields not in the PDO mapping (likemodes_of_operation) are managed internally as stubs.sync()copies TxPDO feedback from shared memory — call it at the start of each tick.tick()advances the CiA 402 state machine and writes RxPDO outputs back — call it at the end of each tick.- Between
sync()andtick(), issue commands freely:home(),enable(),move_absolute(),reset_faults(). - For software homing to a limit switch or sensor, specify the GlobalMemory variable names in
optionsin the axis config. The generatedsync()method will automatically wire them each tick. See Appendix B: DriveHandle for a complete homing example. - Status is available via methods:
is_busy(),is_error(),motor_on(),position(),error_message(). - The DriveHandle is vendor-neutral — switching from Teknic to Yaskawa only changes the struct name and
project.jsonconfiguration.
Scanning and Configuring a Network from the Console
Instead of writing project.json by hand, you can scan the physical bus and build the configuration interactively.
Step 1: Load device definitions
Device definitions describe the PDO layout, available profiles, and modular slot options for each EtherCAT slave. They are generated from ESI (EtherCAT Slave Information) XML files shipped by manufacturers.
ethercat> load
This loads device_definitions.json into memory. To regenerate definitions from ESI XML files:
ethercat> generate --source ./esi
Step 2: Scan the bus
Power on all slaves and run:
ethercat> scan --project_file ./project.json
This queries every slave on the bus for its identity (vendor ID, product code, revision) and writes a starter project.json with one entry per slave. Device names are auto-assigned based on the device definition database.
Step 3: Configure devices
After scanning, each device has a default configuration. Use the configure command to customize PDO profiles, modular slots, and startup SDOs.
List available PDO profiles for a device:
ethercat> configure --action list_profiles --device EL1008_0
Select a profile:
ethercat> configure --action select_profile --device EL1008_0 --profile "Default"
For modular devices (e.g., IO-Link masters), list and assign slots:
ethercat> configure --action list_slots --device IOLink_0
ethercat> configure --action select_slot --device IOLink_0 --slot 0 --module SomeModuleId --name sensor_1
Import an IODD file for an IO-Link port:
ethercat> configure --action import_iodd --device IOLink_0 --slot 0 --file ./sensor.iodd
Add a startup SDO (CoE initialization command):
ethercat> configure --action add_startup --device EL3064_0 --index 0x8000 --sub 1 --value 0x03 --comment "Set range to 0-10V"
Remove a startup SDO:
ethercat> configure --action rm_startup --device EL3064_0 --index 0x8000 --sub 1
List all FQDNs for a device:
ethercat> configure --action list_fqdns --device EL1008_0
Configuring CiA 402 Drives (Teknic ClearPath, Yaskawa, etc.)
For CiA 402 servo drives, you must select the correct PDO profile and add a startup SDO before the drive will work with the DriveHandle. See the full Teknic ClearPath example above for a complete walkthrough.
Common mistake: If you skip profile selection, the drive defaults to Cyclic Synchronous Position (CSP) mode. Moves will fail with overspeed faults (0x80BD) because the
Axishelper sends position commands as PP set-points, but the drive interprets them as cyclic position targets — causing sudden jumps and triggering the overspeed protection.
Step 4: Generate variables and activate
# Auto-generate project variables from PDO entries and configured axes
ethercat> generate_variables
# Start the EtherCAT runtime
ethercat> activate
Step 5: Validate the configuration
After activation, verify the physical bus matches the project configuration:
ethercat> validate
This compares each slave’s identity against what project.json expects and reports mismatches.
Distributed Clocks
Some EtherCAT slaves — most servo drives in CSP/CSV mode, and any slave that does precise sampling or motion control — require Distributed Clocks (DC). DC is a hardware mechanism in which the master distributes a single reference time across the bus so every slave fires its Sync0 (and optionally Sync1) interrupt at the same phase of the cycle. Without DC, a DC-capable slave will typically refuse the SAFEOP → OP transition and report:
EtherCAT ERROR 0-N: Failed to set OP state, slave refused state change (SAFEOP + ERROR).
EtherCAT ERROR 0-N: AL status message 0x0027: "Freerun not supported".
AL status 0x0027 (“Freerun not supported”) is the slave’s way of saying: I need DC sync signals and the master isn’t configuring them.
Enabling DC on a slave
The easiest way is the configure command, which edits project.json for you:
ethercat> configure --device SV660_0 set_dc --assign-activate 0x0300
With no --sync0-cycle-ns, the Sync0 cycle defaults to the project’s runtime_settings.cycle_time_us × 1000, which is what you want almost every time. To override or to enable Sync1 as well:
ethercat> configure --device SV660_0 set_dc \
--assign-activate 0x0700 \
--sync0-cycle-ns 1000000 \
--sync1-cycle-ns 1000000
To disable DC on a slave:
ethercat> configure --device SV660_0 clear_dc
As with the other configure actions, changes are persisted to project.json but the EtherCAT runtime must be restarted to pick them up.
If you prefer to edit project.json directly, each slave’s config block has six DC fields. By default they are all zero / false. To enable DC manually, set:
"config": {
"dc_enabled": true,
"dc_assign_activate": "0x0300",
"dc_sync0_cycle_ns": 10000000,
"dc_sync0_shift_ns": 0,
"dc_sync1_cycle_ns": 0,
"dc_sync1_shift_ns": 0
}
| Field | Meaning |
|---|---|
dc_enabled | Master runs DC setup for this slave and drives the bus time each cycle. |
dc_assign_activate | 16-bit bitmask from the slave’s ESI <OpMode>/<AssignActivate>. Typical values: 0x0300 (Sync0 only, most servo drives), 0x0700 (Sync0 + Sync1), 0x0730 (some high-end drives). Must match what the ESI specifies for the operating mode you’re using. |
dc_sync0_cycle_ns | Sync0 period in nanoseconds. Must equal the EtherCAT cycle time. For a 10 ms cycle, use 10_000_000. For 1 ms, 1_000_000. |
dc_sync0_shift_ns | Phase offset of Sync0 relative to the start of the cycle. Leave at 0 unless the drive manual specifies otherwise. |
dc_sync1_cycle_ns | Sync1 period in nanoseconds. 0 disables Sync1. When non-zero, it is usually the same as dc_sync0_cycle_ns. |
dc_sync1_shift_ns | Phase offset of Sync1. |
When any slave has dc_enabled: true, the master automatically takes on three extra per-cycle responsibilities: it sets its application time, synchronises the reference clock, and distributes that time to the other slaves. No code changes are needed in your control program — the runtime handles it.
Which slaves need DC?
- Servo drives in CSP, CSV, or CST mode (Cyclic Synchronous Position/Velocity/Torque): almost always require DC. This includes Inovance SV660 / SV630, Yaskawa Σ-7/Σ-X, Delta ASDA-A3, Beckhoff AX5000, Omron 1S, and most CiA 402 drives when run in cyclic-synchronous modes.
- Servo drives in PP or PV mode (Profile Position / Profile Velocity): DC is sometimes still required by the firmware even though the mode is not strictly synchronous — check the slave’s ESI. The Inovance SV660 is an example: it declares
AssignActivate=0x0300and will reject OP if DC isn’t configured. - Sampling I/O that needs timestamp correlation (e.g. Beckhoff EL3632 vibration, EL1252 timestamp inputs).
- Simple I/O couplers, digital I/O, and analog I/O without sync requirements (EK1100, EL1008, EL2008, EL3356, IFM IMPACT67): leave
dc_enabled: false.
When in doubt, open the ESI XML in a text editor and look for an <OpMode> element with a non-zero <AssignActivate>. If it’s present, the slave supports DC; if the ESI marks it as required, you must enable it.
Example: Inovance SV660 servo drive
The SV660 is a CiA 402 drive common on Chinese industrial machinery. It requires DC even in PP mode. A minimal slave entry for a 10 ms control cycle:
{
"name": "SV660_0",
"position": 4,
"device_id": {
"vendor_id": 1048576,
"product_code": 786701,
"revision_number": 65536
},
"config": {
"dc_enabled": true,
"dc_assign_activate": "0x0300",
"dc_sync0_cycle_ns": 10000000,
"dc_sync0_shift_ns": 0,
"dc_sync1_cycle_ns": 0,
"dc_sync1_shift_ns": 0,
"watchdog_ms": 100
},
"sync_managers": [ /* ... PDO mappings ... */ ]
}
Vendor ID 1048576 (0x100000) is Inovance. The same entry works for multiple SV660s on the bus — just change name, position, and the PDO mapping.
Troubleshooting
| Symptom | Likely cause |
|---|---|
AL 0x0027 “Freerun not supported” | Slave needs DC but dc_enabled is false. Enable it. |
AL 0x0030 “Invalid DC sync configuration” | dc_assign_activate is wrong for this slave/mode. Try 0x0700 or check the ESI. |
AL 0x002D “Sync manager watchdog” after enabling DC | dc_sync0_cycle_ns doesn’t match runtime_settings.cycle_time_us × 1000. |
| Drive enters OP but position jitter is high | dc_sync0_shift_ns may need tuning — consult the drive manual for recommended shift. |
| Only some DC slaves make it to OP | Usually a cycle-time mismatch. Every DC slave on the bus must use the same dc_sync0_cycle_ns. |
Check dmesg | grep EtherCAT after a failed activation — the IgH master logs each slave’s DC configuration attempt, which makes it easy to spot which slave rejected the transition and why.
SDO Access (CoE)
Read and write CANopen-over-EtherCAT objects at runtime for diagnostics and parameter tuning:
# Read an SDO
ethercat> read_sdo --device RC8_0 --index 0x1001 --sub 0
# Write an SDO
ethercat> write_sdo --device RC8_0 --index 0x8000 --sub 1 --value 0x03
Index values use hexadecimal format with the 0x prefix.
Runtime Monitoring
# Module and master status
ethercat> get_status
# Per-slave AL state, error flags, and identity
ethercat> get_slave_status
# Cycle time, link status, and performance counters
ethercat> get_network_stats
Status FQDNs are also available for live monitoring from the HMI:
| FQDN | Description |
|---|---|
ethercat.module.state | Module state: Idle, Configuring, Op |
ethercat.module.cycle_time | EtherCAT cycle time in microseconds |
ethercat.master.state | Master state: init, preop, safeop, op, mixed, disconnected |
EtherCAT Module Command Reference
All commands use the ethercat. topic prefix.
Network Scanning & Discovery
| Command | Arguments | Description |
|---|---|---|
scan | --project_file (optional), --esi_source (optional) | Scan the bus and write starter project.json |
validate | --project_file (optional), --instance_name (optional) | Compare physical bus against project config |
get_slave_status | – | Per-slave AL state, error flags, and identity |
get_network_stats | – | Cycle time, link status, performance counters |
Device Definitions
| Command | Arguments | Description |
|---|---|---|
generate | --source (optional, default: ./esi), --target (optional) | Generate device definitions from ESI XML files |
load | --source (optional) | Load device definition database into memory |
Configuration Management
| Command | Arguments | Description |
|---|---|---|
show_config | --device (optional), --project_file (optional) | Show active project configuration as JSON |
list_devices | --project_file (optional) | List all configured devices |
list_pdos | --device (optional), --project_file (optional) | List PDO entries with FQDNs, types, and offsets |
generate_variables | --project_file (optional) | Auto-generate project variables from PDO entries and configured axes |
Device Configuration
All configure actions require --device. Use --action to select the operation:
| Action | Extra Arguments | Description |
|---|---|---|
show | – | Show current device configuration |
list_profiles | – | List available PDO profiles |
select_profile | --profile (required) | Select a PDO profile |
list_modules | – | List available modules for a modular device |
list_slots | --verbose (optional) | List slots for a modular device |
select_slot | --slot, --module (required), --name (optional) | Assign a module to a slot |
import_iodd | --slot, --file (required), --module (optional), --name (optional) | Import IODD file for IO-Link configuration |
add_startup | --index, --sub, --value (required), --comment (optional) | Add a startup SDO |
rm_startup | --index, --sub (required) | Remove a startup SDO |
list_fqdns | – | List all FQDNs for the device |
set_dc | --assign-activate (required); --sync0-cycle-ns, --sync0-shift-ns, --sync1-cycle-ns, --sync1-shift-ns (optional) | Enable distributed clocks for the slave |
clear_dc | – | Disable distributed clocks for the slave |
SDO Access
| Command | Arguments | Description |
|---|---|---|
read_sdo | --device, --index, --sub (all required) | Read a CoE object from a slave |
write_sdo | --device, --index, --sub, --value (all required) | Write a CoE object to a slave |
Runtime Control
| Command | Arguments | Description |
|---|---|---|
activate | --project_file (optional) | Start the EtherCAT runtime |
stop | – | Stop the EtherCAT runtime |
get_status | – | Master connection and runtime status |
help | – | Show all available commands |
get_catalog | --project_file (optional) | List all available FQDN endpoints |