Go to the documentation of this file.
12 namespace soem_interface
14 class EthercatBusBase;
47 virtual std::string
getName()
const = 0;
151 template <
typename Value>
162 template <
typename Value>
168 return sendSdoRead(index, subindex, completeAccess, value);
173 return sendSdoRead(index, subindex, completeAccess, value);
178 return sendSdoRead(index, subindex, completeAccess, value);
183 return sendSdoRead(index, subindex, completeAccess, value);
188 return sendSdoRead(index, subindex, completeAccess, value);
194 return sendSdoRead(index, subindex, completeAccess, value);
200 return sendSdoRead(index, subindex, completeAccess, value);
206 return sendSdoRead(index, subindex, completeAccess, value);
211 return sendSdoRead(index, subindex, completeAccess, value);
216 return sendSdoRead(index, subindex, completeAccess, value);
279 virtual bool sendSdoReadGeneric(
const std::string& indexString,
const std::string& subindexString,
280 const std::string& valueTypeString, std::string& valueString);
281 virtual bool sendSdoWriteGeneric(
const std::string& indexString,
const std::string& subindexString,
282 const std::string& valueTypeString,
const std::string& valueString);
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 bool sendSdoWriteGeneric(const std::string &indexString, const std::string &subindexString, const std::string &valueTypeString, const std::string &valueString)
virtual bool sendSdoReadInt8(const uint16_t index, const uint8_t subindex, const bool completeAccess, int8_t &value)
virtual void updateWrite()=0
Called during writing to the ethercat bus. Use this method to stage a command for the slave.
virtual ~EthercatSlaveBase()=default
virtual bool sendSdoReadDouble(const uint16_t index, const uint8_t subindex, const bool completeAccess, double &value)
bool setSerialNumber(unsigned int &serialNumber)
Accessor for device serial number.
virtual bool sendSdoWriteUInt16(const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint16_t value)
virtual bool sendSdoWriteInt64(const uint16_t index, const uint8_t subindex, const bool completeAccess, const int64_t value)
virtual bool sendSdoWriteDouble(const uint16_t index, const uint8_t subindex, const bool completeAccess, const double value)
unsigned int serialNumber_
The serial number of the device.
void printWarnNotImplemented()
Prints a warning. Use this method to suppress compiler warnings.
void setProductName(const std::string &productName)
Sets the product name of the device.
virtual bool sendSdoReadInt16(const uint16_t index, const uint8_t subindex, const bool completeAccess, int16_t &value)
#define ROS_WARN_STREAM(args)
bool sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &value)
std::recursive_mutex mutex_
unsigned __int64 uint64_t
virtual bool getSerialNumber(unsigned int &serialNumber)=0
Accessor for device serial number. It's abstract because it's implementation specific.
std::shared_ptr< EthercatSlaveBase > EthercatSlaveBasePtr
virtual PdoInfo getCurrentPdoInfo() const =0
Gets the current pdo information.
virtual bool sendSdoWriteInt32(const uint16_t index, const uint8_t subindex, const bool completeAccess, const int32_t value)
virtual bool sendSdoReadUInt32(const uint16_t index, const uint8_t subindex, const bool completeAccess, uint32_t &value)
virtual bool startup()=0
Startup non-ethercat specific objects for the slave.
virtual bool sendSdoReadInt32(const uint16_t index, const uint8_t subindex, const bool completeAccess, int32_t &value)
virtual bool sendSdoReadUInt64(const uint16_t index, const uint8_t subindex, const bool completeAccess, uint64_t &value)
Struct defining the Pdo characteristic.
virtual bool sendSdoWriteFloat(const uint16_t index, const uint8_t subindex, const bool completeAccess, const float value)
virtual bool sendSdoReadGeneric(const std::string &indexString, const std::string &subindexString, const std::string &valueTypeString, std::string &valueString)
virtual std::string getName() const =0
Returns the name of the slave.
virtual bool sendSdoReadFloat(const uint16_t index, const uint8_t subindex, const bool completeAccess, float &value)
virtual bool sendSdoWriteInt8(const uint16_t index, const uint8_t subindex, const bool completeAccess, const int8_t value)
virtual bool sendSdoReadUInt16(const uint16_t index, const uint8_t subindex, const bool completeAccess, uint16_t &value)
std::string productName_
The product name of the slave.
std::string getProductName() const
Gets the product name of the device.
virtual bool sendSdoReadInt64(const uint16_t index, const uint8_t subindex, const bool completeAccess, int64_t &value)
uint32_t getAddress() const
Returns the bus address of the slave.
virtual bool sendSdoWriteUInt32(const uint16_t index, const uint8_t subindex, const bool completeAccess, const uint32_t value)
virtual bool sendSdoWriteInt16(const uint16_t index, const uint8_t subindex, const bool completeAccess, const int16_t value)
Base class for generic ethercat slaves using soem.
virtual void shutdown()=0
Used to shutdown slave specific objects.
bool sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value)
EthercatSlaveBase(EthercatBusBase *bus, const uint32_t address)
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)
virtual void updateRead()=0
Called during reading the ethercat bus. Use this method to extract readings from the ethercat bus buf...