YARP CiA-402 EtherCAT Device 0.6.0
YARP device plugin for EtherCAT CiA-402 drives
Loading...
Searching...
No Matches
CiA402::EthercatManager Class Reference

Minimal EtherCAT master built on SOEM for CiA-402 devices. More...

#include <CiA402/EthercatManager.h>

Public Types

enum class  Error : int {
  NoError = 0 , InitFailed = -1 , NoSlavesFound = -2 , ConfigFailed = -3 ,
  SlavesNotOp = -4 , AlreadyInitialized = -5 , NotInitialized = -6 , InvalidSlaveIndex = -7 ,
  PdoExchangeFailed = -8
}
 Error codes returned by EthercatManager APIs. More...
 

Public Member Functions

 EthercatManager ()
 Construct the manager (no I/O started).
 
 ~EthercatManager ()
 Destructor, stops background monitoring and releases resources.
 
 EthercatManager (const EthercatManager &)=delete
 
EthercatManageroperator= (const EthercatManager &)=delete
 
Error init (const std::string &ifname) noexcept
 Initialize the EtherCAT stack and configure slaves.
 
bool isInitialized () const noexcept
 Whether the manager has been successfully initialized.
 
bool isOperational () const noexcept
 Whether the ring is in OPERATIONAL state.
 
Error sendReceive () noexcept
 Perform one cyclic send/receive exchange over the bus.
 
int getWorkingCounter () const noexcept
 Last Working Counter (WKC) observed from the previous cycle.
 
int getExpectedWorkingCounter () const noexcept
 
void setPdoTimeoutUs (int usec) noexcept
 Set receive timeout for PDO exchange (microseconds). Default is EC_TIMEOUTRET from SOEM. Larger values can help on busy systems.
 
int getPdoTimeoutUs () const noexcept
 Get current receive timeout for PDO exchange (microseconds).
 
const RxPDOgetRxPDO (int slaveIndex) const noexcept
 Access the RxPDO (master→slave) buffer for a given slave.
 
RxPDOgetRxPDO (int slaveIndex) noexcept
 
TxView getTxView (int slaveIndex) const noexcept
 Obtain a typed, bounds-checked view over the TxPDO (slave→master).
 
template<typename T>
Error readSDO (int slaveIndex, uint16_t idx, uint8_t subIdx, T &out) noexcept
 Read an SDO value from a slave (blocking call).
 
template<typename T>
Error writeSDO (int slaveIndex, uint16_t idx, uint8_t subIdx, const T &value) noexcept
 Write an SDO value to a slave (blocking call).
 
std::string getName (int slaveIndex) const noexcept
 Get the name of a slave device.
 
Error enableDCSync0 (uint32_t cycleNs, int32_t shiftNs=0) noexcept
 Enable DC Sync0 for a slave.
 
Error disableDCSync0 () noexcept
 Disable DC Sync0 for a slave.
 
void dumpDiagnostics () noexcept
 Print quick diagnostics about bus/slave state and WKC. Call this when a PDO exchange fails to get immediate hints.
 
Error goOperational () noexcept
 Transition all slaves to OPERATIONAL and start monitoring.
 
Error goPreOp () noexcept
 Transition all slaves back to PRE-OP and stop monitoring.
 

Detailed Description

Minimal EtherCAT master built on SOEM for CiA-402 devices.

Responsibilities:

  • Discover and initialize the bus on a given network interface.
  • Configure PDO mappings (including safety/status signals such as STO/SBC).
  • Maintain the cyclic exchange (send/receive) of process data.
  • Expose convenient accessors for RxPDO (outputs) and TxView (inputs).
  • Provide helpers for SDO reads and diagnostic information (WKC).
  • Monitor errors in a background thread.

Notes:

  • SOEM uses 1-based slave indices; all methods follow that convention.
  • Pointers/views returned remain valid until re-initialization or shutdown.

Definition at line 163 of file EthercatManager.h.

Member Enumeration Documentation

◆ Error

enum class CiA402::EthercatManager::Error : int
strong

Error codes returned by EthercatManager APIs.

Enumerator
NoError 

Operation completed successfully.

InitFailed 

Bus/stack initialization failed.

NoSlavesFound 

No EtherCAT slaves were discovered.

ConfigFailed 

PDO/SDO configuration failed.

SlavesNotOp 

Slaves did not reach OP state.

AlreadyInitialized 

init() called more than once.

NotInitialized 

Operation requires a prior successful init().

InvalidSlaveIndex 

Provided slave index is out of range (1..ec_slavecount).

PdoExchangeFailed 

Failed to exchange PDOs or read SDO.

Definition at line 169 of file EthercatManager.h.

Constructor & Destructor Documentation

◆ EthercatManager() [1/2]

EthercatManager::EthercatManager ( )
default

Construct the manager (no I/O started).

◆ ~EthercatManager()

EthercatManager::~EthercatManager ( )

Destructor, stops background monitoring and releases resources.

Definition at line 37 of file EthercatManager.cpp.

◆ EthercatManager() [2/2]

CiA402::EthercatManager::EthercatManager ( const EthercatManager & )
delete

Member Function Documentation

◆ disableDCSync0()

EthercatManager::Error EthercatManager::disableDCSync0 ( )
noexcept

Disable DC Sync0 for a slave.

Returns
Error::NoError on success; an error code otherwise.

Definition at line 759 of file EthercatManager.cpp.

◆ dumpDiagnostics()

void EthercatManager::dumpDiagnostics ( )
noexcept

Print quick diagnostics about bus/slave state and WKC. Call this when a PDO exchange fails to get immediate hints.

Definition at line 521 of file EthercatManager.cpp.

◆ enableDCSync0()

EthercatManager::Error EthercatManager::enableDCSync0 ( uint32_t cycleNs,
int32_t shiftNs = 0 )
noexcept

Enable DC Sync0 for a slave.

Parameters
cycleNsSync cycle time in nanoseconds.
shiftNsSync phase shift in nanoseconds.
Returns
Error::NoError on success; an error code otherwise.

Definition at line 739 of file EthercatManager.cpp.

◆ getExpectedWorkingCounter()

int CiA402::EthercatManager::getExpectedWorkingCounter ( ) const
inlinenoexcept

Definition at line 223 of file EthercatManager.h.

◆ getName()

std::string EthercatManager::getName ( int slaveIndex) const
noexcept

Get the name of a slave device.

Parameters
slaveIndex1-based slave index.
Returns
Slave name as a string.

Definition at line 725 of file EthercatManager.cpp.

◆ getPdoTimeoutUs()

int CiA402::EthercatManager::getPdoTimeoutUs ( ) const
inlinenoexcept

Get current receive timeout for PDO exchange (microseconds).

Definition at line 240 of file EthercatManager.h.

◆ getRxPDO() [1/2]

const RxPDO * EthercatManager::getRxPDO ( int slaveIndex) const
noexcept

Access the RxPDO (master→slave) buffer for a given slave.

Note
Pointer remains valid until re-initialization.

Definition at line 549 of file EthercatManager.cpp.

◆ getRxPDO() [2/2]

RxPDO * EthercatManager::getRxPDO ( int slaveIndex)
noexcept

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 554 of file EthercatManager.cpp.

◆ getTxView()

TxView EthercatManager::getTxView ( int slaveIndex) const
noexcept

Obtain a typed, bounds-checked view over the TxPDO (slave→master).

Definition at line 559 of file EthercatManager.cpp.

◆ getWorkingCounter()

int CiA402::EthercatManager::getWorkingCounter ( ) const
inlinenoexcept

Last Working Counter (WKC) observed from the previous cycle.

Definition at line 218 of file EthercatManager.h.

◆ goOperational()

EthercatManager::Error EthercatManager::goOperational ( )
noexcept

Transition all slaves to OPERATIONAL and start monitoring.

Call this after init() and any SDO configuration reads, right before starting the cyclic control loop. It computes WKC expectations, caches pointers if needed, and launches the background state monitor.

Definition at line 437 of file EthercatManager.cpp.

◆ goPreOp()

EthercatManager::Error EthercatManager::goPreOp ( )
noexcept

Transition all slaves back to PRE-OP and stop monitoring.

Use this to temporarily drop out of OP for tests or reconfiguration. Leaves the manager initialized (SAFE-OP/PRE-OP), but not operational.

Definition at line 479 of file EthercatManager.cpp.

◆ init()

EthercatManager::Error EthercatManager::init ( const std::string & ifname)
noexcept

Initialize the EtherCAT stack and configure slaves.

Parameters
ifnameNetwork interface name (e.g., "eth0").
Returns
Error::NoError on success, specific error otherwise.

Definition at line 239 of file EthercatManager.cpp.

◆ isInitialized()

bool CiA402::EthercatManager::isInitialized ( ) const
inlinenoexcept

Whether the manager has been successfully initialized.

Definition at line 198 of file EthercatManager.h.

◆ isOperational()

bool CiA402::EthercatManager::isOperational ( ) const
inlinenoexcept

Whether the ring is in OPERATIONAL state.

Definition at line 204 of file EthercatManager.h.

◆ operator=()

EthercatManager & CiA402::EthercatManager::operator= ( const EthercatManager & )
delete

◆ readSDO()

template<typename T>
EthercatManager::Error CiA402::EthercatManager::readSDO ( int slaveIndex,
uint16_t idx,
uint8_t subIdx,
T & out )
noexcept

Read an SDO value from a slave (blocking call).

Template Parameters
TTrivially copyable integral type matching the object size.
Parameters
slaveIndex1-based slave index.
idxObject index (e.g., 0x6041).
subIdxObject subindex.
outDestination variable populated on success.
Returns
Error::NoError on success; an error code otherwise.

Definition at line 368 of file EthercatManager.h.

◆ sendReceive()

EthercatManager::Error EthercatManager::sendReceive ( )
noexcept

Perform one cyclic send/receive exchange over the bus.

Returns
Error::NoError on success; PdoExchangeFailed otherwise.

Definition at line 379 of file EthercatManager.cpp.

◆ setPdoTimeoutUs()

void CiA402::EthercatManager::setPdoTimeoutUs ( int usec)
inlinenoexcept

Set receive timeout for PDO exchange (microseconds). Default is EC_TIMEOUTRET from SOEM. Larger values can help on busy systems.

Definition at line 232 of file EthercatManager.h.

◆ writeSDO()

template<typename T>
EthercatManager::Error CiA402::EthercatManager::writeSDO ( int slaveIndex,
uint16_t idx,
uint8_t subIdx,
const T & value )
noexcept

Write an SDO value to a slave (blocking call).

Template Parameters
TTrivially copyable integral type matching the object size.
Parameters
slaveIndex1-based slave index.
idxObject index (e.g., 0x6040).
subIdxObject subindex.
valueValue to write.
Returns
Error::NoError on success; an error code otherwise.

Definition at line 392 of file EthercatManager.h.


The documentation for this class was generated from the following files: