Public Types | Public Member Functions | Private Attributes | List of all members
rokubimini::calibration::SensorCalibration Class Reference

The SensorCalibration class is used for holding the calibration information of each rokubi mini sensor. More...

#include <SensorCalibration.hpp>

Public Types

using NodeHandlePtr = std::shared_ptr< ros::NodeHandle >
 

Public Member Functions

const Eigen::Matrix< double, 6, 6 > & getCalibrationMatrix () const
 Gets the calibration matrix. More...
 
Eigen::Matrix< double, 6, 6 > & getCalibrationMatrix ()
 Non-const version of getCalibrationMatrix() const. Gets the calibration matrix. More...
 
const uint32_t getPassPhrase () const
 Gets the passphrase. More...
 
bool load (const std::string &key, NodeHandlePtr nh)
 Loads the calibrations from the parameter server. More...
 
 SensorCalibration ()=default
 Default constructor. More...
 
void setCalibrationMatrix (const Eigen::Matrix< double, 6, 6 > &calibrationMatrix)
 Sets the calibration matrix. More...
 
void setPassPhrase (const uint32_t passphrase)
 Sets the passphrase. More...
 
 ~SensorCalibration ()=default
 

Private Attributes

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...
 

Detailed Description

The SensorCalibration class is used for holding the calibration information of each rokubi mini sensor.

Definition at line 16 of file SensorCalibration.hpp.

Member Typedef Documentation

Definition at line 19 of file SensorCalibration.hpp.

Constructor & Destructor Documentation

rokubimini::calibration::SensorCalibration::SensorCalibration ( )
default

Default constructor.

This method constructs a SensorCalibration.

rokubimini::calibration::SensorCalibration::~SensorCalibration ( )
default

Member Function Documentation

const Eigen::Matrix< double, 6, 6 > & rokubimini::calibration::SensorCalibration::getCalibrationMatrix ( ) const
inline

Gets the calibration matrix.

Returns
The calibration matrix.

Definition at line 72 of file SensorCalibration.hpp.

Eigen::Matrix< double, 6, 6 > & rokubimini::calibration::SensorCalibration::getCalibrationMatrix ( )
inline

Non-const version of getCalibrationMatrix() const. Gets the calibration matrix.

Returns
The calibration matrix.

Definition at line 84 of file SensorCalibration.hpp.

const uint32_t rokubimini::calibration::SensorCalibration::getPassPhrase ( ) const
inline

Gets the passphrase.

Returns
The passphrase.

Definition at line 48 of file SensorCalibration.hpp.

bool rokubimini::calibration::SensorCalibration::load ( const std::string &  key,
NodeHandlePtr  nh 
)

Loads the calibrations from the parameter server.

Parameters
keyThe key to search in the parameter server.
nhThe 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
calibrationMatrixThe calibration matrix.

Definition at line 96 of file SensorCalibration.hpp.

void rokubimini::calibration::SensorCalibration::setPassPhrase ( const uint32_t  passphrase)
inline

Sets the passphrase.

Parameters
passphraseThe passphrase to be set.

Definition at line 60 of file SensorCalibration.hpp.

Member Data Documentation

Eigen::Matrix< double, 6, 1 > rokubimini::calibration::SensorCalibration::accelerationOffset_
private

The matrix for the acceleration.

Definition at line 155 of file SensorCalibration.hpp.

Eigen::Matrix< double, 6, 1 > rokubimini::calibration::SensorCalibration::angularRateOffset_
private

The offset matrix for the angular rate.

Definition at line 163 of file SensorCalibration.hpp.

Eigen::Matrix< double, 6, 6 > rokubimini::calibration::SensorCalibration::calibrationMatrix_
private

The calibration matrix.

Definition at line 112 of file SensorCalibration.hpp.

Eigen::Matrix< double, 6, 1 > rokubimini::calibration::SensorCalibration::calibrationOffset_
private

The calibration offset matrix.

Definition at line 126 of file SensorCalibration.hpp.

Eigen::Matrix< double, 10, 1 > rokubimini::calibration::SensorCalibration::inertia_
private

The inertia matrix.

Definition at line 171 of file SensorCalibration.hpp.

uint32_t rokubimini::calibration::SensorCalibration::passphrase_ { 0x87654321 }
private

The passphrase.

Definition at line 106 of file SensorCalibration.hpp.

Eigen::Matrix< double, 6, 1 > rokubimini::calibration::SensorCalibration::temperatureGain_
private

The temperature gain matrix.

Definition at line 147 of file SensorCalibration.hpp.

Eigen::Matrix< double, 2, 1 > rokubimini::calibration::SensorCalibration::thermistorCalibration_
private

The thermistor calibration matrix.

Definition at line 140 of file SensorCalibration.hpp.


The documentation for this class was generated from the following files:


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