#include <AHRS.h>
Public Types | |
typedef Eigen::Matrix< double, 3, Eigen::Dynamic > | Vector3s |
Public Member Functions | |
AHRS (const Matrix &stationaryU, const Matrix &stationaryF, double g_e, bool flat=false) | |
std::pair< Mechanization_bRn2, KalmanFilter::State > | aid (const Mechanization_bRn2 &mech, KalmanFilter::State state, const Vector &f, bool Farrell=0) const |
std::pair< Mechanization_bRn2, KalmanFilter::State > | aidGeneral (const Mechanization_bRn2 &mech, KalmanFilter::State state, const Vector &f, const Vector &f_expected, const Rot3 &R_previous) const |
std::pair< Mechanization_bRn2, KalmanFilter::State > | initialize (double g_e) |
std::pair< Mechanization_bRn2, KalmanFilter::State > | integrate (const Mechanization_bRn2 &mech, KalmanFilter::State state, const Vector &u, double dt) |
bool | isAidingAvailable (const Mechanization_bRn2 &mech, const Vector &f, const Vector &u, double ge) const |
void | print (const std::string &s="") const |
print More... | |
virtual | ~AHRS () |
Static Public Member Functions | |
static Matrix3 | Cov (const Vector3s &m) |
Private Types | |
typedef Eigen::Matrix< double, 12, 1 > | Variances |
Private Attributes | |
Matrix3 | F_a_ |
acc bias dynamics More... | |
Matrix3 | F_g_ |
gyro bias dynamics More... | |
KalmanFilter | KF_ |
initial Kalman filter More... | |
Mechanization_bRn2 | mech0_ |
Initial mechanization state. More... | |
Vector3 | n_g_ |
gravity in nav frame More... | |
Matrix3 | n_g_cross_ |
and its skew-symmetric matrix More... | |
Matrix3 | Pa_ |
Matrix3 | Pg_ |
Vector3 | sigmas_v_a_ |
measurement sigma More... | |
Variances | var_w_ |
dynamic noise variances More... | |
|
private |
typedef Eigen::Matrix<double,3,Eigen::Dynamic> gtsam::AHRS::Vector3s |
std::pair< Mechanization_bRn2, KalmanFilter::State > gtsam::AHRS::aid | ( | const Mechanization_bRn2 & | mech, |
KalmanFilter::State | state, | ||
const Vector & | f, | ||
bool | Farrell = 0 |
||
) | const |
std::pair< Mechanization_bRn2, KalmanFilter::State > gtsam::AHRS::aidGeneral | ( | const Mechanization_bRn2 & | mech, |
KalmanFilter::State | state, | ||
const Vector & | f, | ||
const Vector & | f_expected, | ||
const Rot3 & | R_previous | ||
) | const |
std::pair< Mechanization_bRn2, KalmanFilter::State > gtsam::AHRS::initialize | ( | double | g_e | ) |
std::pair< Mechanization_bRn2, KalmanFilter::State > gtsam::AHRS::integrate | ( | const Mechanization_bRn2 & | mech, |
KalmanFilter::State | state, | ||
const Vector & | u, | ||
double | dt | ||
) |
bool gtsam::AHRS::isAidingAvailable | ( | const Mechanization_bRn2 & | mech, |
const Vector & | f, | ||
const Vector & | u, | ||
double | ge | ||
) | const |
void gtsam::AHRS::print | ( | const std::string & | s = "" | ) | const |
|
private |
|
private |
|
private |