EthercatBusBase.cpp
Go to the documentation of this file.
2 
3 namespace rokubimini
4 {
5 namespace soem_interface
6 {
7 EthercatBusBase::EthercatBusBase(const std::string& name) : name_(name), wkc_(0), isRunning_{ true }
8 {
9  // Initialize all SOEM context data pointers that are not used with null.
10  ecatContext_.elist->head = 0;
11  ecatContext_.elist->tail = 0;
12  ecatContext_.port->stack.sock = nullptr;
13  ecatContext_.port->stack.txbuf = nullptr;
15  ecatContext_.port->stack.tempbuf = nullptr;
16  ecatContext_.port->stack.rxbuf = nullptr;
17  ecatContext_.port->stack.rxbufstat = nullptr;
18  ecatContext_.port->stack.rxsa = nullptr;
19  ecatContext_.port->redport = nullptr;
20  // ecatContext_.idxstack->data = nullptr; // This does not compile since SOEM uses a fixed size array of void
21  // pointers.
22  ecatContext_.FOEhook = nullptr;
23 }
24 
25 bool EthercatBusBase::busIsAvailable(const std::string& name)
26 {
27  ec_adaptert* adapter = ec_find_adapters();
28  while (adapter != nullptr)
29  {
30  if (name == std::string(adapter->name))
31  {
32  return true;
33  }
34  adapter = adapter->next;
35  }
36  return false;
37 }
38 
40 {
41  ROS_INFO_STREAM("Available adapters:");
42  ec_adaptert* adapter = ec_find_adapters();
43  while (adapter != nullptr)
44  {
45  ROS_INFO_STREAM("- Name: '" << adapter->name << "', description: '" << adapter->desc << "'");
46  adapter = adapter->next;
47  }
48 }
49 
51 {
52  return busIsAvailable(name_);
53 }
54 
56 {
57  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
58  return *ecatContext_.slavecount;
59 }
60 
62 {
63  for (const auto& existing_slave : slaves_)
64  {
65  if (slave->getAddress() == existing_slave->getAddress())
66  {
67  ROS_ERROR_STREAM("[" << getName() << "] "
68  << "Slave '" << existing_slave->getName() << "' and slave '" << slave->getName()
69  << "' have identical addresses (" << slave->getAddress() << ").");
70  return false;
71  }
72  }
73 
74  slaves_.push_back(slave);
75  return true;
76 }
77 
78 bool EthercatBusBase::startup(const bool sizeCheck)
79 {
80  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
81  /*
82  * Followed by start of the application we need to set up the NIC to be used as
83  * EtherCAT Ethernet interface. In a simple setup we call ec_init(ifname) and if
84  * SOEM comes with support for cable redundancy we call ec_init_redundant that
85  * will open a second port as backup. You can send NULL as ifname if you have a
86  * dedicated NIC selected in the nicdrv.c. It returns >0 if succeeded.
87  */
88  if (!busIsAvailable())
89  {
90  ROS_ERROR_STREAM("[" << getName() << "] "
91  << "Bus is not available.");
93  return false;
94  }
95  if (ecx_init(&ecatContext_, name_.c_str()) <= 0)
96  {
97  ROS_ERROR_STREAM("[" << getName() << "] "
98  << "No socket connection. Execute as root.");
99  return false;
100  }
101 
102  // Initialize SOEM.
103  // Note: ecx_config_init(..) requests the slaves to go to PRE-OP.
104  for (unsigned int retry = 0; retry <= ecatConfigMaxRetries_; retry++)
105  {
107  {
108  // Successful initialization.
109  break;
110  }
111  else if (retry == ecatConfigMaxRetries_)
112  {
113  // Too many failed attempts.
114  ROS_ERROR_STREAM("[" << getName() << "] "
115  << "No slaves have been found.");
116  return false;
117  }
118  // Sleep and retry.
120  ROS_INFO_STREAM("[" << getName() << "] "
121  << "No slaves have been found, retrying " << retry + 1 << "/" << ecatConfigMaxRetries_
122  << " ...");
123  }
124 
125  // Print the slaves which have been detected.
126  ROS_INFO_STREAM("[" << getName() << "] "
127  << "The following " << getNumberOfSlaves() << " slaves have been found and configured:");
128  for (int slave = 1; slave <= getNumberOfSlaves(); slave++)
129  {
130  ROS_INFO_STREAM("[" << getName() << "] "
131  << "Address: " << slave << " - Name: '" << std::string(ecatContext_.slavelist[slave].name)
132  << "'");
133  }
134 
135  // Check if the given slave addresses are valid.
136  bool slave_addresses_are_ok = true;
137  for (const auto& slave : slaves_)
138  {
139  auto address = static_cast<int>(slave->getAddress());
140  if (address == 0)
141  {
142  ROS_ERROR_STREAM("[" << getName() << "] "
143  << "Slave '" << slave->getName() << "': Invalid address " << address << ".");
144  slave_addresses_are_ok = false;
145  }
146  if (address > getNumberOfSlaves())
147  {
148  ROS_ERROR_STREAM("[" << getName() << "] "
149  << "Slave '" << slave->getName() << "': Invalid address " << address << ", "
150  << "only " << getNumberOfSlaves() << " slave(s) found.");
151  slave_addresses_are_ok = false;
152  }
153  }
154  if (!slave_addresses_are_ok)
155  {
156  return false;
157  }
158 
159  // Disable symmetrical transfers.
161 
162  // Initialize the communication interfaces of all slaves.
163  for (auto& slave : slaves_)
164  {
165  if (!slave->startup())
166  {
167  ROS_ERROR_STREAM("[" << getName() << "] "
168  << "Slave '" << slave->getName() << "' was not initialized successfully.");
169  return false;
170  }
171  }
172 
173  // Set up the communication IO mapping.
174  // Note: ecx_config_map_group(..) requests the slaves to go to SAFE-OP.
176 
177  // Check if the size of the IO mapping fits our slaves.
178  bool io_map_is_ok = true;
179  // do this check only if 'sizeCheck' is true
180  if (sizeCheck)
181  {
182  for (const auto& slave : slaves_)
183  {
184  const EthercatSlaveBase::PdoInfo pdo_info = slave->getCurrentPdoInfo();
185  if (pdo_info.rxPdoSize_ != ecatContext_.slavelist[slave->getAddress()].Obytes)
186  {
187  ROS_ERROR_STREAM("[" << getName() << "] "
188  << "RxPDO size mismatch: The slave '" << slave->getName() << "' expects a size of "
189  << pdo_info.rxPdoSize_ << " bytes but the slave found at its address "
190  << slave->getAddress() << " requests "
191  << ecatContext_.slavelist[slave->getAddress()].Obytes << " bytes).");
192  io_map_is_ok = false;
193  }
194  if (pdo_info.txPdoSize_ != ecatContext_.slavelist[slave->getAddress()].Ibytes)
195  {
196  ROS_ERROR_STREAM("[" << getName() << "] "
197  << "TxPDO size mismatch: The slave '" << slave->getName() << "' expects a size of "
198  << pdo_info.txPdoSize_ << " bytes but the slave found at its address "
199  << slave->getAddress() << " requests "
200  << ecatContext_.slavelist[slave->getAddress()].Ibytes << " bytes).");
201  io_map_is_ok = false;
202  }
203  }
204  }
205  if (!io_map_is_ok)
206  {
207  return false;
208  }
209 
210  // Initialize the memory with zeroes.
211  for (int slave = 1; slave <= getNumberOfSlaves(); slave++)
212  {
215  }
216 
217  return true;
218 }
219 
221 {
222  if (!sentProcessData_)
223  {
224  ROS_DEBUG_STREAM("[" << getName() << "] "
225  << "No process data to read.");
226  return;
227  }
228 
231  {
232  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
234  }
235  sentProcessData_ = false;
236 
238  if (!workingCounterIsOk())
239  {
240  ROS_WARN_STREAM_THROTTLE(1.0, "[" << getName() << "] "
241  << "Update Read:" << this);
242  ROS_WARN_STREAM_THROTTLE(1.0, "[" << getName() << "] "
243  << "Working counter is too low: " << wkc_.load() << " < "
245  return;
246  }
247 
249  for (auto& slave : slaves_)
250  {
251  slave->updateRead();
252  }
253 }
254 
256 {
257  if (sentProcessData_)
258  {
259  ROS_DEBUG_STREAM("[" << getName() << "] "
260  << "Sending new process data without reading the previous one.");
261  }
262 
264  for (auto& slave : slaves_)
265  {
266  slave->updateWrite();
267  }
268 
271  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
273  sentProcessData_ = true;
274 }
275 
277 {
278  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
279  // Set the slaves to state Init.
280  if (getNumberOfSlaves() > 0)
281  {
284  }
285 
286  for (auto& slave : slaves_)
287  {
288  slave->shutdown();
289  }
290 
291  // Close the port.
292  if (ecatContext_.port != nullptr)
293  {
294  ROS_INFO_STREAM("[" << getName() << "] "
295  << "Closing socket ...");
297  // Sleep to make sure the socket is closed, because ecx_close is non-blocking.
299  }
300 }
301 
303 {
304  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
305  assert(static_cast<int>(slave) <= getNumberOfSlaves());
307  ecx_writestate(&ecatContext_, slave);
308  ROS_DEBUG_STREAM("Slave " << slave << ": State " << state << " has been set.");
309 }
310 
311 bool EthercatBusBase::waitForState(const uint16_t state, const uint16_t slave, const unsigned int maxRetries,
312  const double retrySleep)
313 {
314  assert(static_cast<int>(slave) <= getNumberOfSlaves());
315  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
316  for (unsigned int retry = 0; retry <= maxRetries; retry++)
317  {
318  if (ecx_statecheck(&ecatContext_, slave, state, static_cast<int>(1e6 * retrySleep)) == state)
319  {
320  ROS_DEBUG_STREAM("Slave " << slave << ": State " << state << " has been reached.");
321  return true;
322  }
323  // TODO: Do this for all states?
326  }
327 
328  ROS_WARN_STREAM("Slave " << slave << ": State " << state << " has not been reached.");
329  return false;
330 }
331 
333 {
334  assert(static_cast<int>(slave) <= getNumberOfSlaves());
335  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
337 }
338 
340 {
341  std::stringstream stream;
342  stream << "Time: " << (static_cast<double>(error.Time.sec) + (static_cast<double>(error.Time.usec) / 1000000.0));
343 
344  switch (error.Etype)
345  {
347  stream << " SDO slave: " << error.Slave << " index: 0x" << std::setfill('0') << std::setw(4) << std::hex
348  << error.Index << "." << std::setfill('0') << std::setw(2) << std::hex
349  << static_cast<uint16_t>(error.SubIdx) << " error: 0x" << std::setfill('0') << std::setw(8) << std::hex
350  << static_cast<unsigned>(error.AbortCode) << " " << ec_sdoerror2string(error.AbortCode);
351  break;
353  stream << " EMERGENCY slave: " << error.Slave << " error: 0x" << std::setfill('0') << std::setw(4) << std::hex
354  << error.ErrorCode;
355  break;
357  stream << " PACKET slave: " << error.Slave << " index: 0x" << std::setfill('0') << std::setw(4) << std::hex
358  << error.Index << "." << std::setfill('0') << std::setw(2) << std::hex
359  << static_cast<uint16_t>(error.SubIdx) << " error: 0x" << std::setfill('0') << std::setw(8) << std::hex
360  << error.ErrorCode;
361  break;
363  stream << " SDO slave: " << error.Slave << " index: 0x" << std::setfill('0') << std::setw(4) << std::hex
364  << error.Index << "." << std::setfill('0') << std::setw(2) << std::hex
365  << static_cast<uint16_t>(error.SubIdx) << " error: 0x" << std::setfill('0') << std::setw(8) << std::hex
366  << static_cast<unsigned>(error.AbortCode) << " " << ec_sdoerror2string(error.AbortCode);
367  break;
369  stream << " SoE slave: " << error.Slave << " index: 0x" << std::setfill('0') << std::setw(4) << std::hex
370  << error.Index << " error: 0x" << std::setfill('0') << std::setw(8) << std::hex
371  << static_cast<unsigned>(error.AbortCode) << " " << ec_soeerror2string(error.ErrorCode);
372  break;
374  stream << " MBX slave: " << error.Slave << " error: 0x" << std::setfill('0') << std::setw(8) << std::hex
375  << error.ErrorCode << " " << ec_mbxerror2string(error.ErrorCode);
376  break;
377  default:
378  stream << " MBX slave: " << error.Slave << " error: 0x" << std::setfill('0') << std::setw(8) << std::hex
379  << static_cast<unsigned>(error.AbortCode);
380  break;
381  }
382  return stream.str();
383 }
384 
386 {
387  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
388  assert(static_cast<int>(slave) <= getNumberOfSlaves());
389 
390  ROS_INFO_STREAM(" slave: " << slave << " alStatusCode: 0x" << std::setfill('0') << std::setw(8) << std::hex
391  << ecatContext_.slavelist[slave].ALstatuscode << " "
393 }
394 
396 {
397  while (ecx_iserror(&ecatContext_))
398  {
399  ec_errort error;
400  if (ecx_poperror(&ecatContext_, &error))
401  {
402  std::string error_str = getErrorString(error);
403  ROS_ERROR_STREAM(error_str);
404  if (error.Slave == slave && error.Index == index)
405  {
406  ROS_ERROR_STREAM("Error in index " << index << slave << "of slave " << slave
407  << ". Error string: " << error_str);
408  return true;
409  }
410  }
411  }
412  return false;
413 }
414 
416 {
417  return wkc_ >= getExpectedWorkingCounter();
418 }
419 
420 void EthercatBusBase::syncDistributedClock0(const uint16_t slave, const bool activate, const double cycleTime,
421  const double cycleShift)
422 {
423  ROS_INFO_STREAM("Bus '" << name_ << "', slave " << slave << ": " << (activate ? "Activating" : "Deactivating")
424  << " distributed clock synchronization...");
425 
426  ecx_dcsync0(&ecatContext_, slave, static_cast<uint8_t>(activate), static_cast<uint32_t>(cycleTime * 1e9),
427  static_cast<int32_t>(1e9 * cycleShift));
428 
429  ROS_INFO_STREAM("Bus '" << name_ << "', slave " << slave << ": " << (activate ? "Activated" : "Deactivated")
430  << " distributed clock synchronization.");
431 }
432 
434 {
435  PdoSizeMap pdo_map;
436 
437  for (const auto& slave : slaves_)
438  {
439  pdo_map.insert(std::make_pair(slave->getName(), getHardwarePdoSizes(slave->getAddress())));
440  }
441 
442  return pdo_map;
443 }
444 
446 {
447  return std::make_pair(ecatContext_.slavelist[slave].Obytes, ecatContext_.slavelist[slave].Ibytes);
448 }
449 
450 int EthercatBusBase::writeFile(const uint16_t slave, const std::string& fileName, const uint32_t& password,
451  const int fileSize, char* fileBuffer, int timeout)
452 {
453  return ecx_FOEwrite(&ecatContext_, slave, const_cast<char*>(fileName.c_str()), password, fileSize, fileBuffer,
454  timeout);
455 }
456 
457 bool EthercatBusBase::writeFirmware(const uint16_t slave, const std::string& fileName, const uint32_t& password,
458  const int fileSize, char* fileBuffer)
459 {
460  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
461  // Set slave to EC_STATE_INIT state.
463  ecx_writestate(&ecatContext_, slave);
465  {
466  ROS_ERROR_STREAM("Could not set slave '" << slave << "' to INIT state.");
467  printALStatus(slave);
468  isRunning_ = false;
469  return false;
470  }
471  ROS_DEBUG_STREAM("Set slave '" << slave << "' to INIT state.");
472 
473  /* read BOOT mailbox data, master -> slave */
475  ecatSlavelist_[slave].SM[0].StartAddr = (uint16)LO_WORD(data);
476  ecatSlavelist_[slave].SM[0].SMlength = (uint16)HI_WORD(data);
477  /* store boot write mailbox address */
478  ecatSlavelist_[slave].mbx_wo = (uint16)LO_WORD(data);
479  /* store boot write mailbox size */
480  ecatSlavelist_[slave].mbx_l = (uint16)HI_WORD(data);
481 
482  /* read BOOT mailbox data, slave -> master */
484  ecatSlavelist_[slave].SM[1].StartAddr = (uint16)LO_WORD(data);
485  ecatSlavelist_[slave].SM[1].SMlength = (uint16)HI_WORD(data);
486  /* store boot read mailbox address */
487  ecatSlavelist_[slave].mbx_ro = (uint16)LO_WORD(data);
488  /* store boot read mailbox size */
489  ecatSlavelist_[slave].mbx_rl = (uint16)HI_WORD(data);
490 
491  ROS_DEBUG(" SM0 A:%4.4x L:%4d F:%8.8x", ecatSlavelist_[slave].SM[0].StartAddr, ecatSlavelist_[slave].SM[0].SMlength,
492  (int)ecatSlavelist_[slave].SM[0].SMflags);
493  ROS_DEBUG(" SM1 A:%4.4x L:%4d F:%8.8x", ecatSlavelist_[slave].SM[1].StartAddr, ecatSlavelist_[slave].SM[1].SMlength,
494  (int)ecatSlavelist_[slave].SM[1].SMflags);
495  /* program SM0 mailbox in for slave */
496  ecx_FPWR(&ecatPort_, ecatSlavelist_[slave].configadr, ECT_REG_SM0, sizeof(ec_smt), &ecatSlavelist_[slave].SM[0],
497  EC_TIMEOUTRET);
498  /* program SM1 mailbox out for slave */
499  ecx_FPWR(&ecatPort_, ecatSlavelist_[slave].configadr, ECT_REG_SM1, sizeof(ec_smt), &ecatSlavelist_[slave].SM[1],
500  EC_TIMEOUTRET);
501 
502  // Set slave to EC_STATE_BOOT state.
504  ecx_writestate(&ecatContext_, slave);
506  {
507  ROS_ERROR_STREAM("Could not set slave '" << slave << "' to BOOT state.");
508  printALStatus(slave);
509  isRunning_ = false;
510  return false;
511  }
512  ROS_DEBUG_STREAM("Set slave '" << slave << "' to BOOT state.");
513 
514  // Send file over EtherCAT.
515  ROS_INFO("Flashing firmware ...");
516  // Write over EtherCAT.
517  ROS_INFO("Writing file over ethercat (FOE)");
518  ROS_DEBUG_STREAM("Size of file buffer: " << fileSize);
519 
520  int wkc = writeFile(slave, fileName, password, fileSize, fileBuffer);
521  ROS_INFO_STREAM("Result wkc: " << wkc);
522  // Check work counter.
523  if (wkc != 1)
524  {
525  ROS_ERROR_STREAM("Writing file over EtherCAT failed (wkc = " << wkc << ").");
526  isRunning_ = false;
527  return false;
528  }
529 
530  ROS_DEBUG_STREAM("Request init state for slave " << slave);
531  // Set slave to EC_STATE_INIT state.
533  ecx_writestate(&ecatContext_, slave);
534 
535  ROS_INFO("Flashing over EtherCAT was successful");
536 
537  isRunning_ = false;
538  return true;
539 }
540 } // namespace soem_interface
541 } // namespace rokubimini
ec_smt SM[EC_MAXSM]
int ecx_send_processdata(ecx_contextt *context)
uint16 mbx_ro
char * ec_ALstatuscode2string(uint16 ALstatuscode)
EC_ERR_TYPE_SDO_ERROR
void threadSleep(const double duration)
Definition: ThreadSleep.cpp:9
EC_ERR_TYPE_SDOINFO_ERROR
int(* rxsa)[EC_MAXBUF]
ECT_SII_BOOTRXMBX
uint16 outputsWKC
bool checkForSdoErrors(const uint16_t slave, const uint16_t index)
#define EC_TIMEOUTSTATE
void syncDistributedClock0(const uint16_t slave, const bool activate, const double cycleTime, const double cycleShift)
uint32 Ibytes
char name[EC_MAXLEN_ADAPTERNAME]
void ecx_close(ecx_contextt *context)
int16 head
bool addSlave(const EthercatSlaveBasePtr &slave)
uint8 * outputs
uint16 ecx_statecheck(ecx_contextt *context, uint16 slave, uint16 reqstate, int timeout)
uint32 usec
int(* FOEhook)(uint16 slave, int packetnumber, int datasize)
uint32 Obytes
uint16 mbx_rl
ec_adaptert * next
std::pair< uint16_t, uint16_t > PdoSizePair
std::unordered_map< std::string, PdoSizePair > PdoSizeMap
void ecx_dcsync0(ecx_contextt *context, uint16 slave, boolean act, uint32 CyclTime, int32 CyclShift)
uint16 state
bool writeFirmware(const uint16_t slave, const std::string &fileName, const uint32_t &password, const int fileSize, char *fileBuffer)
int(* txbuflength)[EC_MAXBUF]
uint8 SubIdx
ec_bufT * tempbuf
int ecx_FPWR(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
unsigned short uint16_t
bool startup(const bool sizeCheck=true)
uint16_t uint16
char * ec_soeerror2string(uint16 errorcode)
EC_ERR_TYPE_EMERGENCY
ECT_REG_SM0
uint16 ALstatuscode
uint32 ecx_readeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, int timeout)
ec_err_type Etype
uint8 blockLRW
ec_eringt * elist
ec_stackT stack
EC_ERR_TYPE_MBX_ERROR
ecx_portt * port
char desc[EC_MAXLEN_ADAPTERNAME]
ECT_SII_BOOTTXMBX
std::atomic< int > wkc_
Working counter of the most recent PDO.
ec_groupt * grouplist
PACKED_END PACKED_BEGIN struct PACKED ec_sm ec_smt
int ecx_config_init(ecx_contextt *context, uint8 usetable)
ec_bufT(* rxbuf)[EC_MAXBUF]
int ecx_init(ecx_contextt *context, const char *ifname)
char name[EC_MAXNAME+1]
int writeFile(const uint16_t slave, const std::string &fileName, const uint32_t &password, const int fileSize, char *fileBuffer, int timeout=EC_TIMEOUTSTATE *10)
unsigned int uint32_t
EC_STATE_BOOT
void setState(const uint16_t state, const uint16_t slave=0)
uint16 Slave
int ecx_writestate(ecx_contextt *context, uint16 slave)
#define ROS_INFO(...)
std::shared_ptr< EthercatSlaveBase > EthercatSlaveBasePtr
int slave
#define FALSE
ec_bufT(* txbuf)[EC_MAXBUF]
ecx_redportt * redport
std::string getErrorString(ec_errort error)
bool sentProcessData_
Bool indicating whether PDO data has been sent and not read yet.
std::vector< EthercatSlaveBasePtr > slaves_
List of slaves.
#define EC_TIMEOUTEEP
ECT_REG_SM1
int ecx_config_map_group(ecx_contextt *context, void *pIOmap, uint8 group)
#define HI_WORD(l)
std::atomic< bool > isRunning_
Internal flag to indicate if the instance is running.
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
int16 tail
#define EC_TIMEOUTRET
#define LO_WORD(l)
int getExpectedWorkingCounter(const uint16_t slave=0) const
bool waitForState(const uint16_t state, const uint16_t slave=0, const unsigned int maxRetries=40, const double retrySleep=0.001)
int32 AbortCode
#define ROS_WARN_STREAM_THROTTLE(rate, args)
ec_timet Time
boolean ecx_iserror(ecx_contextt *context)
uint16 ErrorCode
uint16 mbx_wo
int wkc
ros::Time updateReadStamp_
Time of the last successful PDO reading.
uint16 Index
ros::Time updateWriteStamp_
Time of the last successful PDO writing.
#define ROS_INFO_STREAM(args)
uint32 data
uint32 sec
boolean ecx_poperror(ecx_contextt *context, ec_errort *Ec)
Struct defining the Pdo characteristic.
EC_ERR_TYPE_PACKET_ERROR
const char * ec_sdoerror2string(uint32 sdoerrorcode)
uint16 mbx_l
ec_adaptert * ec_find_adapters(void)
static Time now()
void printALStatus(const uint16_t slave=0)
Prints application layer status.
EC_ERR_TYPE_SOE_ERROR
uint8_t state
int ecx_FOEwrite(ecx_contextt *context, uint16 slave, char *filename, uint32 password, int psize, void *p, int timeout)
#define ROS_ERROR_STREAM(args)
int(* rxbufstat)[EC_MAXBUF]
int ecx_receive_processdata(ecx_contextt *context, int timeout)
const double ecatConfigRetrySleep_
Time to sleep between the retries.
const unsigned int ecatConfigMaxRetries_
Maximal number of retries to configure the EtherCAT bus.
int * sock
char * ec_mbxerror2string(uint16 errorcode)
ec_slavet * slavelist
#define ROS_DEBUG(...)
EC_STATE_INIT
uint16 inputsWKC
int * slavecount
uint8 * inputs


rokubimini_ethercat
Author(s):
autogenerated on Wed Mar 3 2021 03:09:16