RokubiminiEthercatSlave.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 // soem_interface
6 
7 #include <rokubimini/Reading.hpp>
11 
14 
15 #define MAX_FILE_SIZE_FIRMWARE (0x100000)
16 
17 namespace rokubimini
18 {
19 namespace ethercat
20 {
32 {
33 public:
42  RokubiminiEthercatSlave() = delete;
43 
58  const uint32_t address, const PdoTypeEnum pdoTypeEnum);
59 
60  ~RokubiminiEthercatSlave() override = default;
61 
72  bool startup() override;
73 
82  void updateRead() override;
83 
93  void updateWrite() override;
94 
103  void shutdown() override;
104 
115  void setState(const uint16_t state);
116 
127  bool waitForState(const uint16_t state);
128 
138  PdoInfo getCurrentPdoInfo() const override;
139 
149  std::string getName() const override
150  {
151  return name_;
152  }
153 
164  {
165  return currentPdoTypeEnum_;
166  }
167 
168  // Methods for all the SDOs
169 
181  bool getSerialNumber(unsigned int& serialNumber);
182 
195  bool getForceTorqueSamplingRate(int& samplingRate);
196 
210 
222  bool setAccelerationFilter(const unsigned int filter);
223 
235  bool setAngularRateFilter(const unsigned int filter);
236 
248  bool setAccelerationRange(const unsigned int range);
249 
261  bool setAngularRateRange(const unsigned int range);
262 
274  bool setForceTorqueOffset(const Eigen::Matrix<double, 6, 1>& forceTorqueOffset);
275 
287  bool setSensorConfiguration(const configuration::SensorConfiguration& sensorConfiguration);
288 
300  bool setSensorCalibration(const calibration::SensorCalibration& sensorCalibration);
301 
309  bool setConfigMode();
310 
318  bool setRunMode();
319 
329  bool saveConfigParameter();
330 
340  void getReading(rokubimini::Reading& reading) const;
341 
351  bool firmwareUpdate(const std::string& filePath, const std::string& fileName, const uint32_t& password);
352 
359  bool isRunning()
360  {
361  return isRunning_;
362  }
363 
364 private:
375  bool configurePdo(const PdoTypeEnum pdoTypeEnum);
376 
388  bool sendCalibrationMatrixEntry(const uint8_t subId, const double entry);
389 
398  bool readFileToBuffer(const std::string& filePath);
399 
400  using PdoInfos = std::map<PdoTypeEnum, PdoInfo>;
401 
409  const std::string name_;
410 
418 
426  std::atomic<PdoTypeEnum> pdoTypeEnum_;
427 
435  std::atomic<PdoTypeEnum> currentPdoTypeEnum_;
436 
447 
455 
462  char* fileBuffer_;
463 
470  std::atomic<bool> isRunning_;
471 };
472 
473 using RokubiminiEthercatSlavePtr = std::shared_ptr<RokubiminiEthercatSlave>;
474 
475 } // namespace ethercat
476 } // namespace rokubimini
bool setAccelerationRange(const unsigned int range)
Sets an acceleration range to the device.
bool setAngularRateRange(const unsigned int range)
Sets an angular rate range to the device.
bool firmwareUpdate(const std::string &filePath, const std::string &fileName, const uint32_t &password)
Updates the firmware of the device.
void updateRead() override
This method is called by the EthercatBusManager. Each device attached to this bus reads its data from...
bool getForceTorqueSamplingRate(int &samplingRate)
Gets the force torque sampling rate of the device.
bool getSerialNumber(unsigned int &serialNumber)
Accessor for device serial number.
RokubiminiEthercatSlave()=delete
Default constructor is deleted.
void getReading(rokubimini::Reading &reading) const
Gets the internal reading variable.
std::atomic< PdoTypeEnum > currentPdoTypeEnum_
Current PDO type.
Base class for generic ethercat slaves using soem.
unsigned short uint16_t
void updateWrite() override
This method is called by the EthercatBusManager. Each device attached to the bus writes its data to t...
unsigned char uint8_t
void shutdown() override
Shuts down the device.
bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration)
Sets a sensor configuration to the device.
bool configurePdo(const PdoTypeEnum pdoTypeEnum)
Configures a PDO in the Ethercat device.
bool setAccelerationFilter(const unsigned int filter)
Sets an acceleration filter to the device.
The Rokubimini Ethercat Implementation (Slave) class.
bool readFileToBuffer(const std::string &filePath)
Reads the contents of a file to an internal buffer.
bool setAngularRateFilter(const unsigned int filter)
Sets an angular rate filter to the device.
bool isRunning()
Returns if the instance is running.
PdoInfos pdoInfos_
Map between PDO types and their infos.
unsigned int uint32_t
PdoTypeEnum getCurrentPdoTypeEnum() const
Accessor for the current PDO type.
bool saveConfigParameter()
Saves the current configuration to the device.
char * fileBuffer_
The buffer to save the contents of the file.
void setState(const uint16_t state)
Sets the desired EtherCAT state machine state of the device in the bus.
std::shared_ptr< RokubiminiEthercatSlave > RokubiminiEthercatSlavePtr
bool waitForState(const uint16_t state)
Wait for an EtherCAT state machine state to be reached.
bool setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)
Sets a force torque offset to the device.
bool sendCalibrationMatrixEntry(const uint8_t subId, const double entry)
Sends a calibration matrix entry to device.
PdoInfo getCurrentPdoInfo() const override
Accessor for the current PDO info.
bool setConfigMode()
Sets the device in config mode.
Struct defining the Pdo characteristic.
Class for managing an ethercat bus containing one or multiple slaves.
std::string getName() const override
Accessor for device name.
uint8_t state
bool setForceTorqueFilter(const configuration::ForceTorqueFilter &filter)
Sets a force torque filter to the device.
bool startup() override
This method starts up and initializes the device.
bool setSensorCalibration(const calibration::SensorCalibration &sensorCalibration)
Sets a sensor calibration to the device.
Reading reading_
The internal reading variable. It&#39;s used for providing to client code the sensor readings, through the getReading () function.
std::atomic< bool > isRunning_
Internal flag to indicate if the instance is running.


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