Bus.cpp
Go to the documentation of this file.
1 #include "Bus.h"
2 
3 #include <algorithm>
4 #include <iomanip>
5 
6 #include <ethercat.h>
7 
12 
15 
20 
21 #include "ErrorReporting.h"
23 
25 {
26  static constexpr std::uint8_t DEFAULT_ECAT_GROUP = 0;
27 
28  Bus&
30  {
31  static Bus _instance;
32  return _instance;
33  }
34 
35  std::string
36  Bus::logErrorsToFile(std::filesystem::path path, unsigned int lastSeconds)
37  {
38  auto ret = Reporting::getErrorReporting().dumpToFile(path, lastSeconds);
39  if (ret.has_value())
40  {
41  return ret.value().string();
42  }
43  else
44  {
45  return std::string();
46  }
47  }
48 
49  Bus::Bus() : busState(EtherCATState::init), currentGroup(DEFAULT_ECAT_GROUP), errorHandler(this)
50  {
51  setTag("ethercat::Bus");
52  }
53 
54  bool
55  Bus::setPDOMappings()
56  {
58  bool retVal = true;
59  int byteSum = 0;
60 
61  for (std::unique_ptr<SlaveInterface>& slave : slaves)
62  {
63  ARMARX_INFO << "Checking mapping for slave " << slave->getSlaveNumber()
64  << " name: " << slave->getSlaveIdentifier().getName();
65  if (!slave->hasPDOMapping())
66  {
67  ARMARX_INFO << "No mapping needed for " << slave->getSlaveIdentifier().getName();
68  continue;
69  }
70  byteSum +=
71  ec_slave[slave->getSlaveNumber()].Obytes + ec_slave[slave->getSlaveNumber()].Ibytes;
72  if (ec_slave[slave->getSlaveNumber()].outputs == nullptr ||
73  ec_slave[slave->getSlaveNumber()].inputs == nullptr)
74  {
75  BUS_ERROR(iterationCount,
76  "There is a nullpointer in the mapping of slave %d",
77  slave->getSlaveNumber());
78 
79  ARMARX_IMPORTANT << "current slave" << slave->getSlaveNumber();
80  ARMARX_IMPORTANT << "slaveCount: " << ec_slavecount;
81  ARMARX_IMPORTANT << "iomap ptr: 0x" << std::hex << &ioMap << std::dec;
82  ARMARX_IMPORTANT << "sn:" << slave->getSlaveNumber() << std::flush;
83  ARMARX_IMPORTANT << "out: 0x" << std::hex
84  << reinterpret_cast<long>(
85  ec_slave[slave->getSlaveNumber()].outputs)
86  << std::dec << std::flush;
87  ARMARX_IMPORTANT << "in: 0x" << std::hex
88  << reinterpret_cast<long>(ec_slave[slave->getSlaveNumber()].inputs)
89  << std::dec << std::flush;
90  ARMARX_IMPORTANT << "in diff: "
91  << static_cast<long>(ec_slave[slave->getSlaveNumber()].inputs -
92  ec_slave[0].outputs)
93  << std::flush;
94  ARMARX_IMPORTANT << "-------------------------------------------------------";
95 
96 
97  auto ec_errorToString = [](ec_errort const& error) -> std::string
98  {
99  std::stringstream result;
100  result << VAROUT(error.Etype) << "\n"
101  << VAROUT(error.Signal) << "\n"
102  << VAROUT(error.Slave) << "\n"
103  << VAROUT(error.Index) << "\n"
104  << VAROUT(error.SubIdx) << "\n"
105  << "\n";
106  return result.str();
107  };
108 
109  ec_errort error_type;
110  while (ec_poperror(&error_type))
111  {
112  BUS_WARNING(
113  iterationCount, "SOEM error: %s", ec_errorToString(error_type).c_str());
114  }
115  retVal = false;
116  }
117  else
118  {
119  //setting pdo mappings slave inputs are master outputs and vice versa
120  slave->setInputPDO(ec_slave[slave->getSlaveNumber()].outputs);
121  slave->setOutputPDO(ec_slave[slave->getSlaveNumber()].inputs);
122  }
123  }
124  ARMARX_VERBOSE << "PDO size: " << byteSum;
125  return retVal;
126  }
127 
128  bool
129  Bus::createDevices()
130  {
131  auto printAdditionalInformation =
132  [&](const std::string info,
133  const std::vector<std::pair<std::string, std::string>> reasonAndSolutions)
134  {
135  std::this_thread::sleep_for(std::chrono::milliseconds(1));
136  std::stringstream ss;
137  ss << "\n" << info << "\n\n";
138  ss << "Possible reasons are:\n";
139  for (const auto& [reason, solution] : reasonAndSolutions)
140  {
141  ss << "- " << reason << "\n";
142  ss << "(" << solution << ")\n";
143  }
144  ARMARX_IMPORTANT << ss.str();
145  };
146 
147 
148  ARMARX_TRACE;
149 
150  // Error reporter for slave construction
152 
153  ARMARX_VERBOSE << "Constructing slaves.";
154  for (std::uint16_t currentSlaveIndex = 1; currentSlaveIndex <= ec_slavecount;
155  ++currentSlaveIndex)
156  {
157  ARMARX_TRACE;
158 
159  auto createSlaveIdentifierFromESI =
160  [&](std::uint16_t slaveIndex) -> std::optional<SlaveIdentifier>
161  {
162  auto esiHeaderBinary =
164  if (esiHeaderBinary.has_value())
165  {
166  ESIParser p;
167  ESIHeader header = p.parseHeader(esiHeaderBinary.value());
168 
169  SlaveIdentifier sid;
170  sid.slaveIndex = static_cast<std::int16_t>(slaveIndex);
171  sid.vendorID = header.vendorID;
172  sid.productCode = header.productCode;
173  sid.serialNumber = header.serialNumber;
174  sid.revisionNumber = header.revisionNumber;
175  return std::move(sid);
176  }
177  else
178  {
179  return std::nullopt;
180  }
181  };
182 
183  auto maybeSid = createSlaveIdentifierFromESI(currentSlaveIndex);
184  if (!maybeSid.has_value())
185  {
186  BUS_ERROR_LOCAL(reporter,
187  iterationCount,
188  "Failed to create slaveIdentifier from ESI for slave at index %d",
189  currentSlaveIndex);
190  continue;
191  }
192  SlaveIdentifier slaveIdentifier = maybeSid.value();
193 
194  struct
195  {
196  bool found = false;
197  std::string name = "";
198  } foundSlaveInfo;
199 
200  try
201  {
202  BUS_INFO(iterationCount, "Number of slaveFactories is %d", slaveFactories.size());
203  for (SlaveFactory& factory : slaveFactories)
204  {
205  std::unique_ptr<SlaveInterface> slave = factory(slaveIdentifier);
206 
207  if (slave)
208  {
209  if (not foundSlaveInfo.found)
210  {
211  ARMARX_INFO << "Constructed slave "
212  << slave->getSlaveIdentifier().toString() << ".";
213 
214  foundSlaveInfo.name = slave->getSlaveIdentifier().getName();
215  slave->setLocalMinimumLoggingLevel(this->getEffectiveLoggingLevel());
216  slaves.push_back(std::move(slave));
217  foundSlaveInfo.found = true;
218  }
219  else
220  {
221  SLAVE_ERROR_LOCAL(reporter,
222  slaveIdentifier,
223  "Slave already constructed as an `%s`, "
224  "but can also be constructed as an `%s`.",
225  foundSlaveInfo.name.c_str(),
226  slave->getSlaveIdentifier().getNameAsCStr());
227  }
228  }
229  }
230  }
231  catch (LocalException& e)
232  {
233  SLAVE_ERROR_LOCAL(reporter,
234  slaveIdentifier,
235  "Error during slave creation; Reason: %s",
236  e.getReason().c_str());
237  continue;
238  }
239 
240  if (not foundSlaveInfo.found)
241  {
243  reporter, slaveIdentifier, "Could not find a corresponding factory");
244  }
245  }
246 
247  // Not all slaves on the bus could be created correctly
248  // In the sprit of "fail early, fail fast", we do not procede with the device creation
249  if (reporter.hasErrors())
250  {
251  printAdditionalInformation(
252  "One or more slave objects could not be created from the physical slaves found on "
253  "the bus.",
254  {{"No factory is known for a found slave",
255  "The corresponding factory must be registered in the specialization of the "
256  "RTUnit by calling bus.registerSlaveFactory(...) in its constructor"},
257  {"The found slave has different ESI informations (vendorID, productCode and "
258  "serialNumber) than expected by all registered slave factories",
259  "reflash the EEPROM with correct data or adapt the function "
260  "isSlaveIdentifierAccepted() in the corresponding slave class"},
261  {"Corrupted ESI information in the EEPROM of the slave",
262  "Reflash the EEPROM with correct data"}});
263  return false;
264  }
265 
266  BUS_INFO(iterationCount, "Number of slaves pushed into slavesView is %d", slaves.size());
267  // constructing a view of observerptrs on the slaves
268  std::transform(slaves.begin(),
269  slaves.end(),
270  std::back_inserter(slavesView),
271  [](auto& slave) { return std::experimental::make_observer(slave.get()); });
272 
273  // New error reporter for device construction
275 
276  ARMARX_INFO << "Constructing devices.";
277  for (const auto& [_, deviceConfig] : hwconfig.deviceConfigs)
278  {
279  try
280  {
281  const std::string deviceClassName = deviceConfig->getType();
282  const std::string deviceInstanceName = deviceConfig->getName();
283  ARMARX_INFO << "Handling: " << deviceClassName << " name: " << deviceInstanceName
284  << ".";
285 
286  if (deviceFactories.find(deviceClassName) != deviceFactories.end())
287  {
288  auto factory = deviceFactories.at(deviceClassName);
289  ARMARX_CHECK_NOT_NULL(robot)
290  << "Robot is null! You must set the robot via Bus::setRobot()!";
291 
292  std::shared_ptr<DeviceInterface> device = factory(*deviceConfig, robot);
293 
294  // Add devices
295  if (device)
296  {
297  ARMARX_INFO << "Created device " << device->getDeviceName() << " ("
298  << device->getClassName() << ").";
299  devices.push_back(std::move(device));
300  }
301  else
302  {
303  BUS_WARNING_LOCAL(reporter,
304  iterationCount,
305  "Could not create device instance '%s' of class '%s'",
306  deviceInstanceName.c_str(),
307  deviceClassName.c_str());
308  }
309  }
310  else
311  {
312  BUS_ERROR_LOCAL(reporter,
313  iterationCount,
314  "No device factory found for xml-node `%s` with name `%s` in "
315  "hardware config.",
316  deviceClassName.c_str(),
317  deviceInstanceName.c_str());
318  }
319  }
320  catch (LocalException& e)
321  {
322  BUS_ERROR_LOCAL(reporter,
323  iterationCount,
324  "Exception during device creation. Device class: %s; Reason: %s",
325  deviceConfig->getName().c_str(),
326  e.getReason().c_str());
327  continue;
328  }
329  catch (...)
330  {
332  }
333  }
334 
335  ARMARX_VERBOSE << "Checking if hardware config does not contain unnecessary items.";
336  std::vector<std::string> errorsList;
337  if (not hwconfig.checkAllItemsRead(errorsList))
338  {
339  // TODO: Maybe do this on a per-device basis and use DEVICE_FATAL_AND_THROW
340 
341  for (auto& message : errorsList)
342  {
344  }
345  // TODO: Is this the right way to do it?
346  throw std::runtime_error(
347  "The hardware_config did not match the code for the devices, see log");
348  }
349 
350  // There where errors during the creation of the devices.
351  // Better return here instead of trying to continue with possible malformed list of devices.
352  if (reporter.hasErrors())
353  {
354  printAdditionalInformation(
355  "One or more devices could not created from the provided HardwareConfig.",
356  {{"No factory known for device description",
357  "The corresponding device factory must be registered in the specialization of "
358  "the RTUnit by calling bus.registerDeviceFactory(...) in its constructor. It is "
359  "important that the first parameter fits exactly the name used in the "
360  "HardwareConfig"},
361  {"Exception during the construction of the device",
362  "Make sure that there are no programming errors in the constructor of the "
363  "device"}});
364  return false;
365  }
366 
367  // New error reporter for assigning and validating
369 
370  ARMARX_INFO << "Assigning slaves to devices.";
371  for (std::unique_ptr<SlaveInterface>& slave : slaves)
372  {
373  ARMARX_TRACE;
374 
375  bool slaveAssigned = false;
376  for (std::shared_ptr<DeviceInterface>& device : devices)
377  {
378  DeviceInterface::TryAssignResult result = device->tryAssign(*slave);
379  switch (result)
380  {
382  slaveAssigned = true;
383  slave->setParentDeviceName(device->getDeviceName());
384  ARMARX_INFO << "Assigned slave "
385  << slave->getSlaveIdentifier().toMinimalString()
386  << " to device " << device->getDeviceName() << ".";
387  break;
389  // Okay, just continue.
390  break;
392  BUS_FATAL_AND_THROW(iterationCount,
393  "Tried to assign ambiguous slave with name `%s` (idx: "
394  "%u) again to device (%s) with name `%s`.",
395  slave->getSlaveIdentifier().getNameAsCStr(),
396  slave->getSlaveIdentifier().slaveIndex,
397  device->getClassName().c_str(),
398  device->rtGetDeviceName());
399  }
400  }
401 
402  // Slaves without PDOs dont need a device to be assigned to.
403  if (not slaveAssigned && slave->hasPDOMapping())
404  {
405  BUS_ERROR_LOCAL(reporter,
406  iterationCount,
407  "Could not find a device to assign following slave to:\n%s",
408  slave->getSlaveIdentifier().toString().c_str());
409  }
410  }
411 
412  // There where errors during the assigment of the slaves to the devices.
413  // Most likely this is due to the fact, that there are slaves which do not have been assigned.
414  // It does not make sense to continue since not all bus members will be controlled correctly.
415  if (reporter.hasErrors())
416  {
417  printAdditionalInformation(
418  "Not all found slaves could not be assigned to devices",
419  {{"Unexpected slaves are part of the bus",
420  "Disconnect slaves that have not been described in the HardwareConfig from the "
421  "bus or add additional entries to the HardwareConfig to map the whole bus"},
422  {"SlaveIdentifier in the HardwareConfig do not match the actual slaves",
423  "Make sure, that the slave identifiers for all salves in the HardwareConfig are "
424  "correct. This includes vendorID, productCode and serialNumer."}});
425  return false;
426  }
427 
428  ARMARX_INFO << "Sanity checking that devices have all needed slaves assigned.";
429  for (std::shared_ptr<DeviceInterface>& device : devices)
430  {
431  DeviceInterface::AllAssignedResult result = device->onAllAssigned();
432  switch (result)
433  {
435  // Okay, just continue.
436  break;
439  iterationCount,
440  "Device `%s` ("
441  "%s) reports not all slaves valid. Maybe a slave is missing on the bus",
442  device->getClassName().c_str(),
443  device->rtGetDeviceName());
444  }
445  }
446 
447  ARMARX_VERBOSE << "Adding SlaveErrorRegistersDevice to slaves.";
448  for (auto& slave : slaves)
449  {
450  if (slave)
451  slave->setErrorRegistersDevice(std::make_shared<SlaveErrorRegistersDevice>(
452  "SlaveIdx_" + std::to_string(slave->getSlaveIdentifier().slaveIndex) + "." +
453  slave->getSlaveIdentifier().getName(),
454  slave->getSlaveIdentifier().slaveIndex));
455  }
456 
457 
458  return true;
459  }
460 
461  void
462  Bus::setSocketFileDescriptor(int socketFileDescriptor)
463  {
464  this->socketFileDescriptor = socketFileDescriptor;
465  }
466 
467  void
468  Bus::setIfName(const std::string& ifname)
469  {
470  this->ifname = ifname;
471  }
472 
473  bool
474  Bus::rtUpdateBus(bool doErrorHandling, size_t iteration)
475  {
476  ARMARX_TRACE;
477  if (iterationCount != iteration - 1)
478  {
479  BUS_WARNING(
480  iteration,
481  "Updating the bus has been skipped. The number of the last rt-thread iteration the "
482  "bus has been updated was %d and the current iteration is %d.",
483  iterationCount,
484  iteration);
485  }
486  iterationCount = iteration;
487  if (busState != EtherCATState::op)
488  {
489  BUS_WARNING(iterationCount,
490  "UpdateBus can not be executed because the bus is not in op-mode");
491  return false;
492  }
493 
494  // handle emergency stop release
495  BUS_TIMING_START(bus_rtUpdateBus_isEmergencyStopActive);
496  bool const emergencyStopActive = rtIsEmergencyStopActive();
497  BUS_TIMING_CEND(bus_rtUpdateBus_isEmergencyStopActive, iterationCount, 0.3);
498 
499  // the elmo sometimes go from emergency stop state back into fault state for a moment - the time variable is the fix for that
500  BUS_TIMING_START(bus_rtUpdateBus_recoverFromEmergencyStop)
501  if ((not emergencyStopActive and emergencyStopWasActivated))
502  {
503  bool recovered = true;
504  for (std::unique_ptr<SlaveInterface>& slave : slaves)
505  {
506  recovered &= slave->recoverFromEmergencyStop();
507  }
508  if (recovered)
509  {
510  BUS_WARNING(iterationCount, "Recovered from STO (Safe Torque Off)");
511  emergencyStopWasActivated = false;
512  }
513  }
514  else if (emergencyStopActive and not emergencyStopWasActivated)
515  {
516  BUS_WARNING(iterationCount, "STO (Safe Torque Off) active");
517  emergencyStopWasActivated = emergencyStopActive;
518  }
519  BUS_TIMING_CEND(bus_rtUpdateBus_recoverFromEmergencyStop, iterationCount, 0.3)
520  const auto delay = (armarx::rtNow() - busUpdateLastUpdateTime);
521  if (delay.toMilliSecondsDouble() > 40)
522  {
523  BUS_WARNING(iterationCount,
524  "Update bus was not called for a long time: %ld ms",
525  delay.toMilliSeconds());
526  }
527 
528  //send and receive process data
529  BUS_TIMING_START(bus_rtUpdateBus_updatePDO)
530  rtUpdatePDO();
531  busUpdateLastUpdateTime = armarx::rtNow();
532  BUS_TIMING_CEND(bus_rtUpdateBus_updatePDO, iterationCount, 0.6)
533 
534  // Execute every slave.
535  BUS_TIMING_START(bus_rtUpdateBus_executeSlaves)
536  for (std::unique_ptr<SlaveInterface>& slave : slaves)
537  {
538  slave->execute();
539  }
540  BUS_TIMING_CEND(bus_rtUpdateBus_executeSlaves, iterationCount, 0.3)
541 
542  //error handling
543  if (doErrorHandling)
544  {
545  if (!emergencyStopActive)
546  {
547  BUS_TIMING_START(bus_rtUpdateBus_slaveErrorHandling)
548  errorHandler.rtHandleSlaveErrors();
549  BUS_TIMING_CEND(bus_rtUpdateBus_slaveErrorHandling, iterationCount, 0.3)
550  }
551  BUS_TIMING_START(bus_rtUpdateBus_busErrorHandling)
552  errorHandler.rtHandleBusErrors();
553  BUS_TIMING_CEND(bus_rtUpdateBus_busErrorHandling, iterationCount, 0.3)
554  }
555 
556  // Update error registers
557  BUS_TIMING_START(bus_rtUpdateBus_updateErrorRegisters)
558  if (!errorHandler.hasError() && errorRegisterReadingScheduler)
559  {
560  if (errorRegisterReadingScheduler->allRegistersUpdated())
561  {
562  auto data_ref = errorRegisterReadingScheduler->getRegisterData();
563  for (const auto& data : data_ref)
564  {
565  auto index = data.slaveIndex;
566  this->getSlaveAtIndex(index)->getErrorRegistersDevice()->updateValues(&data);
567  }
568  }
569  errorRegisterReadingScheduler->startReadingNextRegisters();
570  }
571  BUS_TIMING_CEND(bus_rtUpdateBus_updateErrorRegisters, iterationCount, 0.3)
572 
573  // Update functional state
574  BUS_TIMING_START(bus_rtUpdateBus_updateFunctionalState)
575  if (errorHandler.isReinitializationActive())
576  {
577  functionalState = BusFunctionalState::Reinitializing;
578  }
579  else if (emergencyStopActive)
580  {
581  functionalState = BusFunctionalState::EmergencyStop;
582  }
583  else
584  {
585  functionalState = BusFunctionalState::Running;
586  }
587  BUS_TIMING_CEND(bus_rtUpdateBus_updateFunctionalState, iterationCount, 0.3)
588 
589  return true;
590  }
591 
592  void
594  {
595  if (busState == EtherCATState::init)
596  {
597  BUS_WARNING(iterationCount, "Bus is already shutdown");
598  }
599  else
600  {
601  ARMARX_IMPORTANT << "Reading EtherCAT error registers from all slaves.";
602  readAllErrorCounters();
603 
604  ARMARX_INFO << "Bus is shutting down";
605 
606  //shutdown the slaves if the bus hasn't died
607  if (busState == EtherCATState::op)
608  {
609  bool found;
610  do
611  {
612  found = false;
613  for (std::unique_ptr<SlaveInterface>& slave : slaves)
614  {
615  ARMARX_INFO << deactivateSpam(1, std::to_string(slave->getSlaveNumber()))
616  << "shutting down slave "
617  << slave->getSlaveIdentifier().getName() << " ("
618  << slave->getSlaveNumber() << "/" << slaves.size() << ")";
619  found |= !slave->shutdown();
620  }
621  rtUpdatePDO();
622  } while (found);
623  }
624 
625  // shutting down bus
626  // requesting init for all slaves
627  if (!switchBusToInit())
628  {
629  ARMARX_DEBUG << "Could not switch all slaves to Init.";
630  }
631  }
632 
633  // closing bus
634  ec_close();
635 
636  socketInitialized = false;
637 
638  ARMARX_DEBUG << "Bus shutdown";
639 
640  functionalState = BusFunctionalState::Shutdown;
641  }
642 
645  {
646  return pdoValidity;
647  }
648 
649  bool
651  {
652  static const std::map<EtherCATState, std::function<bool(Bus*)>> transitions = {
653  {EtherCATState::preOp, &Bus::_preOpToInit},
654  {EtherCATState::safeOp, &Bus::_safeOpToInit},
655  {EtherCATState::op, &Bus::_opToInit},
657  [](Bus* b)
658  {
659  BUS_WARNING(b->iterationCount, "Bus is already in init");
660  return true;
661  }}};
662 
663  ARMARX_VERBOSE << "Switching bus to init";
664 
665  return transitions.at(busState)(this);
666  }
667 
668  bool
670  {
671  static const std::map<EtherCATState, std::function<bool(Bus*)>> transitions = {
672  {EtherCATState::init, &Bus::_initToPreOp},
673  {EtherCATState::safeOp, &Bus::_safeOpToPreOp},
674  {EtherCATState::op, &Bus::_opToPreOp},
676  [](Bus* b)
677  {
678  BUS_WARNING(b->iterationCount, "Bus is already in preOp");
679  return true;
680  }},
681  };
682 
683  ARMARX_VERBOSE << "Switching bus to preOp";
684 
685  return transitions.at(busState)(this);
686  }
687 
688  bool
690  {
691  static const std::map<EtherCATState, std::function<bool(Bus*)>> transitions = {
692  {EtherCATState::init, &Bus::_initToSafeOp},
693  {EtherCATState::preOp, &Bus::_preOpToSafeOp},
694  {EtherCATState::op, &Bus::_opToSafeOp},
696  [](Bus* b)
697  {
698  BUS_WARNING(b->iterationCount, "Bus is already in safeOp");
699  return true;
700  }},
701  };
702 
703  ARMARX_VERBOSE << "Switching bus to safeOp";
704 
705  return transitions.at(busState)(this);
706  }
707 
708  bool
710  {
711  static const std::map<EtherCATState, std::function<bool(Bus*)>> transitions = {
712  {EtherCATState::init, &Bus::_initToOp},
713  {EtherCATState::preOp, &Bus::_preOpToOp},
714  {EtherCATState::safeOp, &Bus::_safeOpToOp},
716  [](Bus* b)
717  {
718  BUS_WARNING(b->iterationCount, "Bus is already in op");
719  return true;
720  }}};
721 
722  return transitions.at(busState)(this);
723  }
724 
725  bool
726  Bus::_initToPreOp()
727  {
728  ARMARX_VERBOSE << "Start switching bus from 'Init' to 'PreOp'";
730  {
731  ARMARX_VERBOSE << "Finish switching bus from 'Init' to 'PreOp'";
732  };
733 
735 
736  if (!socketInitialized && !initSocket())
737  {
738  BUS_ERROR(iterationCount, "Could not init socket. Abort.");
739  return false;
740  }
741 
742  if (ec_config_init(FALSE) <= 0)
743  {
744  BUS_ERROR(iterationCount, "No slaves found on bus");
745  return false;
746  }
747 
748  bool ret = changeBusState(EtherCATState::preOp);
749  if (ret)
750  {
751  // SDOs can now be read and written (flag is used by SDOHandler)
752  sdoAccessAvailable = true;
753  ARMARX_INFO << ec_slavecount << " slaves found and set from Init to PreOp";
754  }
755 
756  return ret;
757  }
758 
759  bool
760  Bus::_initToSafeOp()
761  {
763 
764  return _initToPreOp() and _preOpToSafeOp();
765  }
766 
767  bool
768  Bus::_initToOp()
769  {
771 
772  return _initToPreOp() and _preOpToSafeOp() and _safeOpToOp();
773  }
774 
775  bool
776  Bus::_preOpToInit()
777  {
778  ARMARX_VERBOSE << "Start switching bus from 'PreOp' to 'Init'";
780  {
781  ARMARX_VERBOSE << "Finish switching bus from 'PreOp' to 'Init'";
782  };
783 
785 
786  return changeBusState(EtherCATState::init);
787  }
788 
789  bool
790  Bus::_preOpToSafeOp()
791  {
792  ARMARX_VERBOSE << "Start switching bus from 'PreOp' to 'SafeOp'";
794  {
795  ARMARX_VERBOSE << "Finish switching bus from 'PreOp' to 'SafeOp'";
796  };
797 
799 
800  //prepare Devices to be read to switch to Safe-Op
801  if (slaves.size() > 0)
802  {
803  if (!validateBus())
804  {
805  shutdown();
807  iterationCount,
808  "Bus could not be validated. This indicates a severe hardware-error, "
809  "since the amount of slaves on the bus changed during the initialization "
810  "of the bus which can only happen if a PCB is behaving incorrectly or "
811  "(most likely) a cable is broken. Shutdown bus!");
812  return false;
813  }
814  }
815  else
816  {
817  // Create devices and populate members.
818  if (!this->createDevices())
819  {
820  BUS_ERROR(iterationCount, "Error during slave and device creation");
821  return false;
822  }
823 
824  if (slaves.size() < 1)
825  {
826  BUS_ERROR(iterationCount, "There are no usable devices on the bus!");
827  return false;
828  }
829  ARMARX_INFO << "Devices were created";
830  }
831 
832  for (std::unique_ptr<SlaveInterface>& slave : slaves)
833  {
834  slave->doMappings();
835  }
836 
837  ARMARX_TRACE;
838 
839  for (std::unique_ptr<SlaveInterface>& slave : slaves)
840  {
841  slave->prepareForSafeOp();
842  }
843 
844  ARMARX_TRACE;
845 
846  for (std::unique_ptr<SlaveInterface>& slave : slaves)
847  {
848  slave->finishPreparingForSafeOp();
849  }
850 
851  ARMARX_TRACE;
852 
853  int actualMappedSize = ec_config_map(ioMap.data());
854 
855  if (actualMappedSize > ioMap.size())
856  {
857  ARMARX_ERROR << "Requested IO map size is " << actualMappedSize << ", however only "
858  << ioMap.size()
859  << " have been statically pre-allocated. Increase the IO map size.";
860  return false;
861  }
862 
863  //calculating Workcounter after mapping to have an error indication later
864  int expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
865  ARMARX_IMPORTANT << "Calculated expected workcounter: " << expectedWKC;
866 
867  errorHandler.init(expectedWKC);
868 
869  ///give the devices their mapping
870  if (!setPDOMappings())
871  {
872  BUS_ERROR(
873  iterationCount,
874  "Couldn't map the PDO, maybe the the pc is under to much load. Check if there are "
875  "other performance hungry programs running.\nOr just try to start again");
876  return false;
877  }
878 
879  bool ret = changeBusState(EtherCATState::safeOp);
880 
881  if (ret)
882  {
883  ARMARX_INFO << "IOmapping done, size: " << actualMappedSize
884  << " - all Slaves are in SAFE-OP now\n";
885  }
886 
887  // Run further initialization code for devices
888  for (const auto& device : devices)
889  {
890  device->postSwitchToSafeOp();
891  }
892 
893  ARMARX_TRACE;
894 
895  // Slaves inputs (EtherCAT naming convention) are transfered, outputs NOT.
896  // This means, the slave objects can receive updated data but cannot yet send
897  // data to the slaves via PDO
898  rtUpdatePDO();
899 
900  pdoValidity = PDOValidity::OnlyInputs;
901 
902  return ret;
903  }
904 
905  bool
906  Bus::_preOpToOp()
907  {
908  return _preOpToSafeOp() and _safeOpToOp();
909  }
910 
911  bool
912  Bus::_safeOpToInit()
913  {
914  ARMARX_VERBOSE << "Start switching bus from 'SafeOp' to 'Init'";
916  {
917  ARMARX_VERBOSE << "Finish switching bus from 'SafeOp' to 'Init'";
918  };
919 
921 
922  return changeBusState(EtherCATState::init);
923  }
924 
925  bool
926  Bus::_safeOpToPreOp()
927  {
928  ARMARX_VERBOSE << "Start switching bus from 'SafeOp' to 'PreOp'";
930  {
931  ARMARX_VERBOSE << "Finish switching bus from 'SafeOp' to 'PreOp'";
932  };
933 
935 
936  return changeBusState(EtherCATState::preOp);
937  }
938 
939  bool
940  Bus::_safeOpToOp()
941  {
942  ARMARX_VERBOSE << "Start switching bus from 'SafeOp' to 'Op'";
944  {
945  ARMARX_VERBOSE << "Finish switching bus from 'SafeOp' to 'Op'";
946  };
947 
949 
950  // Give the slaves some time to prepare.
951  for (std::unique_ptr<SlaveInterface>& slave : slaves)
952  {
953  slave->prepareForOp();
954  }
955 
956  for (std::unique_ptr<SlaveInterface>& slave : slaves)
957  {
958  slave->finishPreparingForOp();
959  }
960 
961  // Send one valid process data to make outputs in slaves happy
962  rtUpdatePDO();
963 
964  if (changeBusState(EtherCATState::op))
965  {
966  ARMARX_INFO << "All slaves in op!";
967  }
968  else
969  {
970  return false;
971  }
972 
973  pdoValidity = PDOValidity::Both;
974  pdoAccessAvailable = true;
975 
976  ARMARX_TRACE;
977 
978  // Some devices might have additional initialization to do after all slaves
979  // are in op.
980  for (std::shared_ptr<DeviceInterface>& device : devices)
981  {
982  device->postSwitchToOp();
983  }
984 
985  ARMARX_TRACE;
986 
987 
988  //preparing devices to run
989  size_t slaveReadyCounter = 0;
990  while (slaveReadyCounter != slaves.size())
991  {
992  rtUpdatePDO();
993  slaveReadyCounter = 0;
994  std::string missingSlaves;
995  for (std::unique_ptr<SlaveInterface>& slave : slaves)
996  {
997  if (slave->prepareForRun())
998  {
999  slaveReadyCounter++;
1000  }
1001  else
1002  {
1003  missingSlaves += slave->getSlaveIdentifier().getName() +
1004  " (idx: " + std::to_string(slave->getSlaveNumber()) + "), ";
1005  }
1006  }
1007  ARMARX_INFO << deactivateSpam(1) << "Waiting for "
1008  << (slaves.size() - slaveReadyCounter) << "/" << slaves.size()
1009  << " slaves to get ready: " << missingSlaves;
1010  }
1011 
1012  std::stringstream slaveInfo;
1013  for (std::unique_ptr<SlaveInterface>& slave : slaves)
1014  {
1015  slaveInfo << "#" << slave->getSlaveNumber() << ": "
1016  << slave->getSlaveIdentifier().getName() << "\n";
1017  }
1018  ARMARX_IMPORTANT << "Used slaves: \n" << slaveInfo.str();
1019 
1020  busUpdateLastUpdateTime = armarx::rtNow();
1021 
1022  functionalState = BusFunctionalState::Running;
1023 
1024  return true;
1025  }
1026 
1027  bool
1028  Bus::_opToInit()
1029  {
1030  ARMARX_VERBOSE << "Start switching bus from 'Op' to 'Init'";
1032  {
1033  ARMARX_VERBOSE << "Finish switching bus from 'Op' to 'Init'";
1034  };
1035 
1037 
1038  return changeBusState(EtherCATState::init);
1039  }
1040 
1041  bool
1042  Bus::_opToPreOp()
1043  {
1044  ARMARX_VERBOSE << "Start switching bus from 'Op' to 'PreOp'";
1046  {
1047  ARMARX_VERBOSE << "Finish switching bus from 'Op' to 'PreOp'";
1048  };
1049 
1051 
1052  return changeBusState(EtherCATState::preOp);
1053  }
1054 
1055  bool
1056  Bus::_opToSafeOp()
1057  {
1058  ARMARX_VERBOSE << "Start switching bus from 'Op' to 'SafeOp'";
1060  {
1061  ARMARX_VERBOSE << "Finish switching bus from 'Op' to 'SafeOp'";
1062  };
1063 
1065 
1066 
1067  return changeBusState(EtherCATState::safeOp);
1068  }
1069 
1070  bool
1071  Bus::changeBusState(EtherCATState state)
1072  {
1073  ARMARX_TRACE;
1075  {
1076  busState = readStates();
1077  };
1078 
1079  if (state <= EtherCATState::preOp)
1080  {
1081  pdoValidity = PDOValidity::None;
1082  }
1083 
1084  if (state != EtherCATState::op)
1085  {
1086  pdoAccessAvailable = false;
1087  }
1088 
1089  EtherCATState retState = readStates();
1090  if (retState == state)
1091  {
1092  ARMARX_VERBOSE << "All slaves are already in requested state " << state;
1093  return true;
1094  }
1095  else
1096  {
1097  IceUtil::Time const start = armarx::rtNow();
1098  EtherCATState const retState = changeStateOfBus(state, true);
1099  IceUtil::Time const end = armarx::rtNow();
1100  IceUtil::Time const elapsed = (end - start);
1101 
1102  if (retState != state)
1103  {
1104  ARMARX_INFO << "One or more slaves appear to not have reached the desired state. "
1105  << "If the desired state is lower than the actual one this is fine.";
1106  }
1107 
1108  if (retState < state)
1109  {
1110  readStates();
1111  for (std::uint16_t i = 1; i < ec_slavecount + 1; i++)
1112  {
1113  EtherCATState const actualState = ec_slave[i].state;
1114  if (actualState != state)
1115  {
1116  SLAVE_WARNING(
1117  getSlaveAtIndex(i)->getSlaveIdentifier(),
1118  "Slave did not reach requested state %s after %ld µs (start = "
1119  "%ld µs since epoch, end = %ld µs since epoch). Actual state: %s AL: "
1120  "%s",
1121  state.c_str(),
1122  elapsed.toMicroSeconds(),
1123  start.toMicroSeconds(),
1124  end.toMicroSeconds(),
1125  actualState.c_str(),
1126  ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
1127  }
1128  }
1129 
1130  return false;
1131  }
1132  }
1133 
1134  return true;
1135  }
1136 
1137  bool
1138  Bus::validateBus() const
1139  {
1140  if (slaves.empty())
1141  {
1142  BUS_WARNING(iterationCount, "No slaves have been created. Cannot validate the bus.");
1143  return false;
1144  }
1145 
1146  int w = 0x0000;
1147  int slaveCount = ec_BRD(0x0000, ECT_REG_TYPE, sizeof(w), &w, EC_TIMEOUTSAFE);
1148  if (slaveCount == EC_NOFRAME)
1149  {
1150  BUS_ERROR(iterationCount, "EC_NOFRAME when trying to get slave count.");
1151  return false;
1152  }
1153 
1154  if (static_cast<std::uint16_t>(slaveCount) != slaves.size())
1155  {
1156  BUS_ERROR(iterationCount,
1157  "Could not validate bus! Amount of found slaves is not equal to the previous "
1158  "created slaves. (Found: %u, Expected: %u)",
1159  slaveCount,
1160  slaves.size());
1161  return false;
1162  }
1163 
1164  // If the amount of found slaves is the expected amount, we assume that the bus is fine
1165  // and every slaves is still available.
1166  // It is extremly unlikely, that the physical position of two or more slaves
1167  // on the bus have changed.
1168  return true;
1169  }
1170 
1171  bool
1172  Bus::initSocket()
1173  {
1174  if (socketInitialized)
1175  {
1176  BUS_ERROR(iterationCount, "Socket is already initialized.");
1177  return false;
1178  }
1179 
1180  if (socketFileDescriptor == -1)
1181  {
1182  BUS_WARNING(iterationCount, "socketFileDescriptor is -1 - did you forget to set it?");
1183  return false;
1184  }
1185 
1186  if (!ifname.empty())
1187  {
1188  ARMARX_IMPORTANT << "ec_init(" << ifname << ")";
1189  if (!ec_init(ifname.c_str()))
1190  {
1191  BUS_ERROR(iterationCount,
1192  "Could not init EtherCAT on %s\nExecute as root\n",
1193  ifname.c_str());
1194  return false;
1195  }
1196  }
1197  else if (socketFileDescriptor != -1)
1198  {
1199  ARMARX_INFO << "Using socketFileDescriptor " << socketFileDescriptor
1200  << " to open raw socket";
1201  //initialise SOEM, open socket
1202  if (!ec_init_wsock(socketFileDescriptor))
1203  {
1204  BUS_WARNING(iterationCount,
1205  "No socket connection on %u\nExecute as root\n",
1206  socketFileDescriptor);
1207  return false;
1208  }
1209  }
1210  else
1211  {
1212  BUS_WARNING(iterationCount, "Either socketFileDescriptor or ifname need to be set");
1213  return false;
1214  }
1215 
1216  //We succeed
1217  ARMARX_INFO << "Started SOEM with socketFileDescriptor: " << socketFileDescriptor;
1218 
1219  socketInitialized = true;
1220  return true;
1221  }
1222 
1223  void
1224  Bus::readAllErrorCounters()
1225  {
1226  std::vector<RegisterDataList> registerData;
1227  for (const auto& slave : slaves)
1228  {
1229  registerData.push_back(
1230  RegisterDataList{static_cast<std::uint16_t>(slave->getSlaveIdentifier().slaveIndex),
1231  {
1264  }});
1265  }
1266 
1267 
1268  EtherCATFrameList* frameList =
1270  &registerData);
1271 
1272  int leftRetries = 3;
1273  bool readRegistersSuccessful = false;
1274 
1275  do
1276  {
1277  readRegistersSuccessful = readRegisters(frameList);
1278 
1279  if (not readRegistersSuccessful)
1280  {
1281  leftRetries -= 1;
1282 
1283  if (leftRetries == 0)
1284  {
1285  ARMARX_ERROR << "Repeatedly failed reading error registers. Giving up.";
1286  return;
1287  }
1288  else
1289  {
1290  ARMARX_ERROR << "Failed reading error registers. Left retries: "
1291  << leftRetries;
1292  }
1293  }
1294 
1295  } while (not readRegistersSuccessful);
1296 
1298  &registerData);
1299 
1300  struct ErrorCounters
1301  {
1302  std::uint8_t invalidFrame = 0;
1303  std::uint8_t rxError = 0; // Or physical error count.
1304  std::uint8_t forwardedRxError = 0; // Error counter of a predecessor.
1305  std::uint8_t linkLost = 0;
1306  };
1307 
1308  std::vector<ErrorCounters> counts(4);
1309 
1310  for (const auto& d : registerData)
1311  {
1312  auto copyCounts = [&](datatypes::RegisterEnum type) -> std::uint8_t
1313  { return std::get<datatypes::EtherCATDataType::UNSIGNED8>(d.registerData.at(type)); };
1314 
1315  using RE = datatypes::RegisterEnum;
1316 
1317  counts[0].invalidFrame = copyCounts(RE::FRAME_ERROR_COUNTER_PORT_0);
1318  counts[0].rxError = copyCounts(RE::PHYSICAL_ERROR_COUNTER_PORT_0);
1319  counts[0].forwardedRxError = copyCounts(RE::PREVIOUS_ERROR_COUNTER_PORT_0);
1320  counts[0].linkLost = copyCounts(RE::LOST_LINK_COUNTER_PORT_0);
1321 
1322  counts[1].invalidFrame = copyCounts(RE::FRAME_ERROR_COUNTER_PORT_1);
1323  counts[1].rxError = copyCounts(RE::PHYSICAL_ERROR_COUNTER_PORT_1);
1324  counts[1].forwardedRxError = copyCounts(RE::PREVIOUS_ERROR_COUNTER_PORT_1);
1325  counts[1].linkLost = copyCounts(RE::LOST_LINK_COUNTER_PORT_1);
1326 
1327  counts[2].invalidFrame = copyCounts(RE::FRAME_ERROR_COUNTER_PORT_2);
1328  counts[2].rxError = copyCounts(RE::PHYSICAL_ERROR_COUNTER_PORT_2);
1329  counts[2].forwardedRxError = copyCounts(RE::PREVIOUS_ERROR_COUNTER_PORT_2);
1330  counts[2].linkLost = copyCounts(RE::LOST_LINK_COUNTER_PORT_2);
1331 
1332  counts[3].invalidFrame = copyCounts(RE::FRAME_ERROR_COUNTER_PORT_3);
1333  counts[3].rxError = copyCounts(RE::PHYSICAL_ERROR_COUNTER_PORT_3);
1334  counts[3].forwardedRxError = copyCounts(RE::PREVIOUS_ERROR_COUNTER_PORT_3);
1335  counts[3].linkLost = copyCounts(RE::LOST_LINK_COUNTER_PORT_3);
1336 
1337  auto slave = getSlaveAtIndex(d.slaveIndex);
1338  for (unsigned int i = 0; i < 4; i++)
1339  {
1340  if (counts[i].invalidFrame > 0 || counts[i].rxError > 0 ||
1341  counts[i].forwardedRxError > 0 || counts[i].linkLost > 0)
1342  {
1343  SLAVE_ERROR(slave->getSlaveIdentifier(),
1344  "Error counters on port %u\n"
1345  " - invalid frame: \t\t%u\n"
1346  " - rx error: \t\t%u\n"
1347  " - forwarded rx error: \t%u\n"
1348  " - link lost: \t\t%u",
1349  i,
1350  counts[i].invalidFrame,
1351  counts[i].rxError,
1352  counts[i].forwardedRxError,
1353  counts[i].linkLost);
1354  }
1355  }
1356  }
1357  }
1358 
1359  EtherCATState
1361  {
1362  return busState;
1363  }
1364 
1367  {
1368  return functionalState;
1369  }
1370 
1371  void
1373  {
1374  slaveFactories.push_back(factory);
1375  }
1376 
1377  void
1378  Bus::registerDeviceFactory(const std::string& name, const DeviceFactory& factory)
1379  {
1380  deviceFactories[name] = factory;
1381  }
1382 
1383  void
1385  {
1387  parser.parse();
1388  this->hwconfig = parser.getHardwareConfig();
1389  }
1390 
1391  std::vector<std::experimental::observer_ptr<SlaveInterface>>
1393  {
1394  return slavesView;
1395  std::vector<SlaveInterface*> slaves_raw;
1396  // std::transform(slaves.begin(),
1397  // slaves.end(),
1398  // std::back_inserter(slaves_raw),
1399  // [](auto& slave) { return slave.get(); });
1400  // return slaves_raw;
1401  }
1402 
1403  const std::vector<std::shared_ptr<DeviceInterface>>&
1405  {
1406  return devices;
1407  }
1408 
1409  Bus::~Bus()
1410  {
1411  }
1412 
1414  Bus::getSlaveAtIndex(std::uint16_t slaveIndex) const
1415  {
1416  for (const std::unique_ptr<SlaveInterface>& slave : slaves)
1417  {
1418  if (slave->getSlaveNumber() == slaveIndex)
1419  {
1420  return std::experimental::make_observer(slave.get());
1421  }
1422  }
1423 
1424  return nullptr;
1425  }
1426 
1427  bool
1429  {
1430  bool found = false;
1431  for (const std::unique_ptr<SlaveInterface>& slave : slaves)
1432  {
1433  if (!errorHandler.isSlaveLostOrDuringReinitialization(slave.get()) &&
1434  slave->isEmergencyStopActive())
1435  {
1436  // dont break so that isEmergencyStopActive executed for each operational slave
1437  found = true;
1438  }
1439  }
1440  return found;
1441  }
1442 
1443  bool
1445  {
1446  BUS_TIMING_START(bus_rtHasError)
1447  const bool hasError = errorHandler.hasError();
1448  BUS_TIMING_CEND(bus_rtHasError, iterationCount, 0.5)
1449  return hasError;
1450  }
1451 
1452  void
1454  {
1455  this->robot = robot;
1456  }
1457 
1458  void
1459  Bus::configureErrorCountersReading(bool enable, unsigned int periodInMS)
1460  {
1461  if (!enable)
1462  {
1463  errorRegisterReadingScheduler.reset();
1464  }
1465  else
1466  {
1467  errorRegisterReadingScheduler = std::make_unique<SlaveRegisterReadingScheduler>(
1468  static_cast<std::uint16_t>(slaves.size()),
1469  periodInMS,
1470  std::vector<datatypes::RegisterEnum>{
1471  datatypes::RegisterEnum::LOST_LINK_COUNTER_PORT_0,
1472  datatypes::RegisterEnum::LOST_LINK_COUNTER_PORT_1,
1473  datatypes::RegisterEnum::FRAME_ERROR_COUNTER_PORT_0,
1474  datatypes::RegisterEnum::FRAME_ERROR_COUNTER_PORT_1,
1475  datatypes::RegisterEnum::PHYSICAL_ERROR_COUNTER_PORT_0,
1476  datatypes::RegisterEnum::PHYSICAL_ERROR_COUNTER_PORT_1,
1477  datatypes::RegisterEnum::PREVIOUS_ERROR_COUNTER_PORT_0,
1478  datatypes::RegisterEnum::PREVIOUS_ERROR_COUNTER_PORT_1});
1479  }
1480  }
1481 
1482  std::uint64_t
1484  {
1485  return iterationCount;
1486  }
1487 
1488 } // namespace armarx::control::ethercat
armarx::control::ethercat::Bus::switchBusToPreOp
bool switchBusToPreOp()
Definition: Bus.cpp:669
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:180
armarx::control::ethercat::BusErrorHandler::rtHandleSlaveErrors
void rtHandleSlaveErrors()
Definition: BusErrorHandler.cpp:44
SLAVE_WARNING
#define SLAVE_WARNING(sid,...)
Definition: ErrorReporting.h:303
armarx::control::ethercat::BusIO::rtUpdatePDO
void rtUpdatePDO()
Updates the PDO of all slaves.
Definition: BusIO.cpp:113
armarx::control::ethercat::Bus::setSocketFileDescriptor
void setSocketFileDescriptor(int socketFileDescriptor)
Definition: Bus.cpp:462
armarx::aron::ret
ReaderT::InputType T & ret
Definition: rw.h:21
armarx::control::ethercat::BusIO::changeStateOfBus
EtherCATState changeStateOfBus(EtherCATState state, bool validate=true)
Definition: BusIO.cpp:411
armarx::control::ethercat::BusErrorHandler::rtHandleBusErrors
void rtHandleBusErrors()
Definition: BusErrorHandler.cpp:37
ARMARX_IMPORTANT
#define ARMARX_IMPORTANT
Definition: Logging.h:183
armarx::control::ethercat::PDOValidity::None
@ None
armarx::control::ethercat::BusIO::ioMap
IOMap ioMap
Definition: BusIO.h:211
armarx::control::ethercat::EtherCATState
This class is a wrapper around an enum containing the different EtherCAT states.
Definition: EtherCATState.h:25
armarx::control::ethercat::Bus::configureErrorCountersReading
void configureErrorCountersReading(bool enable, unsigned int periodInMS)
configureErrorCountersReading configure stuff
Definition: Bus.cpp:1459
OnScopeExit.h
BUS_WARNING
#define BUS_WARNING(bin,...)
Definition: ErrorReporting.h:274
index
uint8_t index
Definition: EtherCATFrame.h:59
BUS_ERROR
#define BUS_ERROR(bin,...)
Definition: ErrorReporting.h:277
RtTiming.h
armarx::control::ethercat::BusFunctionalState
BusFunctionalState
Definition: Bus.h:40
ARMARX_CHECK_NOT_NULL
#define ARMARX_CHECK_NOT_NULL(ptr)
This macro evaluates whether ptr is not null and if it turns out to be false it will throw an Express...
Definition: ExpressionException.h:206
armarx::control::ethercat::ESIHandler::readESIBinaryBlob
std::optional< std::vector< std::byte > > readESIBinaryBlob(std::uint16_t slaveIndex, std::uint16_t startAddress, std::uint16_t endAddress) const
Definition: ESI.cpp:16
armarx::control::ethercat::Bus::rtGetEtherCATState
EtherCATState rtGetEtherCATState() const
Definition: Bus.cpp:1360
armarx::control::ethercat::Bus::logErrorsToFile
std::string logErrorsToFile(std::filesystem::path path, unsigned int lastSeconds)
Definition: Bus.cpp:36
armarx::control::ethercat::BusErrorHandler::init
void init(int wkc)
Definition: BusErrorHandler.cpp:94
IceStorm::Parser::parse
int parse(FILE *, bool)
armarx::control::ethercat::DeviceInterface::TryAssignResult::unknown
@ unknown
Used if the slave is unknown to this device. (Expected)
std::experimental::fundamentals_v2::make_observer
observer_ptr< _Tp > make_observer(_Tp *__p) noexcept
armarx::control::ethercat::BusIO::pdoAccessAvailable
bool pdoAccessAvailable
Definition: BusIO.h:203
armarx::control::ethercat::datatypes::RegisterEnum
RegisterEnum
The RegisterEnum enum encodes the slave registers that every slave offers.
Definition: SlaveRegisters.h:37
armarx::control::ethercat::datatypes::RegisterEnum::PREVIOUS_ERROR_COUNTER_PORT_0
@ PREVIOUS_ERROR_COUNTER_PORT_0
BUS_INFO
#define BUS_INFO(bin,...)
Definition: ErrorReporting.h:271
ARMARX_ON_SCOPE_EXIT
#define ARMARX_ON_SCOPE_EXIT
Executes given code when the enclosing scope is left.
Definition: OnScopeExit.h:112
armarx::control::ethercat::Bus::rtHasError
bool rtHasError() const
Definition: Bus.cpp:1444
message
message(STATUS "Boost-Library-Dir: " "${Boost_LIBRARY_DIRS}") message(STATUS "Boost-LIBRARIES
Definition: CMakeLists.txt:8
armarx::control::ethercat::BusFunctionalState::Reinitializing
@ Reinitializing
armarx::control::ethercat::Bus::switchBusToInit
bool switchBusToInit()
Definition: Bus.cpp:650
armarx::control::ethercat::SlaveRegisterReadingScheduler::updateRegisterDataFromEtherCATFrameList
static void updateRegisterDataFromEtherCATFrameList(const EtherCATFrameList *frameList, std::vector< RegisterDataList > *requestedRegisters)
Definition: SlaveRegisterReadingScheduler.cpp:38
armarx::control::ethercat::BusErrorHandler::hasError
bool hasError() const
Definition: BusErrorHandler.cpp:76
armarx::control::ethercat::reporting::Reporting::dumpToFile
std::optional< std::filesystem::path > dumpToFile(std::filesystem::path file, std::uint64_t lastNSeconds=1000000)
Definition: ErrorReporting.cpp:120
std::experimental::fundamentals_v2::observer_ptr
Definition: ManagedIceObject.h:53
armarx::control::ethercat::BusIO::readStates
EtherCATState readStates()
Definition: BusIO.cpp:419
armarx::MultiNodeRapidXMLReader
Definition: MultiNodeRapidXMLReader.h:34
armarx::control::ethercat::datatypes::RegisterEnum::LOST_LINK_COUNTER_PORT_2
@ LOST_LINK_COUNTER_PORT_2
armarx::control::ethercat::Bus::switchBusToSafeOp
bool switchBusToSafeOp()
Definition: Bus.cpp:689
Bus.h
armarx::control::ethercat::datatypes::RegisterEnum::PHYSICAL_ERROR_COUNTER_PORT_3
@ PHYSICAL_ERROR_COUNTER_PORT_3
armarx::control::ethercat::ESI_Header_StartAdress
constexpr std::uint16_t ESI_Header_StartAdress
Definition: ESI.h:35
armarx::control::ethercat::DeviceInterface::TryAssignResult::assigned
@ assigned
Used if the slave was adpoted by this device. (Expected)
ARMARX_TRACE
#define ARMARX_TRACE
Definition: trace.h:69
armarx::control::ethercat::Bus
Brief description of class Bus.
Definition: Bus.h:55
armarx::control::ethercat::datatypes::RegisterEnum::FRAME_ERROR_COUNTER_PORT_1
@ FRAME_ERROR_COUNTER_PORT_1
armarx::control::ethercat::DeviceInterface::AllAssignedResult::slavesMissing
@ slavesMissing
Used if slaves are missing. (Error)
armarx::control::ethercat::datatypes::RegisterEnum::LOST_LINK_COUNTER_PORT_1
@ LOST_LINK_COUNTER_PORT_1
BUS_ERROR_LOCAL
#define BUS_ERROR_LOCAL(reporter, bin,...)
Definition: ErrorReporting.h:286
armarx::control::ethercat::ESI_Header_EndAdress
constexpr std::uint16_t ESI_Header_EndAdress
Definition: ESI.h:36
armarx::control::hardware_config::HardwareConfig::checkAllItemsRead
bool checkAllItemsRead(std::vector< std::string > &errors) const
This method is called when the config is completely read form the HardwareConfig file.
Definition: HardwareConfig.cpp:42
DeviceInterface.h
armarx::control::ethercat::Bus::SlaveFactory
std::function< std::unique_ptr< SlaveInterface >(SlaveIdentifier sid)> SlaveFactory
Definition: Bus.h:130
armarx::control::ethercat::datatypes::RegisterEnumTypeContainer
std::variant< EtherCATDataType::INTEGER8, EtherCATDataType::INTEGER16, EtherCATDataType::INTEGER32, EtherCATDataType::INTEGER64, EtherCATDataType::UNSIGNED8, EtherCATDataType::UNSIGNED16, EtherCATDataType::UNSIGNED32, EtherCATDataType::UNSIGNED64 > RegisterEnumTypeContainer
Definition: SlaveRegisters.h:160
armarx::control::ethercat::Bus::setRobot
void setRobot(const VirtualRobot::RobotPtr &robot)
Definition: Bus.cpp:1453
armarx::control::ethercat::reporting::Reporting::getErrorReporting
static Reporting & getErrorReporting()
Definition: ErrorReporting.cpp:82
armarx::control::ethercat::datatypes::RegisterEnum::PREVIOUS_ERROR_COUNTER_PORT_2
@ PREVIOUS_ERROR_COUNTER_PORT_2
armarx::flush
const LogSender::manipulator flush
Definition: LogSender.h:251
armarx::control::ethercat::Bus::rtGetFunctionalState
BusFunctionalState rtGetFunctionalState() const
Definition: Bus.cpp:1366
data
uint8_t data[1]
Definition: EtherCATFrame.h:68
armarx::control::hardware_config::ConfigParser
Definition: ConfigParser.h:19
ARMARX_DEBUG
#define ARMARX_DEBUG
Definition: Logging.h:177
BUS_TIMING_CEND
#define BUS_TIMING_CEND(name, bin, thresholdMs)
Definition: Timing.h:181
DefaultRapidXmlReader.h
armarx::control::ethercat::PDOValidity
PDOValidity
Definition: Bus.h:33
armarx::control::ethercat
Definition: Bus.cpp:24
SLAVE_ERROR
#define SLAVE_ERROR(sid,...)
Definition: ErrorReporting.h:306
armarx::control::ethercat::EtherCATState::preOp
@ preOp
Pre-operational state.
Definition: EtherCATState.h:40
armarx::control::ethercat::reporting::Reporting::getErrorReporter
Reporter getErrorReporter()
Definition: ErrorReporting.cpp:89
armarx::control::ethercat::Bus::getBus
static Bus & getBus()
This returns the one and only Bus object.
Definition: Bus.cpp:29
armarx::control::ethercat::datatypes::RegisterEnum::PREVIOUS_ERROR_COUNTER_PORT_1
@ PREVIOUS_ERROR_COUNTER_PORT_1
armarx::control::ethercat::Bus::getSlaves
std::vector< std::experimental::observer_ptr< SlaveInterface > > getSlaves() const
Returns all identifiied slaves on the bus.
Definition: Bus.cpp:1392
armarx::control::ethercat::Bus::registerSlaveFactory
void registerSlaveFactory(const SlaveFactory &factory)
Definition: Bus.cpp:1372
armarx::control::ethercat::SlaveRegisterReadingScheduler::createEtherCATFrameListFromRegisterDataList
static EtherCATFrameList * createEtherCATFrameListFromRegisterDataList(const std::vector< RegisterDataList > *requestedRegisters)
Definition: SlaveRegisterReadingScheduler.cpp:20
SlaveInterface.h
armarx::control::ethercat::datatypes::RegisterEnum::LOST_LINK_COUNTER_PORT_3
@ LOST_LINK_COUNTER_PORT_3
ARMARX_ERROR
#define ARMARX_ERROR
Definition: Logging.h:189
SlaveErrorRegistersDevice.h
armarx::control::ethercat::DeviceInterface::TryAssignResult::alreadyAssigned
@ alreadyAssigned
Used if the slave was already adopted before. (Error)
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::to_string
const std::string & to_string(const std::string &s)
Definition: StringHelpers.h:40
Timing.h
armarx::Logging::getEffectiveLoggingLevel
MessageTypeT getEffectiveLoggingLevel() const
Definition: Logging.cpp:117
ErrorReporting.h
armarx::control::ethercat::datatypes::RegisterEnum::PHYSICAL_ERROR_COUNTER_PORT_0
@ PHYSICAL_ERROR_COUNTER_PORT_0
armarx::control::ethercat::EtherCATState::safeOp
@ safeOp
Safe-operational state.
Definition: EtherCATState.h:46
ExpressionException.h
armarx::control::ethercat::datatypes::RegisterEnum::FRAME_ERROR_COUNTER_PORT_2
@ FRAME_ERROR_COUNTER_PORT_2
armarx::control::ethercat::BusIO::sdoAccessAvailable
bool sdoAccessAvailable
Definition: BusIO.h:202
SlaveRegisterReadingScheduler.h
armarx::control::ethercat::DeviceInterface::AllAssignedResult::ok
@ ok
Used if assignments were successful. (Expected)
armarx::control::hardware_config::HardwareConfig::deviceConfigs
std::map< std::string, std::shared_ptr< DeviceConfig > > deviceConfigs
Definition: HardwareConfig.h:59
BUS_FATAL_AND_THROW
#define BUS_FATAL_AND_THROW(bin,...)
Definition: ErrorReporting.h:280
armarx::control::ethercat::BusFunctionalState::Running
@ Running
armarx::control::ethercat::BusErrorHandler::isReinitializationActive
bool isReinitializationActive() const
Definition: BusErrorHandler.cpp:82
IceStorm::parser
Parser * parser
Definition: Parser.cpp:33
armarx::control::ethercat::Bus::shutdown
void shutdown()
Shuts the bus down by executing the shutdown-hook for each slave and afterwards switch all slaves to ...
Definition: Bus.cpp:593
armarx::control::ethercat::DeviceInterface::AllAssignedResult
AllAssignedResult
Definition: DeviceInterface.h:107
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
armarx::control::ethercat::Bus::registerDeviceFactory
void registerDeviceFactory(const std::string &name, const DeviceFactory &factory)
Definition: Bus.cpp:1378
armarx::control::ethercat::BusFunctionalState::Shutdown
@ Shutdown
armarx::control::ethercat::PDOValidity::Both
@ Both
armarx::control::ethercat::EtherCATState::init
@ init
Initial state after switch a EtherCAT slave on.
Definition: EtherCATState.h:37
VAROUT
#define VAROUT(x)
Definition: StringHelpers.h:182
BUS_WARNING_LOCAL
#define BUS_WARNING_LOCAL(reporter, bin,...)
Definition: ErrorReporting.h:284
armarx::control::ethercat::Bus::switchBusToOp
bool switchBusToOp()
Definition: Bus.cpp:709
armarx::transform
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
Definition: algorithm.h:315
armarx::control::ethercat::Bus::setIfName
void setIfName(const std::string &ifname)
Definition: Bus.cpp:468
armarx::control::ethercat::datatypes::RegisterEnum::PHYSICAL_ERROR_COUNTER_PORT_1
@ PHYSICAL_ERROR_COUNTER_PORT_1
armarx::control::ethercat::Bus::getDevices
const std::vector< std::shared_ptr< DeviceInterface > > & getDevices() const
Returns all initialized devices.
Definition: Bus.cpp:1404
armarx::control::ethercat::Bus::getSlaveAtIndex
std::experimental::observer_ptr< SlaveInterface > getSlaveAtIndex(std::uint16_t slaveIndex) const
Definition: Bus.cpp:1414
armarx::control::ethercat::PDOValidity::OnlyInputs
@ OnlyInputs
SLAVE_ERROR_LOCAL
#define SLAVE_ERROR_LOCAL(reporter, sid,...)
Definition: ErrorReporting.h:315
RapidXmlReader.h
armarx::control::ethercat::BusErrorHandler::isSlaveLostOrDuringReinitialization
bool isSlaveLostOrDuringReinitialization(SlaveInterface *slave) const
Definition: BusErrorHandler.cpp:88
armarx::control::ethercat::Bus::DeviceFactory
std::function< std::shared_ptr< DeviceInterface >(hardware_config::DeviceConfig &config, const VirtualRobot::RobotPtr &robot)> DeviceFactory
Definition: Bus.h:136
armarx::control::ethercat::Bus::rtUpdateBus
bool rtUpdateBus(bool doErrorHandling=true, size_t iterationCount=0)
Updates all information on the bus, so all commands will be send to the Bus and all sensor and other ...
Definition: Bus.cpp:474
armarx::Logging::deactivateSpam
SpamFilterDataPtr deactivateSpam(float deactivationDurationSec=10.0f, const std::string &identifier="", bool deactivate=true) const
disables the logging for the current line for the given amount of seconds.
Definition: Logging.cpp:92
ControlThreadOutputBuffer.h
armarx::control::ethercat::DeviceInterface::TryAssignResult
TryAssignResult
Definition: DeviceInterface.h:86
armarx::Logging::setTag
void setTag(const LogTag &tag)
Definition: Logging.cpp:55
armarx::control::ethercat::Bus::setAndParseHardwareConfig
void setAndParseHardwareConfig(const MultiNodeRapidXMLReader &hwconfig)
Definition: Bus.cpp:1384
ARMARX_CHECK_EQUAL
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
Definition: ExpressionException.h:130
armarx::handleExceptions
void handleExceptions()
Definition: Exception.cpp:141
armarx::control::ethercat::EtherCATState::op
@ op
Operational state.
Definition: EtherCATState.h:49
BUS_TIMING_START
#define BUS_TIMING_START(name)
Definition: Timing.h:163
armarx::control::ethercat::Bus::rtIsEmergencyStopActive
bool rtIsEmergencyStopActive() const
Definition: Bus.cpp:1428
armarx::control::ethercat::Bus::getPDOValidity
PDOValidity getPDOValidity() const
Definition: Bus.cpp:644
armarx::control::ethercat::datatypes::RegisterEnum::PHYSICAL_ERROR_COUNTER_PORT_2
@ PHYSICAL_ERROR_COUNTER_PORT_2
armarx::control::ethercat::BusFunctionalState::EmergencyStop
@ EmergencyStop
armarx::control::ethercat::Bus::getIterationCount
std::uint64_t getIterationCount() const
Definition: Bus.cpp:1483
armarx::control::ethercat::datatypes::RegisterEnum::FRAME_ERROR_COUNTER_PORT_0
@ FRAME_ERROR_COUNTER_PORT_0
armarx::control::ethercat::datatypes::RegisterEnum::PREVIOUS_ERROR_COUNTER_PORT_3
@ PREVIOUS_ERROR_COUNTER_PORT_3
armarx::control::ethercat::datatypes::RegisterEnum::FRAME_ERROR_COUNTER_PORT_3
@ FRAME_ERROR_COUNTER_PORT_3
armarx::control::ethercat::BusIO::readRegisters
bool readRegisters(std::vector< RegisterDataList > &registerData)
Definition: BusIO.cpp:433
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18
armarx::control::ethercat::datatypes::RegisterEnum::LOST_LINK_COUNTER_PORT_0
@ LOST_LINK_COUNTER_PORT_0
armarx::rtNow
IceUtil::Time rtNow()
Definition: RtTiming.h:40