Classes | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
rokubimini::soem_interface::EthercatSlaveBase Class Referenceabstract

Base class for generic ethercat slaves using soem. More...

#include <EthercatSlaveBase.hpp>

Inheritance diagram for rokubimini::soem_interface::EthercatSlaveBase:
Inheritance graph
[legend]

Classes

struct  PdoInfo
 Struct defining the Pdo characteristic. More...
 

Public Member Functions

 EthercatSlaveBase (EthercatBusBase *bus, const uint32_t address)
 
uint32_t getAddress () const
 Returns the bus address of the slave. More...
 
virtual PdoInfo getCurrentPdoInfo () const =0
 Gets the current pdo information. More...
 
virtual std::string getName () const =0
 Returns the name of the slave. More...
 
std::string getProductName () const
 Gets the product name of the device. More...
 
virtual bool getSerialNumber (unsigned int &serialNumber)=0
 Accessor for device serial number. It's abstract because it's implementation specific. 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 void shutdown ()=0
 Used to shutdown slave specific objects. More...
 
virtual bool startup ()=0
 Startup non-ethercat specific objects for the slave. More...
 
virtual void updateRead ()=0
 Called during reading the ethercat bus. Use this method to extract readings from the ethercat bus buffer. More...
 
virtual void updateWrite ()=0
 Called during writing to the ethercat bus. Use this method to stage a command for the slave. More...
 
virtual ~EthercatSlaveBase ()=default
 

Protected Member Functions

void printWarnNotImplemented ()
 Prints a warning. Use this method to suppress compiler warnings. More...
 

Protected Attributes

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

Base class for generic ethercat slaves using soem.

Definition at line 19 of file EthercatSlaveBase.hpp.

Constructor & Destructor Documentation

◆ EthercatSlaveBase()

rokubimini::soem_interface::EthercatSlaveBase::EthercatSlaveBase ( EthercatBusBase bus,
const uint32_t  address 
)

Definition at line 9 of file EthercatSlaveBase.cpp.

◆ ~EthercatSlaveBase()

virtual rokubimini::soem_interface::EthercatSlaveBase::~EthercatSlaveBase ( )
virtualdefault

Member Function Documentation

◆ getAddress()

uint32_t rokubimini::soem_interface::EthercatSlaveBase::getAddress ( ) const
inline

Returns the bus address of the slave.

Returns
Bus address.

Definition at line 85 of file EthercatSlaveBase.hpp.

◆ getCurrentPdoInfo()

virtual PdoInfo rokubimini::soem_interface::EthercatSlaveBase::getCurrentPdoInfo ( ) const
pure virtual

Gets the current pdo information.

Returns
The current pdo information.

Implemented in rokubimini::ethercat::RokubiminiEthercatSlave.

◆ getName()

virtual std::string rokubimini::soem_interface::EthercatSlaveBase::getName ( ) const
pure virtual

Returns the name of the slave.

Returns
Name of the ethercat bus

Implemented in rokubimini::ethercat::RokubiminiEthercatSlave.

◆ getProductName()

std::string rokubimini::soem_interface::EthercatSlaveBase::getProductName ( ) const
inline

Gets the product name of the device.

Returns
The product name.

Definition at line 97 of file EthercatSlaveBase.hpp.

◆ getSerialNumber()

bool rokubimini::soem_interface::EthercatSlaveBase::getSerialNumber ( unsigned int &  serialNumber)
pure virtual

Accessor for device serial number. It's abstract because it's implementation specific.

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

Implemented in rokubimini::ethercat::RokubiminiEthercatSlave.

◆ printWarnNotImplemented()

void rokubimini::soem_interface::EthercatSlaveBase::printWarnNotImplemented ( )
inlineprotected

Prints a warning. Use this method to suppress compiler warnings.

Definition at line 288 of file EthercatSlaveBase.hpp.

◆ sendSdoRead()

template<typename Value >
template bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoRead< double > ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
Value &  value 
)

Send a reading SDO.

Parameters
indexIndex of the SDO.
subindexSub-index of the SDO.
completeAccessAccess all sub-inidices at once.
valueReturn argument, will contain the value which was read.
Returns
True if successful.

Definition at line 24 of file EthercatSlaveBase.cpp.

◆ sendSdoReadDouble()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoReadDouble ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
double &  value 
)
inlinevirtual

Definition at line 214 of file EthercatSlaveBase.hpp.

◆ sendSdoReadFloat()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoReadFloat ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
float &  value 
)
inlinevirtual

Definition at line 209 of file EthercatSlaveBase.hpp.

◆ sendSdoReadGeneric()

bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoReadGeneric ( const std::string &  indexString,
const std::string &  subindexString,
const std::string &  valueTypeString,
std::string &  valueString 
)
virtual

Definition at line 74 of file EthercatSlaveBase.cpp.

◆ sendSdoReadInt16()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoReadInt16 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
int16_t value 
)
inlinevirtual

Definition at line 171 of file EthercatSlaveBase.hpp.

◆ sendSdoReadInt32()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoReadInt32 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
int32_t value 
)
inlinevirtual

Definition at line 176 of file EthercatSlaveBase.hpp.

◆ sendSdoReadInt64()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoReadInt64 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
int64_t value 
)
inlinevirtual

Definition at line 181 of file EthercatSlaveBase.hpp.

◆ sendSdoReadInt8()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoReadInt8 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
int8_t value 
)
inlinevirtual

Definition at line 166 of file EthercatSlaveBase.hpp.

◆ sendSdoReadUInt16()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoReadUInt16 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
uint16_t value 
)
inlinevirtual

Definition at line 191 of file EthercatSlaveBase.hpp.

◆ sendSdoReadUInt32()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoReadUInt32 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
uint32_t value 
)
inlinevirtual

Definition at line 197 of file EthercatSlaveBase.hpp.

◆ sendSdoReadUInt64()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoReadUInt64 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
uint64_t value 
)
inlinevirtual

Definition at line 203 of file EthercatSlaveBase.hpp.

◆ sendSdoReadUInt8()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoReadUInt8 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
uint8_t value 
)
inlinevirtual

Definition at line 186 of file EthercatSlaveBase.hpp.

◆ sendSdoWrite()

template<typename Value >
template bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoWrite< double > ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const Value  value 
)

Send a writing SDO.

Parameters
indexIndex of the SDO.
subindexSub-index of the SDO.
completeAccessAccess all sub-inidices at once.
valueValue to write.
Returns
True if successful.

Definition at line 15 of file EthercatSlaveBase.cpp.

◆ sendSdoWriteDouble()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoWriteDouble ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const double  value 
)
inlinevirtual

Definition at line 273 of file EthercatSlaveBase.hpp.

◆ sendSdoWriteFloat()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoWriteFloat ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const float  value 
)
inlinevirtual

Definition at line 267 of file EthercatSlaveBase.hpp.

◆ sendSdoWriteGeneric()

bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoWriteGeneric ( const std::string &  indexString,
const std::string &  subindexString,
const std::string &  valueTypeString,
const std::string &  valueString 
)
virtual

Definition at line 81 of file EthercatSlaveBase.cpp.

◆ sendSdoWriteInt16()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoWriteInt16 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const int16_t  value 
)
inlinevirtual

Definition at line 225 of file EthercatSlaveBase.hpp.

◆ sendSdoWriteInt32()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoWriteInt32 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const int32_t  value 
)
inlinevirtual

Definition at line 231 of file EthercatSlaveBase.hpp.

◆ sendSdoWriteInt64()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoWriteInt64 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const int64_t  value 
)
inlinevirtual

Definition at line 237 of file EthercatSlaveBase.hpp.

◆ sendSdoWriteInt8()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoWriteInt8 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const int8_t  value 
)
inlinevirtual

Definition at line 219 of file EthercatSlaveBase.hpp.

◆ sendSdoWriteUInt16()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoWriteUInt16 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const uint16_t  value 
)
inlinevirtual

Definition at line 249 of file EthercatSlaveBase.hpp.

◆ sendSdoWriteUInt32()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoWriteUInt32 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const uint32_t  value 
)
inlinevirtual

Definition at line 255 of file EthercatSlaveBase.hpp.

◆ sendSdoWriteUInt64()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoWriteUInt64 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const uint64_t  value 
)
inlinevirtual

Definition at line 261 of file EthercatSlaveBase.hpp.

◆ sendSdoWriteUInt8()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::sendSdoWriteUInt8 ( const uint16_t  index,
const uint8_t  subindex,
const bool  completeAccess,
const uint8_t  value 
)
inlinevirtual

Definition at line 243 of file EthercatSlaveBase.hpp.

◆ setProductName()

void rokubimini::soem_interface::EthercatSlaveBase::setProductName ( const std::string &  productName)
inline

Sets the product name of the device.

Parameters
productNameThe product name to set.

Definition at line 139 of file EthercatSlaveBase.hpp.

◆ setSerialNumber()

bool rokubimini::soem_interface::EthercatSlaveBase::setSerialNumber ( unsigned int &  serialNumber)
inline

Accessor for device serial number.

Parameters
serialNumberThe serial number to set.
Returns
True if the serial number could be successfully saved.

Definition at line 126 of file EthercatSlaveBase.hpp.

◆ shutdown()

virtual void rokubimini::soem_interface::EthercatSlaveBase::shutdown ( )
pure virtual

Used to shutdown slave specific objects.

Implemented in rokubimini::ethercat::RokubiminiEthercatSlave.

◆ startup()

virtual bool rokubimini::soem_interface::EthercatSlaveBase::startup ( )
pure virtual

Startup non-ethercat specific objects for the slave.

Returns
True if succesful

Implemented in rokubimini::ethercat::RokubiminiEthercatSlave.

◆ updateRead()

virtual void rokubimini::soem_interface::EthercatSlaveBase::updateRead ( )
pure virtual

Called during reading the ethercat bus. Use this method to extract readings from the ethercat bus buffer.

Implemented in rokubimini::ethercat::RokubiminiEthercatSlave.

◆ updateWrite()

virtual void rokubimini::soem_interface::EthercatSlaveBase::updateWrite ( )
pure virtual

Called during writing to the ethercat bus. Use this method to stage a command for the slave.

Implemented in rokubimini::ethercat::RokubiminiEthercatSlave.

Member Data Documentation

◆ address_

const uint32_t rokubimini::soem_interface::EthercatSlaveBase::address_ { 0 }
protected

Definition at line 298 of file EthercatSlaveBase.hpp.

◆ bus_

EthercatBusBase* rokubimini::soem_interface::EthercatSlaveBase::bus_
protected

Definition at line 296 of file EthercatSlaveBase.hpp.

◆ mutex_

std::recursive_mutex rokubimini::soem_interface::EthercatSlaveBase::mutex_
mutableprotected

Definition at line 294 of file EthercatSlaveBase.hpp.

◆ productName_

std::string rokubimini::soem_interface::EthercatSlaveBase::productName_ { "" }
protected

The product name of the slave.

Definition at line 305 of file EthercatSlaveBase.hpp.

◆ serialNumber_

unsigned int rokubimini::soem_interface::EthercatSlaveBase::serialNumber_ { 0 }
protected

The serial number of the device.

Definition at line 313 of file EthercatSlaveBase.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