12 namespace soem_interface
14 class EthercatBusBase;
47 virtual std::string
getName()
const = 0;
98 template <
typename Value>
109 template <
typename Value>
115 return sendSdoRead(index, subindex, completeAccess, value);
120 return sendSdoRead(index, subindex, completeAccess, value);
125 return sendSdoRead(index, subindex, completeAccess, value);
130 return sendSdoRead(index, subindex, completeAccess, value);
135 return sendSdoRead(index, subindex, completeAccess, value);
141 return sendSdoRead(index, subindex, completeAccess, value);
147 return sendSdoRead(index, subindex, completeAccess, value);
153 return sendSdoRead(index, subindex, completeAccess, value);
158 return sendSdoRead(index, subindex, completeAccess, value);
163 return sendSdoRead(index, subindex, completeAccess, value);
226 virtual bool sendSdoReadGeneric(
const std::string& indexString,
const std::string& subindexString,
227 const std::string& valueTypeString, std::string& valueString);
228 virtual bool sendSdoWriteGeneric(
const std::string& indexString,
const std::string& subindexString,
229 const std::string& valueTypeString,
const std::string& valueString);
virtual bool sendSdoWriteUInt32(const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint32_t value)
virtual PdoInfo getCurrentPdoInfo() const =0
Gets the current pdo information.
void printWarnNotImplemented()
Prints a warning. Use this method to suppress compiler warnings.
virtual bool sendSdoWriteDouble(const uint16_t index, const uint8_t subindex, const bool completeAccess, const double value)
virtual bool startup()=0
Startup non-ethercat specific objects for the slave.
virtual void updateWrite()=0
Called during writing to the ethercat bus. Use this method to stage a command for the slave...
virtual bool sendSdoWriteInt16(const uint16_t index, const uint8_t subindex, const bool completeAccess, const int16_t value)
EthercatSlaveBase(EthercatBusBase *bus, const uint32_t address)
virtual bool sendSdoReadInt32(const uint16_t index, const uint8_t subindex, const bool completeAccess, int32_t &value)
virtual bool sendSdoReadInt8(const uint16_t index, const uint8_t subindex, const bool completeAccess, int8_t &value)
Base class for generic ethercat slaves using soem.
virtual bool sendSdoWriteInt8(const uint16_t index, const uint8_t subindex, const bool completeAccess, const int8_t value)
bool sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &value)
virtual bool sendSdoWriteFloat(const uint16_t index, const uint8_t subindex, const bool completeAccess, const float value)
uint32_t getAddress() const
Returns the bus address of the slave.
std::recursive_mutex mutex_
virtual bool sendSdoWriteUInt8(const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint8_t value)
virtual bool sendSdoWriteUInt16(const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint16_t value)
virtual bool sendSdoWriteInt32(const uint16_t index, const uint8_t subindex, const bool completeAccess, const int32_t value)
virtual bool sendSdoReadUInt64(const uint16_t index, const uint8_t subindex, const bool completeAccess, uint64_t &value)
virtual bool sendSdoWriteInt64(const uint16_t index, const uint8_t subindex, const bool completeAccess, const int64_t value)
virtual void shutdown()=0
Used to shutdown slave specific objects.
virtual void updateRead()=0
Called during reading the ethercat bus. Use this method to extract readings from the ethercat bus buf...
std::shared_ptr< EthercatSlaveBase > EthercatSlaveBasePtr
virtual bool sendSdoReadInt16(const uint16_t index, const uint8_t subindex, const bool completeAccess, int16_t &value)
unsigned __int64 uint64_t
virtual bool sendSdoWriteGeneric(const std::string &indexString, const std::string &subindexString, const std::string &valueTypeString, const std::string &valueString)
virtual bool sendSdoReadFloat(const uint16_t index, const uint8_t subindex, const bool completeAccess, float &value)
#define ROS_WARN_STREAM(args)
virtual bool sendSdoReadUInt32(const uint16_t index, const uint8_t subindex, const bool completeAccess, uint32_t &value)
virtual bool sendSdoReadDouble(const uint16_t index, const uint8_t subindex, const bool completeAccess, double &value)
virtual ~EthercatSlaveBase()=default
Struct defining the Pdo characteristic.
Class for managing an ethercat bus containing one or multiple slaves.
virtual bool sendSdoReadUInt8(const uint16_t index, const uint8_t subindex, const bool completeAccess, uint8_t &value)
bool sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value)
virtual bool sendSdoReadInt64(const uint16_t index, const uint8_t subindex, const bool completeAccess, int64_t &value)
virtual std::string getName() const =0
Returns the name of the slave.
virtual bool sendSdoWriteUInt64(const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint64_t value)
virtual bool sendSdoReadUInt16(const uint16_t index, const uint8_t subindex, const bool completeAccess, uint16_t &value)
virtual bool sendSdoReadGeneric(const std::string &indexString, const std::string &subindexString, const std::string &valueTypeString, std::string &valueString)