EthercatBusBase.cpp
Go to the documentation of this file.
2 #include <thread>
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;
14  ecatContext_.port->stack.txbuflength = 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.
119  std::this_thread::sleep_for(std::chrono::duration<double>(ecatConfigRetrySleep_));
120  ROS_INFO_STREAM("[" << getName() << "] "
121  << "No slaves have been found, retrying " << retry + 1 << "/" << ecatConfigMaxRetries_
122  << " ...");
123  }
124 
125  // Check if the given slave addresses are valid.
126  bool slave_addresses_are_ok = true;
127  for (const auto& slave : slaves_)
128  {
129  auto address = static_cast<int>(slave->getAddress());
130  if (address == 0)
131  {
132  ROS_ERROR_STREAM("[" << getName() << "] "
133  << "Slave '" << slave->getName() << "': Invalid address " << address << ".");
134  slave_addresses_are_ok = false;
135  }
136  if (address > getNumberOfSlaves())
137  {
138  ROS_ERROR_STREAM("[" << getName() << "] "
139  << "Slave '" << slave->getName() << "': Invalid address " << address << ", "
140  << "only " << getNumberOfSlaves() << " slave(s) found.");
141  slave_addresses_are_ok = false;
142  }
143  }
144  if (!slave_addresses_are_ok)
145  {
146  return false;
147  }
148 
149  // Check if the given slave names are valid.
150  for (const auto& slave : slaves_)
151  {
152  auto product_name = slave->getProductName();
153  if (!isCorrectDeviceName(slave->getAddress(), product_name))
154  {
155  ROS_WARN_STREAM("[" << getName() << "] "
156  << "Slave '" << slave->getName() << "': Invalid product name '" << product_name
157  << "' given, didn't match the actual product name of the device: '"
158  << getDeviceName(slave->getAddress()) << "'");
159  slave->setProductName(getDeviceName(slave->getAddress()));
160  }
161  }
162  // Disable symmetrical transfers.
164 
165  // Initialize the communication interfaces of all slaves.
166  for (auto& slave : slaves_)
167  {
168  if (!slave->startup())
169  {
170  ROS_ERROR_STREAM("[" << getName() << "] "
171  << "Slave '" << slave->getName() << "' was not initialized successfully.");
172  return false;
173  }
174  }
175  // wait for the slaves to reach PREOP state
177  // Print how many slaves have been detected.
178  ROS_INFO_STREAM("[" << getName() << "] "
179  << "The following " << getNumberOfSlaves() << " slaves have been found and configured:");
180  unsigned int serial_number;
181  for (auto& slave : slaves_)
182  {
183  ROS_INFO_STREAM("[" << getName() << "] "
184  << "Address: " << slave->getAddress());
185  ROS_INFO_STREAM("[" << getName() << "] "
186  << "Name: '" << slave->getProductName() << "'");
187  slave->getSerialNumber(serial_number);
188  ROS_INFO_STREAM("[" << getName() << "] "
189  << "S/N: " << serial_number);
190  slave->setSerialNumber(serial_number);
191  }
192  // Set up the communication IO mapping.
193  // Note: ecx_config_map_group(..) requests the slaves to go to SAFE-OP.
195 
196  // Check if the size of the IO mapping fits our slaves.
197  bool io_map_is_ok = true;
198  // do this check only if 'sizeCheck' is true
199  if (sizeCheck)
200  {
201  for (const auto& slave : slaves_)
202  {
203  const EthercatSlaveBase::PdoInfo pdo_info = slave->getCurrentPdoInfo();
204  if (pdo_info.rxPdoSize_ != ecatContext_.slavelist[slave->getAddress()].Obytes)
205  {
206  ROS_ERROR_STREAM("[" << getName() << "] "
207  << "RxPDO size mismatch: The slave '" << slave->getName() << "' expects a size of "
208  << pdo_info.rxPdoSize_ << " bytes but the slave found at its address "
209  << slave->getAddress() << " requests "
210  << ecatContext_.slavelist[slave->getAddress()].Obytes << " bytes).");
211  io_map_is_ok = false;
212  }
213  if (pdo_info.txPdoSize_ != ecatContext_.slavelist[slave->getAddress()].Ibytes)
214  {
215  ROS_ERROR_STREAM("[" << getName() << "] "
216  << "TxPDO size mismatch: The slave '" << slave->getName() << "' expects a size of "
217  << pdo_info.txPdoSize_ << " bytes but the slave found at its address "
218  << slave->getAddress() << " requests "
219  << ecatContext_.slavelist[slave->getAddress()].Ibytes << " bytes).");
220  io_map_is_ok = false;
221  }
222  }
223  }
224  if (!io_map_is_ok)
225  {
226  return false;
227  }
228 
229  // Initialize the memory with zeroes.
230  for (int slave = 1; slave <= getNumberOfSlaves(); slave++)
231  {
234  }
235 
236  return true;
237 }
238 
240 {
241  if (!sentProcessData_)
242  {
243  ROS_DEBUG_STREAM("[" << getName() << "] "
244  << "No process data to read.");
245  return;
246  }
247 
250  {
251  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
253  }
254  sentProcessData_ = false;
255 
257  if (!workingCounterIsOk())
258  {
259  ROS_WARN_STREAM_THROTTLE(1.0, "[" << getName() << "] "
260  << "Update Read:" << this);
261  ROS_WARN_STREAM_THROTTLE(1.0, "[" << getName() << "] "
262  << "Working counter is too low: " << wkc_.load() << " < "
264  return;
265  }
266 
268  for (auto& slave : slaves_)
269  {
270  slave->updateRead();
271  }
272 }
273 
275 {
276  if (sentProcessData_)
277  {
278  ROS_DEBUG_STREAM("[" << getName() << "] "
279  << "Sending new process data without reading the previous one.");
280  }
281 
283  for (auto& slave : slaves_)
284  {
285  slave->updateWrite();
286  }
287 
290  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
292  sentProcessData_ = true;
293 }
294 
296 {
297  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
298  // Set the slaves to state Init.
299  if (getNumberOfSlaves() > 0)
300  {
303  }
304 
305  // Close the port.
306  if (ecatContext_.port != nullptr)
307  {
308  ROS_INFO_STREAM("[" << getName() << "] "
309  << "Closing socket ...");
311  // Sleep to make sure the socket is closed, because ecx_close is non-blocking.
312  std::this_thread::sleep_for(std::chrono::milliseconds(500));
313  }
314 }
315 
316 void EthercatBusBase::setState(const uint16_t state, const uint16_t slave)
317 {
318  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
319  assert(static_cast<int>(slave) <= getNumberOfSlaves());
322  ROS_DEBUG_STREAM("Slave " << slave << ": State " << state << " has been set.");
323 }
324 
325 bool EthercatBusBase::waitForState(const uint16_t state, const uint16_t slave, const unsigned int maxRetries,
326  const double retrySleep)
327 {
328  assert(static_cast<int>(slave) <= getNumberOfSlaves());
329  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
330  for (unsigned int retry = 0; retry <= maxRetries; retry++)
331  {
332  if (ecx_statecheck(&ecatContext_, slave, state, static_cast<int>(1e6 * retrySleep)) == state)
333  {
334  ROS_DEBUG_STREAM("Slave " << slave << ": State " << state << " has been reached.");
335  return true;
336  }
337  // TODO: Do this for all states?
340  }
341 
342  ROS_WARN_STREAM("Slave " << slave << ": State " << state << " has not been reached.");
343  return false;
344 }
345 
347 {
348  assert(static_cast<int>(slave) <= getNumberOfSlaves());
349  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
351 }
352 
354 {
355  std::stringstream stream;
356  stream << "Time: " << (static_cast<double>(error.Time.sec) + (static_cast<double>(error.Time.usec) / 1000000.0));
357 
358  switch (error.Etype)
359  {
361  stream << " SDO slave: " << error.Slave << " index: 0x" << std::setfill('0') << std::setw(4) << std::hex
362  << error.Index << "." << std::setfill('0') << std::setw(2) << std::hex
363  << static_cast<uint16_t>(error.SubIdx) << " error: 0x" << std::setfill('0') << std::setw(8) << std::hex
364  << static_cast<unsigned>(error.AbortCode) << " " << ec_sdoerror2string(error.AbortCode);
365  break;
367  stream << " EMERGENCY slave: " << error.Slave << " error: 0x" << std::setfill('0') << std::setw(4) << std::hex
368  << error.ErrorCode;
369  break;
371  stream << " PACKET slave: " << error.Slave << " index: 0x" << std::setfill('0') << std::setw(4) << std::hex
372  << error.Index << "." << std::setfill('0') << std::setw(2) << std::hex
373  << static_cast<uint16_t>(error.SubIdx) << " error: 0x" << std::setfill('0') << std::setw(8) << std::hex
374  << error.ErrorCode;
375  break;
377  stream << " SDO slave: " << error.Slave << " index: 0x" << std::setfill('0') << std::setw(4) << std::hex
378  << error.Index << "." << std::setfill('0') << std::setw(2) << std::hex
379  << static_cast<uint16_t>(error.SubIdx) << " error: 0x" << std::setfill('0') << std::setw(8) << std::hex
380  << static_cast<unsigned>(error.AbortCode) << " " << ec_sdoerror2string(error.AbortCode);
381  break;
383  stream << " SoE slave: " << error.Slave << " index: 0x" << std::setfill('0') << std::setw(4) << std::hex
384  << error.Index << " error: 0x" << std::setfill('0') << std::setw(8) << std::hex
385  << static_cast<unsigned>(error.AbortCode) << " " << ec_soeerror2string(error.ErrorCode);
386  break;
388  stream << " MBX slave: " << error.Slave << " error: 0x" << std::setfill('0') << std::setw(8) << std::hex
389  << error.ErrorCode << " " << ec_mbxerror2string(error.ErrorCode);
390  break;
391  default:
392  stream << " MBX slave: " << error.Slave << " error: 0x" << std::setfill('0') << std::setw(8) << std::hex
393  << static_cast<unsigned>(error.AbortCode);
394  break;
395  }
396  return stream.str();
397 }
398 
400 {
401  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
402  assert(static_cast<int>(slave) <= getNumberOfSlaves());
403 
404  ROS_INFO_STREAM(" slave: " << slave << " alStatusCode: 0x" << std::setfill('0') << std::setw(8) << std::hex
407 }
408 
410 {
411  while (ecx_iserror(&ecatContext_))
412  {
413  ec_errort error;
414  if (ecx_poperror(&ecatContext_, &error))
415  {
416  std::string error_str = getErrorString(error);
417  ROS_ERROR_STREAM(error_str);
418  if (error.Slave == slave && error.Index == index)
419  {
420  ROS_ERROR_STREAM("Error in index " << index << slave << "of slave " << slave
421  << ". Error string: " << error_str);
422  return true;
423  }
424  }
425  }
426  return false;
427 }
428 
430 {
431  return wkc_ >= getExpectedWorkingCounter();
432 }
433 
434 void EthercatBusBase::syncDistributedClock0(const uint16_t slave, const bool activate, const double cycleTime,
435  const double cycleShift)
436 {
437  ROS_INFO_STREAM("Bus '" << name_ << "', slave " << slave << ": " << (activate ? "Activating" : "Deactivating")
438  << " distributed clock synchronization...");
439 
440  ecx_dcsync0(&ecatContext_, slave, static_cast<uint8_t>(activate), static_cast<uint32_t>(cycleTime * 1e9),
441  static_cast<int32_t>(1e9 * cycleShift));
442 
443  ROS_INFO_STREAM("Bus '" << name_ << "', slave " << slave << ": " << (activate ? "Activated" : "Deactivated")
444  << " distributed clock synchronization.");
445 }
446 
448 {
449  PdoSizeMap pdo_map;
450 
451  for (const auto& slave : slaves_)
452  {
453  pdo_map.insert(std::make_pair(slave->getName(), getHardwarePdoSizes(slave->getAddress())));
454  }
455 
456  return pdo_map;
457 }
458 
460 {
461  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
462  assert(static_cast<int>(slave) <= getNumberOfSlaves());
464  return ecatSlavelist_[slave].state;
465 }
466 
468 {
469  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
470  assert(static_cast<int>(slave) <= getNumberOfSlaves());
472 }
473 
475 {
477 }
478 
479 int EthercatBusBase::writeFile(const uint16_t slave, const std::string& fileName, const uint32_t& password,
480  const int fileSize, char* fileBuffer, int timeout)
481 {
482  return ecx_FOEwrite(&ecatContext_, slave, const_cast<char*>(fileName.c_str()), password, fileSize, fileBuffer,
483  timeout);
484 }
485 
486 bool EthercatBusBase::writeFirmware(const uint16_t slave, const std::string& fileName, const uint32_t& password,
487  const int fileSize, char* fileBuffer)
488 {
489  std::lock_guard<std::recursive_mutex> guard(contextMutex_);
490  // Set slave to EC_STATE_INIT state.
494  {
495  ROS_ERROR_STREAM("Could not set slave '" << slave << "' to INIT state.");
497  isRunning_ = false;
498  return false;
499  }
500  ROS_DEBUG_STREAM("Set slave '" << slave << "' to INIT state.");
501 
502  /* read BOOT mailbox data, master -> slave */
504  ecatSlavelist_[slave].SM[0].StartAddr = (uint16)LO_WORD(data);
505  ecatSlavelist_[slave].SM[0].SMlength = (uint16)HI_WORD(data);
506  /* store boot write mailbox address */
508  /* store boot write mailbox size */
510 
511  /* read BOOT mailbox data, slave -> master */
513  ecatSlavelist_[slave].SM[1].StartAddr = (uint16)LO_WORD(data);
514  ecatSlavelist_[slave].SM[1].SMlength = (uint16)HI_WORD(data);
515  /* store boot read mailbox address */
517  /* store boot read mailbox size */
519 
520  ROS_DEBUG(" SM0 A:%4.4x L:%4d F:%8.8x", ecatSlavelist_[slave].SM[0].StartAddr, ecatSlavelist_[slave].SM[0].SMlength,
521  (int)ecatSlavelist_[slave].SM[0].SMflags);
522  ROS_DEBUG(" SM1 A:%4.4x L:%4d F:%8.8x", ecatSlavelist_[slave].SM[1].StartAddr, ecatSlavelist_[slave].SM[1].SMlength,
523  (int)ecatSlavelist_[slave].SM[1].SMflags);
524  /* program SM0 mailbox in for slave */
526  EC_TIMEOUTRET);
527  /* program SM1 mailbox out for slave */
529  EC_TIMEOUTRET);
530 
531  // Set slave to EC_STATE_BOOT state.
535  {
536  ROS_ERROR_STREAM("Could not set slave '" << slave << "' to BOOT state.");
538  isRunning_ = false;
539  return false;
540  }
541  ROS_DEBUG_STREAM("Set slave '" << slave << "' to BOOT state.");
542 
543  // Send file over EtherCAT.
544  ROS_INFO("Flashing firmware ...");
545  // Write over EtherCAT.
546  ROS_INFO("Writing file over ethercat (FOE)");
547  ROS_DEBUG_STREAM("Size of file buffer: " << fileSize);
548 
549  int wkc = writeFile(slave, fileName, password, fileSize, fileBuffer);
550  ROS_INFO_STREAM("Result wkc: " << wkc);
551  // Check work counter.
552  if (wkc != 1)
553  {
554  ROS_ERROR_STREAM("Writing file over EtherCAT failed (wkc = " << wkc << ").");
555  isRunning_ = false;
556  return false;
557  }
558 
559  ROS_DEBUG_STREAM("Request init state for slave " << slave);
560  // Set slave to EC_STATE_INIT state.
563 
564  ROS_INFO("Flashing over EtherCAT was successful");
565 
566  isRunning_ = false;
567  return true;
568 }
569 } // namespace soem_interface
570 } // namespace rokubimini
EC_STATE_BOOT
EC_STATE_BOOT
ec_group::blockLRW
uint8 blockLRW
wkc
int wkc
uint8_t
unsigned char uint8_t
slave
int slave
ec_slave::mbx_ro
uint16 mbx_ro
ecx_send_processdata
int ecx_send_processdata(ecx_contextt *context)
ec_slave::ALstatuscode
uint16 ALstatuscode
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
ecx_init
int ecx_init(ecx_contextt *context, const char *ifname)
ec_smt
PACKED_END PACKED_BEGIN struct PACKED ec_sm ec_smt
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
ec_mbxerror2string
char * ec_mbxerror2string(uint16 errorcode)
rokubimini::soem_interface::EthercatBusBase::getName
const std::string & getName() const
Definition: EthercatBusBase.hpp:50
ecx_FOEwrite
int ecx_FOEwrite(ecx_contextt *context, uint16 slave, char *filename, uint32 password, int psize, void *p, int timeout)
ec_slave::inputs
uint8 * inputs
uint16_t
unsigned short uint16_t
ecx_statecheck
uint16 ecx_statecheck(ecx_contextt *context, uint16 slave, uint16 reqstate, int timeout)
ec_slave::outputs
uint8 * outputs
ecx_writestate
int ecx_writestate(ecx_contextt *context, uint16 slave)
rokubimini::soem_interface::EthercatBusBase::startup
bool startup(const bool sizeCheck=true)
Definition: EthercatBusBase.cpp:78
ec_adapter
rokubimini::soem_interface::EthercatBusBase::getHardwarePdoSizes
PdoSizeMap getHardwarePdoSizes()
Definition: EthercatBusBase.cpp:447
EC_ERR_TYPE_PACKET_ERROR
EC_ERR_TYPE_PACKET_ERROR
rokubimini::soem_interface::EthercatBusBase::getDeviceName
std::string getDeviceName(const uint16_t &slave) const
Definition: EthercatBusBase.hpp:302
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
rokubimini::soem_interface::EthercatSlaveBase::PdoInfo::rxPdoSize_
uint16_t rxPdoSize_
Definition: EthercatSlaveBase.hpp:32
ecx_context::port
ecx_portt * port
EC_ERR_TYPE_SOE_ERROR
EC_ERR_TYPE_SOE_ERROR
rokubimini::soem_interface::EthercatBusBase::shutdown
void shutdown()
Definition: EthercatBusBase.cpp:295
ec_slave::Ibytes
uint32 Ibytes
ec_adapter::next
ec_adaptert * next
rokubimini::soem_interface::EthercatBusBase::printAvailableBusses
static void printAvailableBusses()
Definition: EthercatBusBase.cpp:39
ec_group::outputsWKC
uint16 outputsWKC
ecx_close
void ecx_close(ecx_contextt *context)
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
ec_errort::SubIdx
uint8 SubIdx
ECT_SII_BOOTTXMBX
ECT_SII_BOOTTXMBX
ec_adapter::desc
char desc[EC_MAXLEN_ADAPTERNAME]
ecx_readeeprom
uint32 ecx_readeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, int timeout)
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
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
ec_errort::Etype
ec_err_type Etype
data
data
rokubimini::soem_interface::EthercatSlaveBase::PdoInfo::txPdoSize_
uint16_t txPdoSize_
Definition: EthercatSlaveBase.hpp:34
ec_slave::mbx_wo
uint16 mbx_wo
ec_slave::state
uint16 state
rokubimini::soem_interface::EthercatBusBase::ecatPort_
ecx_portt ecatPort_
Definition: EthercatBusBase.hpp:411
EC_TIMEOUTRET
#define EC_TIMEOUTRET
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
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_STATE_PRE_OP
EC_STATE_PRE_OP
ecx_dcsync0
void ecx_dcsync0(ecx_contextt *context, uint16 slave, boolean act, uint32 CyclTime, int32 CyclShift)
uint32_t
unsigned int uint32_t
ROS_WARN_STREAM_THROTTLE
#define ROS_WARN_STREAM_THROTTLE(period, args)
ecx_readstate
int ecx_readstate(ecx_contextt *context)
ec_group::inputsWKC
uint16 inputsWKC
ec_errort::Slave
uint16 Slave
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
ROS_DEBUG
#define ROS_DEBUG(...)
rokubimini::soem_interface::EthercatSlaveBasePtr
std::shared_ptr< EthercatSlaveBase > EthercatSlaveBasePtr
Definition: EthercatSlaveBase.hpp:316
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::AbortCode
int32 AbortCode
ec_errort
rokubimini::soem_interface::EthercatBusBase::PdoSizeMap
std::unordered_map< std::string, PdoSizePair > PdoSizeMap
Definition: EthercatBusBase.hpp:32
EthercatBusBase.hpp
uint16
uint16_t uint16
ECT_REG_SM1
ECT_REG_SM1
rokubimini
ec_soeerror2string
char * ec_soeerror2string(uint16 errorcode)
ec_sdoerror2string
const char * ec_sdoerror2string(uint32 sdoerrorcode)
ec_errort::ErrorCode
uint16 ErrorCode
EC_STATE_INIT
EC_STATE_INIT
rokubimini::soem_interface::EthercatBusBase::EthercatBusBase
EthercatBusBase()=delete
rokubimini::soem_interface::EthercatBusBase::setState
void setState(const uint16_t state, const uint16_t slave=0)
Definition: EthercatBusBase.cpp:316
ecx_context::grouplist
ec_groupt * grouplist
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
rokubimini::soem_interface::EthercatSlaveBase::PdoInfo
Struct defining the Pdo characteristic.
Definition: EthercatSlaveBase.hpp:25
ec_errort::Time
ec_timet Time
ecx_receive_processdata
int ecx_receive_processdata(ecx_contextt *context, int timeout)
rokubimini::soem_interface::EthercatBusBase::ecatConfigRetrySleep_
const double ecatConfigRetrySleep_
Time to sleep between the retries.
Definition: EthercatBusBase.hpp:403
ecx_context::slavelist
ec_slavet * slavelist
ecx_poperror
boolean ecx_poperror(ecx_contextt *context, ec_errort *Ec)
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_ERR_TYPE_SDO_ERROR
EC_ERR_TYPE_SDO_ERROR
rokubimini::soem_interface::EthercatBusBase::getSlaveALStatusCode
uint16_t getSlaveALStatusCode(uint16_t slave)
Returns the AL Status Code of a slave.
Definition: EthercatBusBase.cpp:467
HI_WORD
#define HI_WORD(l)
ec_find_adapters
ec_adaptert * ec_find_adapters(void)
ec_errort::Index
uint16 Index
FALSE
#define FALSE
EC_TIMEOUTEEP
#define EC_TIMEOUTEEP
rokubimini::soem_interface::EthercatBusBase::updateReadStamp_
ros::Time updateReadStamp_
Time of the last successful PDO reading.
Definition: EthercatBusBase.hpp:396
ECT_REG_SM0
ECT_REG_SM0
EC_TIMEOUTSTATE
#define EC_TIMEOUTSTATE
int32_t
signed int int32_t
rokubimini::soem_interface::EthercatBusBase::ecatContext_
ecx_contextt ecatContext_
Definition: EthercatBusBase.hpp:445
ecx_config_map_group
int ecx_config_map_group(ecx_contextt *context, void *pIOmap, uint8 group)
rokubimini::soem_interface::EthercatBusBase::ecatSlavelist_
ec_slavet ecatSlavelist_[EC_MAXSLAVE]
Definition: EthercatBusBase.hpp:413
ecx_context::slavecount
int * slavecount
LO_WORD
#define LO_WORD(l)
ec_timet::usec
uint32 usec
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
ecx_iserror
boolean ecx_iserror(ecx_contextt *context)
EC_ERR_TYPE_EMERGENCY
EC_ERR_TYPE_EMERGENCY
rokubimini::soem_interface::EthercatBusBase::updateWrite
void updateWrite()
Definition: EthercatBusBase.cpp:274
rokubimini::soem_interface::EthercatBusBase::name_
std::string name_
Name of the bus.
Definition: EthercatBusBase.hpp:381
ec_ALstatuscode2string
char * ec_ALstatuscode2string(uint16 ALstatuscode)
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
ROS_INFO
#define ROS_INFO(...)
ecx_FPWR
int ecx_FPWR(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
ec_adapter::name
char name[EC_MAXLEN_ADAPTERNAME]
rokubimini::soem_interface::EthercatBusBase::syncDistributedClock0
void syncDistributedClock0(const uint16_t slave, const bool activate, const double cycleTime, const double cycleShift)
Definition: EthercatBusBase.cpp:434
ECT_SII_BOOTRXMBX
ECT_SII_BOOTRXMBX
ec_timet::sec
uint32 sec
ec_slave::mbx_l
uint16 mbx_l
ec_slave::Obytes
uint32 Obytes
ecx_config_init
int ecx_config_init(ecx_contextt *context, uint8 usetable)
EC_ERR_TYPE_MBX_ERROR
EC_ERR_TYPE_MBX_ERROR
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
ec_slave::mbx_rl
uint16 mbx_rl
rokubimini::soem_interface::EthercatBusBase::getNumberOfSlaves
int getNumberOfSlaves() const
Definition: EthercatBusBase.cpp:55
EC_ERR_TYPE_SDOINFO_ERROR
EC_ERR_TYPE_SDOINFO_ERROR
ec_slave::SM
ec_smt SM[EC_MAXSM]
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
ros::Time::now
static Time now()
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