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, const 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
rokubimini::calibration::SensorCalibration::setCalibrationMatrix
void setCalibrationMatrix(const Eigen::Matrix< double, 6, 6 > &calibrationMatrix)
Sets the calibration matrix.
Definition: SensorCalibration.hpp:96
rokubimini::calibration::SensorCalibration::calibrationMatrix_
Eigen::Matrix< double, 6, 6 > calibrationMatrix_
The calibration matrix.
Definition: SensorCalibration.hpp:112
rokubimini::calibration::SensorCalibration::passphrase_
uint32_t passphrase_
The passphrase.
Definition: SensorCalibration.hpp:106
rokubimini::calibration::SensorCalibration::getCalibrationMatrix
const Eigen::Matrix< double, 6, 6 > & getCalibrationMatrix() const
Gets the calibration matrix.
Definition: SensorCalibration.hpp:72
ros.h
rokubimini::calibration::SensorCalibration::getCalibrationMatrix
Eigen::Matrix< double, 6, 6 > & getCalibrationMatrix()
Definition: SensorCalibration.hpp:84
rokubimini::calibration::SensorCalibration::temperatureGain_
Eigen::Matrix< double, 6, 1 > temperatureGain_
The temperature gain matrix.
Definition: SensorCalibration.hpp:147
rokubimini::calibration::SensorCalibration::calibrationOffset_
Eigen::Matrix< double, 6, 1 > calibrationOffset_
The calibration offset matrix.
Definition: SensorCalibration.hpp:126
rokubimini::calibration::SensorCalibration::angularRateOffset_
Eigen::Matrix< double, 6, 1 > angularRateOffset_
The offset matrix for the angular rate.
Definition: SensorCalibration.hpp:163
rokubimini::calibration::SensorCalibration::getPassPhrase
const uint32_t getPassPhrase() const
Gets the passphrase.
Definition: SensorCalibration.hpp:48
rokubimini::calibration::SensorCalibration::SensorCalibration
SensorCalibration()=default
Default constructor.
rokubimini::calibration::SensorCalibration::~SensorCalibration
~SensorCalibration()=default
rokubimini::calibration::SensorCalibration::load
bool load(const std::string &key, const NodeHandlePtr &nh)
Loads the calibrations from the parameter server.
Definition: SensorCalibration.cpp:7
rokubimini
Tests Configuration.
Definition: ForceTorqueCalibration.hpp:5
rokubimini::calibration::SensorCalibration::thermistorCalibration_
Eigen::Matrix< double, 2, 1 > thermistorCalibration_
The thermistor calibration matrix.
Definition: SensorCalibration.hpp:140
rokubimini::calibration::SensorCalibration::NodeHandlePtr
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
Definition: SensorCalibration.hpp:19
rokubimini::calibration::SensorCalibration::accelerationOffset_
Eigen::Matrix< double, 6, 1 > accelerationOffset_
The matrix for the acceleration.
Definition: SensorCalibration.hpp:155
rokubimini::calibration::SensorCalibration::setPassPhrase
void setPassPhrase(const uint32_t passphrase)
Sets the passphrase.
Definition: SensorCalibration.hpp:60
rokubimini::calibration::SensorCalibration
The SensorCalibration class is used for holding the calibration information of each rokubi mini senso...
Definition: SensorCalibration.hpp:16
rokubimini::calibration::SensorCalibration::inertia_
Eigen::Matrix< double, 10, 1 > inertia_
The inertia matrix.
Definition: SensorCalibration.hpp:171


rokubimini
Author(s):
autogenerated on Sat Apr 15 2023 02:53:52