Go to the documentation of this file.
7 #include <unordered_map>
22 namespace soem_interface
32 using PdoSizeMap = std::unordered_map<std::string, PdoSizePair>;
124 bool startup(
const bool sizeCheck =
true);
157 const double retrySleep = 0.001);
190 const double cycleShift);
221 template <
typename Value>
226 const int size =
sizeof(Value);
227 Value value_copy = value;
237 << std::setfill(
'0') << std::setw(4) << std::hex << index <<
", SID 0x"
238 << std::setfill(
'0') << std::setw(2) << std::hex <<
static_cast<uint16_t>(subindex)
254 template <
typename Value>
259 int size =
sizeof(Value);
269 << std::setfill(
'0') << std::setw(4) << std::hex << index <<
", SID 0x"
270 << std::setfill(
'0') << std::setw(2) << std::hex <<
static_cast<uint16_t>(subindex)
274 if (size !=
sizeof(Value))
276 ROS_ERROR_STREAM(
"Slave " <<
slave <<
": Size mismatch (expected " <<
sizeof(Value) <<
" bytes, read " << size
277 <<
" bytes) for reading SDO (ID: 0x" << std::setfill(
'0') << std::setw(4) << std::hex
278 << index <<
", SID 0x" << std::setfill(
'0') << std::setw(2) << std::hex
279 <<
static_cast<uint16_t>(subindex) <<
").");
321 template <
typename TxPdo>
335 template <
typename RxPdo>
355 char* fileBuffer,
int timeout = EC_TIMEOUTSTATE * 10);
ec_SMcommtypet ecatSmCommtype_[EC_MAX_MAPT]
void readTxPdo(const uint16_t slave, TxPdo &txPdo) const
bool writeFirmware(const uint16_t slave, const std::string &fileName, const uint32_t &password, const int fileSize, char *fileBuffer)
#define ROS_ERROR_STREAM(args)
const std::string & getName() const
void writeRxPdo(const uint16_t slave, const RxPdo &rxPdo)
const ros::Time & getUpdateWriteStamp() const
bool startup(const bool sizeCheck=true)
PdoSizeMap getHardwarePdoSizes()
std::string getDeviceName(const uint16_t &slave) const
bool addSlave(const EthercatSlaveBasePtr &slave)
const unsigned int ecatConfigMaxRetries_
Maximal number of retries to configure the EtherCAT bus.
static void printAvailableBusses()
int getExpectedWorkingCounter(const uint16_t slave=0) const
bool busIsAvailable() const
bool sendSdoRead(const uint16_t slave, const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &value)
std::pair< uint16_t, uint16_t > PdoSizePair
bool workingCounterIsOk() const
ec_groupt ecatGrouplist_[EC_MAXGROUP]
PACKED_BEGIN struct PACKED ec_SMcommtype ec_SMcommtypet
PACKED_END PACKED_BEGIN struct PACKED ec_PDOdesc ec_PDOdesct
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 sendSdoWrite(const uint16_t slave, const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value)
int ecx_SDOwrite(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubIndex, boolean CA, int psize, void *p, int Timeout)
ec_PDOdesct ecatPdoDesc_[EC_MAX_MAPT]
void printALStatus(const uint16_t slave=0)
Prints application layer status.
std::atomic< int > wkc_
Working counter of the most recent PDO.
ec_idxstackT ecatIdxStack_
bool isRunning()
Returns if the instance is running.
std::shared_ptr< EthercatSlaveBase > EthercatSlaveBasePtr
uint8 ecatEsiBuf_[EC_MAXEEPBUF]
bool sentProcessData_
Bool indicating whether PDO data has been sent and not read yet.
std::unordered_map< std::string, PdoSizePair > PdoSizeMap
~EthercatBusBase()=default
void setState(const uint16_t state, const uint16_t slave=0)
const double ecatConfigRetrySleep_
Time to sleep between the retries.
std::recursive_mutex contextMutex_
std::shared_ptr< EthercatBusBase > EthercatBusBasePtr
uint16_t getSlaveALStatusCode(uint16_t slave)
Returns the AL Status Code of a slave.
ros::Time updateReadStamp_
Time of the last successful PDO reading.
PACKED_END struct ec_idxstack ec_idxstackT
ec_PDOassignt ecatPdoAssign_[EC_MAX_MAPT]
ecx_contextt ecatContext_
ec_slavet ecatSlavelist_[EC_MAXSLAVE]
std::string getErrorString(ec_errort error)
int ecx_SDOread(ecx_contextt *context, uint16 slave, uint16 index, uint8 subindex, boolean CA, int *psize, void *p, int timeout)
std::string name_
Name of the bus.
uint8_t getSlaveState(uint16_t slave)
std::vector< EthercatSlaveBasePtr > slaves_
List of slaves.
void syncDistributedClock0(const uint16_t slave, const bool activate, const double cycleTime, const double cycleShift)
Class for managing an ethercat bus containing one or multiple slaves.
const ros::Time & getUpdateReadStamp() const
PACKED_END PACKED_BEGIN struct PACKED ec_PDOassign ec_PDOassignt
bool isCorrectDeviceName(const uint16_t &slave, const std::string &deviceName) const
std::atomic< bool > isRunning_
Internal flag to indicate if the instance is running.
uint32 ecatEsiMap_[EC_MAXEEPBITMAP]
int getNumberOfSlaves() const
bool waitForState(const uint16_t state, const uint16_t slave=0, const unsigned int maxRetries=40, const double retrySleep=0.001)
ros::Time updateWriteStamp_
Time of the last successful PDO writing.
bool checkForSdoErrors(const uint16_t slave, const uint16_t index)