Rokubimini.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <atomic>
4 #include <functional>
5 #include <mutex>
6 #include <string>
7 
8 #include <rokubimini/Reading.hpp>
14 
15 #include <ros/node_handle.h>
16 
17 namespace rokubimini
18 {
26 {
27 public:
28  using NodeHandlePtr = std::shared_ptr<ros::NodeHandle>;
29  using ReadingCb = std::function<void(const std::string&, const Reading&)>;
30  using ErrorCb = std::function<void(const std::string&)>;
31  using ErrorRecoveredCb = std::function<void(const std::string&)>;
32  using FatalCb = std::function<void(const std::string&)>;
33  using FatalRecoveredCb = std::function<void(const std::string&)>;
34  using DeviceDisconnectedCb = std::function<void(const std::string&)>;
35  using DeviceReconnectedCb = std::function<void(const std::string&)>;
36 
37  // Anonymous callbacks do not include the name of the device.
38  using AnonymousReadingCb = std::function<void(const Reading&)>;
39  using AnonymousErrorCb = std::function<void(void)>;
40 
47  Rokubimini() = default;
48  virtual ~Rokubimini() = default;
49 
57  std::string getName() const
58  {
59  return name_;
60  }
61 
70  {
71  return configuration_;
72  }
73 
82  {
83  return configuration_;
84  }
85 
94  bool loadRokubiminiSetup(std::shared_ptr<rokubimini::setup::Rokubimini> setup);
95 
104  void addReadingCb(const ReadingCb& readingCb, const int priority = 0)
105  {
106  readingCbs_.insert({ priority, readingCb });
107  }
108 
117  void addErrorCb(const ErrorCb& errorCb, const int priority = 0)
118  {
119  errorCbs_.insert({ priority, errorCb });
120  }
121 
130  void addErrorRecoveredCb(const ErrorRecoveredCb& errorRecoveredCb, const int priority = 0)
131  {
132  errorRecoveredCbs_.insert({ priority, errorRecoveredCb });
133  }
134 
143  void addFatalCb(const FatalCb& fatalCb, const int priority = 0)
144  {
145  fatalCbs_.insert({ priority, fatalCb });
146  }
147 
156  void addFatalRecoveredCb(const FatalRecoveredCb& fatalRecoveredCb, const int priority = 0)
157  {
158  fatalRecoveredCbs_.insert({ priority, fatalRecoveredCb });
159  }
160 
170  {
171  deviceDisconnectedCbs_.insert({ priority, deviceDisconnectedCb });
172  }
173 
183  {
184  deviceReconnectedCbs_.insert({ priority, deviceReconnectedCb });
185  }
186 
195 
205 
215  virtual void updateProcessReading() = 0;
216 
227  virtual void shutdownWithCommunication() = 0;
228 
239  virtual void shutdownWithoutCommunication(){ /* do nothing */ };
240 
249  void clearGoalStateEnum();
250 
257  void errorCb();
258 
265  void errorRecoveredCb();
266 
274  bool deviceIsInErrorState();
275 
282  void fatalCb();
283 
290  void fatalRecoveredCb();
291 
299  bool deviceIsInFatalState();
300 
307  void deviceDisconnectedCb();
308 
315  void deviceReconnectedCb();
316 
323  virtual bool deviceIsMissing() const = 0;
324 
334  {
335  return statusword_;
336  }
337 
348  virtual bool getSerialNumber(unsigned int& serialNumber) = 0;
349 
361  virtual bool getForceTorqueSamplingRate(int& samplingRate) = 0;
362 
374  virtual bool setForceTorqueFilter(const configuration::ForceTorqueFilter& filter) = 0;
375 
386  virtual bool setAccelerationFilter(const unsigned int filter) = 0;
387 
398  virtual bool setAngularRateFilter(const unsigned int filter) = 0;
399 
410  virtual bool setAccelerationRange(const unsigned int range) = 0;
411 
422  virtual bool setAngularRateRange(const unsigned int range) = 0;
423 
434  virtual bool setForceTorqueOffset(const Eigen::Matrix<double, 6, 1>& forceTorqueOffset) = 0;
435 
446  virtual bool setSensorConfiguration(const configuration::SensorConfiguration& sensorConfiguration) = 0;
447 
458  virtual bool setSensorCalibration(const calibration::SensorCalibration& sensorCalibration) = 0;
459 
469  virtual bool saveConfigParameter() = 0;
470 
478  Reading getReading() const;
479 
488  void getReading(Reading& reading) const;
489 
503  void setNodeHandle(const NodeHandlePtr& nh)
504  {
505  nh_ = nh;
506  }
507 
515  virtual void createRosPublishers() = 0;
516 
523  virtual void createRosServices() = 0;
524 
533  virtual void publishRosMessages() = 0;
534 
535 protected:
544  virtual void doStartupWithCommunication() = 0;
545 
556  void setStatusword(Statusword& statusword);
557 
564  static constexpr double NAN_VALUE = std::numeric_limits<double>::quiet_NaN();
565 
572  std::string name_;
573 
581 
589 
596  std::atomic<bool> statuswordRequested_{ false };
597 
604  mutable std::recursive_mutex readingMutex_;
605 
613 
621 
628  std::multimap<int, ReadingCb, std::greater<int>> readingCbs_;
629 
636  std::multimap<int, ErrorCb, std::greater<int>> errorCbs_;
637 
644  std::multimap<int, ErrorRecoveredCb, std::greater<int>> errorRecoveredCbs_;
645 
652  std::multimap<int, FatalCb, std::greater<int>> fatalCbs_;
653 
660  std::multimap<int, FatalRecoveredCb, std::greater<int>> fatalRecoveredCbs_;
661 
668  std::multimap<int, DeviceDisconnectedCb, std::greater<int>> deviceDisconnectedCbs_;
669 
676  std::multimap<int, DeviceReconnectedCb, std::greater<int>> deviceReconnectedCbs_;
677 };
678 
679 } // namespace rokubimini
virtual void updateProcessReading()=0
Updates the Rokubimini object with new measurements.
Class holding the force-torque filter settings.
virtual bool deviceIsMissing() const =0
Checks if the device is missing.
virtual bool getForceTorqueSamplingRate(int &samplingRate)=0
Gets the force torque sampling rate of the device. It&#39;s virtual since it&#39;s implementation-specific.
Class representing a rokubi mini device.
Definition: Rokubimini.hpp:25
bool deviceIsInErrorState()
Checks if the device is in error state.
Definition: Rokubimini.cpp:87
Class holding the configuration of the sensor.
std::multimap< int, FatalRecoveredCb, std::greater< int > > fatalRecoveredCbs_
Definition: Rokubimini.hpp:660
virtual bool setSensorCalibration(const calibration::SensorCalibration &sensorCalibration)=0
Sets a sensor calibration to the device. It&#39;s virtual since it&#39;s implementation-specific.
void deviceDisconnectedCb()
Calls the callbacks in the device disconnected callbacks list.
Definition: Rokubimini.cpp:116
std::function< void(const std::string &)> DeviceReconnectedCb
Definition: Rokubimini.hpp:35
Statusword statusword_
The current statusword.
Definition: Rokubimini.hpp:588
bool deviceIsInFatalState()
Checks if the device is in fatal state.
Definition: Rokubimini.cpp:110
void setStatusword(Statusword &statusword)
Sets the statusword of the device.
Definition: Rokubimini.cpp:181
static constexpr double NAN_VALUE
NaN abbreviation for convenience.
Definition: Rokubimini.hpp:564
std::function< void(const std::string &)> FatalCb
Definition: Rokubimini.hpp:32
std::function< void(const std::string &)> ErrorCb
Definition: Rokubimini.hpp:30
virtual bool setForceTorqueFilter(const configuration::ForceTorqueFilter &filter)=0
Sets a force torque filter to the device. It&#39;s virtual since it&#39;s implementation-specific.
void errorRecoveredCb()
Calls the callbacks in the error recovered callbacks list.
Definition: Rokubimini.cpp:78
bool loadRokubiminiSetup(std::shared_ptr< rokubimini::setup::Rokubimini > setup)
Loads the configuration of the device from the {Rokubimini Setup} provided.
Definition: Rokubimini.cpp:8
std::function< void(const std::string &)> FatalRecoveredCb
Definition: Rokubimini.hpp:33
NodeHandlePtr nh_
The node handle of the ROS node, used by the publishers.
Definition: Rokubimini.hpp:620
virtual bool setAccelerationRange(const unsigned int range)=0
Sets an acceleration range to the device. It&#39;s virtual since it&#39;s implementation-specific.
virtual void createRosServices()=0
Creates ROS services for the rokubimini device. It&#39;s virtual because it&#39;s implementation specific...
std::multimap< int, FatalCb, std::greater< int > > fatalCbs_
Definition: Rokubimini.hpp:652
virtual bool setAngularRateRange(const unsigned int range)=0
Sets an angular rate range to the device. It&#39;s virtual since it&#39;s implementation-specific.
Class representing the readings received from the rokubi mini devices.
Definition: Reading.hpp:35
void clearGoalStateEnum()
Clears the goal state enumeration.
Definition: Rokubimini.hpp:239
Class representing the different states the communication or the sensors can be in.
Definition: Statusword.hpp:20
void startupWithoutCommunication()
Starts up a Rokubimini device before communication has been established by the BusManager.
Definition: Rokubimini.cpp:61
std::function< void(const std::string &, const Reading &)> ReadingCb
Definition: Rokubimini.hpp:29
virtual ~Rokubimini()=default
const configuration::Configuration & getConfiguration() const
Gets the Configuration of the device.
Definition: Rokubimini.hpp:81
Statusword getStatusword() const
Gets the statusword of the device.
Definition: Rokubimini.hpp:333
std::string getName() const
Gets the name of the device.
Definition: Rokubimini.hpp:57
Class holding the sensor configuration settings.
The SensorCalibration class is used for holding the calibration information of each rokubi mini senso...
std::multimap< int, DeviceReconnectedCb, std::greater< int > > deviceReconnectedCbs_
Definition: Rokubimini.hpp:676
virtual void shutdownWithoutCommunication()
Definition: Rokubimini.hpp:239
configuration::Configuration configuration_
The Configuration of the device.
Definition: Rokubimini.hpp:580
void addErrorRecoveredCb(const ErrorRecoveredCb &errorRecoveredCb, const int priority=0)
Adds an error recovered callback to a list.
Definition: Rokubimini.hpp:130
std::function< void(const Reading &)> AnonymousReadingCb
Definition: Rokubimini.hpp:38
void deviceReconnectedCb()
Calls the callbacks in the device reconnected callbacks list.
Definition: Rokubimini.cpp:160
void addErrorCb(const ErrorCb &errorCb, const int priority=0)
Adds an error callback to a list.
Definition: Rokubimini.hpp:117
virtual void publishRosMessages()=0
Publishes ROS messages with data from the rokubimini device. It&#39;s virtual because it&#39;s implementation...
void errorCb()
Calls the callbacks in the error callbacks list.
Definition: Rokubimini.cpp:70
void addFatalRecoveredCb(const FatalRecoveredCb &fatalRecoveredCb, const int priority=0)
Adds an fatal recovered callback to a list.
Definition: Rokubimini.hpp:156
std::atomic< bool > statuswordRequested_
Flag indicating if a statusword has been actively requested.
Definition: Rokubimini.hpp:596
std::multimap< int, ErrorCb, std::greater< int > > errorCbs_
Definition: Rokubimini.hpp:636
std::multimap< int, DeviceDisconnectedCb, std::greater< int > > deviceDisconnectedCbs_
Definition: Rokubimini.hpp:668
void fatalCb()
Calls the callbacks in the fatal callbacks list.
Definition: Rokubimini.cpp:93
Reading reading_
The reading of the device.
Definition: Rokubimini.hpp:612
void setNodeHandle(const NodeHandlePtr &nh)
Sets the nodeHandle of the device.
Definition: Rokubimini.hpp:503
Reading getReading() const
Gets the reading from the Rokubimini device.
Definition: Rokubimini.cpp:169
void addFatalCb(const FatalCb &fatalCb, const int priority=0)
Adds an fatal callback to a list.
Definition: Rokubimini.hpp:143
void addDeviceDisconnectedCb(const DeviceDisconnectedCb &deviceDisconnectedCb, const int priority=0)
Adds a device disconnencted callback to a list.
Definition: Rokubimini.hpp:169
std::multimap< int, ErrorRecoveredCb, std::greater< int > > errorRecoveredCbs_
Definition: Rokubimini.hpp:644
virtual bool setAccelerationFilter(const unsigned int filter)=0
Sets an acceleration filter to the device. It&#39;s virtual since it&#39;s implementation-specific.
std::function< void(const std::string &)> DeviceDisconnectedCb
Definition: Rokubimini.hpp:34
void addDeviceReconnectedCb(const DeviceReconnectedCb &deviceReconnectedCb, const int priority=0)
Adds a device reconnected callback to a list.
Definition: Rokubimini.hpp:182
void fatalRecoveredCb()
Calls the callbacks in the fatal recovered callbacks list.
Definition: Rokubimini.cpp:101
virtual void shutdownWithCommunication()=0
Shuts down a Rokubimini device before communication has been closed.
void startupWithCommunication()
Starts up a Rokubimini device after communication has been established.
Definition: Rokubimini.cpp:15
virtual void doStartupWithCommunication()=0
std::multimap< int, ReadingCb, std::greater< int > > readingCbs_
Definition: Rokubimini.hpp:628
virtual bool setAngularRateFilter(const unsigned int filter)=0
Sets an angular rate filter to the device. It&#39;s virtual since it&#39;s implementation-specific.
virtual bool setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)=0
Sets a force torque offset to the device. It&#39;s virtual since it&#39;s implementation-specific.
virtual bool getSerialNumber(unsigned int &serialNumber)=0
Gets the serial number of the device. It&#39;s virtual since it&#39;s implementation-specific.
void addReadingCb(const ReadingCb &readingCb, const int priority=0)
Adds a reading callback to a list.
Definition: Rokubimini.hpp:104
configuration::Configuration & getConfiguration()
Non-const version of getConfiguration() const. Gets the Configuration of the device.
Definition: Rokubimini.hpp:69
std::string name_
The name of the device.
Definition: Rokubimini.hpp:572
std::function< void(const std::string &)> ErrorRecoveredCb
Definition: Rokubimini.hpp:31
virtual bool saveConfigParameter()=0
Saves the current configuration to the device. It&#39;s virtual since it&#39;s implementation-specific.
std::recursive_mutex readingMutex_
The mutex for accessing the reading.
Definition: Rokubimini.hpp:604
virtual void createRosPublishers()=0
Creates ROS publishers for the rokubimini device. It&#39;s virtual because it&#39;s implementation specific...
virtual bool setSensorConfiguration(const configuration::SensorConfiguration &sensorConfiguration)=0
Sets a sensor configuration to the device. It&#39;s virtual since it&#39;s implementation-specific.
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
Definition: Rokubimini.hpp:28
Rokubimini()=default
Default constructor.
Tests Configuration.
std::function< void(void)> AnonymousErrorCb
Definition: Rokubimini.hpp:39


rokubimini
Author(s):
autogenerated on Wed Mar 3 2021 03:09:12