The Rokubimini Ethercat Implementation (Slave) class. More...
#include <RokubiminiEthercatSlave.hpp>
Public Member Functions | |
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) |
Accessor for device serial number. More... | |
bool | isRunning () |
Returns if the instance is running. 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 | 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... | |
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 | 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 | |
Public Member Functions inherited from rokubimini::soem_interface::EthercatSlaveBase | |
EthercatSlaveBase (EthercatBusBase *bus, const uint32_t address) | |
uint32_t | getAddress () const |
Returns the bus address of the slave. 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) |
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... | |
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 | |
std::atomic< PdoTypeEnum > | currentPdoTypeEnum_ |
Current PDO type. 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... | |
Additional Inherited Members | |
Protected Member Functions inherited from rokubimini::soem_interface::EthercatSlaveBase | |
void | printWarnNotImplemented () |
Prints a warning. Use this method to suppress compiler warnings. More... | |
Protected Attributes inherited from rokubimini::soem_interface::EthercatSlaveBase | |
const uint32_t | address_ { 0 } |
EthercatBusBase * | bus_ |
std::recursive_mutex | mutex_ |
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 31 of file RokubiminiEthercatSlave.hpp.
|
private |
Definition at line 400 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 335 of file RokubiminiEthercatSlave.cpp.
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 393 of file RokubiminiEthercatSlave.cpp.
|
overridevirtual |
Accessor for the current PDO info.
Implements rokubimini::soem_interface::EthercatSlaveBase.
Definition at line 328 of file RokubiminiEthercatSlave.cpp.
|
inline |
Accessor for the current PDO type.
Definition at line 163 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 99 of file RokubiminiEthercatSlave.cpp.
|
inlineoverridevirtual |
Accessor for device name.
Implements rokubimini::soem_interface::EthercatSlaveBase.
Definition at line 149 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 297 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::getSerialNumber | ( | unsigned int & | serialNumber | ) |
Accessor for device serial number.
serialNumber | The serial number to get. |
Definition at line 88 of file RokubiminiEthercatSlave.cpp.
|
inline |
Returns if the instance is running.
Definition at line 359 of file RokubiminiEthercatSlave.hpp.
|
private |
Reads the contents of a file to an internal buffer.
filePath | The path of the file. |
Definition at line 361 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::saveConfigParameter | ( | ) |
Saves the current configuration to the device.
Definition at line 280 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 210 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 132 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 150 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 141 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 159 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::setConfigMode | ( | ) |
Sets the device in config mode.
Definition at line 260 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 110 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 168 of file RokubiminiEthercatSlave.cpp.
bool rokubimini::ethercat::RokubiminiEthercatSlave::setRunMode | ( | ) |
Sets the device in run mode.
Definition at line 273 of file RokubiminiEthercatSlave.cpp.
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 215 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 188 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 316 of file RokubiminiEthercatSlave.cpp.
|
overridevirtual |
Shuts down the device.
Implements rokubimini::soem_interface::EthercatSlaveBase.
Definition at line 312 of file RokubiminiEthercatSlave.cpp.
|
overridevirtual |
This method starts up and initializes the device.
Implements rokubimini::soem_interface::EthercatSlaveBase.
Definition at line 35 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 41 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 303 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 322 of file RokubiminiEthercatSlave.cpp.
|
private |
Current PDO type.
Definition at line 435 of file RokubiminiEthercatSlave.hpp.
|
private |
The buffer to save the contents of the file.
Definition at line 462 of file RokubiminiEthercatSlave.hpp.
|
private |
The size of the file.
Definition at line 454 of file RokubiminiEthercatSlave.hpp.
|
private |
Internal flag to indicate if the instance is running.
Definition at line 470 of file RokubiminiEthercatSlave.hpp.
|
private |
Name of the sensor.
Definition at line 409 of file RokubiminiEthercatSlave.hpp.
|
private |
Map between PDO types and their infos.
Definition at line 417 of file RokubiminiEthercatSlave.hpp.
|
private |
Definition at line 426 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 446 of file RokubiminiEthercatSlave.hpp.