EthercatBusBase.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <cassert>
4 // std
5 #include <atomic>
6 #include <string>
7 #include <unordered_map>
8 #include <utility>
9 #include <vector>
10 
11 // soem
12 #include <soem/ethercat.h>
13 
14 // soem_interface
16 
17 #include <ros/ros.h>
18 #include <ros/console.h>
19 
20 namespace rokubimini
21 {
22 namespace soem_interface
23 {
29 {
30 public:
31  using PdoSizePair = std::pair<uint16_t, uint16_t>;
32  using PdoSizeMap = std::unordered_map<std::string, PdoSizePair>;
33 
34  EthercatBusBase() = delete;
39  explicit EthercatBusBase(const std::string& name);
40 
44  ~EthercatBusBase() = default;
45 
50  const std::string& getName() const
51  {
52  return name_;
53  }
54 
60  {
61  return updateReadStamp_;
62  }
63 
69  {
70  return updateWriteStamp_;
71  }
72 
78  static bool busIsAvailable(const std::string& name);
79 
83  static void printAvailableBusses();
84 
89  bool busIsAvailable() const;
90 
95  int getNumberOfSlaves() const;
96 
102  bool addSlave(const EthercatSlaveBasePtr& slave);
103 
110 
118 
124  bool startup(const bool sizeCheck = true);
125 
129  void updateRead();
130 
134  void updateWrite();
135 
139  void shutdown();
140 
146  void setState(const uint16_t state, const uint16_t slave = 0);
147 
156  bool waitForState(const uint16_t state, const uint16_t slave = 0, const unsigned int maxRetries = 40,
157  const double retrySleep = 0.001);
158 
164  std::string getErrorString(ec_errort error);
165 
171  void printALStatus(const uint16_t slave = 0);
172 
179  bool checkForSdoErrors(const uint16_t slave, const uint16_t index);
180 
189  void syncDistributedClock0(const uint16_t slave, const bool activate, const double cycleTime,
190  const double cycleShift);
191 
201 
211 
221  template <typename Value>
222  bool sendSdoWrite(const uint16_t slave, const uint16_t index, const uint8_t subindex, const bool completeAccess,
223  const Value value)
224  {
225  assert(static_cast<int>(slave) <= getNumberOfSlaves());
226  const int size = sizeof(Value);
227  Value value_copy = value; // copy value to make it modifiable
228  int wkc = 0;
229  {
230  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
231  wkc = ecx_SDOwrite(&ecatContext_, slave, index, subindex, static_cast<boolean>(completeAccess), size, &value_copy,
232  EC_TIMEOUTRXM);
233  }
234  if (wkc <= 0)
235  {
236  ROS_ERROR_STREAM("Slave " << slave << ": Working counter too low (" << wkc << ") for writing SDO (ID: 0x"
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)
239  << ").");
240  return false;
241  }
242  return true;
243  }
244 
254  template <typename Value>
255  bool sendSdoRead(const uint16_t slave, const uint16_t index, const uint8_t subindex, const bool completeAccess,
256  Value& value)
257  {
258  assert(static_cast<int>(slave) <= getNumberOfSlaves());
259  int size = sizeof(Value);
260  int wkc = 0;
261  {
262  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
263  wkc = ecx_SDOread(&ecatContext_, slave, index, subindex, static_cast<boolean>(completeAccess), &size, &value,
264  EC_TIMEOUTRXM);
265  }
266  if (wkc <= 0)
267  {
268  ROS_ERROR_STREAM("Slave " << slave << ": Working counter too low (" << wkc << ") for reading SDO (ID: 0x"
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)
271  << ").");
272  return false;
273  }
274  if (size != sizeof(Value))
275  {
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) << ").");
280  return false;
281  }
282  return true;
283  }
284 
290  int getExpectedWorkingCounter(const uint16_t slave = 0) const;
291 
296  bool workingCounterIsOk() const;
297 
302  std::string getDeviceName(const uint16_t& slave) const
303  {
304  return std::string(ecatContext_.slavelist[slave].name);
305  }
306 
311  bool isCorrectDeviceName(const uint16_t& slave, const std::string& deviceName) const
312  {
313  return getDeviceName(slave) == deviceName;
314  }
315 
321  template <typename TxPdo>
322  void readTxPdo(const uint16_t slave, TxPdo& txPdo) const
323  {
324  assert(static_cast<int>(slave) <= getNumberOfSlaves());
325  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
326  assert(sizeof(TxPdo) == ecatContext_.slavelist[slave].Ibytes);
327  memcpy(&txPdo, ecatContext_.slavelist[slave].inputs, sizeof(TxPdo));
328  }
329 
335  template <typename RxPdo>
336  void writeRxPdo(const uint16_t slave, const RxPdo& rxPdo)
337  {
338  assert(static_cast<int>(slave) <= getNumberOfSlaves());
339  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
340  assert(sizeof(RxPdo) == ecatContext_.slavelist[slave].Obytes);
341  memcpy(ecatContext_.slavelist[slave].outputs, &rxPdo, sizeof(RxPdo));
342  }
343 
354  int writeFile(const uint16_t slave, const std::string& fileName, const uint32_t& password, const int fileSize,
355  char* fileBuffer, int timeout = EC_TIMEOUTSTATE * 10);
365  bool writeFirmware(const uint16_t slave, const std::string& fileName, const uint32_t& password, const int fileSize,
366  char* fileBuffer);
367 
374  bool isRunning()
375  {
376  return isRunning_;
377  }
378 
379 protected:
381  std::string name_;
382 
384  std::vector<EthercatSlaveBasePtr> slaves_;
385 
387  bool sentProcessData_{ false };
388 
390  std::atomic<int> wkc_;
391 
393  std::atomic<bool> isRunning_;
394 
399 
401  const unsigned int ecatConfigMaxRetries_{ 5 };
403  const double ecatConfigRetrySleep_{ 1.0 };
404 
405  // EtherCAT input/output mapping of the slaves within the datagrams.
406  char ioMap_[4096];
407 
408  // EtherCAT context data elements:
409 
410  // Port reference.
412  // List of slave data. Index 0 is reserved for the master, higher indices for the slaves.
414  // Number of slaves found in the network.
415  int ecatSlavecount_{ 0 };
416  // Slave group structure.
418  // Internal, reference to EEPROM cache buffer.
420  // Internal, reference to EEPROM cache map.
422  // Internal, reference to error list.
424  // Internal, reference to processdata stack buffer info.
426  // Boolean indicating if an error is available in error stack.
427  boolean ecatError_{ FALSE };
428  // Reference to last DC time from slaves.
430  // Internal, SM buffer.
432  // Internal, PDO assign list.
434  // Internal, PDO description list.
436  // Internal, SM list from EEPROM.
438  // Internal, FMMU list from EEPROM.
440 
441  mutable std::recursive_mutex contextMutex_;
442  // EtherCAT context data.
443  // Note: SOEM does not use dynamic memory allocation (new/delete). Therefore
444  // all context pointers must be null or point to an existing member.
446  &ecatSlavelist_[0],
448  EC_MAXSLAVE,
449  &ecatGrouplist_[0],
450  EC_MAXGROUP,
451  &ecatEsiBuf_[0],
452  &ecatEsiMap_[0],
453  0,
454  &ecatEList_,
455  &ecatIdxStack_,
456  &ecatError_,
457  0,
458  0,
459  &ecatDcTime_,
460  &ecatSmCommtype_[0],
461  &ecatPdoAssign_[0],
462  &ecatPdoDesc_[0],
463  &ecatSm_,
464  &ecatFmmu_,
465  nullptr };
466 };
467 
468 using EthercatBusBasePtr = std::shared_ptr<EthercatBusBase>;
469 
470 } // namespace soem_interface
471 } // namespace rokubimini
rokubimini::soem_interface::EthercatBusBase::ecatSmCommtype_
ec_SMcommtypet ecatSmCommtype_[EC_MAX_MAPT]
Definition: EthercatBusBase.hpp:431
wkc
int wkc
uint8_t
unsigned char uint8_t
slave
int slave
rokubimini::soem_interface::EthercatBusBase::readTxPdo
void readTxPdo(const uint16_t slave, TxPdo &txPdo) const
Definition: EthercatBusBase.hpp:322
rokubimini::soem_interface::EthercatBusBase::writeFirmware
bool writeFirmware(const uint16_t slave, const std::string &fileName, const uint32_t &password, const int fileSize, char *fileBuffer)
Definition: EthercatBusBase.cpp:486
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
rokubimini::soem_interface::EthercatBusBase::getName
const std::string & getName() const
Definition: EthercatBusBase.hpp:50
ec_slave::inputs
uint8 * inputs
uint16_t
unsigned short uint16_t
ec_slave::outputs
uint8 * outputs
rokubimini::soem_interface::EthercatBusBase::ecatError_
boolean ecatError_
Definition: EthercatBusBase.hpp:427
rokubimini::soem_interface::EthercatBusBase::writeRxPdo
void writeRxPdo(const uint16_t slave, const RxPdo &rxPdo)
Definition: EthercatBusBase.hpp:336
EC_MAXEEPBUF
#define EC_MAXEEPBUF
rokubimini::soem_interface::EthercatBusBase::getUpdateWriteStamp
const ros::Time & getUpdateWriteStamp() const
Definition: EthercatBusBase.hpp:68
rokubimini::soem_interface::EthercatBusBase::startup
bool startup(const bool sizeCheck=true)
Definition: EthercatBusBase.cpp:78
ros.h
EthercatSlaveBase.hpp
rokubimini::soem_interface::EthercatBusBase::getHardwarePdoSizes
PdoSizeMap getHardwarePdoSizes()
Definition: EthercatBusBase.cpp:447
rokubimini::soem_interface::EthercatBusBase::ecatEList_
ec_eringt ecatEList_
Definition: EthercatBusBase.hpp:423
rokubimini::soem_interface::EthercatBusBase::getDeviceName
std::string getDeviceName(const uint16_t &slave) const
Definition: EthercatBusBase.hpp:302
uint32
uint32_t uint32
rokubimini::soem_interface::EthercatBusBase::addSlave
bool addSlave(const EthercatSlaveBasePtr &slave)
Definition: EthercatBusBase.cpp:61
rokubimini::soem_interface::EthercatBusBase::ecatConfigMaxRetries_
const unsigned int ecatConfigMaxRetries_
Maximal number of retries to configure the EtherCAT bus.
Definition: EthercatBusBase.hpp:401
EC_TIMEOUTRXM
#define EC_TIMEOUTRXM
ec_group
EC_MAXGROUP
#define EC_MAXGROUP
int64
int64_t int64
rokubimini::soem_interface::EthercatBusBase::ecatDcTime_
int64 ecatDcTime_
Definition: EthercatBusBase.hpp:429
rokubimini::soem_interface::EthercatBusBase::shutdown
void shutdown()
Definition: EthercatBusBase.cpp:295
ec_slave::Ibytes
uint32 Ibytes
rokubimini::soem_interface::EthercatBusBase::ecatFmmu_
ec_eepromFMMUt ecatFmmu_
Definition: EthercatBusBase.hpp:439
rokubimini::soem_interface::EthercatBusBase::printAvailableBusses
static void printAvailableBusses()
Definition: EthercatBusBase.cpp:39
rokubimini::soem_interface::EthercatBusBase::ecatSlavecount_
int ecatSlavecount_
Definition: EthercatBusBase.hpp:415
rokubimini::soem_interface::EthercatBusBase::getExpectedWorkingCounter
int getExpectedWorkingCounter(const uint16_t slave=0) const
Definition: EthercatBusBase.cpp:346
rokubimini::soem_interface::EthercatBusBase::busIsAvailable
bool busIsAvailable() const
Definition: EthercatBusBase.cpp:50
rokubimini::soem_interface::EthercatBusBase::sendSdoRead
bool sendSdoRead(const uint16_t slave, const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &value)
Definition: EthercatBusBase.hpp:255
rokubimini::soem_interface::EthercatBusBase::PdoSizePair
std::pair< uint16_t, uint16_t > PdoSizePair
Definition: EthercatBusBase.hpp:31
rokubimini::soem_interface::EthercatBusBase::workingCounterIsOk
bool workingCounterIsOk() const
Definition: EthercatBusBase.cpp:429
uint8
uint8_t uint8
rokubimini::soem_interface::EthercatBusBase::ecatGrouplist_
ec_groupt ecatGrouplist_[EC_MAXGROUP]
Definition: EthercatBusBase.hpp:417
ethercat.h
ec_SMcommtypet
PACKED_BEGIN struct PACKED ec_SMcommtype ec_SMcommtypet
rokubimini::soem_interface::EthercatBusBase::ecatPort_
ecx_portt ecatPort_
Definition: EthercatBusBase.hpp:411
ec_PDOdesct
PACKED_END PACKED_BEGIN struct PACKED ec_PDOdesc ec_PDOdesct
console.h
rokubimini::soem_interface::EthercatBusBase::writeFile
int writeFile(const uint16_t slave, const std::string &fileName, const uint32_t &password, const int fileSize, char *fileBuffer, int timeout=EC_TIMEOUTSTATE *10)
Definition: EthercatBusBase.cpp:479
ec_eepromSM
uint32_t
unsigned int uint32_t
rokubimini::soem_interface::EthercatBusBase::sendSdoWrite
bool sendSdoWrite(const uint16_t slave, const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value)
Definition: EthercatBusBase.hpp:222
ecx_SDOwrite
int ecx_SDOwrite(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubIndex, boolean CA, int psize, void *p, int Timeout)
rokubimini::soem_interface::EthercatBusBase::ecatPdoDesc_
ec_PDOdesct ecatPdoDesc_[EC_MAX_MAPT]
Definition: EthercatBusBase.hpp:435
rokubimini::soem_interface::EthercatBusBase::printALStatus
void printALStatus(const uint16_t slave=0)
Prints application layer status.
Definition: EthercatBusBase.cpp:399
rokubimini::soem_interface::EthercatBusBase::wkc_
std::atomic< int > wkc_
Working counter of the most recent PDO.
Definition: EthercatBusBase.hpp:390
rokubimini::soem_interface::EthercatBusBase::ecatIdxStack_
ec_idxstackT ecatIdxStack_
Definition: EthercatBusBase.hpp:425
rokubimini::soem_interface::EthercatBusBase::isRunning
bool isRunning()
Returns if the instance is running.
Definition: EthercatBusBase.hpp:374
rokubimini::soem_interface::EthercatSlaveBasePtr
std::shared_ptr< EthercatSlaveBase > EthercatSlaveBasePtr
Definition: EthercatSlaveBase.hpp:316
rokubimini::soem_interface::EthercatBusBase::ecatEsiBuf_
uint8 ecatEsiBuf_[EC_MAXEEPBUF]
Definition: EthercatBusBase.hpp:419
rokubimini::soem_interface::EthercatBusBase::sentProcessData_
bool sentProcessData_
Bool indicating whether PDO data has been sent and not read yet.
Definition: EthercatBusBase.hpp:387
ec_errort
rokubimini::soem_interface::EthercatBusBase::PdoSizeMap
std::unordered_map< std::string, PdoSizePair > PdoSizeMap
Definition: EthercatBusBase.hpp:32
rokubimini
EC_MAX_MAPT
#define EC_MAX_MAPT
rokubimini::soem_interface::EthercatBusBase::~EthercatBusBase
~EthercatBusBase()=default
ec_eepromFMMU
rokubimini::soem_interface::EthercatBusBase::EthercatBusBase
EthercatBusBase()=delete
ec_slave::name
char name[EC_MAXNAME+1]
ec_ering
rokubimini::soem_interface::EthercatBusBase::setState
void setState(const uint16_t state, const uint16_t slave=0)
Definition: EthercatBusBase.cpp:316
rokubimini::soem_interface::EthercatBusBase::ecatConfigRetrySleep_
const double ecatConfigRetrySleep_
Time to sleep between the retries.
Definition: EthercatBusBase.hpp:403
ecx_context::slavelist
ec_slavet * slavelist
rokubimini::soem_interface::EthercatBusBase::contextMutex_
std::recursive_mutex contextMutex_
Definition: EthercatBusBase.hpp:441
rokubimini::soem_interface::EthercatBusBase::ioMap_
char ioMap_[4096]
Definition: EthercatBusBase.hpp:406
EC_MAXEEPBITMAP
#define EC_MAXEEPBITMAP
rokubimini::soem_interface::EthercatBusBasePtr
std::shared_ptr< EthercatBusBase > EthercatBusBasePtr
Definition: EthercatBusBase.hpp:468
rokubimini::soem_interface::EthercatBusBase::getSlaveALStatusCode
uint16_t getSlaveALStatusCode(uint16_t slave)
Returns the AL Status Code of a slave.
Definition: EthercatBusBase.cpp:467
ecx_portt
ec_slave
FALSE
#define FALSE
ecx_context
rokubimini::soem_interface::EthercatBusBase::updateReadStamp_
ros::Time updateReadStamp_
Time of the last successful PDO reading.
Definition: EthercatBusBase.hpp:396
rokubimini::soem_interface::EthercatBusBase::ecatSm_
ec_eepromSMt ecatSm_
Definition: EthercatBusBase.hpp:437
ros::Time
ec_idxstackT
PACKED_END struct ec_idxstack ec_idxstackT
rokubimini::soem_interface::EthercatBusBase::ecatPdoAssign_
ec_PDOassignt ecatPdoAssign_[EC_MAX_MAPT]
Definition: EthercatBusBase.hpp:433
rokubimini::soem_interface::EthercatBusBase::ecatContext_
ecx_contextt ecatContext_
Definition: EthercatBusBase.hpp:445
rokubimini::soem_interface::EthercatBusBase::ecatSlavelist_
ec_slavet ecatSlavelist_[EC_MAXSLAVE]
Definition: EthercatBusBase.hpp:413
rokubimini::soem_interface::EthercatBusBase::getErrorString
std::string getErrorString(ec_errort error)
Definition: EthercatBusBase.cpp:353
rokubimini::soem_interface::EthercatBusBase::updateRead
void updateRead()
Definition: EthercatBusBase.cpp:239
rokubimini::soem_interface::EthercatBusBase::updateWrite
void updateWrite()
Definition: EthercatBusBase.cpp:274
ecx_SDOread
int ecx_SDOread(ecx_contextt *context, uint16 slave, uint16 index, uint8 subindex, boolean CA, int *psize, void *p, int timeout)
rokubimini::soem_interface::EthercatBusBase::name_
std::string name_
Name of the bus.
Definition: EthercatBusBase.hpp:381
rokubimini::soem_interface::EthercatBusBase::getSlaveState
uint8_t getSlaveState(uint16_t slave)
Definition: EthercatBusBase.cpp:459
rokubimini::soem_interface::EthercatBusBase::slaves_
std::vector< EthercatSlaveBasePtr > slaves_
List of slaves.
Definition: EthercatBusBase.hpp:384
rokubimini::soem_interface::EthercatBusBase::syncDistributedClock0
void syncDistributedClock0(const uint16_t slave, const bool activate, const double cycleTime, const double cycleShift)
Definition: EthercatBusBase.cpp:434
rokubimini::soem_interface::EthercatBusBase
Class for managing an ethercat bus containing one or multiple slaves.
Definition: EthercatBusBase.hpp:28
rokubimini::soem_interface::EthercatBusBase::getUpdateReadStamp
const ros::Time & getUpdateReadStamp() const
Definition: EthercatBusBase.hpp:59
ec_slave::Obytes
uint32 Obytes
ec_PDOassignt
PACKED_END PACKED_BEGIN struct PACKED ec_PDOassign ec_PDOassignt
rokubimini::soem_interface::EthercatBusBase::isCorrectDeviceName
bool isCorrectDeviceName(const uint16_t &slave, const std::string &deviceName) const
Definition: EthercatBusBase.hpp:311
rokubimini::soem_interface::EthercatBusBase::isRunning_
std::atomic< bool > isRunning_
Internal flag to indicate if the instance is running.
Definition: EthercatBusBase.hpp:393
rokubimini::soem_interface::EthercatBusBase::ecatEsiMap_
uint32 ecatEsiMap_[EC_MAXEEPBITMAP]
Definition: EthercatBusBase.hpp:421
EC_MAXSLAVE
#define EC_MAXSLAVE
rokubimini::soem_interface::EthercatBusBase::getNumberOfSlaves
int getNumberOfSlaves() const
Definition: EthercatBusBase.cpp:55
rokubimini::soem_interface::EthercatBusBase::waitForState
bool waitForState(const uint16_t state, const uint16_t slave=0, const unsigned int maxRetries=40, const double retrySleep=0.001)
Definition: EthercatBusBase.cpp:325
rokubimini::soem_interface::EthercatBusBase::updateWriteStamp_
ros::Time updateWriteStamp_
Time of the last successful PDO writing.
Definition: EthercatBusBase.hpp:398
rokubimini::soem_interface::EthercatBusBase::checkForSdoErrors
bool checkForSdoErrors(const uint16_t slave, const uint16_t index)
Definition: EthercatBusBase.cpp:409


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