Skyward boardcore
Loading...
Searching...
No Matches
Boardcore::StateInitializer Class Reference

Utility used to initialize the extended kalman filter's state. More...

#include <StateInitializer.h>

Public Member Functions

 StateInitializer ()
 Initialize the state of the Extended Kalman Filter.
 
void eCompass (const Eigen::Vector3f acc, const Eigen::Vector3f mag)
 Ecompass algorithm to estimate the attitude before the liftoff.
 
void triad (const Eigen::Vector3f &acc, const Eigen::Vector3f &mag, const Eigen::Vector3f &nedMag)
 Triad algorithm to estimate the attitude before the liftoff.
 
Eigen::Matrix< float, 13, 1 > getInitX ()
 

Detailed Description

Utility used to initialize the extended kalman filter's state.

The intended use is the following:

  • Instantiate the object, the state is initialized to zero;
  • Call either eCompass or triad to set the initial orientation;
  • Get the initial state for the kalman with getInitX.

Definition at line 44 of file StateInitializer.h.

Constructor & Destructor Documentation

◆ StateInitializer()

Boardcore::StateInitializer::StateInitializer ( )

Initialize the state of the Extended Kalman Filter.

The state is initialized to zero. Velocity should be null and gyro biases can be left to zero since the sensor performs self-calibration and the measurements are already compensated.

Definition at line 30 of file StateInitializer.cpp.

Member Function Documentation

◆ eCompass()

void Boardcore::StateInitializer::eCompass ( const Eigen::Vector3f acc,
const Eigen::Vector3f mag )

Ecompass algorithm to estimate the attitude before the liftoff.

ecompass reference: https://de.mathworks.com/help/fusion/ref/ecompass.html

Parameters
acc3x1 accelerometer readings [x y z][m/s^2].
mag3x1 magnetometer readings [x y z][uT].

Definition at line 32 of file StateInitializer.cpp.

◆ getInitX()

Matrix< float, 13, 1 > Boardcore::StateInitializer::getInitX ( )

Definition at line 88 of file StateInitializer.cpp.

◆ triad()

void Boardcore::StateInitializer::triad ( const Eigen::Vector3f & acc,
const Eigen::Vector3f & mag,
const Eigen::Vector3f & nedMag )

Triad algorithm to estimate the attitude before the liftoff.

triad reference: https://en.wikipedia.org/wiki/Triad_method https://www.aero.iitb.ac.in/satelliteWiki/index.php/Triad_Algorithm

Parameters
accNormalized accelerometer readings [x y z].
magNormalized magnetometer readings [x y z].
nedMagNormalized magnetic field vector in NED frame [x y z].

Definition at line 55 of file StateInitializer.cpp.


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