Public Types | Public Member Functions | Static Public Member Functions | Private Types | Private Attributes | List of all members
gtsam::AHRS Class Reference

#include <AHRS.h>

Public Types

typedef Eigen::Matrix< double, 3, Eigen::DynamicVector3s
 

Public Member Functions

 AHRS (const Matrix &stationaryU, const Matrix &stationaryF, double g_e, bool flat=false)
 
std::pair< Mechanization_bRn2, KalmanFilter::Stateaid (const Mechanization_bRn2 &mech, KalmanFilter::State state, const Vector &f, bool Farrell=0) const
 
std::pair< Mechanization_bRn2, KalmanFilter::StateaidGeneral (const Mechanization_bRn2 &mech, KalmanFilter::State state, const Vector &f, const Vector &f_expected, const Rot3 &R_previous) const
 
std::pair< Mechanization_bRn2, KalmanFilter::Stateinitialize (double g_e)
 
std::pair< Mechanization_bRn2, KalmanFilter::Stateintegrate (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...
 

Detailed Description

Definition at line 17 of file AHRS.h.

Member Typedef Documentation

typedef Eigen::Matrix<double,12,1> gtsam::AHRS::Variances
private

Definition at line 29 of file AHRS.h.

Definition at line 41 of file AHRS.h.

Constructor & Destructor Documentation

gtsam::AHRS::AHRS ( const Matrix stationaryU,
const Matrix stationaryF,
double  g_e,
bool  flat = false 
)

AHRS constructor

Parameters
stationaryUinitial interval of gyro measurements, 3xn matrix
stationaryFinitial interval of accelerator measurements, 3xn matrix
g_eif given, initializes gravity with correct value g_e

Definition at line 24 of file AHRS.cpp.

gtsam::AHRS::~AHRS ( )
virtual

Definition at line 252 of file AHRS.cpp.

Member Function Documentation

std::pair< Mechanization_bRn2, KalmanFilter::State > gtsam::AHRS::aid ( const Mechanization_bRn2 mech,
KalmanFilter::State  state,
const Vector f,
bool  Farrell = 0 
) const

Aid the AHRS with an accelerometer reading, typically called when isAidingAvailable == true

Parameters
mechcurrent mechanization state
statecurrent Kalman filter state
faccelerometer reading
Farrell

Definition at line 159 of file AHRS.cpp.

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

Definition at line 206 of file AHRS.cpp.

Matrix3 gtsam::AHRS::Cov ( const Vector3s m)
static

Definition at line 16 of file AHRS.cpp.

std::pair< Mechanization_bRn2, KalmanFilter::State > gtsam::AHRS::initialize ( double  g_e)

Definition at line 63 of file AHRS.cpp.

std::pair< Mechanization_bRn2, KalmanFilter::State > gtsam::AHRS::integrate ( const Mechanization_bRn2 mech,
KalmanFilter::State  state,
const Vector u,
double  dt 
)

Definition at line 110 of file AHRS.cpp.

bool gtsam::AHRS::isAidingAvailable ( const Mechanization_bRn2 mech,
const Vector f,
const Vector u,
double  ge 
) const

Definition at line 146 of file AHRS.cpp.

void gtsam::AHRS::print ( const std::string &  s = "") const

print

Definition at line 236 of file AHRS.cpp.

Member Data Documentation

Matrix3 gtsam::AHRS::F_a_
private

acc bias dynamics

Definition at line 27 of file AHRS.h.

Matrix3 gtsam::AHRS::F_g_
private

gyro bias dynamics

Definition at line 26 of file AHRS.h.

KalmanFilter gtsam::AHRS::KF_
private

initial Kalman filter

Definition at line 23 of file AHRS.h.

Mechanization_bRn2 gtsam::AHRS::mech0_
private

Initial mechanization state.

Definition at line 22 of file AHRS.h.

Vector3 gtsam::AHRS::n_g_
private

gravity in nav frame

Definition at line 34 of file AHRS.h.

Matrix3 gtsam::AHRS::n_g_cross_
private

and its skew-symmetric matrix

Definition at line 35 of file AHRS.h.

Matrix3 gtsam::AHRS::Pa_
private

Definition at line 37 of file AHRS.h.

Matrix3 gtsam::AHRS::Pg_
private

Definition at line 37 of file AHRS.h.

Vector3 gtsam::AHRS::sigmas_v_a_
private

measurement sigma

Definition at line 33 of file AHRS.h.

Variances gtsam::AHRS::var_w_
private

dynamic noise variances

Definition at line 30 of file AHRS.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:03