Header file for the Attitude-Bias-Calibration Equivariant Filter. More...
#include <gtsam/base/Matrix.h>
#include <gtsam/base/Vector.h>
#include <gtsam/geometry/Rot3.h>
#include <gtsam/geometry/Unit3.h>
#include <gtsam/inference/Symbol.h>
#include <gtsam/navigation/ImuBias.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/slam/dataset.h>
#include <chrono>
#include <cmath>
#include <fstream>
#include <functional>
#include <iostream>
#include <numeric>
#include <string>
#include <vector>
#include "ABC.h"
Go to the source code of this file.
Classes | |
class | gtsam::abc_eqf_lib::EqF< N > |
Equivariant Filter (EqF) implementation. More... | |
struct | gtsam::traits< abc_eqf_lib::EqF< N > > |
Namespaces | |
gtsam | |
traits | |
gtsam::abc_eqf_lib | |
Functions | |
template<size_t N> | |
Vector | gtsam::abc_eqf_lib::lift (const State< N > &xi, const Input &u) |
Matrix | gtsam::abc_eqf_lib::numericalDifferential (std::function< Vector(const Vector &)> f, const Vector &x) |
Calculate numerical differential. More... | |
template<size_t N> | |
State< N > | gtsam::abc_eqf_lib::operator* (const G< N > &X, const State< N > &xi) |
template<size_t N> | |
Vector3 | gtsam::abc_eqf_lib::outputAction (const G< N > &X, const Unit3 &y, int idx) |
template<size_t N> | |
Matrix | gtsam::abc_eqf_lib::stateActionDiff (const State< N > &xi) |
template<size_t N> | |
Input | gtsam::abc_eqf_lib::velocityAction (const G< N > &X, const Input &u) |
Header file for the Attitude-Bias-Calibration Equivariant Filter.
This file contains declarations for the Equivariant Filter (EqF) for attitude estimation with both gyroscope bias and sensor extrinsic calibration, based on the paper: "Overcoming Bias: Equivariant Filter Design for Biased Attitude Estimation with Online Calibration" by Fornasier et al. Authors: Darshan Rajasekaran & Jennifer Oum
Definition in file ABC_EQF.h.