Skyward boardcore
|
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 () |
Utility used to initialize the extended kalman filter's state.
The intended use is the following:
Definition at line 44 of file StateInitializer.h.
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.
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
acc | 3x1 accelerometer readings [x y z][m/s^2]. |
mag | 3x1 magnetometer readings [x y z][uT]. |
Definition at line 32 of file StateInitializer.cpp.
Matrix< float, 13, 1 > Boardcore::StateInitializer::getInitX | ( | ) |
Definition at line 88 of file StateInitializer.cpp.
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
acc | Normalized accelerometer readings [x y z]. |
mag | Normalized magnetometer readings [x y z]. |
nedMag | Normalized magnetic field vector in NED frame [x y z]. |
Definition at line 55 of file StateInitializer.cpp.