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::Time & | getUpdateReadStamp () const |
const ros::Time & | getUpdateWriteStamp () 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 () |
Class for managing an ethercat bus containing one or multiple slaves.
Definition at line 28 of file EthercatBusBase.hpp.
using rokubimini::soem_interface::EthercatBusBase::PdoSizeMap = std::unordered_map<std::string, PdoSizePair> |
Definition at line 32 of file EthercatBusBase.hpp.
using rokubimini::soem_interface::EthercatBusBase::PdoSizePair = std::pair<uint16_t, uint16_t> |
Definition at line 31 of file EthercatBusBase.hpp.
|
delete |
|
explicit |
Constructor.
name | Name of the bus, e.g. "eth0". |
Definition at line 7 of file EthercatBusBase.cpp.
|
default |
Destructor.
bool rokubimini::soem_interface::EthercatBusBase::addSlave | ( | const EthercatSlaveBasePtr & | slave | ) |
Add an EtherCAT slave. @slave EtherCAT slave.
Definition at line 61 of file EthercatBusBase.cpp.
bool rokubimini::soem_interface::EthercatBusBase::busIsAvailable | ( | ) | const |
Check if this bus is available.
Definition at line 50 of file EthercatBusBase.cpp.
|
static |
Check if a bus is available.
name | Name of the bus. |
Definition at line 25 of file EthercatBusBase.cpp.
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.
slave | Address of the slave. |
index | Index of the SDO. |
Definition at line 409 of file EthercatBusBase.cpp.
|
inline |
Return the device name of the provided slave.
Definition at line 302 of file EthercatBusBase.hpp.
std::string rokubimini::soem_interface::EthercatBusBase::getErrorString | ( | ec_errort | error | ) |
Generate and return the error string.
error | EtherCAT error object. |
Definition at line 353 of file EthercatBusBase.cpp.
int rokubimini::soem_interface::EthercatBusBase::getExpectedWorkingCounter | ( | const uint16_t | slave = 0 | ) | const |
Get the PDO expected working counter.
slave | Address of the slave, 0 for all slaves. |
Definition at line 346 of file EthercatBusBase.cpp.
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
Definition at line 447 of file EthercatBusBase.cpp.
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.
slave | Address of the slave |
Definition at line 474 of file EthercatBusBase.cpp.
|
inline |
int rokubimini::soem_interface::EthercatBusBase::getNumberOfSlaves | ( | ) | const |
Get the number of slaves which were detected on this bus.
Definition at line 55 of file EthercatBusBase.cpp.
Returns the AL Status Code of a slave.
[in] | slave | Address of the slave. |
Definition at line 467 of file EthercatBusBase.cpp.
Return the state of a slave. @slave EtherCAT slave.
Definition at line 459 of file EthercatBusBase.cpp.
|
inline |
Get the time of the last successful PDO reading.
Definition at line 59 of file EthercatBusBase.hpp.
|
inline |
Get the time of the last successful PDO writing.
Definition at line 68 of file EthercatBusBase.hpp.
|
inline |
Check whether the provided device name matches that of the provided slave.
Definition at line 311 of file EthercatBusBase.hpp.
|
inline |
Returns if the instance is running.
Definition at line 374 of file EthercatBusBase.hpp.
void rokubimini::soem_interface::EthercatBusBase::printALStatus | ( | const uint16_t | slave = 0 | ) |
Prints application layer status.
[in] | slave | Address of the slave, 0 for all slaves. |
Definition at line 399 of file EthercatBusBase.cpp.
|
static |
Print all available busses.
Definition at line 39 of file EthercatBusBase.cpp.
|
inline |
Read a TxPDO from the buffer.
slave | Address of the slave. |
txPdo | Return argument, TxPDO container. |
Definition at line 322 of file EthercatBusBase.hpp.
|
inline |
Send a reading SDO.
slave | Address of the slave. |
index | Index of the SDO. |
subindex | Sub-index of the SDO. |
completeAccess | Access all sub-indices at once. |
value | Return argument, will contain the value which was read. |
Definition at line 255 of file EthercatBusBase.hpp.
|
inline |
Send a writing SDO.
slave | Address of the slave. |
index | Index of the SDO. |
subindex | Sub-index of the SDO. |
completeAccess | Access all sub-indices at once. |
value | Value to write. |
Definition at line 222 of file EthercatBusBase.hpp.
void rokubimini::soem_interface::EthercatBusBase::setState | ( | const uint16_t | state, |
const uint16_t | slave = 0 |
||
) |
Set the desired EtherCAT state machine state.
state | Desired state. |
slave | Address of the slave, 0 for all slaves. |
Definition at line 316 of file EthercatBusBase.cpp.
void rokubimini::soem_interface::EthercatBusBase::shutdown | ( | ) |
Shutdown the bus communication.
Definition at line 295 of file EthercatBusBase.cpp.
bool rokubimini::soem_interface::EthercatBusBase::startup | ( | const bool | sizeCheck = true | ) |
Startup the bus communication.
sizeCheck | perform a check of the Rx and Tx Pdo sizes defined in the PdoInfo oject of the slaves |
Definition at line 78 of file EthercatBusBase.cpp.
void rokubimini::soem_interface::EthercatBusBase::syncDistributedClock0 | ( | const uint16_t | slave, |
const bool | activate, | ||
const double | cycleTime, | ||
const double | cycleShift | ||
) |
Synchronize the distributed clocks.
slave | Address of the slave. | |
activate | True to activate the distr. clock, false to deactivate. | |
[in] | timeStep | The time step |
Definition at line 434 of file EthercatBusBase.cpp.
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.
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.
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.
state | Desired state. |
slave | Address of the slave, 0 for all slaves. |
maxRetries | Maximum number of retries. |
retrySleep | Duration to sleep between the retries. |
Definition at line 325 of file EthercatBusBase.cpp.
bool rokubimini::soem_interface::EthercatBusBase::workingCounterIsOk | ( | ) | const |
Check if the current working counter for all slaves is high enough.
Definition at line 429 of file EthercatBusBase.cpp.
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.
slave | Address of the slave. |
filename | The name of the file that will be written in the slave. |
password | The password for authorization. |
fileSize | The size of the file to write. |
fileBuffer | The buffer having the contents of the file. |
timeout | Timeout per mailbox cycle in us, default is EC_TIMEOUTSTATE * 10 |
Definition at line 479 of file EthercatBusBase.cpp.
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.
slave | Address of the slave. |
fileName | The name of the file that will be written in the slave. |
password | The password for authorization. |
fileSize | The size of the file to write. |
fileBuffer | The buffer having the contents of the file. |
Definition at line 486 of file EthercatBusBase.cpp.
|
inline |
Write an RxPDO to the buffer.
slave | Address of the slave. |
rxPdo | RxPDO container. |
Definition at line 336 of file EthercatBusBase.hpp.
|
mutableprotected |
Definition at line 441 of file EthercatBusBase.hpp.
|
protected |
Maximal number of retries to configure the EtherCAT bus.
Definition at line 401 of file EthercatBusBase.hpp.
|
protected |
Time to sleep between the retries.
Definition at line 403 of file EthercatBusBase.hpp.
|
protected |
Definition at line 445 of file EthercatBusBase.hpp.
|
protected |
Definition at line 429 of file EthercatBusBase.hpp.
|
protected |
Definition at line 423 of file EthercatBusBase.hpp.
Definition at line 427 of file EthercatBusBase.hpp.
|
protected |
Definition at line 419 of file EthercatBusBase.hpp.
|
protected |
Definition at line 421 of file EthercatBusBase.hpp.
|
protected |
Definition at line 439 of file EthercatBusBase.hpp.
|
protected |
Definition at line 417 of file EthercatBusBase.hpp.
|
protected |
Definition at line 425 of file EthercatBusBase.hpp.
|
protected |
Definition at line 433 of file EthercatBusBase.hpp.
|
protected |
Definition at line 435 of file EthercatBusBase.hpp.
|
protected |
Definition at line 411 of file EthercatBusBase.hpp.
|
protected |
Definition at line 415 of file EthercatBusBase.hpp.
|
protected |
Definition at line 413 of file EthercatBusBase.hpp.
|
protected |
Definition at line 437 of file EthercatBusBase.hpp.
|
protected |
Definition at line 431 of file EthercatBusBase.hpp.
|
protected |
Definition at line 406 of file EthercatBusBase.hpp.
|
protected |
Internal flag to indicate if the instance is running.
Definition at line 393 of file EthercatBusBase.hpp.
|
protected |
Name of the bus.
Definition at line 381 of file EthercatBusBase.hpp.
|
protected |
Bool indicating whether PDO data has been sent and not read yet.
Definition at line 387 of file EthercatBusBase.hpp.
|
protected |
List of slaves.
Definition at line 384 of file EthercatBusBase.hpp.
|
protected |
Time of the last successful PDO reading.
Definition at line 396 of file EthercatBusBase.hpp.
|
protected |
Time of the last successful PDO writing.
Definition at line 398 of file EthercatBusBase.hpp.
|
protected |
Working counter of the most recent PDO.
Definition at line 390 of file EthercatBusBase.hpp.