Go to the documentation of this file.
5 namespace soem_interface
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;
22 ecatContext_.FOEhook =
nullptr;
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() <<
").");
91 <<
"Bus is not available.");
98 <<
"No socket connection. Execute as root.");
115 <<
"No slaves have been found.");
126 bool slave_addresses_are_ok =
true;
129 auto address =
static_cast<int>(
slave->getAddress());
133 <<
"Slave '" <<
slave->getName() <<
"': Invalid address " << address <<
".");
134 slave_addresses_are_ok =
false;
139 <<
"Slave '" <<
slave->getName() <<
"': Invalid address " << address <<
", "
141 slave_addresses_are_ok =
false;
144 if (!slave_addresses_are_ok)
152 auto product_name =
slave->getProductName();
156 <<
"Slave '" <<
slave->getName() <<
"': Invalid product name '" << product_name
157 <<
"' given, didn't match the actual product name of the device: '"
168 if (!
slave->startup())
171 <<
"Slave '" <<
slave->getName() <<
"' was not initialized successfully.");
179 <<
"The following " <<
getNumberOfSlaves() <<
" slaves have been found and configured:");
180 unsigned int serial_number;
184 <<
"Address: " <<
slave->getAddress());
186 <<
"Name: '" <<
slave->getProductName() <<
"'");
187 slave->getSerialNumber(serial_number);
189 <<
"S/N: " << serial_number);
190 slave->setSerialNumber(serial_number);
197 bool io_map_is_ok =
true;
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 "
211 io_map_is_ok =
false;
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 "
220 io_map_is_ok =
false;
244 <<
"No process data to read.");
260 <<
"Update Read:" <<
this);
262 <<
"Working counter is too low: " <<
wkc_.load() <<
" < "
279 <<
"Sending new process data without reading the previous one.");
285 slave->updateWrite();
309 <<
"Closing socket ...");
312 std::this_thread::sleep_for(std::chrono::milliseconds(500));
326 const double retrySleep)
330 for (
unsigned int retry = 0; retry <= maxRetries; retry++)
355 std::stringstream stream;
356 stream <<
"Time: " << (
static_cast<double>(error.
Time.
sec) + (
static_cast<double>(error.
Time.
usec) / 1000000.0));
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
367 stream <<
" EMERGENCY slave: " << error.
Slave <<
" error: 0x" << std::setfill(
'0') << std::setw(4) << std::hex
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
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
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
388 stream <<
" MBX slave: " << error.
Slave <<
" error: 0x" << std::setfill(
'0') << std::setw(8) << std::hex
392 stream <<
" MBX slave: " << error.
Slave <<
" error: 0x" << std::setfill(
'0') << std::setw(8) << std::hex
393 <<
static_cast<unsigned>(error.
AbortCode);
404 ROS_INFO_STREAM(
" slave: " <<
slave <<
" alStatusCode: 0x" << std::setfill(
'0') << std::setw(8) << std::hex
421 <<
". Error string: " << error_str);
435 const double cycleShift)
438 <<
" distributed clock synchronization...");
441 static_cast<int32_t>(1e9 * cycleShift));
444 <<
" distributed clock synchronization.");
480 const int fileSize,
char* fileBuffer,
int timeout)
487 const int fileSize,
char* fileBuffer)
546 ROS_INFO(
"Writing file over ethercat (FOE)");
564 ROS_INFO(
"Flashing over EtherCAT was successful");
int ecx_send_processdata(ecx_contextt *context)
bool writeFirmware(const uint16_t slave, const std::string &fileName, const uint32_t &password, const int fileSize, char *fileBuffer)
int ecx_init(ecx_contextt *context, const char *ifname)
PACKED_END PACKED_BEGIN struct PACKED ec_sm ec_smt
#define ROS_ERROR_STREAM(args)
char * ec_mbxerror2string(uint16 errorcode)
const std::string & getName() const
int ecx_FOEwrite(ecx_contextt *context, uint16 slave, char *filename, uint32 password, int psize, void *p, int timeout)
uint16 ecx_statecheck(ecx_contextt *context, uint16 slave, uint16 reqstate, int timeout)
int ecx_writestate(ecx_contextt *context, uint16 slave)
bool startup(const bool sizeCheck=true)
PdoSizeMap getHardwarePdoSizes()
std::string getDeviceName(const uint16_t &slave) const
bool addSlave(const EthercatSlaveBasePtr &slave)
const unsigned int ecatConfigMaxRetries_
Maximal number of retries to configure the EtherCAT bus.
static void printAvailableBusses()
void ecx_close(ecx_contextt *context)
int getExpectedWorkingCounter(const uint16_t slave=0) const
bool busIsAvailable() const
char desc[EC_MAXLEN_ADAPTERNAME]
uint32 ecx_readeeprom(ecx_contextt *context, uint16 slave, uint16 eeproma, int timeout)
#define ROS_DEBUG_STREAM(args)
std::pair< uint16_t, uint16_t > PdoSizePair
bool workingCounterIsOk() const
#define ROS_WARN_STREAM(args)
int writeFile(const uint16_t slave, const std::string &fileName, const uint32_t &password, const int fileSize, char *fileBuffer, int timeout=EC_TIMEOUTSTATE *10)
void ecx_dcsync0(ecx_contextt *context, uint16 slave, boolean act, uint32 CyclTime, int32 CyclShift)
#define ROS_WARN_STREAM_THROTTLE(period, args)
int ecx_readstate(ecx_contextt *context)
void printALStatus(const uint16_t slave=0)
Prints application layer status.
std::atomic< int > wkc_
Working counter of the most recent PDO.
std::shared_ptr< EthercatSlaveBase > EthercatSlaveBasePtr
bool sentProcessData_
Bool indicating whether PDO data has been sent and not read yet.
std::unordered_map< std::string, PdoSizePair > PdoSizeMap
char * ec_soeerror2string(uint16 errorcode)
const char * ec_sdoerror2string(uint32 sdoerrorcode)
void setState(const uint16_t state, const uint16_t slave=0)
#define ROS_INFO_STREAM(args)
Struct defining the Pdo characteristic.
int ecx_receive_processdata(ecx_contextt *context, int timeout)
const double ecatConfigRetrySleep_
Time to sleep between the retries.
boolean ecx_poperror(ecx_contextt *context, ec_errort *Ec)
std::recursive_mutex contextMutex_
uint16_t getSlaveALStatusCode(uint16_t slave)
Returns the AL Status Code of a slave.
ec_adaptert * ec_find_adapters(void)
ros::Time updateReadStamp_
Time of the last successful PDO reading.
ecx_contextt ecatContext_
int ecx_config_map_group(ecx_contextt *context, void *pIOmap, uint8 group)
ec_slavet ecatSlavelist_[EC_MAXSLAVE]
std::string getErrorString(ec_errort error)
boolean ecx_iserror(ecx_contextt *context)
std::string name_
Name of the bus.
char * ec_ALstatuscode2string(uint16 ALstatuscode)
uint8_t getSlaveState(uint16_t slave)
std::vector< EthercatSlaveBasePtr > slaves_
List of slaves.
int ecx_FPWR(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout)
char name[EC_MAXLEN_ADAPTERNAME]
void syncDistributedClock0(const uint16_t slave, const bool activate, const double cycleTime, const double cycleShift)
int ecx_config_init(ecx_contextt *context, uint8 usetable)
bool isCorrectDeviceName(const uint16_t &slave, const std::string &deviceName) const
std::atomic< bool > isRunning_
Internal flag to indicate if the instance is running.
int getNumberOfSlaves() const
EC_ERR_TYPE_SDOINFO_ERROR
bool waitForState(const uint16_t state, const uint16_t slave=0, const unsigned int maxRetries=40, const double retrySleep=0.001)
ros::Time updateWriteStamp_
Time of the last successful PDO writing.
bool checkForSdoErrors(const uint16_t slave, const uint16_t index)