66 void eCompass(
const Eigen::Vector3f acc,
const Eigen::Vector3f mag);
79 void triad(
const Eigen::Vector3f& acc,
const Eigen::Vector3f& mag,
80 const Eigen::Vector3f& nedMag);
82 Eigen::Matrix<float, 13, 1>
getInitX();
85 Eigen::Matrix<float, 13, 1> x_init;
static PrintLogger getLogger(const string &name)
Utility used to initialize the extended kalman filter's state.
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()
void eCompass(const Eigen::Vector3f acc, const Eigen::Vector3f mag)
Ecompass algorithm to estimate the attitude before the liftoff.
StateInitializer()
Initialize the state of the Extended Kalman Filter.
This file includes all the types the logdecoder script will decode.