The SensorCalibration class is used for holding the calibration information of each rokubi mini sensor.
More...
#include <SensorCalibration.hpp>
|
Eigen::Matrix< double, 6, 1 > | accelerationOffset_ |
| The matrix for the acceleration. More...
|
|
Eigen::Matrix< double, 6, 1 > | angularRateOffset_ |
| The offset matrix for the angular rate. More...
|
|
Eigen::Matrix< double, 6, 6 > | calibrationMatrix_ |
| The calibration matrix. More...
|
|
Eigen::Matrix< double, 6, 1 > | calibrationOffset_ |
| The calibration offset matrix. More...
|
|
Eigen::Matrix< double, 10, 1 > | inertia_ |
| The inertia matrix. More...
|
|
uint32_t | passphrase_ { 0x87654321 } |
| The passphrase. More...
|
|
Eigen::Matrix< double, 6, 1 > | temperatureGain_ |
| The temperature gain matrix. More...
|
|
Eigen::Matrix< double, 2, 1 > | thermistorCalibration_ |
| The thermistor calibration matrix. More...
|
|
The SensorCalibration class is used for holding the calibration information of each rokubi mini sensor.
Definition at line 16 of file SensorCalibration.hpp.
rokubimini::calibration::SensorCalibration::SensorCalibration |
( |
| ) |
|
|
default |
rokubimini::calibration::SensorCalibration::~SensorCalibration |
( |
| ) |
|
|
default |
const Eigen::Matrix< double, 6, 6 > & rokubimini::calibration::SensorCalibration::getCalibrationMatrix |
( |
| ) |
const |
|
inline |
Eigen::Matrix< double, 6, 6 > & rokubimini::calibration::SensorCalibration::getCalibrationMatrix |
( |
| ) |
|
|
inline |
const uint32_t rokubimini::calibration::SensorCalibration::getPassPhrase |
( |
| ) |
const |
|
inline |
bool rokubimini::calibration::SensorCalibration::load |
( |
const std::string & |
key, |
|
|
NodeHandlePtr |
nh |
|
) |
| |
Loads the calibrations from the parameter server.
- Parameters
-
key | The key to search in the parameter server. |
nh | The ROS NodeHandle to access the parameter server. |
- Returns
- True if the calibrations were loaded successfully.
Definition at line 7 of file SensorCalibration.cpp.
void rokubimini::calibration::SensorCalibration::setCalibrationMatrix |
( |
const Eigen::Matrix< double, 6, 6 > & |
calibrationMatrix | ) |
|
|
inline |
Sets the calibration matrix.
- Parameters
-
calibrationMatrix | The calibration matrix. |
Definition at line 96 of file SensorCalibration.hpp.
void rokubimini::calibration::SensorCalibration::setPassPhrase |
( |
const uint32_t |
passphrase | ) |
|
|
inline |
Sets the passphrase.
- Parameters
-
passphrase | The passphrase to be set. |
Definition at line 60 of file SensorCalibration.hpp.
Eigen::Matrix< double, 6, 1 > rokubimini::calibration::SensorCalibration::accelerationOffset_ |
|
private |
Eigen::Matrix< double, 6, 1 > rokubimini::calibration::SensorCalibration::angularRateOffset_ |
|
private |
Eigen::Matrix< double, 6, 6 > rokubimini::calibration::SensorCalibration::calibrationMatrix_ |
|
private |
Eigen::Matrix< double, 6, 1 > rokubimini::calibration::SensorCalibration::calibrationOffset_ |
|
private |
Eigen::Matrix< double, 10, 1 > rokubimini::calibration::SensorCalibration::inertia_ |
|
private |
uint32_t rokubimini::calibration::SensorCalibration::passphrase_ { 0x87654321 } |
|
private |
Eigen::Matrix< double, 6, 1 > rokubimini::calibration::SensorCalibration::temperatureGain_ |
|
private |
Eigen::Matrix< double, 2, 1 > rokubimini::calibration::SensorCalibration::thermistorCalibration_ |
|
private |
The documentation for this class was generated from the following files: