SensorCalibration.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <eigen3/Eigen/Core>
4 #include <ros/ros.h>
5 
6 namespace rokubimini
7 {
8 namespace calibration
9 {
17 {
18 public:
19  using NodeHandlePtr = std::shared_ptr<ros::NodeHandle>;
28  SensorCalibration() = default;
29  ~SensorCalibration() = default;
30 
39  bool load(const std::string& key, NodeHandlePtr nh);
40 
48  const uint32_t getPassPhrase() const
49  {
50  return passphrase_;
51  }
52 
60  void setPassPhrase(const uint32_t passphrase)
61  {
62  passphrase_ = passphrase;
63  }
64 
72  const Eigen::Matrix<double, 6, 6>& getCalibrationMatrix() const
73  {
74  return calibrationMatrix_;
75  }
76 
84  Eigen::Matrix<double, 6, 6>& getCalibrationMatrix()
85  {
86  return calibrationMatrix_;
87  }
88 
96  void setCalibrationMatrix(const Eigen::Matrix<double, 6, 6>& calibrationMatrix)
97  {
98  calibrationMatrix_ = calibrationMatrix;
99  }
100 
101 private:
106  uint32_t passphrase_{ 0x87654321 };
107 
112  Eigen::Matrix<double, 6, 6> calibrationMatrix_;
113 
120  // double calibrationTemperature_{ 0.0 };
121 
126  Eigen::Matrix<double, 6, 1> calibrationOffset_;
127 
134  // uint8_t adcRange_{ 0 };
135 
140  Eigen::Matrix<double, 2, 1> thermistorCalibration_;
141 
147  Eigen::Matrix<double, 6, 1> temperatureGain_;
148 
155  Eigen::Matrix<double, 6, 1> accelerationOffset_;
156 
163  Eigen::Matrix<double, 6, 1> angularRateOffset_;
164 
171  Eigen::Matrix<double, 10, 1> inertia_;
172 
179  // uint32_t calibrationDate_{ 0 };
180 
188  // uint8_t serialNumber_{ 0 };
189 
196  // uint8_t firmwareVersion_{ 0 };
197 };
198 
199 } // namespace calibration
200 } // namespace rokubimini
Eigen::Matrix< double, 2, 1 > thermistorCalibration_
The thermistor calibration matrix.
Eigen::Matrix< double, 6, 6 > & getCalibrationMatrix()
Non-const version of getCalibrationMatrix() const. Gets the calibration matrix.
Eigen::Matrix< double, 6, 1 > accelerationOffset_
The matrix for the acceleration.
Eigen::Matrix< double, 10, 1 > inertia_
The inertia matrix.
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
The SensorCalibration class is used for holding the calibration information of each rokubi mini senso...
void setPassPhrase(const uint32_t passphrase)
Sets the passphrase.
Eigen::Matrix< double, 6, 6 > calibrationMatrix_
The calibration matrix.
bool load(const std::string &key, NodeHandlePtr nh)
Loads the calibrations from the parameter server.
const uint32_t getPassPhrase() const
Gets the passphrase.
Eigen::Matrix< double, 6, 1 > temperatureGain_
The temperature gain matrix.
Eigen::Matrix< double, 6, 1 > calibrationOffset_
The calibration offset matrix.
void setCalibrationMatrix(const Eigen::Matrix< double, 6, 6 > &calibrationMatrix)
Sets the calibration matrix.
Eigen::Matrix< double, 6, 1 > angularRateOffset_
The offset matrix for the angular rate.
const Eigen::Matrix< double, 6, 6 > & getCalibrationMatrix() const
Gets the calibration matrix.
SensorCalibration()=default
Default constructor.
Tests Configuration.


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