Go to the documentation of this file.
11 #include <gtsam_unstable/dllexport.h>
16 class GTSAM_UNSTABLE_EXPORT
AHRS {
51 std::pair<Mechanization_bRn2, KalmanFilter::State>
initialize(
double g_e);
53 std::pair<Mechanization_bRn2, KalmanFilter::State> integrate(
67 std::pair<Mechanization_bRn2, KalmanFilter::State> aid(
69 const Vector&
f,
bool Farrell=0)
const;
71 std::pair<Mechanization_bRn2, KalmanFilter::State> aidGeneral(
76 void print(
const std::string&
s =
"")
const;
Matrix3 n_g_cross_
and its skew-symmetric matrix
Vector3 sigmas_v_a_
measurement sigma
KalmanFilter KF_
initial Kalman filter
Variances var_w_
dynamic noise variances
Matrix3 F_g_
gyro bias dynamics
Vector3 n_g_
gravity in nav frame
void print(const Matrix &A, const string &s, ostream &stream)
Matrix3 F_a_
acc bias dynamics
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Simple linear Kalman filter. Implemented using factor graphs, i.e., does Cholesky-based SRIF,...
GaussianDensity::shared_ptr State
Mechanization_bRn2 mech0_
Initial mechanization state.
Eigen::Matrix< double, 3, Eigen::Dynamic > Vector3s
Eigen::Matrix< double, 12, 1 > Variances
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:01:48