RokubiminiEthercat.hpp
Go to the documentation of this file.
1 #pragma once
2 
5 #include <rokubimini_msgs/FirmwareUpdateEthercat.h>
6 #include <rokubimini_msgs/ResetWrench.h>
7 
8 namespace rokubimini
9 {
10 namespace ethercat
11 {
25 {
26 public:
35  RokubiminiEthercat() = default;
36  ~RokubiminiEthercat() override = default;
37 
48  void doStartupWithCommunication() override;
49 
59  void updateProcessReading() override;
60 
68  bool deviceIsMissing() const override;
69 
81  void shutdownWithCommunication() override;
82 
98  {
99  slavePtr_ = slavePtr;
100  }
101 
112  void setState(const uint16_t state)
113  {
114  slavePtr_->setState(state);
115  }
116 
128  {
129  return slavePtr_->waitForState(state);
130  }
131 
142  // Missing: Methods for calling SDO
143  bool getSerialNumber(unsigned int& samplingRate) override;
144 
157  bool getForceTorqueSamplingRate(int& samplingRate) override;
158 
171  bool setForceTorqueFilter(const configuration::ForceTorqueFilter& filter) override;
172 
184  bool setAccelerationFilter(const unsigned int filter) override;
185 
197  bool setAngularRateFilter(const unsigned int filter) override;
198 
210  bool setAccelerationRange(const unsigned int range) override;
211 
223  bool setAngularRateRange(const unsigned int range) override;
224 
236  bool setForceTorqueOffset(const Eigen::Matrix<double, 6, 1>& forceTorqueOffset) override;
237 
249  bool setSensorConfiguration(const configuration::SensorConfiguration& sensorConfiguration) override;
250 
262  bool setSensorCalibration(const calibration::SensorCalibration& sensorCalibration) override;
263 
271  bool setConfigMode();
272 
280  bool setRunMode();
290  bool saveConfigParameter() override;
291 
298  void createRosPublishers() override;
299 
306  void signalShutdown();
307 
318  bool firmwareUpdateCallback(rokubimini_msgs::FirmwareUpdateEthercat::Request& request,
319  rokubimini_msgs::FirmwareUpdateEthercat::Response& response);
320 
331  bool resetWrenchCallback(rokubimini_msgs::ResetWrench::Request& request,
332  rokubimini_msgs::ResetWrench::Response& response);
339  void createRosServices() override;
340 
348  void publishRosMessages() override;
349 
364  template <typename Value>
365  bool sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess, Value& value);
366 
380  bool sendSdoReadGeneric(const std::string& indexString, const std::string& subindexString,
381  const std::string& valueTypeString, std::string& valueString);
382 
396  template <typename Value>
397  bool sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value);
398 
413  bool sendSdoWriteGeneric(const std::string& indexString, const std::string& subindexString,
414  const std::string& valueTypeString, const std::string& valueString);
415 
416 protected:
425 
426  using RosPublisherPtr = std::shared_ptr<ros::Publisher>;
427 
436 
444 
452 
460 
468 
476 
484  std::atomic<bool> computeMeanWrenchFlag_{ false };
485 
493  std::atomic<uint32_t> wrenchMessageCount_{ 0 };
494 
501  mutable std::recursive_mutex meanWrenchOffsetMutex_;
502 
511 
518  geometry_msgs::Wrench meanWrenchOffset_;
519 };
520 
521 template <>
522 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
523  int8_t& value);
524 template <>
525 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
526  int16_t& value);
527 template <>
528 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
529  int32_t& value);
530 template <>
531 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
532  int64_t& value);
533 template <>
534 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
535  uint8_t& value);
536 template <>
537 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
538  uint16_t& value);
539 template <>
540 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
541  uint32_t& value);
542 template <>
543 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
544  uint64_t& value);
545 template <>
546 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
547  float& value);
548 template <>
549 bool RokubiminiEthercat::sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess,
550  double& value);
551 
552 template <>
553 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
554  const int8_t value);
555 template <>
556 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
557  const int16_t value);
558 template <>
559 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
560  const int32_t value);
561 template <>
562 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
563  const int64_t value);
564 template <>
565 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
566  const uint8_t value);
567 template <>
568 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
569  const uint16_t value);
570 template <>
571 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
572  const uint32_t value);
573 template <>
574 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
575  const uint64_t value);
576 template <>
577 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
578  const float value);
579 template <>
580 bool RokubiminiEthercat::sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess,
581  const double value);
582 
583 } // namespace ethercat
584 } // namespace rokubimini
void shutdownWithCommunication() override
Shuts down a Rokubimini Ethercat device before communication has been closed.
std::shared_ptr< ros::Publisher > RosPublisherPtr
void setState(const uint16_t state)
Sets the desired EtherCAT state machine state of the device in the bus.
std::atomic< uint32_t > wrenchMessageCount_
The counter that is used for the computation of the mean of the wrench measurements. Used for the "reset service" callback.
void createRosPublishers() override
Adds ROS publishers related to the device.
RokubiminiEthercatSlavePtr slavePtr_
The pointer to implementation.
bool saveConfigParameter() override
Saves the current configuration to the device.
bool sendSdoReadGeneric(const std::string &indexString, const std::string &subindexString, const std::string &valueTypeString, std::string &valueString)
Sends a generic reading SDO to the Ethercat device.
void signalShutdown()
Signals shutdown for the ROS node. It&#39;s used if a firmware update was successful. ...
unsigned short uint16_t
bool setAccelerationRange(const unsigned int range) override
Sets an acceleration range to the device.
bool resetWrenchCallback(rokubimini_msgs::ResetWrench::Request &request, rokubimini_msgs::ResetWrench::Response &response)
The callback for the reset wrench ROS service.
unsigned char uint8_t
bool setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset) override
Sets a force torque offset to the device.
bool setForceTorqueFilter(const configuration::ForceTorqueFilter &filter) override
Sets a force torque filter to the device.
bool sendSdoWrite(const uint16_t index, const uint8_t subindex, const bool completeAccess, const Value value)
RosPublisherPtr readingPublisher_
The rokubimini_msgs::Reading publisher.
bool setSensorCalibration(const calibration::SensorCalibration &sensorCalibration) override
Sets a sensor calibration to the device.
bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration) override
Sets a sensor configuration to the device.
bool firmwareUpdateCallback(rokubimini_msgs::FirmwareUpdateEthercat::Request &request, rokubimini_msgs::FirmwareUpdateEthercat::Response &response)
The callback for the firmware update ROS service.
void updateProcessReading() override
Updates the RokubiminiEthercat object with new measurements.
bool setAngularRateFilter(const unsigned int filter) override
Sets an angular rate filter to the device.
bool setAccelerationFilter(const unsigned int filter) override
Sets an acceleration filter to the device.
RosPublisherPtr imuPublisher_
The sensor_msgs::Imu publisher.
bool getForceTorqueSamplingRate(int &samplingRate) override
Gets the force torque sampling rate of the device.
unsigned int uint32_t
signed short int16_t
ros::ServiceServer resetWrenchService_
The service for resetting the sensor wrench measurements.
bool waitForState(const uint16_t state)
Wait for an EtherCAT state machine state to be reached.
unsigned __int64 uint64_t
RokubiminiEthercat()=default
Default constructor.
bool sendSdoWriteGeneric(const std::string &indexString, const std::string &subindexString, const std::string &valueTypeString, const std::string &valueString)
Sends a generic write SDO to the Ethercat device.
signed char int8_t
void createRosServices() override
Adds ROS services related to the device.
std::shared_ptr< RokubiminiEthercatSlave > RokubiminiEthercatSlavePtr
bool setConfigMode()
Sets the device in config mode.
bool setRunMode()
Sets the device in run mode.
void setSlavePointer(const RokubiminiEthercatSlavePtr &slavePtr)
Sets a pointer to the implementation.
std::atomic< bool > computeMeanWrenchFlag_
The flag for enabling the computation of the mean of the wrench measurements. Used withing the "reset...
std::recursive_mutex meanWrenchOffsetMutex_
The mutex for accessing the mean of the wrench measurements. Used for the "reset service" callback...
RosPublisherPtr wrenchPublisher_
The sensor_msgs::Wrench publisher.
ros::ServiceServer firmwareUpdateService_
The service for firmware updates.
bool deviceIsMissing() const override
Checks if the device is missing.
signed __int64 int64_t
bool getSerialNumber(unsigned int &samplingRate) override
Gets the serial number of the device.
RosPublisherPtr temperaturePublisher_
The sensor_msgs::Temperature publisher.
bool sendSdoRead(const uint16_t index, const uint8_t subindex, const bool completeAccess, Value &value)
uint8_t state
signed int int32_t
geometry_msgs::Wrench meanWrenchOffset_
The computed mean wrench offset. Used for the "reset service" callback.
void publishRosMessages() override
Publishes ROS messages with data from the rokubimini device.
bool setAngularRateRange(const unsigned int range) override
Sets an angular rate range to the device.


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