Public Types | Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
rokubimini::soem_interface::EthercatBusBase Class Reference

Class for managing an ethercat bus containing one or multiple slaves. More...

#include <EthercatBusBase.hpp>

Public Types

using PdoSizeMap = std::unordered_map< std::string, PdoSizePair >
 
using PdoSizePair = std::pair< uint16_t, uint16_t >
 

Public Member Functions

bool addSlave (const EthercatSlaveBasePtr &slave)
 
bool busIsAvailable () const
 
bool checkForSdoErrors (const uint16_t slave, const uint16_t index)
 
 EthercatBusBase ()=delete
 
 EthercatBusBase (const std::string &name)
 
std::string getDeviceName (const uint16_t &slave) const
 
std::string getErrorString (ec_errort error)
 
int getExpectedWorkingCounter (const uint16_t slave=0) const
 
PdoSizeMap getHardwarePdoSizes ()
 
PdoSizePair getHardwarePdoSizes (const uint16_t slave)
 
const std::string & getName () const
 
int getNumberOfSlaves () const
 
uint16_t getSlaveALStatusCode (uint16_t slave)
 Returns the AL Status Code of a slave. More...
 
uint8_t getSlaveState (uint16_t slave)
 
const ros::TimegetUpdateReadStamp () const
 
const ros::TimegetUpdateWriteStamp () const
 
bool isCorrectDeviceName (const uint16_t &slave, const std::string &deviceName) const
 
bool isRunning ()
 Returns if the instance is running. More...
 
void printALStatus (const uint16_t slave=0)
 Prints application layer status. More...
 
template<typename TxPdo >
void readTxPdo (const uint16_t slave, TxPdo &txPdo) const
 
template<typename Value >
bool sendSdoRead (const uint16_t slave, const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &value)
 
template<typename Value >
bool sendSdoWrite (const uint16_t slave, const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value)
 
void setState (const uint16_t state, const uint16_t slave=0)
 
void shutdown ()
 
bool startup (const bool sizeCheck=true)
 
void syncDistributedClock0 (const uint16_t slave, const bool activate, const double cycleTime, const double cycleShift)
 
void updateRead ()
 
void updateWrite ()
 
bool waitForState (const uint16_t state, const uint16_t slave=0, const unsigned int maxRetries=40, const double retrySleep=0.001)
 
bool workingCounterIsOk () const
 
int writeFile (const uint16_t slave, const std::string &fileName, const uint32_t &password, const int fileSize, char *fileBuffer, int timeout=EC_TIMEOUTSTATE *10)
 
bool writeFirmware (const uint16_t slave, const std::string &fileName, const uint32_t &password, const int fileSize, char *fileBuffer)
 
template<typename RxPdo >
void writeRxPdo (const uint16_t slave, const RxPdo &rxPdo)
 
 ~EthercatBusBase ()=default
 

Static Public Member Functions

static bool busIsAvailable (const std::string &name)
 
static void printAvailableBusses ()
 

Protected Attributes

std::recursive_mutex contextMutex_
 
const unsigned int ecatConfigMaxRetries_ { 5 }
 Maximal number of retries to configure the EtherCAT bus. More...
 
const double ecatConfigRetrySleep_ { 1.0 }
 Time to sleep between the retries. More...
 
ecx_contextt ecatContext_
 
int64 ecatDcTime_ { 0 }
 
ec_eringt ecatEList_
 
boolean ecatError_ { FALSE }
 
uint8 ecatEsiBuf_ [EC_MAXEEPBUF]
 
uint32 ecatEsiMap_ [EC_MAXEEPBITMAP]
 
ec_eepromFMMUt ecatFmmu_
 
ec_groupt ecatGrouplist_ [EC_MAXGROUP]
 
ec_idxstackT ecatIdxStack_
 
ec_PDOassignt ecatPdoAssign_ [EC_MAX_MAPT]
 
ec_PDOdesct ecatPdoDesc_ [EC_MAX_MAPT]
 
ecx_portt ecatPort_
 
int ecatSlavecount_ { 0 }
 
ec_slavet ecatSlavelist_ [EC_MAXSLAVE]
 
ec_eepromSMt ecatSm_
 
ec_SMcommtypet ecatSmCommtype_ [EC_MAX_MAPT]
 
char ioMap_ [4096]
 
std::atomic< bool > isRunning_
 Internal flag to indicate if the instance is running. More...
 
std::string name_
 Name of the bus. More...
 
bool sentProcessData_ { false }
 Bool indicating whether PDO data has been sent and not read yet. More...
 
std::vector< EthercatSlaveBasePtrslaves_
 List of slaves. More...
 
ros::Time updateReadStamp_
 Time of the last successful PDO reading. More...
 
ros::Time updateWriteStamp_
 Time of the last successful PDO writing. More...
 
std::atomic< int > wkc_
 Working counter of the most recent PDO. More...
 

Detailed Description

Class for managing an ethercat bus containing one or multiple slaves.

Definition at line 28 of file EthercatBusBase.hpp.

Member Typedef Documentation

◆ PdoSizeMap

using rokubimini::soem_interface::EthercatBusBase::PdoSizeMap = std::unordered_map<std::string, PdoSizePair>

Definition at line 32 of file EthercatBusBase.hpp.

◆ PdoSizePair

Definition at line 31 of file EthercatBusBase.hpp.

Constructor & Destructor Documentation

◆ EthercatBusBase() [1/2]

rokubimini::soem_interface::EthercatBusBase::EthercatBusBase ( )
delete

◆ EthercatBusBase() [2/2]

rokubimini::soem_interface::EthercatBusBase::EthercatBusBase ( const std::string &  name)
explicit

Constructor.

Parameters
nameName of the bus, e.g. "eth0".

Definition at line 7 of file EthercatBusBase.cpp.

◆ ~EthercatBusBase()

rokubimini::soem_interface::EthercatBusBase::~EthercatBusBase ( )
default

Destructor.

Member Function Documentation

◆ addSlave()

bool rokubimini::soem_interface::EthercatBusBase::addSlave ( const EthercatSlaveBasePtr slave)

Add an EtherCAT slave. @slave EtherCAT slave.

Returns
True if successful.

Definition at line 61 of file EthercatBusBase.cpp.

◆ busIsAvailable() [1/2]

bool rokubimini::soem_interface::EthercatBusBase::busIsAvailable ( ) const

Check if this bus is available.

Returns
True if available.

Definition at line 50 of file EthercatBusBase.cpp.

◆ busIsAvailable() [2/2]

bool rokubimini::soem_interface::EthercatBusBase::busIsAvailable ( const std::string &  name)
static

Check if a bus is available.

Parameters
nameName of the bus.
Returns
True if available.

Definition at line 25 of file EthercatBusBase.cpp.

◆ checkForSdoErrors()

bool rokubimini::soem_interface::EthercatBusBase::checkForSdoErrors ( const uint16_t  slave,
const uint16_t  index 
)

Check if an error for the SDO index of the slave exists.

Parameters
slaveAddress of the slave.
indexIndex of the SDO.
Returns
True if an error for the index exists.

Definition at line 409 of file EthercatBusBase.cpp.

◆ getDeviceName()

std::string rokubimini::soem_interface::EthercatBusBase::getDeviceName ( const uint16_t slave) const
inline

Return the device name of the provided slave.

Returns
The device name.

Definition at line 302 of file EthercatBusBase.hpp.

◆ getErrorString()

std::string rokubimini::soem_interface::EthercatBusBase::getErrorString ( ec_errort  error)

Generate and return the error string.

Parameters
errorEtherCAT error object.
Returns
The error string.

Definition at line 353 of file EthercatBusBase.cpp.

◆ getExpectedWorkingCounter()

int rokubimini::soem_interface::EthercatBusBase::getExpectedWorkingCounter ( const uint16_t  slave = 0) const

Get the PDO expected working counter.

Parameters
slaveAddress of the slave, 0 for all slaves.
Returns
Expected working counter.

Definition at line 346 of file EthercatBusBase.cpp.

◆ getHardwarePdoSizes() [1/2]

EthercatBusBase::PdoSizeMap rokubimini::soem_interface::EthercatBusBase::getHardwarePdoSizes ( )

Returns a map of the actually requested PDO sizes (Rx & Tx) This is useful for slaves where the PDO size at startup is unknown This method shall be used after adding the slaves and after executing the "startup" method

Returns
std::unordered_map with the addresses and the corresponding Pdo sizes

Definition at line 447 of file EthercatBusBase.cpp.

◆ getHardwarePdoSizes() [2/2]

EthercatBusBase::PdoSizePair rokubimini::soem_interface::EthercatBusBase::getHardwarePdoSizes ( const uint16_t  slave)

Returns a pair with the TxPdo and RxPdo sizes for the requested address Overloads the "PdoSizeMap getHardwarePdoSizes()" method.

Parameters
slaveAddress of the slave
Returns
std::pair with the rx (first) and tx (second) Pdo sizes

Definition at line 474 of file EthercatBusBase.cpp.

◆ getName()

const std::string& rokubimini::soem_interface::EthercatBusBase::getName ( ) const
inline

Get the name of the bus.

Returns
Name of the bus.

Definition at line 50 of file EthercatBusBase.hpp.

◆ getNumberOfSlaves()

int rokubimini::soem_interface::EthercatBusBase::getNumberOfSlaves ( ) const

Get the number of slaves which were detected on this bus.

Returns
Number of slaves.

Definition at line 55 of file EthercatBusBase.cpp.

◆ getSlaveALStatusCode()

uint16_t rokubimini::soem_interface::EthercatBusBase::getSlaveALStatusCode ( uint16_t  slave)

Returns the AL Status Code of a slave.

Parameters
[in]slaveAddress of the slave.
Returns
The AL Status code of the slave.

Definition at line 467 of file EthercatBusBase.cpp.

◆ getSlaveState()

uint8_t rokubimini::soem_interface::EthercatBusBase::getSlaveState ( uint16_t  slave)

Return the state of a slave. @slave EtherCAT slave.

Returns
The EtherCAT state of the slave.

Definition at line 459 of file EthercatBusBase.cpp.

◆ getUpdateReadStamp()

const ros::Time& rokubimini::soem_interface::EthercatBusBase::getUpdateReadStamp ( ) const
inline

Get the time of the last successful PDO reading.

Returns
Stamp.

Definition at line 59 of file EthercatBusBase.hpp.

◆ getUpdateWriteStamp()

const ros::Time& rokubimini::soem_interface::EthercatBusBase::getUpdateWriteStamp ( ) const
inline

Get the time of the last successful PDO writing.

Returns
Stamp.

Definition at line 68 of file EthercatBusBase.hpp.

◆ isCorrectDeviceName()

bool rokubimini::soem_interface::EthercatBusBase::isCorrectDeviceName ( const uint16_t slave,
const std::string &  deviceName 
) const
inline

Check whether the provided device name matches that of the provided slave.

Returns
True if the provided device name matches the name of the given slave.

Definition at line 311 of file EthercatBusBase.hpp.

◆ isRunning()

bool rokubimini::soem_interface::EthercatBusBase::isRunning ( )
inline

Returns if the instance is running.

Returns
True if the instance is running.

Definition at line 374 of file EthercatBusBase.hpp.

◆ printALStatus()

void rokubimini::soem_interface::EthercatBusBase::printALStatus ( const uint16_t  slave = 0)

Prints application layer status.

Parameters
[in]slaveAddress of the slave, 0 for all slaves.

Definition at line 399 of file EthercatBusBase.cpp.

◆ printAvailableBusses()

void rokubimini::soem_interface::EthercatBusBase::printAvailableBusses ( )
static

Print all available busses.

Definition at line 39 of file EthercatBusBase.cpp.

◆ readTxPdo()

template<typename TxPdo >
void rokubimini::soem_interface::EthercatBusBase::readTxPdo ( const uint16_t  slave,
TxPdo &  txPdo 
) const
inline

Read a TxPDO from the buffer.

Parameters
slaveAddress of the slave.
txPdoReturn argument, TxPDO container.

Definition at line 322 of file EthercatBusBase.hpp.

◆ sendSdoRead()

template<typename Value >
bool rokubimini::soem_interface::EthercatBusBase::sendSdoRead ( const uint16_t  slave,
const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
Value &  value 
)
inline

Send a reading SDO.

Parameters
slaveAddress of the slave.
indexIndex of the SDO.
subindexSub-index of the SDO.
completeAccessAccess all sub-indices at once.
valueReturn argument, will contain the value which was read.
Returns
True if successful.

Definition at line 255 of file EthercatBusBase.hpp.

◆ sendSdoWrite()

template<typename Value >
bool rokubimini::soem_interface::EthercatBusBase::sendSdoWrite ( const uint16_t  slave,
const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const Value  value 
)
inline

Send a writing SDO.

Parameters
slaveAddress of the slave.
indexIndex of the SDO.
subindexSub-index of the SDO.
completeAccessAccess all sub-indices at once.
valueValue to write.
Returns
True if successful.

Definition at line 222 of file EthercatBusBase.hpp.

◆ setState()

void rokubimini::soem_interface::EthercatBusBase::setState ( const uint16_t  state,
const uint16_t  slave = 0 
)

Set the desired EtherCAT state machine state.

Parameters
stateDesired state.
slaveAddress of the slave, 0 for all slaves.

Definition at line 316 of file EthercatBusBase.cpp.

◆ shutdown()

void rokubimini::soem_interface::EthercatBusBase::shutdown ( )

Shutdown the bus communication.

Definition at line 295 of file EthercatBusBase.cpp.

◆ startup()

bool rokubimini::soem_interface::EthercatBusBase::startup ( const bool  sizeCheck = true)

Startup the bus communication.

Parameters
sizeCheckperform a check of the Rx and Tx Pdo sizes defined in the PdoInfo oject of the slaves
Returns
True if successful.

Definition at line 78 of file EthercatBusBase.cpp.

◆ syncDistributedClock0()

void rokubimini::soem_interface::EthercatBusBase::syncDistributedClock0 ( const uint16_t  slave,
const bool  activate,
const double  cycleTime,
const double  cycleShift 
)

Synchronize the distributed clocks.

Parameters
slaveAddress of the slave.
activateTrue to activate the distr. clock, false to deactivate.
[in]timeStepThe time step

Definition at line 434 of file EthercatBusBase.cpp.

◆ updateRead()

void rokubimini::soem_interface::EthercatBusBase::updateRead ( )

Update step 1: Read all PDOs.

Receive the EtherCAT data.

Check the working counter.

Each slave attached to this bus reads its data to the buffer.

Definition at line 239 of file EthercatBusBase.cpp.

◆ updateWrite()

void rokubimini::soem_interface::EthercatBusBase::updateWrite ( )

Update step 2: Write all PDOs.

Each slave attached to this bus write its data to the buffer.

Send the EtherCAT data.

Definition at line 274 of file EthercatBusBase.cpp.

◆ waitForState()

bool rokubimini::soem_interface::EthercatBusBase::waitForState ( const uint16_t  state,
const uint16_t  slave = 0,
const unsigned int  maxRetries = 40,
const double  retrySleep = 0.001 
)

Wait for an EtherCAT state machine state to be reached.

Parameters
stateDesired state.
slaveAddress of the slave, 0 for all slaves.
maxRetriesMaximum number of retries.
retrySleepDuration to sleep between the retries.
Returns
True if the state has been reached within the timeout.

Definition at line 325 of file EthercatBusBase.cpp.

◆ workingCounterIsOk()

bool rokubimini::soem_interface::EthercatBusBase::workingCounterIsOk ( ) const

Check if the current working counter for all slaves is high enough.

Returns
True if the working counter is equal or higher than expected.

Definition at line 429 of file EthercatBusBase.cpp.

◆ writeFile()

int rokubimini::soem_interface::EthercatBusBase::writeFile ( const uint16_t  slave,
const std::string &  fileName,
const uint32_t password,
const int  fileSize,
char *  fileBuffer,
int  timeout = EC_TIMEOUTSTATE * 10 
)

Write file via FoE. It's blocking.

Parameters
slaveAddress of the slave.
filenameThe name of the file that will be written in the slave.
passwordThe password for authorization.
fileSizeThe size of the file to write.
fileBufferThe buffer having the contents of the file.
timeoutTimeout per mailbox cycle in us, default is EC_TIMEOUTSTATE * 10
Returns
Workcounter from last slave response

Definition at line 479 of file EthercatBusBase.cpp.

◆ writeFirmware()

bool rokubimini::soem_interface::EthercatBusBase::writeFirmware ( const uint16_t  slave,
const std::string &  fileName,
const uint32_t password,
const int  fileSize,
char *  fileBuffer 
)

Writes firmware to a slave.

Parameters
slaveAddress of the slave.
fileNameThe name of the file that will be written in the slave.
passwordThe password for authorization.
fileSizeThe size of the file to write.
fileBufferThe buffer having the contents of the file.
Returns
True if the transfer (FoE) was successful.

Definition at line 486 of file EthercatBusBase.cpp.

◆ writeRxPdo()

template<typename RxPdo >
void rokubimini::soem_interface::EthercatBusBase::writeRxPdo ( const uint16_t  slave,
const RxPdo &  rxPdo 
)
inline

Write an RxPDO to the buffer.

Parameters
slaveAddress of the slave.
rxPdoRxPDO container.

Definition at line 336 of file EthercatBusBase.hpp.

Member Data Documentation

◆ contextMutex_

std::recursive_mutex rokubimini::soem_interface::EthercatBusBase::contextMutex_
mutableprotected

Definition at line 441 of file EthercatBusBase.hpp.

◆ ecatConfigMaxRetries_

const unsigned int rokubimini::soem_interface::EthercatBusBase::ecatConfigMaxRetries_ { 5 }
protected

Maximal number of retries to configure the EtherCAT bus.

Definition at line 401 of file EthercatBusBase.hpp.

◆ ecatConfigRetrySleep_

const double rokubimini::soem_interface::EthercatBusBase::ecatConfigRetrySleep_ { 1.0 }
protected

Time to sleep between the retries.

Definition at line 403 of file EthercatBusBase.hpp.

◆ ecatContext_

ecx_contextt rokubimini::soem_interface::EthercatBusBase::ecatContext_
protected

◆ ecatDcTime_

int64 rokubimini::soem_interface::EthercatBusBase::ecatDcTime_ { 0 }
protected

Definition at line 429 of file EthercatBusBase.hpp.

◆ ecatEList_

ec_eringt rokubimini::soem_interface::EthercatBusBase::ecatEList_
protected

Definition at line 423 of file EthercatBusBase.hpp.

◆ ecatError_

boolean rokubimini::soem_interface::EthercatBusBase::ecatError_ { FALSE }
protected

Definition at line 427 of file EthercatBusBase.hpp.

◆ ecatEsiBuf_

uint8 rokubimini::soem_interface::EthercatBusBase::ecatEsiBuf_[EC_MAXEEPBUF]
protected

Definition at line 419 of file EthercatBusBase.hpp.

◆ ecatEsiMap_

uint32 rokubimini::soem_interface::EthercatBusBase::ecatEsiMap_[EC_MAXEEPBITMAP]
protected

Definition at line 421 of file EthercatBusBase.hpp.

◆ ecatFmmu_

ec_eepromFMMUt rokubimini::soem_interface::EthercatBusBase::ecatFmmu_
protected

Definition at line 439 of file EthercatBusBase.hpp.

◆ ecatGrouplist_

ec_groupt rokubimini::soem_interface::EthercatBusBase::ecatGrouplist_[EC_MAXGROUP]
protected

Definition at line 417 of file EthercatBusBase.hpp.

◆ ecatIdxStack_

ec_idxstackT rokubimini::soem_interface::EthercatBusBase::ecatIdxStack_
protected

Definition at line 425 of file EthercatBusBase.hpp.

◆ ecatPdoAssign_

ec_PDOassignt rokubimini::soem_interface::EthercatBusBase::ecatPdoAssign_[EC_MAX_MAPT]
protected

Definition at line 433 of file EthercatBusBase.hpp.

◆ ecatPdoDesc_

ec_PDOdesct rokubimini::soem_interface::EthercatBusBase::ecatPdoDesc_[EC_MAX_MAPT]
protected

Definition at line 435 of file EthercatBusBase.hpp.

◆ ecatPort_

ecx_portt rokubimini::soem_interface::EthercatBusBase::ecatPort_
protected

Definition at line 411 of file EthercatBusBase.hpp.

◆ ecatSlavecount_

int rokubimini::soem_interface::EthercatBusBase::ecatSlavecount_ { 0 }
protected

Definition at line 415 of file EthercatBusBase.hpp.

◆ ecatSlavelist_

ec_slavet rokubimini::soem_interface::EthercatBusBase::ecatSlavelist_[EC_MAXSLAVE]
protected

Definition at line 413 of file EthercatBusBase.hpp.

◆ ecatSm_

ec_eepromSMt rokubimini::soem_interface::EthercatBusBase::ecatSm_
protected

Definition at line 437 of file EthercatBusBase.hpp.

◆ ecatSmCommtype_

ec_SMcommtypet rokubimini::soem_interface::EthercatBusBase::ecatSmCommtype_[EC_MAX_MAPT]
protected

Definition at line 431 of file EthercatBusBase.hpp.

◆ ioMap_

char rokubimini::soem_interface::EthercatBusBase::ioMap_[4096]
protected

Definition at line 406 of file EthercatBusBase.hpp.

◆ isRunning_

std::atomic<bool> rokubimini::soem_interface::EthercatBusBase::isRunning_
protected

Internal flag to indicate if the instance is running.

Definition at line 393 of file EthercatBusBase.hpp.

◆ name_

std::string rokubimini::soem_interface::EthercatBusBase::name_
protected

Name of the bus.

Definition at line 381 of file EthercatBusBase.hpp.

◆ sentProcessData_

bool rokubimini::soem_interface::EthercatBusBase::sentProcessData_ { false }
protected

Bool indicating whether PDO data has been sent and not read yet.

Definition at line 387 of file EthercatBusBase.hpp.

◆ slaves_

std::vector<EthercatSlaveBasePtr> rokubimini::soem_interface::EthercatBusBase::slaves_
protected

List of slaves.

Definition at line 384 of file EthercatBusBase.hpp.

◆ updateReadStamp_

ros::Time rokubimini::soem_interface::EthercatBusBase::updateReadStamp_
protected

Time of the last successful PDO reading.

Definition at line 396 of file EthercatBusBase.hpp.

◆ updateWriteStamp_

ros::Time rokubimini::soem_interface::EthercatBusBase::updateWriteStamp_
protected

Time of the last successful PDO writing.

Definition at line 398 of file EthercatBusBase.hpp.

◆ wkc_

std::atomic<int> rokubimini::soem_interface::EthercatBusBase::wkc_
protected

Working counter of the most recent PDO.

Definition at line 390 of file EthercatBusBase.hpp.


The documentation for this class was generated from the following files:
rokubimini::soem_interface::EthercatBusBase::ecatSmCommtype_
ec_SMcommtypet ecatSmCommtype_[EC_MAX_MAPT]
Definition: EthercatBusBase.hpp:431
rokubimini::soem_interface::EthercatBusBase::ecatError_
boolean ecatError_
Definition: EthercatBusBase.hpp:427
rokubimini::soem_interface::EthercatBusBase::ecatEList_
ec_eringt ecatEList_
Definition: EthercatBusBase.hpp:423
EC_MAXGROUP
#define EC_MAXGROUP
rokubimini::soem_interface::EthercatBusBase::ecatDcTime_
int64 ecatDcTime_
Definition: EthercatBusBase.hpp:429
rokubimini::soem_interface::EthercatBusBase::ecatFmmu_
ec_eepromFMMUt ecatFmmu_
Definition: EthercatBusBase.hpp:439
rokubimini::soem_interface::EthercatBusBase::ecatSlavecount_
int ecatSlavecount_
Definition: EthercatBusBase.hpp:415
rokubimini::soem_interface::EthercatBusBase::ecatGrouplist_
ec_groupt ecatGrouplist_[EC_MAXGROUP]
Definition: EthercatBusBase.hpp:417
rokubimini::soem_interface::EthercatBusBase::ecatPort_
ecx_portt ecatPort_
Definition: EthercatBusBase.hpp:411
rokubimini::soem_interface::EthercatBusBase::ecatPdoDesc_
ec_PDOdesct ecatPdoDesc_[EC_MAX_MAPT]
Definition: EthercatBusBase.hpp:435
rokubimini::soem_interface::EthercatBusBase::ecatIdxStack_
ec_idxstackT ecatIdxStack_
Definition: EthercatBusBase.hpp:425
rokubimini::soem_interface::EthercatBusBase::ecatEsiBuf_
uint8 ecatEsiBuf_[EC_MAXEEPBUF]
Definition: EthercatBusBase.hpp:419
rokubimini::soem_interface::EthercatBusBase::ecatSm_
ec_eepromSMt ecatSm_
Definition: EthercatBusBase.hpp:437
rokubimini::soem_interface::EthercatBusBase::ecatPdoAssign_
ec_PDOassignt ecatPdoAssign_[EC_MAX_MAPT]
Definition: EthercatBusBase.hpp:433
rokubimini::soem_interface::EthercatBusBase::ecatSlavelist_
ec_slavet ecatSlavelist_[EC_MAXSLAVE]
Definition: EthercatBusBase.hpp:413
rokubimini::soem_interface::EthercatBusBase::ecatEsiMap_
uint32 ecatEsiMap_[EC_MAXEEPBITMAP]
Definition: EthercatBusBase.hpp:421
EC_MAXSLAVE
#define EC_MAXSLAVE


rokubimini_ethercat
Author(s):
autogenerated on Sat Apr 15 2023 02:53:56