3 #include <eigen3/Eigen/Core> ~SensorCalibration()=default
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.
uint32_t passphrase_
The passphrase.
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.