Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
rokubimini::ethercat::RokubiminiEthercatSlave Class Reference

The Rokubimini Ethercat Implementation (Slave) class. More...

#include <RokubiminiEthercatSlave.hpp>

Inheritance diagram for rokubimini::ethercat::RokubiminiEthercatSlave:
Inheritance graph
[legend]

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
 
- 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...
 
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< PdoTypeEnumcurrentPdoTypeEnum_
 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< PdoTypeEnumpdoTypeEnum_
 
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

- 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 }
 
EthercatBusBasebus_
 
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...
 

Detailed Description

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.

Member Typedef Documentation

◆ PdoInfos

Definition at line 516 of file RokubiminiEthercatSlave.hpp.

Constructor & Destructor Documentation

◆ RokubiminiEthercatSlave() [1/2]

rokubimini::ethercat::RokubiminiEthercatSlave::RokubiminiEthercatSlave ( )
delete

Default constructor is deleted.

◆ RokubiminiEthercatSlave() [2/2]

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.

◆ ~RokubiminiEthercatSlave()

rokubimini::ethercat::RokubiminiEthercatSlave::~RokubiminiEthercatSlave ( )
overridedefault

Member Function Documentation

◆ configurePdo()

bool rokubimini::ethercat::RokubiminiEthercatSlave::configurePdo ( const PdoTypeEnum  pdoTypeEnum)
private

Configures a PDO in the Ethercat device.

Parameters
pdoTypeEnumThe type of the PDO.
Returns
True if the PDO was configured successfully.

Definition at line 467 of file RokubiminiEthercatSlave.cpp.

◆ createDataFlagsDiagnostics()

void rokubimini::ethercat::RokubiminiEthercatSlave::createDataFlagsDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper stat)

Creates the Data Flags Diagnostics status.

Parameters
statThe status to be filled with the new diagnostics

Definition at line 351 of file RokubiminiEthercatSlave.cpp.

◆ fetchSerialNumber()

unsigned int rokubimini::ethercat::RokubiminiEthercatSlave::fetchSerialNumber ( ) const
inline

Accessor for device serial number.

Returns
The fetched serial number.

Definition at line 205 of file RokubiminiEthercatSlave.hpp.

◆ firmwareUpdate()

bool rokubimini::ethercat::RokubiminiEthercatSlave::firmwareUpdate ( const std::string &  filePath,
const std::string &  fileName,
const uint32_t password 
)

Updates the firmware of the device.

Parameters
filePathThe path to find the firmware file
fileNameThe name of the file that will be written in the slave.
passwordThe password for authorization.
Returns
True if the transfer (FoE) was successful.

Definition at line 525 of file RokubiminiEthercatSlave.cpp.

◆ getALStatusCode()

uint16_t rokubimini::ethercat::RokubiminiEthercatSlave::getALStatusCode ( )
private

Returns the AL Status Code of the slave.

Returns
The AL Status Code.

Definition at line 282 of file RokubiminiEthercatSlave.cpp.

◆ getCurrentPdoInfo()

RokubiminiEthercatSlave::PdoInfo rokubimini::ethercat::RokubiminiEthercatSlave::getCurrentPdoInfo ( ) const
overridevirtual

Accessor for the current PDO info.

Returns
The current PDO info.

Implements rokubimini::soem_interface::EthercatSlaveBase.

Definition at line 460 of file RokubiminiEthercatSlave.cpp.

◆ getCurrentPdoTypeEnum()

PdoTypeEnum rokubimini::ethercat::RokubiminiEthercatSlave::getCurrentPdoTypeEnum ( ) const
inline

Accessor for the current PDO type.

Returns
The current PDO type.

Definition at line 178 of file RokubiminiEthercatSlave.hpp.

◆ getForceTorqueSamplingRate()

bool rokubimini::ethercat::RokubiminiEthercatSlave::getForceTorqueSamplingRate ( int &  samplingRate)

Gets the force torque sampling rate of the device.

Parameters
samplingRateThe force torque sampling rate to be fetched.
Returns
True if the force torque sampling rate was successfully fetched.

Definition at line 103 of file RokubiminiEthercatSlave.cpp.

◆ getName()

std::string rokubimini::ethercat::RokubiminiEthercatSlave::getName ( ) const
inlineoverridevirtual

Accessor for device name.

Returns
The name of the device.

Implements rokubimini::soem_interface::EthercatSlaveBase.

Definition at line 164 of file RokubiminiEthercatSlave.hpp.

◆ getReading()

void rokubimini::ethercat::RokubiminiEthercatSlave::getReading ( rokubimini::Reading reading) const

Gets the internal reading variable.

Parameters
readingThe variable to store the reading.

Definition at line 427 of file RokubiminiEthercatSlave.cpp.

◆ getSerialNumber()

bool rokubimini::ethercat::RokubiminiEthercatSlave::getSerialNumber ( unsigned int &  serialNumber)
overridevirtual

Accessor for device serial number.

Parameters
serialNumberThe serial number to get.
Returns
True if the serial number could be successfully fetched.

Implements rokubimini::soem_interface::EthercatSlaveBase.

Definition at line 92 of file RokubiminiEthercatSlave.cpp.

◆ getSlaveStateString()

std::string rokubimini::ethercat::RokubiminiEthercatSlave::getSlaveStateString ( uint8_t  state)
private

Returns the EtherCAT State of the device in a string.

Parameters
stateThe state to look up.
Returns
A string containing the EtherCAT State.

Definition at line 287 of file RokubiminiEthercatSlave.cpp.

◆ getState()

uint8_t rokubimini::ethercat::RokubiminiEthercatSlave::getState ( )
private

Returns the EtherCAT State of the device.

Returns
The EtherCAT State.

Definition at line 277 of file RokubiminiEthercatSlave.cpp.

◆ isRunning()

bool rokubimini::ethercat::RokubiminiEthercatSlave::isRunning ( )
inline

Returns if the instance is running.

Returns
True if the instance is running.

Definition at line 386 of file RokubiminiEthercatSlave.hpp.

◆ preSetupConfiguration()

void rokubimini::ethercat::RokubiminiEthercatSlave::preSetupConfiguration ( )

Pre-setup configuration hook.

Definition at line 42 of file RokubiminiEthercatSlave.cpp.

◆ readFileToBuffer()

bool rokubimini::ethercat::RokubiminiEthercatSlave::readFileToBuffer ( const std::string &  filePath)
private

Reads the contents of a file to an internal buffer.

Parameters
filePathThe path of the file.
Returns
True if operation was successful.

Definition at line 493 of file RokubiminiEthercatSlave.cpp.

◆ resetDataFlags()

void rokubimini::ethercat::RokubiminiEthercatSlave::resetDataFlags ( )

Resets the Data Flags variable currentDataFlagsDiagnostics_.

Definition at line 345 of file RokubiminiEthercatSlave.cpp.

◆ runsAsync()

bool rokubimini::ethercat::RokubiminiEthercatSlave::runsAsync ( ) const
inline

Returns if the driver runs asynchronously.

Returns
True if there is.

Definition at line 418 of file RokubiminiEthercatSlave.hpp.

◆ saveConfigParameter()

bool rokubimini::ethercat::RokubiminiEthercatSlave::saveConfigParameter ( )

Saves the current configuration to the device.

Returns
True if the configuration was successfully saved in the device.

Definition at line 410 of file RokubiminiEthercatSlave.cpp.

◆ sendCalibrationMatrixEntry()

bool rokubimini::ethercat::RokubiminiEthercatSlave::sendCalibrationMatrixEntry ( const uint8_t  subId,
const double  entry 
)
private

Sends a calibration matrix entry to device.

Parameters
subIdThe sub-index of the SDO to write to.
entryThe entry on the matrix.
Returns
True if the operation was successful.

Definition at line 214 of file RokubiminiEthercatSlave.cpp.

◆ setAccelerationFilter()

bool rokubimini::ethercat::RokubiminiEthercatSlave::setAccelerationFilter ( const unsigned int  filter)

Sets an acceleration filter to the device.

Parameters
filterThe filter to be set.
Returns
True if the acceleration torque filter was successfully set.

Definition at line 136 of file RokubiminiEthercatSlave.cpp.

◆ setAccelerationRange()

bool rokubimini::ethercat::RokubiminiEthercatSlave::setAccelerationRange ( const unsigned int  range)

Sets an acceleration range to the device.

Parameters
rangeThe range to be set.
Returns
True if the acceleration range was successfully set.

Definition at line 154 of file RokubiminiEthercatSlave.cpp.

◆ setAngularRateFilter()

bool rokubimini::ethercat::RokubiminiEthercatSlave::setAngularRateFilter ( const unsigned int  filter)

Sets an angular rate filter to the device.

Parameters
filterThe filter to be set.
Returns
True if the angular rate filter was successfully set.

Definition at line 145 of file RokubiminiEthercatSlave.cpp.

◆ setAngularRateRange()

bool rokubimini::ethercat::RokubiminiEthercatSlave::setAngularRateRange ( const unsigned int  range)

Sets an angular rate range to the device.

Parameters
rangeThe range to be set.
Returns
True if the angular rate range was successfully set.

Definition at line 163 of file RokubiminiEthercatSlave.cpp.

◆ setConfigMode()

bool rokubimini::ethercat::RokubiminiEthercatSlave::setConfigMode ( )

Sets the device in config mode.

Returns
True if the operation was successful.

Definition at line 264 of file RokubiminiEthercatSlave.cpp.

◆ setForceTorqueFilter()

bool rokubimini::ethercat::RokubiminiEthercatSlave::setForceTorqueFilter ( const configuration::ForceTorqueFilter filter)

Sets a force torque filter to the device.

Parameters
filterThe filter to be set.
Returns
True if the force torque filter was successfully set.

Definition at line 114 of file RokubiminiEthercatSlave.cpp.

◆ setForceTorqueOffset()

bool rokubimini::ethercat::RokubiminiEthercatSlave::setForceTorqueOffset ( const Eigen::Matrix< double, 6, 1 > &  forceTorqueOffset)

Sets a force torque offset to the device.

Parameters
forceTorqueOffsetThe offset to be set.
Returns
True if the offset was successfully set.

Definition at line 172 of file RokubiminiEthercatSlave.cpp.

◆ setRunMode()

bool rokubimini::ethercat::RokubiminiEthercatSlave::setRunMode ( )

Sets the device in run mode.

Returns
True if the operation was successful.

Definition at line 403 of file RokubiminiEthercatSlave.cpp.

◆ setRunsAsync()

void rokubimini::ethercat::RokubiminiEthercatSlave::setRunsAsync ( bool  runsAsync)
inline

Sets the runsAsync_ variable.

Parameters
runsAsyncThe variable to set.

Definition at line 430 of file RokubiminiEthercatSlave.hpp.

◆ setSensorCalibration()

bool rokubimini::ethercat::RokubiminiEthercatSlave::setSensorCalibration ( const calibration::SensorCalibration sensorCalibration)

Sets a sensor calibration to the device.

Parameters
sensorCalibrationThe calibration to be set.
Returns
True if the calibration was successfully set.

Definition at line 219 of file RokubiminiEthercatSlave.cpp.

◆ setSensorConfiguration()

bool rokubimini::ethercat::RokubiminiEthercatSlave::setSensorConfiguration ( const configuration::SensorConfiguration sensorConfiguration)

Sets a sensor configuration to the device.

Parameters
sensorConfigurationThe configuration to be set.
Returns
True if the configuration was successfully set.

Definition at line 192 of file RokubiminiEthercatSlave.cpp.

◆ setState()

void rokubimini::ethercat::RokubiminiEthercatSlave::setState ( const uint16_t  state)

Sets the desired EtherCAT state machine state of the device in the bus.

Parameters
stateDesired state.

Definition at line 448 of file RokubiminiEthercatSlave.cpp.

◆ shutdown()

void rokubimini::ethercat::RokubiminiEthercatSlave::shutdown ( )
overridevirtual

Shuts down the device.

Implements rokubimini::soem_interface::EthercatSlaveBase.

Definition at line 442 of file RokubiminiEthercatSlave.cpp.

◆ startup()

bool rokubimini::ethercat::RokubiminiEthercatSlave::startup ( )
overridevirtual

This method starts up and initializes the device.

Returns
True if the startup was successful.

Implements rokubimini::soem_interface::EthercatSlaveBase.

Definition at line 36 of file RokubiminiEthercatSlave.cpp.

◆ updateConnectionStatus()

void rokubimini::ethercat::RokubiminiEthercatSlave::updateConnectionStatus ( diagnostic_updater::DiagnosticStatusWrapper stat)

Fills the Device Connection Status (ROS diagnostics).

Parameters
statThe status to be filled with the new diagnostics.

Definition at line 292 of file RokubiminiEthercatSlave.cpp.

◆ updateDataFlags()

void rokubimini::ethercat::RokubiminiEthercatSlave::updateDataFlags ( )

Updates the Data Flags variable currentDataFlagsDiagnostics_.

Definition at line 335 of file RokubiminiEthercatSlave.cpp.

◆ updateRead()

void rokubimini::ethercat::RokubiminiEthercatSlave::updateRead ( )
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.

◆ updateWrite()

void rokubimini::ethercat::RokubiminiEthercatSlave::updateWrite ( )
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.

◆ waitForState()

bool rokubimini::ethercat::RokubiminiEthercatSlave::waitForState ( const uint16_t  state)

Wait for an EtherCAT state machine state to be reached.

Parameters
stateDesired state.
Returns
True if the state has been reached within the timeout.

Definition at line 454 of file RokubiminiEthercatSlave.cpp.

Member Data Documentation

◆ currentDataFlagsDiagnostics_

Statusword rokubimini::ethercat::RokubiminiEthercatSlave::currentDataFlagsDiagnostics_
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.

◆ currentPdoTypeEnum_

std::atomic< PdoTypeEnum > rokubimini::ethercat::RokubiminiEthercatSlave::currentPdoTypeEnum_
private

Current PDO type.

Definition at line 551 of file RokubiminiEthercatSlave.hpp.

◆ dataFlagsMutex_

std::recursive_mutex rokubimini::ethercat::RokubiminiEthercatSlave::dataFlagsMutex_
mutableprivate

Mutex prohibiting simultaneous access to the Data Flags structure.

Definition at line 612 of file RokubiminiEthercatSlave.hpp.

◆ fileBuffer_

char * rokubimini::ethercat::RokubiminiEthercatSlave::fileBuffer_
private

The buffer to save the contents of the file.

Definition at line 578 of file RokubiminiEthercatSlave.hpp.

◆ fileSize_

int rokubimini::ethercat::RokubiminiEthercatSlave::fileSize_
private

The size of the file.

Definition at line 570 of file RokubiminiEthercatSlave.hpp.

◆ isRunning_

std::atomic< bool > rokubimini::ethercat::RokubiminiEthercatSlave::isRunning_
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.

◆ name_

std::string rokubimini::ethercat::RokubiminiEthercatSlave::name_
private

Name of the sensor.

Definition at line 525 of file RokubiminiEthercatSlave.hpp.

◆ pdoInfos_

PdoInfos rokubimini::ethercat::RokubiminiEthercatSlave::pdoInfos_
private

Map between PDO types and their infos.

Definition at line 533 of file RokubiminiEthercatSlave.hpp.

◆ pdoTypeEnum_

std::atomic<PdoTypeEnum> rokubimini::ethercat::RokubiminiEthercatSlave::pdoTypeEnum_
private

Definition at line 542 of file RokubiminiEthercatSlave.hpp.

◆ reading_

Reading rokubimini::ethercat::RokubiminiEthercatSlave::reading_
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.

◆ runsAsync_

std::atomic<bool> rokubimini::ethercat::RokubiminiEthercatSlave::runsAsync_
private

Definition at line 594 of file RokubiminiEthercatSlave.hpp.


The documentation for this class was generated from the following files:


rokubimini_ethercat
Author(s):
autogenerated on Sat Apr 15 2023 02:53:56