Go to the documentation of this file.
16 #define MAX_FILE_SIZE_FIRMWARE (0x100000)
bool configurePdo(const PdoTypeEnum pdoTypeEnum)
Configures a PDO in the Ethercat device.
bool runsAsync() const
Returns if the driver runs asynchronously.
bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration)
Sets a sensor configuration to the device.
unsigned int fetchSerialNumber() const
Accessor for device serial number.
bool getForceTorqueSamplingRate(int &samplingRate)
Gets the force torque sampling rate of the device.
void updateConnectionStatus(diagnostic_updater::DiagnosticStatusWrapper &stat)
Fills the Device Connection Status (ROS diagnostics).
uint16_t getALStatusCode()
Returns the AL Status Code of the slave.
bool readFileToBuffer(const std::string &filePath)
Reads the contents of a file to an internal buffer.
void updateWrite() override
This method is called by the EthercatBusManager. Each device attached to the bus writes its data to t...
RokubiminiEthercatSlave()=delete
Default constructor is deleted.
void createDataFlagsDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Creates the Data Flags Diagnostics status.
void updateRead() override
This method is called by the EthercatBusManager. Each device attached to this bus reads its data from...
std::recursive_mutex dataFlagsMutex_
Mutex prohibiting simultaneous access to the Data Flags structure.
bool setRunMode()
Sets the device in run mode.
void shutdown() override
Shuts down the device.
unsigned int serialNumber_
The serial number of the device.
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 startup() override
This method starts up and initializes the device.
std::atomic< PdoTypeEnum > currentPdoTypeEnum_
Current PDO type.
std::string getName() const override
Accessor for device name.
char * fileBuffer_
The buffer to save the contents of the file.
bool setAccelerationRange(const unsigned int range)
Sets an acceleration range to the device.
PdoInfo getCurrentPdoInfo() const override
Accessor for the current PDO info.
~RokubiminiEthercatSlave() override=default
const static std::map< uint8_t, std::string > STATE_TO_STRING
bool setConfigMode()
Sets the device in config mode.
bool setAngularRateRange(const unsigned int range)
Sets an angular rate range to the device.
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.
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.
bool saveConfigParameter()
Saves the current configuration to the device.
void updateDataFlags()
Updates the Data Flags variable currentDataFlagsDiagnostics_.
std::shared_ptr< RokubiminiEthercatSlave > RokubiminiEthercatSlavePtr
bool setSensorCalibration(const calibration::SensorCalibration &sensorCalibration)
Sets a sensor calibration to the device.
bool setAccelerationFilter(const unsigned int filter)
Sets an acceleration filter to the device.
std::atomic< PdoTypeEnum > pdoTypeEnum_
std::atomic< bool > isRunning_
Internal flag to indicate if the instance is running.
void preSetupConfiguration()
Pre-setup configuration hook.
int fileSize_
The size of the file.
void resetDataFlags()
Resets the Data Flags variable currentDataFlagsDiagnostics_.
The Rokubimini Ethercat Implementation (Slave) class.
void setRunsAsync(bool runsAsync)
Sets the runsAsync_ variable.
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.
std::string getSlaveStateString(uint8_t state)
Returns the EtherCAT State of the device in a string.
bool firmwareUpdate(const std::string &filePath, const std::string &fileName, const uint32_t &password)
Updates the firmware of the device.
Base class for generic ethercat slaves using soem.
std::map< PdoTypeEnum, PdoInfo > PdoInfos
bool isRunning()
Returns if the instance is running.
Class for managing an ethercat bus containing one or multiple slaves.
void getReading(rokubimini::Reading &reading) const
Gets the internal reading variable.
Reading reading_
The internal reading variable. It's used for providing to client code the sensor readings,...
bool setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)
Sets a force torque offset to the device.
std::atomic< bool > runsAsync_