RokubiminiEthercatSlave.hpp
Go to the documentation of this file.
1 #pragma once
2 
4 // soem_interface
7 
8 #include <rokubimini/Reading.hpp>
12 
15 
16 #define MAX_FILE_SIZE_FIRMWARE (0x100000)
17 
18 namespace rokubimini
19 {
20 namespace ethercat
21 {
33 const static std::map<uint8_t, std::string> STATE_TO_STRING = { { EC_STATE_INIT, "Initialization state" },
34  { EC_STATE_PRE_OP, "Pre-Operational state" },
35  { EC_STATE_SAFE_OP, "Safe-Operational state" },
36  { EC_STATE_OPERATIONAL, "Operational state" } };
38 {
39 public:
48  RokubiminiEthercatSlave() = delete;
49 
64  const uint32_t address, const PdoTypeEnum pdoTypeEnum);
65 
66  ~RokubiminiEthercatSlave() override = default;
67 
78  bool startup() override;
79 
87  void preSetupConfiguration();
88 
97  void updateRead() override;
98 
108  void updateWrite() override;
109 
118  void shutdown() override;
119 
130  void setState(const uint16_t state);
131 
142  bool waitForState(const uint16_t state);
143 
153  PdoInfo getCurrentPdoInfo() const override;
154 
164  std::string getName() const override
165  {
166  return name_;
167  }
168 
179  {
180  return currentPdoTypeEnum_;
181  }
182 
194  bool getSerialNumber(unsigned int& serialNumber) override;
195 
205  inline unsigned int fetchSerialNumber() const
206  {
207  return serialNumber_;
208  }
209 
222  bool getForceTorqueSamplingRate(int& samplingRate);
223 
237 
249  bool setAccelerationFilter(const unsigned int filter);
250 
262  bool setAngularRateFilter(const unsigned int filter);
263 
275  bool setAccelerationRange(const unsigned int range);
276 
288  bool setAngularRateRange(const unsigned int range);
289 
301  bool setForceTorqueOffset(const Eigen::Matrix<double, 6, 1>& forceTorqueOffset);
302 
314  bool setSensorConfiguration(const configuration::SensorConfiguration& sensorConfiguration);
315 
327  bool setSensorCalibration(const calibration::SensorCalibration& sensorCalibration);
328 
336  bool setConfigMode();
337 
345  bool setRunMode();
346 
356  bool saveConfigParameter();
357 
367  void getReading(rokubimini::Reading& reading) const;
368 
378  bool firmwareUpdate(const std::string& filePath, const std::string& fileName, const uint32_t& password);
379 
386  bool isRunning()
387  {
388  return isRunning_;
389  }
390 
400 
410 
418  bool runsAsync() const
419  {
420  return runsAsync_;
421  }
422 
431  {
433  }
434 
442  void resetDataFlags();
443 
451  void updateDataFlags();
452 
453 private:
464  bool configurePdo(const PdoTypeEnum pdoTypeEnum);
465 
477  bool sendCalibrationMatrixEntry(const uint8_t subId, const double entry);
478 
487  bool readFileToBuffer(const std::string& filePath);
488 
496  uint8_t getState();
497 
505 
514  std::string getSlaveStateString(uint8_t state);
515 
516  using PdoInfos = std::map<PdoTypeEnum, PdoInfo>;
517 
525  const std::string name_;
526 
534 
542  std::atomic<PdoTypeEnum> pdoTypeEnum_;
543 
551  std::atomic<PdoTypeEnum> currentPdoTypeEnum_;
552 
563 
571 
578  char* fileBuffer_;
579 
586  std::atomic<bool> isRunning_;
587 
594  std::atomic<bool> runsAsync_;
595 
604 
612  mutable std::recursive_mutex dataFlagsMutex_;
613 };
614 
615 using RokubiminiEthercatSlavePtr = std::shared_ptr<RokubiminiEthercatSlave>;
616 
617 } // namespace ethercat
618 } // namespace rokubimini
rokubimini::ethercat::RokubiminiEthercatSlave::configurePdo
bool configurePdo(const PdoTypeEnum pdoTypeEnum)
Configures a PDO in the Ethercat device.
Definition: RokubiminiEthercatSlave.cpp:467
uint8_t
unsigned char uint8_t
rokubimini::ethercat::RokubiminiEthercatSlave::runsAsync
bool runsAsync() const
Returns if the driver runs asynchronously.
Definition: RokubiminiEthercatSlave.hpp:418
rokubimini::ethercat::RokubiminiEthercatSlave::setSensorConfiguration
bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration)
Sets a sensor configuration to the device.
Definition: RokubiminiEthercatSlave.cpp:192
rokubimini::ethercat::RokubiminiEthercatSlave::fetchSerialNumber
unsigned int fetchSerialNumber() const
Accessor for device serial number.
Definition: RokubiminiEthercatSlave.hpp:205
rokubimini::ethercat::RokubiminiEthercatSlave::getForceTorqueSamplingRate
bool getForceTorqueSamplingRate(int &samplingRate)
Gets the force torque sampling rate of the device.
Definition: RokubiminiEthercatSlave.cpp:103
rokubimini::ethercat::RokubiminiEthercatSlave::updateConnectionStatus
void updateConnectionStatus(diagnostic_updater::DiagnosticStatusWrapper &stat)
Fills the Device Connection Status (ROS diagnostics).
Definition: RokubiminiEthercatSlave.cpp:292
uint16_t
unsigned short uint16_t
SensorConfiguration.hpp
EthercatSlaveBase.hpp
rokubimini::ethercat::RokubiminiEthercatSlave::getALStatusCode
uint16_t getALStatusCode()
Returns the AL Status Code of the slave.
Definition: RokubiminiEthercatSlave.cpp:282
rokubimini::ethercat::RokubiminiEthercatSlave::readFileToBuffer
bool readFileToBuffer(const std::string &filePath)
Reads the contents of a file to an internal buffer.
Definition: RokubiminiEthercatSlave.cpp:493
rokubimini::ethercat::RokubiminiEthercatSlave::updateWrite
void updateWrite() override
This method is called by the EthercatBusManager. Each device attached to the bus writes its data to t...
Definition: RokubiminiEthercatSlave.cpp:433
rokubimini::ethercat::RokubiminiEthercatSlave::RokubiminiEthercatSlave
RokubiminiEthercatSlave()=delete
Default constructor is deleted.
Reading.hpp
rokubimini::ethercat::RokubiminiEthercatSlave::createDataFlagsDiagnostics
void createDataFlagsDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Creates the Data Flags Diagnostics status.
Definition: RokubiminiEthercatSlave.cpp:351
EC_STATE_SAFE_OP
EC_STATE_SAFE_OP
rokubimini::ethercat::RokubiminiEthercatSlave::updateRead
void updateRead() override
This method is called by the EthercatBusManager. Each device attached to this bus reads its data from...
Definition: RokubiminiEthercatSlave.cpp:45
rokubimini::ethercat::RokubiminiEthercatSlave::dataFlagsMutex_
std::recursive_mutex dataFlagsMutex_
Mutex prohibiting simultaneous access to the Data Flags structure.
Definition: RokubiminiEthercatSlave.hpp:612
rokubimini::ethercat::RokubiminiEthercatSlave::setRunMode
bool setRunMode()
Sets the device in run mode.
Definition: RokubiminiEthercatSlave.cpp:403
rokubimini::ethercat::RokubiminiEthercatSlave::shutdown
void shutdown() override
Shuts down the device.
Definition: RokubiminiEthercatSlave.cpp:442
diagnostic_updater.h
rokubimini::Reading
rokubimini::soem_interface::EthercatSlaveBase::serialNumber_
unsigned int serialNumber_
The serial number of the device.
Definition: EthercatSlaveBase.hpp:313
rokubimini::ethercat::RokubiminiEthercatSlave::setForceTorqueFilter
bool setForceTorqueFilter(const configuration::ForceTorqueFilter &filter)
Sets a force torque filter to the device.
Definition: RokubiminiEthercatSlave.cpp:114
rokubimini::ethercat::RokubiminiEthercatSlave::pdoInfos_
PdoInfos pdoInfos_
Map between PDO types and their infos.
Definition: RokubiminiEthercatSlave.hpp:533
rokubimini::ethercat::PdoTypeEnum
PdoTypeEnum
Definition: PdoTypeEnum.hpp:8
rokubimini::ethercat::RokubiminiEthercatSlave::name_
const std::string name_
Name of the sensor.
Definition: RokubiminiEthercatSlave.hpp:525
EC_STATE_PRE_OP
EC_STATE_PRE_OP
uint32_t
unsigned int uint32_t
rokubimini::ethercat::RokubiminiEthercatSlave::startup
bool startup() override
This method starts up and initializes the device.
Definition: RokubiminiEthercatSlave.cpp:36
rokubimini::configuration::ForceTorqueFilter
rokubimini::ethercat::RokubiminiEthercatSlave::currentPdoTypeEnum_
std::atomic< PdoTypeEnum > currentPdoTypeEnum_
Current PDO type.
Definition: RokubiminiEthercatSlave.hpp:551
rokubimini::ethercat::RokubiminiEthercatSlave::getName
std::string getName() const override
Accessor for device name.
Definition: RokubiminiEthercatSlave.hpp:164
rokubimini::ethercat::RokubiminiEthercatSlave::fileBuffer_
char * fileBuffer_
The buffer to save the contents of the file.
Definition: RokubiminiEthercatSlave.hpp:578
RxPdo.hpp
rokubimini::ethercat::RokubiminiEthercatSlave::setAccelerationRange
bool setAccelerationRange(const unsigned int range)
Sets an acceleration range to the device.
Definition: RokubiminiEthercatSlave.cpp:154
rokubimini::ethercat::RokubiminiEthercatSlave::getCurrentPdoInfo
PdoInfo getCurrentPdoInfo() const override
Accessor for the current PDO info.
Definition: RokubiminiEthercatSlave.cpp:460
rokubimini::ethercat::RokubiminiEthercatSlave::~RokubiminiEthercatSlave
~RokubiminiEthercatSlave() override=default
rokubimini::ethercat::STATE_TO_STRING
const static std::map< uint8_t, std::string > STATE_TO_STRING
Definition: RokubiminiEthercatSlave.hpp:33
rokubimini::ethercat::RokubiminiEthercatSlave::setConfigMode
bool setConfigMode()
Sets the device in config mode.
Definition: RokubiminiEthercatSlave.cpp:264
EthercatBusBase.hpp
rokubimini
EC_STATE_INIT
EC_STATE_INIT
SensorCalibration.hpp
rokubimini::ethercat::RokubiminiEthercatSlave::setAngularRateRange
bool setAngularRateRange(const unsigned int range)
Sets an angular rate range to the device.
Definition: RokubiminiEthercatSlave.cpp:163
rokubimini::ethercat::RokubiminiEthercatSlave::waitForState
bool waitForState(const uint16_t state)
Wait for an EtherCAT state machine state to be reached.
Definition: RokubiminiEthercatSlave.cpp:454
ForceTorqueFilter.hpp
rokubimini::ethercat::RokubiminiEthercatSlave::getSerialNumber
bool getSerialNumber(unsigned int &serialNumber) override
Accessor for device serial number.
Definition: RokubiminiEthercatSlave.cpp:92
rokubimini::ethercat::RokubiminiEthercatSlave::getCurrentPdoTypeEnum
PdoTypeEnum getCurrentPdoTypeEnum() const
Accessor for the current PDO type.
Definition: RokubiminiEthercatSlave.hpp:178
rokubimini::ethercat::RokubiminiEthercatSlave::currentDataFlagsDiagnostics_
Statusword currentDataFlagsDiagnostics_
The current Data Flags Diagnostics (Data Status) which is updated when a new frame is published and i...
Definition: RokubiminiEthercatSlave.hpp:603
rokubimini::ethercat::RokubiminiEthercatSlave::sendCalibrationMatrixEntry
bool sendCalibrationMatrixEntry(const uint8_t subId, const double entry)
Sends a calibration matrix entry to device.
Definition: RokubiminiEthercatSlave.cpp:214
rokubimini::ethercat::RokubiminiEthercatSlave::getState
uint8_t getState()
Returns the EtherCAT State of the device.
Definition: RokubiminiEthercatSlave.cpp:277
rokubimini::soem_interface::EthercatSlaveBase::PdoInfo
Struct defining the Pdo characteristic.
Definition: EthercatSlaveBase.hpp:25
rokubimini::ethercat::RokubiminiEthercatSlave::saveConfigParameter
bool saveConfigParameter()
Saves the current configuration to the device.
Definition: RokubiminiEthercatSlave.cpp:410
rokubimini::ethercat::RokubiminiEthercatSlave::updateDataFlags
void updateDataFlags()
Updates the Data Flags variable currentDataFlagsDiagnostics_.
Definition: RokubiminiEthercatSlave.cpp:335
rokubimini::ethercat::RokubiminiEthercatSlavePtr
std::shared_ptr< RokubiminiEthercatSlave > RokubiminiEthercatSlavePtr
Definition: RokubiminiEthercatSlave.hpp:615
rokubimini::ethercat::RokubiminiEthercatSlave::setSensorCalibration
bool setSensorCalibration(const calibration::SensorCalibration &sensorCalibration)
Sets a sensor calibration to the device.
Definition: RokubiminiEthercatSlave.cpp:219
rokubimini::ethercat::RokubiminiEthercatSlave::setAccelerationFilter
bool setAccelerationFilter(const unsigned int filter)
Sets an acceleration filter to the device.
Definition: RokubiminiEthercatSlave.cpp:136
rokubimini::ethercat::RokubiminiEthercatSlave::pdoTypeEnum_
std::atomic< PdoTypeEnum > pdoTypeEnum_
Definition: RokubiminiEthercatSlave.hpp:542
rokubimini::ethercat::RokubiminiEthercatSlave::isRunning_
std::atomic< bool > isRunning_
Internal flag to indicate if the instance is running.
Definition: RokubiminiEthercatSlave.hpp:586
rokubimini::ethercat::RokubiminiEthercatSlave::preSetupConfiguration
void preSetupConfiguration()
Pre-setup configuration hook.
Definition: RokubiminiEthercatSlave.cpp:42
rokubimini::ethercat::RokubiminiEthercatSlave::fileSize_
int fileSize_
The size of the file.
Definition: RokubiminiEthercatSlave.hpp:570
rokubimini::ethercat::RokubiminiEthercatSlave::resetDataFlags
void resetDataFlags()
Resets the Data Flags variable currentDataFlagsDiagnostics_.
Definition: RokubiminiEthercatSlave.cpp:345
rokubimini::ethercat::RokubiminiEthercatSlave
The Rokubimini Ethercat Implementation (Slave) class.
Definition: RokubiminiEthercatSlave.hpp:37
rokubimini::ethercat::RokubiminiEthercatSlave::setRunsAsync
void setRunsAsync(bool runsAsync)
Sets the runsAsync_ variable.
Definition: RokubiminiEthercatSlave.hpp:430
rokubimini::ethercat::RokubiminiEthercatSlave::setState
void setState(const uint16_t state)
Sets the desired EtherCAT state machine state of the device in the bus.
Definition: RokubiminiEthercatSlave.cpp:448
diagnostic_updater::DiagnosticStatusWrapper
rokubimini::configuration::SensorConfiguration
rokubimini::ethercat::RokubiminiEthercatSlave::setAngularRateFilter
bool setAngularRateFilter(const unsigned int filter)
Sets an angular rate filter to the device.
Definition: RokubiminiEthercatSlave.cpp:145
rokubimini::calibration::SensorCalibration
rokubimini::ethercat::RokubiminiEthercatSlave::getSlaveStateString
std::string getSlaveStateString(uint8_t state)
Returns the EtherCAT State of the device in a string.
Definition: RokubiminiEthercatSlave.cpp:287
rokubimini::ethercat::RokubiminiEthercatSlave::firmwareUpdate
bool firmwareUpdate(const std::string &filePath, const std::string &fileName, const uint32_t &password)
Updates the firmware of the device.
Definition: RokubiminiEthercatSlave.cpp:525
rokubimini::soem_interface::EthercatSlaveBase
Base class for generic ethercat slaves using soem.
Definition: EthercatSlaveBase.hpp:19
rokubimini::ethercat::RokubiminiEthercatSlave::PdoInfos
std::map< PdoTypeEnum, PdoInfo > PdoInfos
Definition: RokubiminiEthercatSlave.hpp:516
rokubimini::ethercat::RokubiminiEthercatSlave::isRunning
bool isRunning()
Returns if the instance is running.
Definition: RokubiminiEthercatSlave.hpp:386
rokubimini::soem_interface::EthercatBusBase
Class for managing an ethercat bus containing one or multiple slaves.
Definition: EthercatBusBase.hpp:28
rokubimini::ethercat::RokubiminiEthercatSlave::getReading
void getReading(rokubimini::Reading &reading) const
Gets the internal reading variable.
Definition: RokubiminiEthercatSlave.cpp:427
PdoTypeEnum.hpp
rokubimini::ethercat::RokubiminiEthercatSlave::reading_
Reading reading_
The internal reading variable. It's used for providing to client code the sensor readings,...
Definition: RokubiminiEthercatSlave.hpp:562
rokubimini::Statusword
rokubimini::ethercat::RokubiminiEthercatSlave::setForceTorqueOffset
bool setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)
Sets a force torque offset to the device.
Definition: RokubiminiEthercatSlave.cpp:172
EC_STATE_OPERATIONAL
EC_STATE_OPERATIONAL
rokubimini::ethercat::RokubiminiEthercatSlave::runsAsync_
std::atomic< bool > runsAsync_
Definition: RokubiminiEthercatSlave.hpp:594


rokubimini_ethercat
Author(s):
autogenerated on Sat Apr 15 2023 02:53:56