11#include "Mechanization_bRn2.h"
12#include <gtsam_unstable/dllexport.h>
17class GTSAM_UNSTABLE_EXPORT
AHRS {
29 typedef Eigen::Matrix<double,12,1> Variances;
41 typedef Eigen::Matrix<double,3,Eigen::Dynamic> Vector3s;
42 static Matrix3 Cov(
const Vector3s& m);
50 AHRS(
const Matrix& stationaryU,
const Matrix& stationaryF,
double g_e,
bool flat=
false);
52 std::pair<Mechanization_bRn2, KalmanFilter::State> initialize(
double g_e);
54 std::pair<Mechanization_bRn2, KalmanFilter::State> integrate(
56 const Vector& u,
double dt);
59 const Vector& f,
const Vector& u,
double ge)
const;
68 std::pair<Mechanization_bRn2, KalmanFilter::State> aid(
70 const Vector& f,
bool Farrell=0)
const;
72 std::pair<Mechanization_bRn2, KalmanFilter::State> aidGeneral(
74 const Vector& f,
const Vector& f_expected,
const Rot3& R_previous)
const;
77 void print(
const std::string& s =
"")
const;
81 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Simple linear Kalman filter.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:155
Kalman Filter class.
Definition: KalmanFilter.h:41
GaussianDensity::shared_ptr State
The Kalman filter state is simply a GaussianDensity.
Definition: KalmanFilter.h:56
Definition: Mechanization_bRn2.h:17