Configuration.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <climits>
4 #include <mutex>
5 #include <string>
6 
7 // #define EIGEN_INITIALIZE_MATRICES_BY_NAN
8 
12 #include <eigen3/Eigen/Core>
13 
14 namespace rokubimini
15 {
16 namespace configuration
17 {
25 {
26 public:
27  using NodeHandlePtr = std::shared_ptr<ros::NodeHandle>;
34  Configuration() = default;
35 
42  Configuration(const Configuration& other);
43  virtual ~Configuration() = default;
44 
51  Configuration& operator=(const Configuration& other);
52 
62  void load(const std::string& key, NodeHandlePtr nh);
63 
71  void setSetReadingToNanOnDisconnect(const bool setReadingToNanOnDisconnect);
72 
81  bool getSetReadingToNanOnDisconnect() const;
82 
90  void setForceTorqueFilter(const ForceTorqueFilter& forceTorqueFilter);
91 
100 
108  void setForceTorqueOffset(const Eigen::Matrix<double, 6, 1>& forceTorqueOffset);
109 
117  const Eigen::Matrix<double, 6, 1>& getForceTorqueOffset() const;
118 
126  void setUseCustomCalibration(const bool useCustomCalibration);
127 
135  bool getUseCustomCalibration() const;
136 
144  void setSensorConfiguration(const SensorConfiguration& sensorConfiguration);
145 
154 
162  void setSensorCalibration(const calibration::SensorCalibration& sensorCalibration);
163 
172 
180  void setImuAccelerationFilter(const unsigned int imuAccelerationFilter);
181 
189  unsigned int getImuAccelerationFilter() const;
190 
198  void setImuAngularRateFilter(const unsigned int imuAngularRateFilter);
199 
207  unsigned int getImuAngularRateFilter() const;
208 
216  void setImuAccelerationRange(const uint8_t imuAccelerationRange);
217 
225  uint8_t getImuAccelerationRange() const;
226 
234  void setImuAngularRateRange(const uint8_t imuAngularRateRange);
235 
243  uint8_t getImuAngularRateRange() const;
244 
252  void setSaveConfiguration(const bool saveConfiguration);
253 
261  bool getSaveConfiguration() const;
262 
272  bool hasImuAngularRateRange() const;
273 
284  bool hasSetReadingToNanOnDisconnect() const;
285 
296  bool hasSensorConfiguration() const;
297 
308  bool hasForceTorqueFilter() const;
309 
319  bool hasForceTorqueOffset() const;
320 
330  bool hasUseCustomCalibration() const;
331 
342  bool hasSensorCalibration() const;
343 
354  bool hasImuAccelerationRange() const;
355 
366  bool hasImuAccelerationFilter() const;
367 
378  bool hasImuAngularRateFilter() const;
379 
390  bool hasSaveConfiguration() const;
397  void printConfiguration() const;
398 
399 protected:
406  mutable std::recursive_mutex mutex_;
407 
415 
423 
431 
439 
447 
455 
463 
471 
479 
487 
495 
503 
510  unsigned int imuAngularRateFilter_;
511 
519 
526  unsigned int imuAccelerationRange_;
527 
535 
542  unsigned int imuAngularRateRange_;
543 
551 
558  Eigen::Matrix<double, 6, 1> forceTorqueOffset_;
559 
567 
575 
583 };
584 
585 } // namespace configuration
586 
587 } // namespace rokubimini
bool hasForceTorqueOffset() const
Checks if the value of the forceTorqueOffset_ variable has been set by the user in the configuration ...
bool hasImuAccelerationRange() const
Checks if the value of the imuAccelerationRange_ variable has been set by the user in the configurati...
void setUseCustomCalibration(const bool useCustomCalibration)
Sets the useCustomCalibration variable.
Class holding the force-torque filter settings.
bool hasSetReadingToNanOnDisconnect() const
Checks if the value of the setReadingToNanOnDisconnect_ variable has been set by the user in the conf...
bool getSetReadingToNanOnDisconnect() const
Gets the setReadingToNanOnDisconnect variable.
Eigen::Matrix< double, 6, 1 > forceTorqueOffset_
The forceTorqueOffset variable.
std::recursive_mutex mutex_
Mutex for synchronized access on the object&#39;s private variables.
bool hasForceTorqueFilter() const
Checks if the value of the forceTorqueFilter_ variable has been set by the user in the configuration ...
bool hasSensorCalibration() const
Checks if the value of the sensorCalibration_ variable has been set by the user in the configuration ...
Class holding the configuration of the sensor.
Configuration()=default
Default constructor.
bool hasForceTorqueOffset_
Flag indicating if forceTorqueOffset_ is set.
bool hasImuAngularRateFilter_
Flag indicating if imuAngularRateFilter_ is set.
SensorConfiguration sensorConfiguration_
The sensorConfiguration variable.
const ForceTorqueFilter & getForceTorqueFilter() const
Gets the forceTorqueFilter variable.
bool hasSensorConfiguration_
Flag indicating if sensorConfiguration_ is set.
bool hasUseCustomCalibration_
Flag indicating if useCustomCalibration_ is set.
void setImuAccelerationRange(const uint8_t imuAccelerationRange)
Sets the imuAccelerationRange variable.
void setImuAngularRateRange(const uint8_t imuAngularRateRange)
Sets the imuAngularRateRange variable.
bool hasImuAngularRateFilter() const
Checks if the value of the imuAngularRateFilter_ variable has been set by the user in the configurati...
bool hasImuAccelerationRange_
Flag indicating if imuAccelerationRange_ is set.
void setSensorConfiguration(const SensorConfiguration &sensorConfiguration)
Sets the sensorConfiguration variable.
bool hasSensorConfiguration() const
Checks if the value of the sensorConfiguration_ variable has been set by the user in the configuratio...
const Eigen::Matrix< double, 6, 1 > & getForceTorqueOffset() const
Gets the forceTorqueOffset variable.
bool hasImuAngularRateRange() const
Checks if the value of the imuAngularRateRange_ variable has been set by the user in the configuratio...
unsigned int imuAngularRateFilter_
The imuAngularRateFilter variable.
bool getUseCustomCalibration() const
Gets the useCustomCalibration variable.
bool hasSetReadingToNanOnDisconnect_
Flag indicating if setReadingToNanOnDisconnect_ is set.
bool getSaveConfiguration() const
Gets the saveConfiguration variable.
calibration::SensorCalibration sensorCalibration_
The sensorCalibration variable.
unsigned int getImuAngularRateFilter() const
Gets the imuAccelerationFilter variable.
Class holding the sensor configuration settings.
bool hasSaveConfiguration() const
Checks if the value of the saveConfiguration_ variable has been set by the user in the configuration ...
bool saveConfiguration_
The saveConfiguration_ variable.
bool hasImuAccelerationFilter_
Flag indicating if imuAccelerationFilter_ is set.
The SensorCalibration class is used for holding the calibration information of each rokubi mini senso...
bool hasImuAngularRateRange_
Flag indicating if imuAngularRateRange_ is set.
bool hasUseCustomCalibration() const
Checks if the value of the useCustomCalibration_ variable has been set by the user in the configurati...
uint8_t getImuAccelerationRange() const
Gets the imuAccelerationRange variable.
void setForceTorqueFilter(const ForceTorqueFilter &forceTorqueFilter)
Sets the forceTorqueFilter variable.
bool hasSaveConfiguration_
Flag indicating if saveConfiguration_ is set.
void load(const std::string &key, NodeHandlePtr nh)
Loads the configuration from the parameter server.
void setImuAccelerationFilter(const unsigned int imuAccelerationFilter)
Sets the imuAccelerationFilter variable.
void setSetReadingToNanOnDisconnect(const bool setReadingToNanOnDisconnect)
Sets the setReadingToNanOnDisconnect variable.
const calibration::SensorCalibration & getSensorCalibration() const
Gets the sensorCalibration variable.
unsigned int getImuAccelerationFilter() const
uint8_t getImuAngularRateRange() const
Gets the imuAngularRateRange variable.
unsigned int imuAccelerationRange_
The imuAccelerationRange variable.
bool setReadingToNanOnDisconnect_
The setReadingToNanOnDisconnect variable.
bool hasForceTorqueFilter_
Flag indicating if forceTorqueFilter_ is set.
ForceTorqueFilter forceTorqueFilter_
The forceTorqueFilter variable.
void printConfiguration() const
Prints the existing Configuration.
void setSensorCalibration(const calibration::SensorCalibration &sensorCalibration)
Sets the sensorCalibration variable.
unsigned int imuAccelerationFilter_
The imuAccelerationFilter variable.
unsigned int imuAngularRateRange_
The imuAngularRateRange variable.
bool useCustomCalibration_
The useCustomCalibration variable.
bool hasImuAccelerationFilter() const
Checks if the value of the imuAccelerationFilter_ variable has been set by the user in the configurat...
void setForceTorqueOffset(const Eigen::Matrix< double, 6, 1 > &forceTorqueOffset)
Sets the forceTorqueOffset variable.
void setSaveConfiguration(const bool saveConfiguration)
Sets the saveConfiguration variable.
bool hasSensorCalibration_
Flag indicating if sensorCalibration_ is set.
Configuration & operator=(const Configuration &other)
Assignment operator for Configuration.
void setImuAngularRateFilter(const unsigned int imuAngularRateFilter)
Sets the imuAngularRateFilter variable.
const SensorConfiguration & getSensorConfiguration() const
Gets the sensorConfiguration variable.
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
Tests Configuration.


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