EthercatSlaveBase.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 // std
4 #include <cstdint>
5 #include <memory>
6 #include <mutex>
7 
8 #include <ros/console.h>
9 
10 namespace rokubimini
11 {
12 namespace soem_interface
13 {
14 class EthercatBusBase;
15 
20 {
21 public:
25  struct PdoInfo
26  {
27  // The id of the rx pdo
29  // The id of the tx pdo
31  // The size of the rx pdo
33  // The size of the tx pdo
35  // The value referencing the current pdo type on slave side
37  };
38 
39  EthercatSlaveBase(EthercatBusBase* bus, const uint32_t address);
40  virtual ~EthercatSlaveBase() = default;
41 
47  virtual std::string getName() const = 0;
48 
54  virtual bool startup() = 0;
55 
60  virtual void updateRead() = 0;
61 
66  virtual void updateWrite() = 0;
67 
71  virtual void shutdown() = 0;
72 
78  virtual PdoInfo getCurrentPdoInfo() const = 0;
79 
86  {
87  return address_;
88  }
89 
97  std::string getProductName() const
98  {
99  return productName_;
100  }
101 
113  virtual bool getSerialNumber(unsigned int& serialNumber) = 0;
114 
126  inline bool setSerialNumber(unsigned int& serialNumber)
127  {
128  serialNumber_ = serialNumber;
129  return true;
130  }
131 
139  void setProductName(const std::string& productName)
140  {
141  productName_ = productName;
142  }
151  template <typename Value>
152  bool sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value);
153 
162  template <typename Value>
163  bool sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess, Value& value);
164 
165  // Send SDOs.
166  virtual bool sendSdoReadInt8(const uint16_t index, const uint8_t subindex, const bool completeAccess, int8_t& value)
167  {
168  return sendSdoRead(index, subindex, completeAccess, value);
169  }
170 
171  virtual bool sendSdoReadInt16(const uint16_t index, const uint8_t subindex, const bool completeAccess, int16_t& value)
172  {
173  return sendSdoRead(index, subindex, completeAccess, value);
174  }
175 
176  virtual bool sendSdoReadInt32(const uint16_t index, const uint8_t subindex, const bool completeAccess, int32_t& value)
177  {
178  return sendSdoRead(index, subindex, completeAccess, value);
179  }
180 
181  virtual bool sendSdoReadInt64(const uint16_t index, const uint8_t subindex, const bool completeAccess, int64_t& value)
182  {
183  return sendSdoRead(index, subindex, completeAccess, value);
184  }
185 
186  virtual bool sendSdoReadUInt8(const uint16_t index, const uint8_t subindex, const bool completeAccess, uint8_t& value)
187  {
188  return sendSdoRead(index, subindex, completeAccess, value);
189  }
190 
191  virtual bool sendSdoReadUInt16(const uint16_t index, const uint8_t subindex, const bool completeAccess,
192  uint16_t& value)
193  {
194  return sendSdoRead(index, subindex, completeAccess, value);
195  }
196 
197  virtual bool sendSdoReadUInt32(const uint16_t index, const uint8_t subindex, const bool completeAccess,
198  uint32_t& value)
199  {
200  return sendSdoRead(index, subindex, completeAccess, value);
201  }
202 
203  virtual bool sendSdoReadUInt64(const uint16_t index, const uint8_t subindex, const bool completeAccess,
204  uint64_t& value)
205  {
206  return sendSdoRead(index, subindex, completeAccess, value);
207  }
208 
209  virtual bool sendSdoReadFloat(const uint16_t index, const uint8_t subindex, const bool completeAccess, float& value)
210  {
211  return sendSdoRead(index, subindex, completeAccess, value);
212  }
213 
214  virtual bool sendSdoReadDouble(const uint16_t index, const uint8_t subindex, const bool completeAccess, double& value)
215  {
216  return sendSdoRead(index, subindex, completeAccess, value);
217  }
218 
219  virtual bool sendSdoWriteInt8(const uint16_t index, const uint8_t subindex, const bool completeAccess,
220  const int8_t value)
221  {
222  return sendSdoWrite(index, subindex, false, value);
223  }
224 
225  virtual bool sendSdoWriteInt16(const uint16_t index, const uint8_t subindex, const bool completeAccess,
226  const int16_t value)
227  {
228  return sendSdoWrite(index, subindex, false, value);
229  }
230 
231  virtual bool sendSdoWriteInt32(const uint16_t index, const uint8_t subindex, const bool completeAccess,
232  const int32_t value)
233  {
234  return sendSdoWrite(index, subindex, false, value);
235  }
236 
237  virtual bool sendSdoWriteInt64(const uint16_t index, const uint8_t subindex, const bool completeAccess,
238  const int64_t value)
239  {
240  return sendSdoWrite(index, subindex, false, value);
241  }
242 
243  virtual bool sendSdoWriteUInt8(const uint16_t index, const uint8_t subindex, const bool completeAccess,
244  const uint8_t value)
245  {
246  return sendSdoWrite(index, subindex, false, value);
247  }
248 
249  virtual bool sendSdoWriteUInt16(const uint16_t index, const uint8_t subindex, const bool completeAccess,
250  const uint16_t value)
251  {
252  return sendSdoWrite(index, subindex, false, value);
253  }
254 
255  virtual bool sendSdoWriteUInt32(const uint16_t index, const uint8_t subindex, const bool completeAccess,
256  const uint32_t value)
257  {
258  return sendSdoWrite(index, subindex, false, value);
259  }
260 
261  virtual bool sendSdoWriteUInt64(const uint16_t index, const uint8_t subindex, const bool completeAccess,
262  const uint64_t value)
263  {
264  return sendSdoWrite(index, subindex, false, value);
265  }
266 
267  virtual bool sendSdoWriteFloat(const uint16_t index, const uint8_t subindex, const bool completeAccess,
268  const float value)
269  {
270  return sendSdoWrite(index, subindex, false, value);
271  }
272 
273  virtual bool sendSdoWriteDouble(const uint16_t index, const uint8_t subindex, const bool completeAccess,
274  const double value)
275  {
276  return sendSdoWrite(index, subindex, false, value);
277  }
278 
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);
283 
284 protected:
289  {
290  ROS_WARN_STREAM("Functionality is not implemented.");
291  }
292 
293  // Mutex prohibiting simultaneous access to EtherCAT slave.
294  mutable std::recursive_mutex mutex_;
295  // Non owning pointer to the ethercat bus
297  // The bus address
298  const uint32_t address_{ 0 };
305  std::string productName_{ "" };
306 
313  unsigned int serialNumber_{ 0 };
314 };
315 
316 using EthercatSlaveBasePtr = std::shared_ptr<EthercatSlaveBase>;
317 
318 } // namespace soem_interface
319 } // namespace rokubimini
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 getSerialNumber(unsigned int &serialNumber)=0
Accessor for device serial number. It&#39;s abstract because it&#39;s implementation specific.
virtual bool sendSdoWriteInt8(const uint16_t index, const uint8_t subindex, const bool completeAccess, const int8_t value)
unsigned int serialNumber_
The serial number of the device.
unsigned short uint16_t
bool sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &value)
unsigned char uint8_t
virtual bool sendSdoWriteFloat(const uint16_t index, const uint8_t subindex, const bool completeAccess, const float value)
bool setSerialNumber(unsigned int &serialNumber)
Accessor for device serial number.
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)
unsigned int uint32_t
std::string getProductName() const
Gets the product name of the device.
virtual bool sendSdoWriteInt64(const uint16_t index, const uint8_t subindex, const bool completeAccess, const int64_t value)
signed short int16_t
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)
std::string productName_
The product name of the slave.
signed char int8_t
uint32_t getAddress() const
Returns the bus address of the slave.
#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)
signed __int64 int64_t
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)
signed int int32_t
virtual std::string getName() const =0
Returns the name of the slave.
void setProductName(const std::string &productName)
Sets the product name of the device.
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)


rokubimini_ethercat
Author(s):
autogenerated on Sat Apr 15 2023 02:51:33