5 namespace soem_interface
28 while (adapter !=
nullptr)
30 if (name == std::string(adapter->
name))
34 adapter = adapter->
next;
43 while (adapter !=
nullptr)
46 adapter = adapter->
next;
63 for (
const auto& existing_slave :
slaves_)
65 if (slave->getAddress() == existing_slave->getAddress())
68 <<
"Slave '" << existing_slave->getName() <<
"' and slave '" << slave->getName()
69 <<
"' have identical addresses (" << slave->getAddress() <<
").");
74 slaves_.push_back(slave);
91 <<
"Bus is not available.");
98 <<
"No socket connection. Execute as root.");
115 <<
"No slaves have been found.");
127 <<
"The following " <<
getNumberOfSlaves() <<
" slaves have been found and configured:");
136 bool slave_addresses_are_ok =
true;
139 auto address =
static_cast<int>(
slave->getAddress());
143 <<
"Slave '" <<
slave->getName() <<
"': Invalid address " << address <<
".");
144 slave_addresses_are_ok =
false;
149 <<
"Slave '" <<
slave->getName() <<
"': Invalid address " << address <<
", " 151 slave_addresses_are_ok =
false;
154 if (!slave_addresses_are_ok)
163 for (
auto&
slave : slaves_)
165 if (!
slave->startup())
168 <<
"Slave '" <<
slave->getName() <<
"' was not initialized successfully.");
178 bool io_map_is_ok =
true;
182 for (
const auto&
slave : slaves_)
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 " 192 io_map_is_ok =
false;
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 " 201 io_map_is_ok =
false;
225 <<
"No process data to read.");
241 <<
"Update Read:" <<
this);
243 <<
"Working counter is too low: " <<
wkc_.load() <<
" < " 260 <<
"Sending new process data without reading the previous one.");
266 slave->updateWrite();
295 <<
"Closing socket ...");
308 ROS_DEBUG_STREAM(
"Slave " << slave <<
": State " << state <<
" has been set.");
312 const double retrySleep)
316 for (
unsigned int retry = 0; retry <= maxRetries; retry++)
320 ROS_DEBUG_STREAM(
"Slave " << slave <<
": State " << state <<
" has been reached.");
328 ROS_WARN_STREAM(
"Slave " << slave <<
": State " << state <<
" has not been reached.");
341 std::stringstream stream;
342 stream <<
"Time: " << (
static_cast<double>(error.
Time.
sec) + (static_cast<double>(error.
Time.
usec) / 1000000.0));
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
353 stream <<
" EMERGENCY slave: " << error.
Slave <<
" error: 0x" << std::setfill(
'0') << std::setw(4) << std::hex
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
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
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
374 stream <<
" MBX slave: " << error.
Slave <<
" error: 0x" << std::setfill(
'0') << std::setw(8) << std::hex
378 stream <<
" MBX slave: " << error.
Slave <<
" error: 0x" << std::setfill(
'0') << std::setw(8) << std::hex
379 <<
static_cast<unsigned>(error.
AbortCode);
390 ROS_INFO_STREAM(
" slave: " << slave <<
" alStatusCode: 0x" << std::setfill(
'0') << std::setw(8) << std::hex
404 if (error.
Slave == slave && error.
Index == index)
406 ROS_ERROR_STREAM(
"Error in index " << index << slave <<
"of slave " << slave
407 <<
". Error string: " << error_str);
421 const double cycleShift)
423 ROS_INFO_STREAM(
"Bus '" <<
name_ <<
"', slave " << slave <<
": " << (activate ?
"Activating" :
"Deactivating")
424 <<
" distributed clock synchronization...");
427 static_cast<int32_t>(1e9 * cycleShift));
429 ROS_INFO_STREAM(
"Bus '" <<
name_ <<
"', slave " << slave <<
": " << (activate ?
"Activated" :
"Deactivated")
430 <<
" distributed clock synchronization.");
451 const int fileSize,
char* fileBuffer,
int timeout)
458 const int fileSize,
char* fileBuffer)
517 ROS_INFO(
"Writing file over ethercat (FOE)");
520 int wkc =
writeFile(slave, fileName, password, fileSize, fileBuffer);
525 ROS_ERROR_STREAM(
"Writing file over EtherCAT failed (wkc = " << wkc <<
").");
535 ROS_INFO(
"Flashing over EtherCAT was successful");
int ecx_send_processdata(ecx_contextt *context)
char * ec_ALstatuscode2string(uint16 ALstatuscode)
void threadSleep(const double duration)
EC_ERR_TYPE_SDOINFO_ERROR
bool checkForSdoErrors(const uint16_t slave, const uint16_t index)
const std::string & getName() const
void syncDistributedClock0(const uint16_t slave, const bool activate, const double cycleTime, const double cycleShift)
char name[EC_MAXLEN_ADAPTERNAME]
void ecx_close(ecx_contextt *context)
bool addSlave(const EthercatSlaveBasePtr &slave)
uint16 ecx_statecheck(ecx_contextt *context, uint16 slave, uint16 reqstate, int timeout)
int(* FOEhook)(uint16 slave, int packetnumber, int datasize)
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)
bool writeFirmware(const uint16_t slave, const std::string &fileName, const uint32_t &password, const int fileSize, char *fileBuffer)
int(* txbuflength)[EC_MAXBUF]
int ecx_FPWR(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
bool startup(const bool sizeCheck=true)
char * ec_soeerror2string(uint16 errorcode)
uint32 ecx_readeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, int timeout)
char desc[EC_MAXLEN_ADAPTERNAME]
std::atomic< int > wkc_
Working counter of the most recent PDO.
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)
int writeFile(const uint16_t slave, const std::string &fileName, const uint32_t &password, const int fileSize, char *fileBuffer, int timeout=EC_TIMEOUTSTATE *10)
ec_slavet ecatSlavelist_[EC_MAXSLAVE]
void setState(const uint16_t state, const uint16_t slave=0)
int ecx_writestate(ecx_contextt *context, uint16 slave)
std::shared_ptr< EthercatSlaveBase > EthercatSlaveBasePtr
ec_bufT(* txbuf)[EC_MAXBUF]
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.
int ecx_config_map_group(ecx_contextt *context, void *pIOmap, uint8 group)
bool workingCounterIsOk() const
std::atomic< bool > isRunning_
Internal flag to indicate if the instance is running.
#define ROS_WARN_STREAM(args)
ecx_contextt ecatContext_
std::recursive_mutex contextMutex_
#define ROS_DEBUG_STREAM(args)
int getNumberOfSlaves() const
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)
#define ROS_WARN_STREAM_THROTTLE(rate, args)
boolean ecx_iserror(ecx_contextt *context)
bool busIsAvailable() const
ros::Time updateReadStamp_
Time of the last successful PDO reading.
ros::Time updateWriteStamp_
Time of the last successful PDO writing.
#define ROS_INFO_STREAM(args)
boolean ecx_poperror(ecx_contextt *context, ec_errort *Ec)
Struct defining the Pdo characteristic.
const char * ec_sdoerror2string(uint32 sdoerrorcode)
ec_adaptert * ec_find_adapters(void)
PdoSizeMap getHardwarePdoSizes()
void printALStatus(const uint16_t slave=0)
Prints application layer status.
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.
std::string name_
Name of the bus.
char * ec_mbxerror2string(uint16 errorcode)
static void printAvailableBusses()