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...
 
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 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_
 

Detailed Description

Base class for generic ethercat slaves using soem.

Definition at line 19 of file EthercatSlaveBase.hpp.

Constructor & Destructor Documentation

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

Definition at line 9 of file EthercatSlaveBase.cpp.

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

Member Function Documentation

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.

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, and soem_interface_examples::ExampleSlave.

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, and soem_interface_examples::ExampleSlave.

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

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

Definition at line 235 of file EthercatSlaveBase.hpp.

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.

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

Definition at line 161 of file EthercatSlaveBase.hpp.

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

Definition at line 156 of file EthercatSlaveBase.hpp.

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.

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 118 of file EthercatSlaveBase.hpp.

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 123 of file EthercatSlaveBase.hpp.

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 128 of file EthercatSlaveBase.hpp.

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 113 of file EthercatSlaveBase.hpp.

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 138 of file EthercatSlaveBase.hpp.

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 144 of file EthercatSlaveBase.hpp.

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 150 of file EthercatSlaveBase.hpp.

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 133 of file EthercatSlaveBase.hpp.

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.

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 220 of file EthercatSlaveBase.hpp.

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 214 of file EthercatSlaveBase.hpp.

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.

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 172 of file EthercatSlaveBase.hpp.

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 178 of file EthercatSlaveBase.hpp.

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 184 of file EthercatSlaveBase.hpp.

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 166 of file EthercatSlaveBase.hpp.

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 196 of file EthercatSlaveBase.hpp.

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 202 of file EthercatSlaveBase.hpp.

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 208 of file EthercatSlaveBase.hpp.

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 190 of file EthercatSlaveBase.hpp.

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

Used to shutdown slave specific objects.

Implemented in rokubimini::ethercat::RokubiminiEthercatSlave, and soem_interface_examples::ExampleSlave.

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, and soem_interface_examples::ExampleSlave.

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, and soem_interface_examples::ExampleSlave.

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, and soem_interface_examples::ExampleSlave.

Member Data Documentation

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

Definition at line 245 of file EthercatSlaveBase.hpp.

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

Definition at line 243 of file EthercatSlaveBase.hpp.

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

Definition at line 241 of file EthercatSlaveBase.hpp.


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


rokubimini_ethercat
Author(s):
autogenerated on Wed Mar 3 2021 03:09:16