gtsam/gtsam_unstable/slam/AHRS.h

84 lines
2.4 KiB
C
Raw Permalink Normal View History

2013-05-21 07:16:44 +08:00
/*
* AHRS.h
*
* Created on: Jan 26, 2012
* Author: cbeall3
*/
2022-02-20 15:53:15 +08:00
#pragma once
2013-05-21 07:16:44 +08:00
#include "Mechanization_bRn2.h"
#include <gtsam_unstable/dllexport.h>
2013-05-21 07:16:44 +08:00
#include <gtsam/linear/KalmanFilter.h>
namespace gtsam {
2013-05-22 01:24:49 +08:00
class GTSAM_UNSTABLE_EXPORT AHRS {
2013-05-21 07:16:44 +08:00
private:
// Initial state
Mechanization_bRn2 mech0_; ///< Initial mechanization state
KalmanFilter KF_; ///< initial Kalman filter
// Quantities needed for integration
2014-12-04 19:30:41 +08:00
Matrix3 F_g_; ///< gyro bias dynamics
Matrix3 F_a_; ///< acc bias dynamics
typedef Eigen::Matrix<double,12,1> Variances;
Variances var_w_; ///< dynamic noise variances
2013-05-21 07:16:44 +08:00
// Quantities needed for aiding
2014-12-04 19:30:41 +08:00
Vector3 sigmas_v_a_; ///< measurement sigma
Vector3 n_g_; ///< gravity in nav frame
Matrix3 n_g_cross_; ///< and its skew-symmetric matrix
2013-05-21 07:16:44 +08:00
2014-12-04 19:30:41 +08:00
Matrix3 Pg_, Pa_;
2013-05-21 07:16:44 +08:00
public:
2014-12-04 19:30:41 +08:00
typedef Eigen::Matrix<double,3,Eigen::Dynamic> Vector3s;
static Matrix3 Cov(const Vector3s& m);
2013-05-21 07:16:44 +08:00
/**
* AHRS constructor
* @param stationaryU initial interval of gyro measurements, 3xn matrix
* @param stationaryF initial interval of accelerator measurements, 3xn matrix
* @param g_e if given, initializes gravity with correct value g_e
*/
AHRS(const Matrix& stationaryU, const Matrix& stationaryF, double g_e, bool flat=false);
2013-05-21 07:16:44 +08:00
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;
/**
* Aid the AHRS with an accelerometer reading, typically called when isAidingAvailable == true
* @param mech current mechanization state
* @param state current Kalman filter state
* @param f accelerometer reading
* @param Farrell
*/
2013-05-21 07:16:44 +08:00
std::pair<Mechanization_bRn2, KalmanFilter::State> aid(
const Mechanization_bRn2& mech, KalmanFilter::State state,
const Vector& f, bool Farrell=0) const;
2013-05-21 07:16:44 +08:00
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;
2013-05-21 07:16:44 +08:00
/// print
void print(const std::string& s = "") const;
virtual ~AHRS();
2020-03-23 00:46:25 +08:00
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
2013-05-21 07:16:44 +08:00
};
} /* namespace gtsam */