Go to the documentation of this file.
21 , pdoTypeEnum_(pdoTypeEnum)
30 pdo_info.rxPdoSize_ =
sizeof(RxPdo);
31 pdo_info.txPdoSize_ =
sizeof(TxPdoA);
32 pdo_info.moduleId_ = 0x00119800;
47 std::lock_guard<std::recursive_mutex> lock(
mutex_);
94 std::lock_guard<std::recursive_mutex> lock(
mutex_);
98 serialNumber =
static_cast<unsigned int>(serial_number);
99 ROS_DEBUG(
"[%s] Reading serial number: %u",
name_.c_str(), serialNumber);
105 std::lock_guard<std::recursive_mutex> lock(
mutex_);
109 samplingRate =
static_cast<int>(sampling_rate);
110 ROS_DEBUG(
"[%s] Force/Torque sampling rate: %d Hz",
name_.c_str(), samplingRate);
116 std::lock_guard<std::recursive_mutex> lock(
mutex_);
138 std::lock_guard<std::recursive_mutex> lock(
mutex_);
139 ROS_DEBUG(
"[%s] Setting acceleration filter: %u",
name_.c_str(), filter);
147 std::lock_guard<std::recursive_mutex> lock(
mutex_);
148 ROS_DEBUG(
"[%s] Setting angular rate filter: %u",
name_.c_str(), filter);
156 std::lock_guard<std::recursive_mutex> lock(
mutex_);
157 ROS_DEBUG(
"[%s] Setting acceleration range: %u",
name_.c_str(), range);
165 std::lock_guard<std::recursive_mutex> lock(
mutex_);
166 ROS_DEBUG(
"[%s] Setting angular rate range: %u",
name_.c_str(), range);
174 std::lock_guard<std::recursive_mutex> lock(
mutex_);
175 ROS_DEBUG_STREAM(
"[" <<
name_.c_str() <<
"] Setting Force/Torque offset: " << forceTorqueOffset << std::endl);
178 static_cast<float>(forceTorqueOffset(0, 0)));
180 static_cast<float>(forceTorqueOffset(1, 0)));
182 static_cast<float>(forceTorqueOffset(2, 0)));
184 static_cast<float>(forceTorqueOffset(3, 0)));
186 static_cast<float>(forceTorqueOffset(4, 0)));
188 static_cast<float>(forceTorqueOffset(5, 0)));
194 std::lock_guard<std::recursive_mutex> lock(
mutex_);
221 std::lock_guard<std::recursive_mutex> lock(
mutex_);
268 std::this_thread::sleep_for(std::chrono::milliseconds(500));
271 ROS_ERROR(
"[%s] Slave failed to switch to PREOP state",
name_.c_str());
296 std::bitset<8> status_bits(status);
298 bool has_error = status_bits[4];
315 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Working counter is too low, expected working counter is " +
327 stat.
add(
"EtherCAT Address", std::to_string(
address_));
329 stat.
add(
"Has Error", has_error ?
"Yes" :
"No");
330 std::stringstream al_status_code_stream;
331 al_status_code_stream <<
"0x" << std::setfill(
'0') << std::setw(8) << std::hex << al_status_code;
332 stat.
add(
"Error Code", al_status_code_stream.str());
355 std::bitset<32> bits(status_word.
getData());
360 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Errors in Data Flags");
364 stat.
summary(diagnostic_msgs::DiagnosticStatus::WARN,
"Errors in Data Flags");
368 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"No errors in Data Flags");
370 stat.
add(
"ADC Saturated", bits[0] ?
"Yes" :
"No");
371 stat.
add(
"ACC Saturated", bits[1] ?
"Yes" :
"No");
372 stat.
add(
"Gyroscope Saturated", bits[2] ?
"Yes" :
"No");
373 stat.
add(
"ADC is out of sync", bits[3] ?
"Yes" :
"No");
374 stat.
add(
"Sensing Range Exceeded", bits[4] ?
"Yes" :
"No");
375 stat.
add(
"High temperature in Rokubimini Sensor", bits[5] ?
"Yes" :
"No");
376 stat.
add(
"Supply voltage exceeds limits", bits[6] ?
"Yes" :
"No");
377 stat.
add(
"Reserved 1", bits[7] ?
"Yes" :
"No");
378 stat.
add(
"Reserved 2", bits[8] ?
"Yes" :
"No");
379 stat.
add(
"Reserved 3", bits[9] ?
"Yes" :
"No");
380 stat.
add(
"Reserved 4", bits[10] ?
"Yes" :
"No");
381 stat.
add(
"Reserved 5", bits[11] ?
"Yes" :
"No");
382 stat.
add(
"Reserved 6", bits[12] ?
"Yes" :
"No");
383 stat.
add(
"Reserved 7", bits[13] ?
"Yes" :
"No");
384 stat.
add(
"Reserved 8", bits[14] ?
"Yes" :
"No");
385 stat.
add(
"Reserved 9", bits[15] ?
"Yes" :
"No");
386 stat.
add(
"Reserved 10", bits[16] ?
"Yes" :
"No");
387 stat.
add(
"Reserved 11", bits[17] ?
"Yes" :
"No");
388 stat.
add(
"Reserved 12", bits[18] ?
"Yes" :
"No");
389 stat.
add(
"Reserved 13", bits[19] ?
"Yes" :
"No");
390 stat.
add(
"Reserved 14", bits[20] ?
"Yes" :
"No");
391 stat.
add(
"Reserved 15", bits[21] ?
"Yes" :
"No");
392 stat.
add(
"Reserved 16", bits[22] ?
"Yes" :
"No");
393 stat.
add(
"Reserved 17", bits[23] ?
"Yes" :
"No");
394 stat.
add(
"Reserved 18", bits[24] ?
"Yes" :
"No");
395 stat.
add(
"Reserved 19", bits[25] ?
"Yes" :
"No");
396 stat.
add(
"Reserved 20", bits[26] ?
"Yes" :
"No");
397 stat.
add(
"Reserved 21", bits[27] ?
"Yes" :
"No");
398 stat.
add(
"Reserved 22", bits[28] ?
"Yes" :
"No");
399 stat.
add(
"Reserved 23", bits[29] ?
"Yes" :
"No");
400 stat.
add(
"Reserved 24", bits[30] ?
"Yes" :
"No");
401 stat.
add(
"Reserved 25", bits[31] ?
"Yes" :
"No");
412 std::lock_guard<std::recursive_mutex> lock(
mutex_);
415 uint8_t retain_configuration = 0x01;
421 ROS_ERROR(
"[%s] Could not save configuration parameters on device. Status value is: %u",
name_.c_str(), status);
429 std::lock_guard<std::recursive_mutex> lock(
mutex_);
435 std::lock_guard<std::recursive_mutex> lock(
mutex_);
450 std::lock_guard<std::recursive_mutex> lock(
mutex_);
456 std::lock_guard<std::recursive_mutex> lock(
mutex_);
463 std::lock_guard<std::recursive_mutex> lock(
mutex_);
469 std::lock_guard<std::recursive_mutex> lock(
mutex_);
496 std::ifstream file(filePath, std::ios::binary);
497 std::string file_buffer;
501 while ((ch = file.get()) != std::istream::traits_type::eof())
503 file_buffer.push_back(
static_cast<char>(ch));
505 fileBuffer_ =
const_cast<char*
>(file_buffer.c_str());
506 fileSize_ =
static_cast<int>(file_buffer.size());
517 <<
"Failed to open file " << filePath);
521 <<
"The firmware was read successfully. Size of file buffer: " <<
fileSize_);
529 std::lock_guard<std::recursive_mutex> lock(
mutex_);
533 <<
"Could not read file in path " << filePath <<
".");
static constexpr double G_TO_METERS_PER_SECOND_SQUARED
bool configurePdo(const PdoTypeEnum pdoTypeEnum)
Configures a PDO in the Ethercat device.
bool runsAsync() const
Returns if the driver runs asynchronously.
void readTxPdo(const uint16_t slave, TxPdo &txPdo) const
bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration)
Sets a sensor configuration to the device.
bool writeFirmware(const uint16_t slave, const std::string &fileName, const uint32_t &password, const int fileSize, char *fileBuffer)
unsigned int fetchSerialNumber() const
Accessor for device serial number.
uint8_t getInertiaCompensationActive() const
#define ROS_ERROR_STREAM(args)
#define OD_SENSOR_FORCE_TORQUE_OFFSET_SID_6
void add(const std::string &key, const bool &b)
bool getForceTorqueSamplingRate(int &samplingRate)
Gets the force torque sampling rate of the device.
const std::string & getName() const
void updateConnectionStatus(diagnostic_updater::DiagnosticStatusWrapper &stat)
Fills the Device Connection Status (ROS diagnostics).
void writeRxPdo(const uint16_t slave, const RxPdo &rxPdo)
uint8_t getImuActive() const
bool hasErrorAccSaturated() const
void setStatusword(const Statusword &statusword)
void setForceTorqueSaturated(const bool isForceTorqueSaturated)
#define OD_SENSOR_FORCE_TORQUE_OFFSET_SID_3
uint16_t getALStatusCode()
Returns the AL Status Code of the slave.
#define OD_SENSOR_CONFIGURATION_SID_TEMPERATURE_COMPENSATION
uint8_t getOrientationEstimationActive() const
float estimatedOrientationW_
#define OD_SENSOR_FORCE_TORQUE_OFFSET_SID_5
#define OD_ACCELERATION_FILTER_ID
bool readFileToBuffer(const std::string &filePath)
Reads the contents of a file to an internal buffer.
#define OD_FORCE_TORQUE_FILTER_SID_FIR_DISABLE
Eigen::Matrix< double, 6, 6 > & getCalibrationMatrix()
void updateWrite() override
This method is called by the EthercatBusManager. Each device attached to the bus writes its data to t...
#define OD_FORCE_TORQUE_FILTER_SID_CHOP_ENABLE
#define OD_SENSOR_CONFIGURATION_SID_COORD_SYSTEM_CONFIGURATION
int getExpectedWorkingCounter(const uint16_t slave=0) const
#define OD_ACCELERATION_RANGE_ID
#define OD_TX_PDO_ID_VAL_A
RokubiminiEthercatSlave()=delete
Default constructor is deleted.
const uint32_t getPassPhrase() const
const Statusword & getStatusword() const
void createDataFlagsDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Creates the Data Flags Diagnostics status.
#define ROS_DEBUG_STREAM(args)
bool workingCounterIsOk() const
void updateRead() override
This method is called by the EthercatBusManager. Each device attached to this bus reads its data from...
#define OD_FORCE_TORQUE_FILTER_ID
std::recursive_mutex dataFlagsMutex_
Mutex prohibiting simultaneous access to the Data Flags structure.
bool setRunMode()
Sets the device in run mode.
TempType & getTemperature()
void shutdown() override
Shuts down the device.
#define OD_SENSOR_FORCE_TORQUE_OFFSET_SID_2
bool hasErrorSensingRangeExceeded() const
bool setForceTorqueFilter(const configuration::ForceTorqueFilter &filter)
Sets a force torque filter to the device.
PdoInfos pdoInfos_
Map between PDO types and their infos.
const std::string name_
Name of the sensor.
bool sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &value)
void setData(const uint32_t data)
#define OD_SENSOR_CONFIGURATION_SID_CALIBRATION_MATRIX_ACTIVE
bool startup() override
This method starts up and initializes the device.
void summary(const diagnostic_msgs::DiagnosticStatus &src)
float estimatedOrientationX_
#define OD_ANGULAR_RATE_FILTER_ID
#define OD_SAMPLING_RATE_ID
std::atomic< PdoTypeEnum > currentPdoTypeEnum_
Current PDO type.
std::string getName() const override
Accessor for device name.
std::recursive_mutex mutex_
char * fileBuffer_
The buffer to save the contents of the file.
bool setAccelerationRange(const unsigned int range)
Sets an acceleration range to the device.
bool isRunning()
Returns if the instance is running.
PdoInfo getCurrentPdoInfo() const override
Accessor for the current PDO info.
float estimatedOrientationZ_
const static std::map< uint8_t, std::string > STATE_TO_STRING
#define OD_SENSOR_CONFIGURATION_SID_IMU_ACTIVE
uint32_t warningsErrorsFatals_
bool hasFatalSupplyVoltage() const
float estimatedOrientationY_
bool setConfigMode()
Sets the device in config mode.
#define MAX_FILE_SIZE_FIRMWARE
#define OD_SENSOR_FORCE_TORQUE_OFFSET_ID
#define OD_SENSOR_CONFIGURATION_SID_INERTIA_COMPENSATION
#define OD_FORCE_TORQUE_FILTER_SID_FAST_ENABLE
bool setAngularRateRange(const unsigned int range)
Sets an angular rate range to the device.
uint8_t getCalibrationMatrixActive() const
bool waitForState(const uint16_t state)
Wait for an EtherCAT state machine state to be reached.
bool getSerialNumber(unsigned int &serialNumber) override
Accessor for device serial number.
PdoTypeEnum getCurrentPdoTypeEnum() const
Accessor for the current PDO type.
void setState(const uint16_t state, const uint16_t slave=0)
Statusword currentDataFlagsDiagnostics_
The current Data Flags Diagnostics (Data Status) which is updated when a new frame is published and i...
bool sendCalibrationMatrixEntry(const uint8_t subId, const double entry)
Sends a calibration matrix entry to device.
uint8_t getState()
Returns the EtherCAT State of the device.
Struct defining the Pdo characteristic.
uint16_t getSincFilterSize() const
bool hasErrorAdcSaturated() const
uint16_t getSlaveALStatusCode(uint16_t slave)
Returns the AL Status Code of a slave.
bool saveConfigParameter()
Saves the current configuration to the device.
static constexpr double DEG_TO_RAD
void updateDataFlags()
Updates the Data Flags variable currentDataFlagsDiagnostics_.
bool setSensorCalibration(const calibration::SensorCalibration &sensorCalibration)
Sets a sensor calibration to the device.
#define OD_SENSOR_CONFIGURATION_ID
bool setAccelerationFilter(const unsigned int filter)
Sets an acceleration filter to the device.
std::atomic< PdoTypeEnum > pdoTypeEnum_
#define OD_SENSOR_FORCE_TORQUE_OFFSET_SID_1
std::atomic< bool > isRunning_
Internal flag to indicate if the instance is running.
uint8_t getCoordinateSystemConfigurationActive() const
uint8_t getChopEnable() const
#define OD_CONTROL_SID_STATUS
void preSetupConfiguration()
Pre-setup configuration hook.
int fileSize_
The size of the file.
std::string getProductName() const
Gets the product name of the device.
uint8_t getSkipEnable() const
void resetDataFlags()
Resets the Data Flags variable currentDataFlagsDiagnostics_.
#define OD_CONTROL_SID_COMMAND
void setState(const uint16_t state)
Sets the desired EtherCAT state machine state of the device in the bus.
bool setAngularRateFilter(const unsigned int filter)
Sets an angular rate filter to the device.
bool hasErrorGyroSaturated() const
uint8_t getFastEnable() const
#define OD_ANGULAR_RATE_RANGE_ID
std::string getSlaveStateString(uint8_t state)
Returns the EtherCAT State of the device in a string.
uint8_t getSlaveState(uint16_t slave)
bool firmwareUpdate(const std::string &filePath, const std::string &fileName, const uint32_t &password)
Updates the firmware of the device.
#define OD_SENSOR_CALIBRATION_ID
Base class for generic ethercat slaves using soem.
bool hasErrorAdcOutOfSync() const
bool sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value)
Class for managing an ethercat bus containing one or multiple slaves.
void getReading(rokubimini::Reading &reading) const
Gets the internal reading variable.
const ros::Time & getUpdateReadStamp() const
Reading reading_
The internal reading variable. It's used for providing to client code the sensor readings,...
uint16_t forceTorqueSaturated_
#define OD_FORCE_TORQUE_FILTER_SID_SINC_SIZE
bool setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)
Sets a force torque offset to the device.
#define OD_IDENTITY_SID_SERIAL_NUMBER
uint8_t getTemperatureCompensationActive() const
#define OD_SENSOR_CONFIGURATION_SID_ORIENTATION_ESTIMATION
#define OD_RX_PDO_ID_VAL_A
bool waitForState(const uint16_t state, const uint16_t slave=0, const unsigned int maxRetries=40, const double retrySleep=0.001)
bool hasWarningOvertemperature() const
#define OD_SENSOR_FORCE_TORQUE_OFFSET_SID_4