The Rokubimini Ethercat Implementation (Slave) class. More...
#include <RokubiminiEthercatSlave.hpp>
Public Member Functions | |
void | createDataFlagsDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Creates the Data Flags Diagnostics status. More... | |
unsigned int | fetchSerialNumber () const |
Accessor for device serial number. More... | |
bool | firmwareUpdate (const std::string &filePath, const std::string &fileName, const uint32_t &password) |
Updates the firmware of the device. More... | |
PdoInfo | getCurrentPdoInfo () const override |
Accessor for the current PDO info. More... | |
PdoTypeEnum | getCurrentPdoTypeEnum () const |
Accessor for the current PDO type. More... | |
bool | getForceTorqueSamplingRate (int &samplingRate) |
Gets the force torque sampling rate of the device. More... | |
std::string | getName () const override |
Accessor for device name. More... | |
void | getReading (rokubimini::Reading &reading) const |
Gets the internal reading variable. More... | |
bool | getSerialNumber (unsigned int &serialNumber) override |
Accessor for device serial number. More... | |
bool | isRunning () |
Returns if the instance is running. More... | |
void | preSetupConfiguration () |
Pre-setup configuration hook. More... | |
void | resetDataFlags () |
Resets the Data Flags variable currentDataFlagsDiagnostics_ . More... | |
RokubiminiEthercatSlave ()=delete | |
Default constructor is deleted. More... | |
RokubiminiEthercatSlave (const std::string &name, rokubimini::soem_interface::EthercatBusBase *bus, const uint32_t address, const PdoTypeEnum pdoTypeEnum) | |
bool | runsAsync () const |
Returns if the driver runs asynchronously. More... | |
bool | saveConfigParameter () |
Saves the current configuration to the device. More... | |
bool | setAccelerationFilter (const unsigned int filter) |
Sets an acceleration filter to the device. More... | |
bool | setAccelerationRange (const unsigned int range) |
Sets an acceleration range to the device. More... | |
bool | setAngularRateFilter (const unsigned int filter) |
Sets an angular rate filter to the device. More... | |
bool | setAngularRateRange (const unsigned int range) |
Sets an angular rate range to the device. More... | |
bool | setConfigMode () |
Sets the device in config mode. More... | |
bool | setForceTorqueFilter (const configuration::ForceTorqueFilter &filter) |
Sets a force torque filter to the device. More... | |
bool | setForceTorqueOffset (const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset) |
Sets a force torque offset to the device. More... | |
bool | setRunMode () |
Sets the device in run mode. More... | |
void | setRunsAsync (bool runsAsync) |
Sets the runsAsync_ variable. More... | |
bool | setSensorCalibration (const calibration::SensorCalibration &sensorCalibration) |
Sets a sensor calibration to the device. More... | |
bool | setSensorConfiguration (const configuration::SensorConfiguration &sensorConfiguration) |
Sets a sensor configuration to the device. More... | |
void | setState (const uint16_t state) |
Sets the desired EtherCAT state machine state of the device in the bus. More... | |
void | shutdown () override |
Shuts down the device. More... | |
bool | startup () override |
This method starts up and initializes the device. More... | |
void | updateConnectionStatus (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Fills the Device Connection Status (ROS diagnostics). More... | |
void | updateDataFlags () |
Updates the Data Flags variable currentDataFlagsDiagnostics_ . More... | |
void | updateRead () override |
This method is called by the EthercatBusManager. Each device attached to this bus reads its data from the buffer. More... | |
void | updateWrite () override |
This method is called by the EthercatBusManager. Each device attached to the bus writes its data to the buffer. More... | |
bool | waitForState (const uint16_t state) |
Wait for an EtherCAT state machine state to be reached. More... | |
~RokubiminiEthercatSlave () override=default | |
![]() | |
EthercatSlaveBase (EthercatBusBase *bus, const uint32_t address) | |
uint32_t | getAddress () const |
Returns the bus address of the slave. More... | |
std::string | getProductName () const |
Gets the product name of the device. More... | |
template<typename Value > | |
bool | sendSdoRead (const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &value) |
virtual bool | sendSdoReadDouble (const uint16_t index, const uint8_t subindex, const bool completeAccess, double &value) |
virtual bool | sendSdoReadFloat (const uint16_t index, const uint8_t subindex, const bool completeAccess, float &value) |
virtual bool | sendSdoReadGeneric (const std::string &indexString, const std::string &subindexString, const std::string &valueTypeString, std::string &valueString) |
virtual bool | sendSdoReadInt16 (const uint16_t index, const uint8_t subindex, const bool completeAccess, int16_t &value) |
virtual bool | sendSdoReadInt32 (const uint16_t index, const uint8_t subindex, const bool completeAccess, int32_t &value) |
virtual bool | sendSdoReadInt64 (const uint16_t index, const uint8_t subindex, const bool completeAccess, int64_t &value) |
virtual bool | sendSdoReadInt8 (const uint16_t index, const uint8_t subindex, const bool completeAccess, int8_t &value) |
virtual bool | sendSdoReadUInt16 (const uint16_t index, const uint8_t subindex, const bool completeAccess, uint16_t &value) |
virtual bool | sendSdoReadUInt32 (const uint16_t index, const uint8_t subindex, const bool completeAccess, uint32_t &value) |
virtual bool | sendSdoReadUInt64 (const uint16_t index, const uint8_t subindex, const bool completeAccess, uint64_t &value) |
virtual bool | sendSdoReadUInt8 (const uint16_t index, const uint8_t subindex, const bool completeAccess, uint8_t &value) |
template<typename Value > | |
bool | sendSdoWrite (const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value) |
virtual bool | sendSdoWriteDouble (const uint16_t index, const uint8_t subindex, const bool completeAccess, const double value) |
virtual bool | sendSdoWriteFloat (const uint16_t index, const uint8_t subindex, const bool completeAccess, const float value) |
virtual bool | sendSdoWriteGeneric (const std::string &indexString, const std::string &subindexString, const std::string &valueTypeString, const std::string &valueString) |
virtual bool | sendSdoWriteInt16 (const uint16_t index, const uint8_t subindex, const bool completeAccess, const int16_t value) |
virtual bool | sendSdoWriteInt32 (const uint16_t index, const uint8_t subindex, const bool completeAccess, const int32_t value) |
virtual bool | sendSdoWriteInt64 (const uint16_t index, const uint8_t subindex, const bool completeAccess, const int64_t value) |
virtual bool | sendSdoWriteInt8 (const uint16_t index, const uint8_t subindex, const bool completeAccess, const int8_t value) |
virtual bool | sendSdoWriteUInt16 (const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint16_t value) |
virtual bool | sendSdoWriteUInt32 (const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint32_t value) |
virtual bool | sendSdoWriteUInt64 (const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint64_t value) |
virtual bool | sendSdoWriteUInt8 (const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint8_t value) |
void | setProductName (const std::string &productName) |
Sets the product name of the device. More... | |
bool | setSerialNumber (unsigned int &serialNumber) |
Accessor for device serial number. More... | |
virtual | ~EthercatSlaveBase ()=default |
Private Types | |
using | PdoInfos = std::map< PdoTypeEnum, PdoInfo > |
Private Member Functions | |
bool | configurePdo (const PdoTypeEnum pdoTypeEnum) |
Configures a PDO in the Ethercat device. More... | |
uint16_t | getALStatusCode () |
Returns the AL Status Code of the slave. More... | |
std::string | getSlaveStateString (uint8_t state) |
Returns the EtherCAT State of the device in a string. More... | |
uint8_t | getState () |
Returns the EtherCAT State of the device. More... | |
bool | readFileToBuffer (const std::string &filePath) |
Reads the contents of a file to an internal buffer. More... | |
bool | sendCalibrationMatrixEntry (const uint8_t subId, const double entry) |
Sends a calibration matrix entry to device. More... | |
Private Attributes | |
Statusword | currentDataFlagsDiagnostics_ |
The current Data Flags Diagnostics (Data Status) which is updated when a new frame is published and is published by the DataFlagsDiagnosticsPublisher. More... | |
std::atomic< PdoTypeEnum > | currentPdoTypeEnum_ |
Current PDO type. More... | |
std::recursive_mutex | dataFlagsMutex_ |
Mutex prohibiting simultaneous access to the Data Flags structure. More... | |
char * | fileBuffer_ |
The buffer to save the contents of the file. More... | |
int | fileSize_ |
The size of the file. More... | |
std::atomic< bool > | isRunning_ |
Internal flag to indicate if the instance is running. More... | |
const std::string | name_ |
Name of the sensor. More... | |
PdoInfos | pdoInfos_ |
Map between PDO types and their infos. More... | |
std::atomic< PdoTypeEnum > | pdoTypeEnum_ |
Reading | reading_ |
The internal reading variable. It's used for providing to client code the sensor readings, through the getReading () function. More... | |
std::atomic< bool > | runsAsync_ |
Additional Inherited Members | |
![]() | |
void | printWarnNotImplemented () |
Prints a warning. Use this method to suppress compiler warnings. More... | |
![]() | |
const uint32_t | address_ { 0 } |
EthercatBusBase * | bus_ |
std::recursive_mutex | mutex_ |
std::string | productName_ { "" } |
The product name of the slave. More... | |
unsigned int | serialNumber_ { 0 } |
The serial number of the device. More... | |
The Rokubimini Ethercat Implementation (Slave) class.
It's the implementation in the BRIDGE pattern used. It provides the implementation to be called by the interface (RokubiminiEthercat) in order to communicate with the EtherCAT Device.
Definition at line 37 of file RokubiminiEthercatSlave.hpp.
|
private |
Definition at line 516 of file RokubiminiEthercatSlave.hpp.
|
delete |
Default constructor is deleted.
rokubimini::ethercat::RokubiminiEthercatSlave::RokubiminiEthercatSlave | ( | const std::string & | name, |
rokubimini::soem_interface::EthercatBusBase * | bus, | ||
const uint32_t | address, | ||
const PdoTypeEnum | pdoTypeEnum | ||
) |
Definition at line 16 of file RokubiminiEthercatSlave.cpp.
|
overridedefault |
|
private |
Configures a PDO in the Ethercat device.
pdoTypeEnum | The type of the PDO. |
Definition at line 467 of file RokubiminiEthercatSlave.cpp.
void rokubimini::ethercat::RokubiminiEthercatSlave::createDataFlagsDiagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) |
Creates the Data Flags Diagnostics status.
stat | The status to be filled with the new diagnostics |
Definition at line 351 of file RokubiminiEthercatSlave.cpp.
|
inline |
Accessor for device serial number.
Definition at line 205 of file RokubiminiEthercatSlave.hpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::firmwareUpdate | ( | const std::string & | filePath, |
const std::string & | fileName, | ||
const uint32_t & | password | ||
) |
Updates the firmware of the device.
filePath | The path to find the firmware file |
fileName | The name of the file that will be written in the slave. |
password | The password for authorization. |
Definition at line 525 of file RokubiminiEthercatSlave.cpp.
|
private |
Returns the AL Status Code of the slave.
Definition at line 282 of file RokubiminiEthercatSlave.cpp.
|
overridevirtual |
Accessor for the current PDO info.
Implements rokubimini::soem_interface::EthercatSlaveBase.
Definition at line 460 of file RokubiminiEthercatSlave.cpp.
|
inline |
Accessor for the current PDO type.
Definition at line 178 of file RokubiminiEthercatSlave.hpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::getForceTorqueSamplingRate | ( | int & | samplingRate | ) |
Gets the force torque sampling rate of the device.
samplingRate | The force torque sampling rate to be fetched. |
Definition at line 103 of file RokubiminiEthercatSlave.cpp.
|
inlineoverridevirtual |
Accessor for device name.
Implements rokubimini::soem_interface::EthercatSlaveBase.
Definition at line 164 of file RokubiminiEthercatSlave.hpp.
void rokubimini::ethercat::RokubiminiEthercatSlave::getReading | ( | rokubimini::Reading & | reading | ) | const |
Gets the internal reading variable.
reading | The variable to store the reading. |
Definition at line 427 of file RokubiminiEthercatSlave.cpp.
|
overridevirtual |
Accessor for device serial number.
serialNumber | The serial number to get. |
Implements rokubimini::soem_interface::EthercatSlaveBase.
Definition at line 92 of file RokubiminiEthercatSlave.cpp.
|
private |
Returns the EtherCAT State of the device in a string.
state | The state to look up. |
Definition at line 287 of file RokubiminiEthercatSlave.cpp.
|
private |
Returns the EtherCAT State of the device.
Definition at line 277 of file RokubiminiEthercatSlave.cpp.
|
inline |
Returns if the instance is running.
Definition at line 386 of file RokubiminiEthercatSlave.hpp.
void rokubimini::ethercat::RokubiminiEthercatSlave::preSetupConfiguration | ( | ) |
Pre-setup configuration hook.
Definition at line 42 of file RokubiminiEthercatSlave.cpp.
|
private |
Reads the contents of a file to an internal buffer.
filePath | The path of the file. |
Definition at line 493 of file RokubiminiEthercatSlave.cpp.
void rokubimini::ethercat::RokubiminiEthercatSlave::resetDataFlags | ( | ) |
Resets the Data Flags variable currentDataFlagsDiagnostics_
.
Definition at line 345 of file RokubiminiEthercatSlave.cpp.
|
inline |
Returns if the driver runs asynchronously.
Definition at line 418 of file RokubiminiEthercatSlave.hpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::saveConfigParameter | ( | ) |
Saves the current configuration to the device.
Definition at line 410 of file RokubiminiEthercatSlave.cpp.
|
private |
Sends a calibration matrix entry to device.
subId | The sub-index of the SDO to write to. |
entry | The entry on the matrix. |
Definition at line 214 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::setAccelerationFilter | ( | const unsigned int | filter | ) |
Sets an acceleration filter to the device.
filter | The filter to be set. |
Definition at line 136 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::setAccelerationRange | ( | const unsigned int | range | ) |
Sets an acceleration range to the device.
range | The range to be set. |
Definition at line 154 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::setAngularRateFilter | ( | const unsigned int | filter | ) |
Sets an angular rate filter to the device.
filter | The filter to be set. |
Definition at line 145 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::setAngularRateRange | ( | const unsigned int | range | ) |
Sets an angular rate range to the device.
range | The range to be set. |
Definition at line 163 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::setConfigMode | ( | ) |
Sets the device in config mode.
Definition at line 264 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::setForceTorqueFilter | ( | const configuration::ForceTorqueFilter & | filter | ) |
Sets a force torque filter to the device.
filter | The filter to be set. |
Definition at line 114 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::setForceTorqueOffset | ( | const Eigen::Matrix< double, 6, 1 > & | forceTorqueOffset | ) |
Sets a force torque offset to the device.
forceTorqueOffset | The offset to be set. |
Definition at line 172 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::setRunMode | ( | ) |
Sets the device in run mode.
Definition at line 403 of file RokubiminiEthercatSlave.cpp.
|
inline |
Sets the runsAsync_ variable.
runsAsync | The variable to set. |
Definition at line 430 of file RokubiminiEthercatSlave.hpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::setSensorCalibration | ( | const calibration::SensorCalibration & | sensorCalibration | ) |
Sets a sensor calibration to the device.
sensorCalibration | The calibration to be set. |
Definition at line 219 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::setSensorConfiguration | ( | const configuration::SensorConfiguration & | sensorConfiguration | ) |
Sets a sensor configuration to the device.
sensorConfiguration | The configuration to be set. |
Definition at line 192 of file RokubiminiEthercatSlave.cpp.
void rokubimini::ethercat::RokubiminiEthercatSlave::setState | ( | const uint16_t | state | ) |
Sets the desired EtherCAT state machine state of the device in the bus.
state | Desired state. |
Definition at line 448 of file RokubiminiEthercatSlave.cpp.
|
overridevirtual |
Shuts down the device.
Implements rokubimini::soem_interface::EthercatSlaveBase.
Definition at line 442 of file RokubiminiEthercatSlave.cpp.
|
overridevirtual |
This method starts up and initializes the device.
Implements rokubimini::soem_interface::EthercatSlaveBase.
Definition at line 36 of file RokubiminiEthercatSlave.cpp.
void rokubimini::ethercat::RokubiminiEthercatSlave::updateConnectionStatus | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) |
Fills the Device Connection Status (ROS diagnostics).
stat | The status to be filled with the new diagnostics. |
Definition at line 292 of file RokubiminiEthercatSlave.cpp.
void rokubimini::ethercat::RokubiminiEthercatSlave::updateDataFlags | ( | ) |
Updates the Data Flags variable currentDataFlagsDiagnostics_
.
Definition at line 335 of file RokubiminiEthercatSlave.cpp.
|
overridevirtual |
This method is called by the EthercatBusManager. Each device attached to this bus reads its data from the buffer.
Implements rokubimini::soem_interface::EthercatSlaveBase.
Definition at line 45 of file RokubiminiEthercatSlave.cpp.
|
overridevirtual |
This method is called by the EthercatBusManager. Each device attached to the bus writes its data to the buffer.
Implements rokubimini::soem_interface::EthercatSlaveBase.
Definition at line 433 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::waitForState | ( | const uint16_t | state | ) |
Wait for an EtherCAT state machine state to be reached.
state | Desired state. |
Definition at line 454 of file RokubiminiEthercatSlave.cpp.
|
private |
The current Data Flags Diagnostics (Data Status) which is updated when a new frame is published and is published by the DataFlagsDiagnosticsPublisher.
Definition at line 603 of file RokubiminiEthercatSlave.hpp.
|
private |
Current PDO type.
Definition at line 551 of file RokubiminiEthercatSlave.hpp.
|
mutableprivate |
Mutex prohibiting simultaneous access to the Data Flags structure.
Definition at line 612 of file RokubiminiEthercatSlave.hpp.
|
private |
The buffer to save the contents of the file.
Definition at line 578 of file RokubiminiEthercatSlave.hpp.
|
private |
The size of the file.
Definition at line 570 of file RokubiminiEthercatSlave.hpp.
|
private |
Internal flag to indicate if the instance is running.
Internal flag to indicate if the instance is running asynchronously or not.
Definition at line 586 of file RokubiminiEthercatSlave.hpp.
|
private |
Name of the sensor.
Definition at line 525 of file RokubiminiEthercatSlave.hpp.
|
private |
Map between PDO types and their infos.
Definition at line 533 of file RokubiminiEthercatSlave.hpp.
|
private |
Definition at line 542 of file RokubiminiEthercatSlave.hpp.
|
private |
The internal reading variable. It's used for providing to client code the sensor readings, through the getReading () function.
Definition at line 562 of file RokubiminiEthercatSlave.hpp.
|
private |
Definition at line 594 of file RokubiminiEthercatSlave.hpp.