0.4.1
Loading...
Searching...
No Matches
NAV::ImuFusion Class Reference

Combines signals of sensors that provide the same signal-type to one signal. More...

Public Member Functions

void guiConfig () override
 ImGui config window which is shown on double click.
 
 ImuFusion ()
 Default constructor.
 
 ImuFusion (const ImuFusion &)=delete
 Copy constructor.
 
 ImuFusion (ImuFusion &&)=delete
 Move constructor.
 
ImuFusionoperator= (const ImuFusion &)=delete
 Copy assignment operator.
 
ImuFusionoperator= (ImuFusion &&)=delete
 Move assignment operator.
 
void restore (const json &j) override
 Restores the node from a json object.
 
json save () const override
 Saves the node into a json object.
 
std::string type () const override
 String representation of the Class Type.
 
 ~ImuFusion () override
 Destructor.
 
- Public Member Functions inherited from NAV::Imu
 Imu (const Imu &)=delete
 Copy constructor.
 
 Imu (Imu &&)=delete
 Move constructor.
 
const ImuPosimuPosition () const
 Position and rotation information for conversion from platform to body frame.
 
Imuoperator= (const Imu &)=delete
 Copy assignment operator.
 
Imuoperator= (Imu &&)=delete
 Move assignment operator.
 
 ~Imu () override=default
 Destructor.
 
- Public Member Functions inherited from NAV::Node
virtual void afterCreateLink (OutputPin &startPin, InputPin &endPin)
 Called when a new link was established.
 
virtual void afterDeleteLink (OutputPin &startPin, InputPin &endPin)
 Called when a link was deleted.
 
bool doDeinitialize (bool wait=false)
 Asks the node worker to deinitialize the node.
 
bool doDisable (bool wait=false)
 Asks the node worker to disable the node.
 
bool doEnable ()
 Enable the node.
 
bool doInitialize (bool wait=false)
 Asks the node worker to initialize the node.
 
bool doReinitialize (bool wait=false)
 Asks the node worker to reinitialize the node.
 
virtual void flush ()
 Function called by the flow executer after finishing to flush out remaining data.
 
template<typename T>
std::optional< InputPin::IncomingLink::ValueWrapper< T > > getInputValue (size_t portIndex) const
 Get Input Value connected on the pin. Only const data types.
 
Mode getMode () const
 Get the current mode of the node.
 
const ImVec2 & getSize () const
 Get the size of the node.
 
State getState () const
 Get the current state of the node.
 
bool hasInputPinWithSameTime (const InsTime &insTime) const
 Checks wether there is an input pin with the same time.
 
InputPininputPinFromId (ax::NodeEditor::PinId pinId)
 Returns the pin with the given id.
 
size_t inputPinIndexFromId (ax::NodeEditor::PinId pinId) const
 Returns the index of the pin.
 
void invokeCallbacks (size_t portIndex, const std::shared_ptr< const NodeData > &data)
 Calls all registered callbacks on the specified output port.
 
bool isDisabled () const
 Checks if the node is disabled.
 
bool isInitialized () const
 Checks if the node is initialized.
 
bool isOnlyRealtime () const
 Checks if the node is only working in real time (sensors, network interfaces, ...)
 
bool isTransient () const
 Checks if the node is changing its state currently.
 
std::string nameId () const
 Node name and id.
 
 Node (const Node &)=delete
 Copy constructor.
 
 Node (Node &&)=delete
 Move constructor.
 
 Node (std::string name)
 Constructor.
 
void notifyOutputValueChanged (size_t pinIdx, const InsTime &insTime, const std::scoped_lock< std::mutex > &&guard)
 Notifies connected nodes about the change.
 
virtual bool onCreateLink (OutputPin &startPin, InputPin &endPin)
 Called when a new link is to be established.
 
virtual void onDeleteLink (OutputPin &startPin, InputPin &endPin)
 Called when a link is to be deleted.
 
Nodeoperator= (const Node &)=delete
 Copy assignment operator.
 
Nodeoperator= (Node &&)=delete
 Move assignment operator.
 
OutputPinoutputPinFromId (ax::NodeEditor::PinId pinId)
 Returns the pin with the given id.
 
size_t outputPinIndexFromId (ax::NodeEditor::PinId pinId) const
 Returns the index of the pin.
 
void releaseInputValue (size_t portIndex)
 Unblocks the connected node. Has to be called when the input value should be released and getInputValue was not called.
 
std::scoped_lock< std::mutex > requestOutputValueLock (size_t pinIdx)
 Blocks the thread till the output values was read by all connected nodes.
 
virtual bool resetNode ()
 Resets the node. It is guaranteed that the node is initialized when this is called.
 
virtual void restoreAtferLink (const json &j)
 Restores link related properties of the node from a json object.
 
void wakeWorker ()
 Wakes the worker thread.
 
virtual ~Node ()
 Destructor.
 

Static Public Member Functions

static std::string category ()
 String representation of the Class Category.
 
static std::string typeStatic ()
 String representation of the Class Type.
 
- Static Public Member Functions inherited from NAV::Node
static std::string toString (State state)
 Converts the state into a printable text.
 

Protected Attributes

ImuPos _imuPos
 Position and rotation information for conversion from platform to body frame.
 
- Protected Attributes inherited from NAV::Imu
ImuPos _imuPos
 Position and rotation information for conversion from platform to body frame.
 
- Protected Attributes inherited from NAV::Node
ImVec2 _guiConfigDefaultWindowSize
 
bool _hasConfig
 Flag if the config window should be shown.
 
bool _lockConfigDuringRun
 Lock the config when executing post-processing.
 
bool _onlyRealTime
 Whether the node can run in post-processing or only real-time.
 

Private Types

enum class  ImuFusionType : uint8_t {
  IRWKF ,
  Bspline ,
  COUNT
}
 Possible KF-types for the IMU fusion. More...
 

Private Member Functions

void combineSignals (const std::shared_ptr< const ImuObs > &imuObs)
 Combines the signals.
 
void deinitialize () override
 Deinitialize the node.
 
bool initialize () override
 Initialize the node.
 
void initializeMountingAngles ()
 Initializes the rotation matrices used for the mounting angles of the sensors.
 
void measurementNoiseMatrix_R (Eigen::MatrixXd &R, size_t pinIndex=0) const
 Calculates the initial measurement noise matrix R.
 
void recvSignal (InputPin::NodeDataQueue &queue, size_t pinIdx)
 Receive Function for the signal at the time tₖ
 
void updateNumberOfInputPins ()
 Adds/Deletes Input Pins depending on the variable _nInputPins.
 

Static Private Member Functions

static Eigen::MatrixXd measurementNoiseMatrix_R_adaptive (double alpha, const Eigen::MatrixXd &R, const Eigen::VectorXd &e, const Eigen::MatrixXd &H, const Eigen::MatrixXd &P)
 Calculates the adaptive measurement noise matrix R.
 

Private Attributes

bool _autoInitKF
 Auto-initialize the Kalman Filter - GUI setting.
 
double _averageEndTime
 Time until averaging ends and filtering starts in [s].
 
InsTime _avgEndTime
 Time until averaging ends and filtering starts as 'InsTime'.
 
std::vector< Eigen::Vector3d > _biasCovariances
 Container for the bias covariances.
 
bool _checkKalmanMatricesRanks
 Check the rank of the Kalman matrices every iteration (computationally expensive)
 
std::vector< std::shared_ptr< const NAV::ImuObs > > _cumulatedImuObs
 Container that collects all imuObs for averaging for auto-init of the KF.
 
std::vector< size_t > _cumulatedPinIds
 Container that collects all pinIds for averaging for auto-init of the KF.
 
InsTime _firstTimestamp
 Saves the first timestamp in [s].
 
bool _imuBiasesIdentical
 If the multiple IMUs have the same bias, GUI input cells can be reduced considerably.
 
bool _imuCharacteristicsIdentical
 If the multiple IMUs have the same characteristics, GUI input cells can be reduced considerably.
 
double _imuFrequency
 Highest IMU sample rate in [Hz] (for time step in KF prediction)
 
ImuFusionType _imuFusionType
 KF-type for the IMU fusion, selected in the GUI.
 
bool _imuPosSet
 Check whether the combined solution has an '_imuPos' set.
 
std::vector< Eigen::Matrix3d > _imuRotations_accel
 Rotations of all connected accelerometers - key: pinIndex, value: Rotation matrix of the accelerometer platform to body frame.
 
std::vector< Eigen::Matrix3d > _imuRotations_gyro
 Rotations of all connected gyros - key: pinIndex, value: Rotation matrix of the gyro platform to body frame.
 
Eigen::Vector3d _initCoeffsAccelTemp
 Temporary vector for the initial coefficients for acceleration.
 
Eigen::Vector3d _initCoeffsAngRateTemp
 Temporary vector for the initial coefficients for angular rate.
 
Eigen::Vector3d _initCovarianceCoeffsAccelTemp
 Temporary vector for the initial coefficients' initial covariance for the acceleration.
 
Eigen::Vector3d _initCovarianceCoeffsAngRateTemp
 Temporary vector for the initial coefficients' initial covariance for the angular rate.
 
bool _initJerkAngAcc
 flag to determine how jerk and angular acceleration states are initialized if '_autoInitKF = true'
 
KalmanFilter _kalmanFilter
 Kalman Filter representation.
 
bool _kfInitialized
 flag to check whether KF has been auto-initialized
 
InsTime _lastFiltObs
 Previous observation (for timestamp)
 
double _latestKnot
 Latest knot in [s].
 
InsTime _latestTimestamp
 Saves the timestamp of the measurement before in [s].
 
std::vector< Eigen::Vector3d > _measurementNoiseVariances
 Container for measurement noises of each sensor.
 
size_t _nInputPins
 Number of input pins.
 
const uint8_t _numBsplines
 Number of quadratic B-splines that make up the entire 3D stacked B-spline.
 
const uint8_t _numMeasurements
 Number of measurements overall.
 
uint8_t _numStates
 Number of states overall.
 
uint8_t _numStatesEst
 Number of estimated states (depends on imuFusionType)
 
const uint8_t _numStatesEstBsplineKF
 Number of states estimated by the B-spline KF (3 stacked B-splines in 3D for angular rate and specific force: 3*3*2 = 18)
 
const uint8_t _numStatesEstIRWKF
 Number of states estimated by the IRW-KF (angular rate, angular acceleration, specific force, jerk, all in 3D: 4*3 = 12)
 
const uint8_t _numStatesPerPin
 Number of states per pin (biases of accel and gyro)
 
std::vector< PinData_pinData
 Stores parameter data for each connected sensor.
 
PinDataBsplineKF _pinDataBsplineKF
 Stores Bspline-KF specific parameter data.
 
PinDataIRWKF _pinDataIRWKF
 Stores IRW-KF specific parameter data.
 
std::vector< Eigen::VectorXd > _processNoiseVariances
 Container for process noise of each state.
 
Eigen::Vector3d _procNoiseCoeffsAccelTemp
 Temporary vector for the initial coefficients' process noise for the acceleration.
 
Eigen::Vector3d _procNoiseCoeffsAngRateTemp
 Temporary vector for the initial coefficients' process noise for the angular rate.
 
double _splineSpacing
 Time difference between two quadratic B-splines in the stacked B-spline.
 
double _timeSinceStartup
 Time since startup in [s].
 

Static Private Attributes

static constexpr size_t OUTPUT_PORT_INDEX_BIASES
 Flow (ImuBiases)
 
static constexpr size_t OUTPUT_PORT_INDEX_COMBINED_SIGNAL
 Flow (ImuObs)
 

Friends

constexpr const char * to_string (ImuFusionType value)
 Converts the enum to a string.
 

Additional Inherited Members

- Public Types inherited from NAV::Node
enum class  Mode : uint8_t {
  REAL_TIME ,
  POST_PROCESSING
}
 Different Modes the Node can work in. More...
 
enum class  State : uint8_t {
  Disabled ,
  Deinitialized ,
  DoInitialize ,
  Initializing ,
  Initialized ,
  DoDeinitialize ,
  Deinitializing ,
  DoShutdown ,
  Shutdown
}
 Possible states of the node. More...
 
- Data Fields inherited from NAV::Node
bool callbacksEnabled
 Enables the callbacks.
 
ax::NodeEditor::NodeId id
 Unique Id of the Node.
 
std::vector< InputPininputPins
 List of input pins.
 
Kind kind
 Kind of the Node.
 
std::string name
 Name of the Node.
 
std::vector< OutputPinoutputPins
 List of output pins.
 
std::multimap< InsTime, std::pair< OutputPin *, size_t > > pollEvents
 Map with callback events (sorted by time)
 
- Protected Member Functions inherited from NAV::Imu
 Imu (std::string name)
 Constructor.
 

Detailed Description

Combines signals of sensors that provide the same signal-type to one signal.

Definition at line 28 of file ImuFusion.hpp.

Member Enumeration Documentation

◆ ImuFusionType

enum class NAV::ImuFusion::ImuFusionType : uint8_t
strongprivate

Possible KF-types for the IMU fusion.

Enumerator
IRWKF 

IRW Kalman filter.

Bspline 

B-spline Kalman filter.

COUNT 

Number of items in the enum.

Definition at line 232 of file ImuFusion.hpp.

Constructor & Destructor Documentation

◆ ImuFusion() [1/3]

NAV::ImuFusion::ImuFusion ( )

Default constructor.

Definition at line 342 of file ImuFusion.cpp.

◆ ~ImuFusion()

NAV::ImuFusion::~ImuFusion ( )
override

Destructor.

Definition at line 354 of file ImuFusion.cpp.

◆ ImuFusion() [2/3]

NAV::ImuFusion::ImuFusion ( const ImuFusion & )
delete

Copy constructor.

◆ ImuFusion() [3/3]

NAV::ImuFusion::ImuFusion ( ImuFusion && )
delete

Move constructor.

Member Function Documentation

◆ category()

std::string NAV::ImuFusion::category ( )
staticnodiscard

String representation of the Class Category.

Definition at line 369 of file ImuFusion.cpp.

◆ combineSignals()

void NAV::ImuFusion::combineSignals ( const std::shared_ptr< const ImuObs > & imuObs)
private

Combines the signals.

Parameters
[in]imuObsImu observation

Definition at line 1478 of file ImuFusion.cpp.

◆ deinitialize()

void NAV::ImuFusion::deinitialize ( )
overrideprivatevirtual

Deinitialize the node.

Reimplemented from NAV::Node.

Definition at line 1305 of file ImuFusion.cpp.

◆ guiConfig()

void NAV::ImuFusion::guiConfig ( )
overridevirtual

ImGui config window which is shown on double click.

Attention
Don't forget to set _hasConfig to true in the constructor of the node

Reimplemented from NAV::Imu.

Definition at line 374 of file ImuFusion.cpp.

◆ initialize()

bool NAV::ImuFusion::initialize ( )
overrideprivatevirtual

Initialize the node.

Reimplemented from NAV::Node.

Definition at line 1195 of file ImuFusion.cpp.

◆ initializeMountingAngles()

void NAV::ImuFusion::initializeMountingAngles ( )
private

Initializes the rotation matrices used for the mounting angles of the sensors.

Definition at line 1332 of file ImuFusion.cpp.

◆ measurementNoiseMatrix_R()

void NAV::ImuFusion::measurementNoiseMatrix_R ( Eigen::MatrixXd & R,
size_t pinIndex = 0 ) const
private

Calculates the initial measurement noise matrix R.

Parameters
[in]RMeasurement noise uncertainty matrix for sensor at 'pinIndex'
[in]pinIndexIndex of pin to identify sensor

Definition at line 1585 of file ImuFusion.cpp.

◆ measurementNoiseMatrix_R_adaptive()

Eigen::MatrixXd NAV::ImuFusion::measurementNoiseMatrix_R_adaptive ( double alpha,
const Eigen::MatrixXd & R,
const Eigen::VectorXd & e,
const Eigen::MatrixXd & H,
const Eigen::MatrixXd & P )
staticnodiscardprivate

Calculates the adaptive measurement noise matrix R.

Parameters
[in]alphaForgetting factor (i.e. weight on previous estimates), 0 < alpha < 1
[in]RMeasurement noise covariance matrix at the previous epoch
[in]eVector of residuals
[in]HDesign matrix
[in]PError covariance matrix
Returns
Measurement noise matrix R
Note
See https://arxiv.org/pdf/1702.00884.pdf

Definition at line 1580 of file ImuFusion.cpp.

◆ operator=() [1/2]

ImuFusion & NAV::ImuFusion::operator= ( const ImuFusion & )
delete

Copy assignment operator.

◆ operator=() [2/2]

ImuFusion & NAV::ImuFusion::operator= ( ImuFusion && )
delete

Move assignment operator.

◆ recvSignal()

void NAV::ImuFusion::recvSignal ( InputPin::NodeDataQueue & queue,
size_t pinIdx )
private

Receive Function for the signal at the time tₖ

Parameters
[in]queueQueue with all the received data messages
[in]pinIdxIndex of the pin the data is received on

Definition at line 1347 of file ImuFusion.cpp.

◆ restore()

void NAV::ImuFusion::restore ( const json & j)
overridevirtual

Restores the node from a json object.

Parameters
[in]jJson object with the node state

Reimplemented from NAV::Imu.

Definition at line 1112 of file ImuFusion.cpp.

◆ save()

json NAV::ImuFusion::save ( ) const
nodiscardoverridevirtual

Saves the node into a json object.

Reimplemented from NAV::Imu.

Definition at line 1083 of file ImuFusion.cpp.

◆ type()

std::string NAV::ImuFusion::type ( ) const
nodiscardoverridevirtual

String representation of the Class Type.

Implements NAV::Node.

Definition at line 364 of file ImuFusion.cpp.

◆ typeStatic()

std::string NAV::ImuFusion::typeStatic ( )
staticnodiscard

String representation of the Class Type.

Definition at line 359 of file ImuFusion.cpp.

◆ updateNumberOfInputPins()

void NAV::ImuFusion::updateNumberOfInputPins ( )
private

Adds/Deletes Input Pins depending on the variable _nInputPins.

Definition at line 1310 of file ImuFusion.cpp.

Friends And Related Symbol Documentation

◆ to_string

const char * to_string ( ImuFusionType value)
friend

Converts the enum to a string.

Parameters
[in]valueEnum value to convert into text
Returns
String representation of the enum

Definition at line 247 of file ImuFusion.hpp.

Field Documentation

◆ _autoInitKF

bool NAV::ImuFusion::_autoInitKF
private

Auto-initialize the Kalman Filter - GUI setting.

Definition at line 154 of file ImuFusion.hpp.

◆ _averageEndTime

double NAV::ImuFusion::_averageEndTime
private

Time until averaging ends and filtering starts in [s].

Definition at line 148 of file ImuFusion.hpp.

◆ _avgEndTime

InsTime NAV::ImuFusion::_avgEndTime
private

Time until averaging ends and filtering starts as 'InsTime'.

Definition at line 151 of file ImuFusion.hpp.

◆ _biasCovariances

std::vector<Eigen::Vector3d> NAV::ImuFusion::_biasCovariances
private

Container for the bias covariances.

Definition at line 196 of file ImuFusion.hpp.

◆ _checkKalmanMatricesRanks

bool NAV::ImuFusion::_checkKalmanMatricesRanks
private

Check the rank of the Kalman matrices every iteration (computationally expensive)

Definition at line 226 of file ImuFusion.hpp.

◆ _cumulatedImuObs

std::vector<std::shared_ptr<const NAV::ImuObs> > NAV::ImuFusion::_cumulatedImuObs
private

Container that collects all imuObs for averaging for auto-init of the KF.

Definition at line 163 of file ImuFusion.hpp.

◆ _cumulatedPinIds

std::vector<size_t> NAV::ImuFusion::_cumulatedPinIds
private

Container that collects all pinIds for averaging for auto-init of the KF.

Definition at line 166 of file ImuFusion.hpp.

◆ _firstTimestamp

InsTime NAV::ImuFusion::_firstTimestamp
private

Saves the first timestamp in [s].

Definition at line 213 of file ImuFusion.hpp.

◆ _imuBiasesIdentical

bool NAV::ImuFusion::_imuBiasesIdentical
private

If the multiple IMUs have the same bias, GUI input cells can be reduced considerably.

Definition at line 160 of file ImuFusion.hpp.

◆ _imuCharacteristicsIdentical

bool NAV::ImuFusion::_imuCharacteristicsIdentical
private

If the multiple IMUs have the same characteristics, GUI input cells can be reduced considerably.

Definition at line 157 of file ImuFusion.hpp.

◆ _imuFrequency

double NAV::ImuFusion::_imuFrequency
private

Highest IMU sample rate in [Hz] (for time step in KF prediction)

Definition at line 145 of file ImuFusion.hpp.

◆ _imuFusionType

ImuFusionType NAV::ImuFusion::_imuFusionType
private

KF-type for the IMU fusion, selected in the GUI.

Definition at line 244 of file ImuFusion.hpp.

◆ _imuPos

ImuPos NAV::ImuFusion::_imuPos
protected

Position and rotation information for conversion from platform to body frame.

Definition at line 66 of file ImuFusion.hpp.

◆ _imuPosSet

bool NAV::ImuFusion::_imuPosSet
private

Check whether the combined solution has an '_imuPos' set.

Definition at line 229 of file ImuFusion.hpp.

◆ _imuRotations_accel

std::vector<Eigen::Matrix3d> NAV::ImuFusion::_imuRotations_accel
private

Rotations of all connected accelerometers - key: pinIndex, value: Rotation matrix of the accelerometer platform to body frame.

Definition at line 203 of file ImuFusion.hpp.

◆ _imuRotations_gyro

std::vector<Eigen::Matrix3d> NAV::ImuFusion::_imuRotations_gyro
private

Rotations of all connected gyros - key: pinIndex, value: Rotation matrix of the gyro platform to body frame.

Definition at line 206 of file ImuFusion.hpp.

◆ _initCoeffsAccelTemp

Eigen::Vector3d NAV::ImuFusion::_initCoeffsAccelTemp
private

Temporary vector for the initial coefficients for acceleration.

Definition at line 185 of file ImuFusion.hpp.

◆ _initCoeffsAngRateTemp

Eigen::Vector3d NAV::ImuFusion::_initCoeffsAngRateTemp
private

Temporary vector for the initial coefficients for angular rate.

Definition at line 183 of file ImuFusion.hpp.

◆ _initCovarianceCoeffsAccelTemp

Eigen::Vector3d NAV::ImuFusion::_initCovarianceCoeffsAccelTemp
private

Temporary vector for the initial coefficients' initial covariance for the acceleration.

Definition at line 189 of file ImuFusion.hpp.

◆ _initCovarianceCoeffsAngRateTemp

Eigen::Vector3d NAV::ImuFusion::_initCovarianceCoeffsAngRateTemp
private

Temporary vector for the initial coefficients' initial covariance for the angular rate.

Definition at line 187 of file ImuFusion.hpp.

◆ _initJerkAngAcc

bool NAV::ImuFusion::_initJerkAngAcc
private

flag to determine how jerk and angular acceleration states are initialized if '_autoInitKF = true'

Definition at line 169 of file ImuFusion.hpp.

◆ _kalmanFilter

KalmanFilter NAV::ImuFusion::_kalmanFilter
private

Kalman Filter representation.

Definition at line 141 of file ImuFusion.hpp.

◆ _kfInitialized

bool NAV::ImuFusion::_kfInitialized
private

flag to check whether KF has been auto-initialized

Definition at line 172 of file ImuFusion.hpp.

◆ _lastFiltObs

InsTime NAV::ImuFusion::_lastFiltObs
private

Previous observation (for timestamp)

Definition at line 104 of file ImuFusion.hpp.

◆ _latestKnot

double NAV::ImuFusion::_latestKnot
private

Latest knot in [s].

Definition at line 219 of file ImuFusion.hpp.

◆ _latestTimestamp

InsTime NAV::ImuFusion::_latestTimestamp
private

Saves the timestamp of the measurement before in [s].

Definition at line 210 of file ImuFusion.hpp.

◆ _measurementNoiseVariances

std::vector<Eigen::Vector3d> NAV::ImuFusion::_measurementNoiseVariances
private

Container for measurement noises of each sensor.

Definition at line 200 of file ImuFusion.hpp.

◆ _nInputPins

size_t NAV::ImuFusion::_nInputPins
private

Number of input pins.

Definition at line 117 of file ImuFusion.hpp.

◆ _numBsplines

const uint8_t NAV::ImuFusion::_numBsplines
private

Number of quadratic B-splines that make up the entire 3D stacked B-spline.

Definition at line 126 of file ImuFusion.hpp.

◆ _numMeasurements

const uint8_t NAV::ImuFusion::_numMeasurements
private

Number of measurements overall.

Definition at line 132 of file ImuFusion.hpp.

◆ _numStates

uint8_t NAV::ImuFusion::_numStates
private

Number of states overall.

Definition at line 138 of file ImuFusion.hpp.

◆ _numStatesEst

uint8_t NAV::ImuFusion::_numStatesEst
private

Number of estimated states (depends on imuFusionType)

Definition at line 135 of file ImuFusion.hpp.

◆ _numStatesEstBsplineKF

const uint8_t NAV::ImuFusion::_numStatesEstBsplineKF
private

Number of states estimated by the B-spline KF (3 stacked B-splines in 3D for angular rate and specific force: 3*3*2 = 18)

Definition at line 123 of file ImuFusion.hpp.

◆ _numStatesEstIRWKF

const uint8_t NAV::ImuFusion::_numStatesEstIRWKF
private

Number of states estimated by the IRW-KF (angular rate, angular acceleration, specific force, jerk, all in 3D: 4*3 = 12)

Definition at line 120 of file ImuFusion.hpp.

◆ _numStatesPerPin

const uint8_t NAV::ImuFusion::_numStatesPerPin
private

Number of states per pin (biases of accel and gyro)

Definition at line 129 of file ImuFusion.hpp.

◆ _pinData

std::vector<PinData> NAV::ImuFusion::_pinData
private

Stores parameter data for each connected sensor.

Definition at line 176 of file ImuFusion.hpp.

◆ _pinDataBsplineKF

PinDataBsplineKF NAV::ImuFusion::_pinDataBsplineKF
private

Stores Bspline-KF specific parameter data.

Definition at line 180 of file ImuFusion.hpp.

◆ _pinDataIRWKF

PinDataIRWKF NAV::ImuFusion::_pinDataIRWKF
private

Stores IRW-KF specific parameter data.

Definition at line 178 of file ImuFusion.hpp.

◆ _processNoiseVariances

std::vector<Eigen::VectorXd> NAV::ImuFusion::_processNoiseVariances
private

Container for process noise of each state.

Definition at line 198 of file ImuFusion.hpp.

◆ _procNoiseCoeffsAccelTemp

Eigen::Vector3d NAV::ImuFusion::_procNoiseCoeffsAccelTemp
private

Temporary vector for the initial coefficients' process noise for the acceleration.

Definition at line 193 of file ImuFusion.hpp.

◆ _procNoiseCoeffsAngRateTemp

Eigen::Vector3d NAV::ImuFusion::_procNoiseCoeffsAngRateTemp
private

Temporary vector for the initial coefficients' process noise for the angular rate.

Definition at line 191 of file ImuFusion.hpp.

◆ _splineSpacing

double NAV::ImuFusion::_splineSpacing
private

Time difference between two quadratic B-splines in the stacked B-spline.

Definition at line 222 of file ImuFusion.hpp.

◆ _timeSinceStartup

double NAV::ImuFusion::_timeSinceStartup
private

Time since startup in [s].

Definition at line 216 of file ImuFusion.hpp.

◆ OUTPUT_PORT_INDEX_BIASES

size_t NAV::ImuFusion::OUTPUT_PORT_INDEX_BIASES
staticconstexprprivate

Flow (ImuBiases)

Definition at line 70 of file ImuFusion.hpp.

◆ OUTPUT_PORT_INDEX_COMBINED_SIGNAL

size_t NAV::ImuFusion::OUTPUT_PORT_INDEX_COMBINED_SIGNAL
staticconstexprprivate

Flow (ImuObs)

Definition at line 69 of file ImuFusion.hpp.


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