SensorConfiguration.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <cstdint>
4 #include <ros/console.h>
5 #include <ros/node_handle.h>
6 
7 namespace rokubimini
8 {
9 namespace configuration
10 {
18 {
19 public:
20  using NodeHandlePtr = std::shared_ptr<ros::NodeHandle>;
27  SensorConfiguration() = default;
28 
44  SensorConfiguration(const uint8_t calibrationMatrixActive, const uint8_t temperatureCompensationActive,
45  const uint8_t imuActive, const uint8_t coordinateSystemConfigurationActive,
46  const uint8_t inertiaCompensationActive, const uint8_t orientationEstimationActive);
47 
48  ~SensorConfiguration() = default;
49 
59  bool load(const std::string& key, NodeHandlePtr nh);
60 
69  {
71  }
72 
80  void setCalibrationMatrixActive(const uint8_t calibrationMatrixActive)
81  {
82  calibrationMatrixActive_ = calibrationMatrixActive;
83  }
84 
93  {
95  }
96 
104  void setTemperatureCompensationActive(const uint8_t temperatureCompensationActive)
105  {
106  temperatureCompensationActive_ = temperatureCompensationActive;
107  }
108 
116  uint8_t getImuActive() const
117  {
118  return imuActive_;
119  }
120 
128  void setImuActive(const uint8_t imuActive)
129  {
130  imuActive_ = imuActive;
131  }
132 
141  {
143  }
144 
152  void setCoordinateSystemConfigurationActive(const uint8_t coordinateSystemConfigurationActive)
153  {
154  coordinateSystemConfigurationActive_ = coordinateSystemConfigurationActive;
155  }
156 
165  {
167  }
168 
176  void setInertiaCompensationActive(const uint8_t inertiaCompensationActive)
177  {
178  inertiaCompensationActive_ = inertiaCompensationActive;
179  }
180 
189  {
191  }
192 
200  void setOrientationEstimationActive(const uint8_t orientationEstimationActive)
201  {
202  orientationEstimationActive_ = orientationEstimationActive;
203  }
204 
211  void print() const;
212 
213 private:
221 
229 
236  uint8_t imuActive_;
237 
245 
253 
261 };
262 
263 } // namespace configuration
264 } // namespace rokubimini
void setCoordinateSystemConfigurationActive(const uint8_t coordinateSystemConfigurationActive)
Sets the coordinateSystemConfigurationActive variable.
void setTemperatureCompensationActive(const uint8_t temperatureCompensationActive)
Sets the temperatureCompensationActive variable.
uint8_t getTemperatureCompensationActive() const
Gets the temperatureCompensationActive variable.
void setImuActive(const uint8_t imuActive)
Sets the imuActive variable.
void print() const
Prints the existing sensor configuration settings.
uint8_t getInertiaCompensationActive() const
Gets the inertiaCompensationActive variable.
void setCalibrationMatrixActive(const uint8_t calibrationMatrixActive)
Sets the calibrationMatrixActive variable.
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
Class holding the sensor configuration settings.
uint8_t getCoordinateSystemConfigurationActive() const
Gets the coordinateSystemConfigurationActive variable.
uint8_t getOrientationEstimationActive() const
Gets the orientationEstimationActive variable.
void setOrientationEstimationActive(const uint8_t orientationEstimationActive)
Sets the orientationEstimationActive variable.
uint8_t getCalibrationMatrixActive() const
Gets the calibrationMatrixActive variable.
void setInertiaCompensationActive(const uint8_t inertiaCompensationActive)
Sets the inertiaCompensationActive variable.
bool load(const std::string &key, NodeHandlePtr nh)
Loads the sensor configuration from the parameter server.
SensorConfiguration()=default
Default constructor.
uint8_t getImuActive() const
Gets the imuActive variable.
Tests Configuration.


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