Go to the documentation of this file.
37 namespace abc_eqf_lib {
40 using namespace gtsam;
124 Matrix stateTransitionMatrix(
const Input& u,
double dt)
const;
130 Matrix inputMatrixBt()
const;
138 Matrix measurementMatrixC(
const Unit3&
d,
int idx)
const;
145 Matrix outputMatrixDt(
int idx)
const;
166 void propagation(
const Input& u,
double dt);
191 L.head<3>() = u.
w -
xi.b;
194 L.segment<3>(3) = -u.
W() *
xi.b;
197 for (
size_t i = 0;
i <
N;
i++) {
198 L.segment<3>(6 + 3 *
i) =
xi.S[
i].inverse().matrix() *
L.head<3>();
218 std::array<Rot3, N> new_S;
220 for (
size_t i = 0;
i <
N;
i++) {
221 new_S[
i] =
X.A.inverse() *
xi.S[
i] *
X.B[
i];
250 return X.A.inverse().matrix() *
y.unitVector();
252 if (idx >=
static_cast<int>(
N)) {
253 throw std::out_of_range(
"Calibration index out of range");
255 return X.B[idx].inverse().matrix() *
y.unitVector();
274 for (
int j = 0;
j <
m;
j++) {
281 Df.col(
j) = (fplus - fminus) / (2 *
h);
300 return xi.localCoordinates(transformed);
303 Vector zeros = Vector::Zero(6 + 3 *
N);
322 X_hat(
G<
N>::identity(
N)),
324 xi_0(
State<
N>::identity()) {
326 throw std::invalid_argument(
327 "Initial covariance dimensions must match the degrees of freedom");
333 throw std::invalid_argument(
334 "Covariance matrix must be semi-positive definite");
338 throw std::invalid_argument(
339 "Number of calibration states must be non-negative");
343 throw std::invalid_argument(
344 "Number of direction sensors must be at least 2");
369 State<N> state_est = stateEstimate();
372 Matrix Phi_DT = stateTransitionMatrix(u,
dt);
373 Matrix Bt = inputMatrixBt();
376 Matrix M_DT = (Bt * tempSigma * Bt.transpose()) *
dt;
379 Sigma = Phi_DT * Sigma * Phi_DT.transpose() + M_DT;
390 if (
y.cal_idx >
static_cast<int>(
N)) {
391 throw std::invalid_argument(
"Calibration index out of range");
404 Matrix Ct = measurementMatrixC(
y.d,
y.cal_idx);
407 Matrix Dt = outputMatrixDt(
y.cal_idx);
408 Matrix S = Ct * Sigma * Ct.transpose() + Dt *
y.Sigma * Dt.transpose();
409 Matrix K = Sigma * Ct.transpose() *
S.inverse();
410 Vector Delta = InnovationLift *
K * delta_vec;
412 Sigma = (Matrix::Identity(dof, dof) -
K * Ct) * Sigma;
424 A1.block<3, 3>(0, 3) = -I_3x3;
425 A1.block<3, 3>(3, 3) = W0;
439 Matrix Phi1 = Matrix::Zero(6, 6);
441 Matrix3 Phi12 = -
dt * (I_3x3 + (
dt / 2) * W0 + ((
dt *
dt) / 6) * W0 * W0);
442 Matrix3 Phi22 = I_3x3 +
dt * W0 + ((
dt *
dt) / 2) * W0 * W0;
444 Phi1.block<3, 3>(0, 0) = I_3x3;
445 Phi1.block<3, 3>(0, 3) = Phi12;
446 Phi1.block<3, 3>(3, 3) = Phi22;
460 for (
size_t i = 0;
i <
N; ++
i) {
461 B2.block<3, 3>(3 *
i, 3 *
i) = X_hat.B[
i].matrix();
476 Matrix Cc = Matrix::Zero(3, 3 *
N);
481 Cc.block<3, 3>(0, 3 * idx) =
Rot3::Hat(
d.unitVector());
488 temp.block<3, 3>(0, 0) = wedge_d;
489 temp.block<3, 3>(0, 3) = Matrix3::Zero();
490 temp.block(0, 6, 3, 3 *
N) = Cc;
492 return wedge_d * temp;
503 if (idx >=
static_cast<int>(
N)) {
504 throw std::out_of_range(
"Calibration index out of range");
506 return X_hat.B[idx].matrix();
508 return X_hat.A.matrix();
Equivariant Filter (EqF) implementation.
State< N > stateEstimate() const
Matrix outputMatrixDt(int idx) const
typedef and functions to augment Eigen's VectorXd
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const double d[K][N]
typedef and functions to augment Eigen's MatrixXd
Matrix inputMatrixBt() const
State class representing the state of the Biased Attitude System.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Matrix stateActionDiff(const State< N > &xi)
Core components for Attitude-Bias-Calibration systems.
State< N > operator*(const G< N > &X, const State< N > &xi)
EqF(const Matrix &Sigma, int m)
Matrix stateTransitionMatrix(const Input &u, double dt) const
3D rotation represented as a rotation matrix or quaternion
Matrix stateMatrixA(const Input &u) const
Vector lift(const State< N > &xi, const Input &u)
utility functions for loading datasets
Computes eigenvalues and eigenvectors of selfadjoint matrices.
Matrix measurementMatrixC(const Unit3 &d, int idx) const
Matrix repBlock(const Matrix &A, int n)
Repeat a block matrix n times along the diagonal.
static G exp(const Vector &x)
Exponential map of the tangent space elements to the group.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Matrix numericalDifferential(std::function< Vector(const Vector &)> f, const Vector &x)
Calculate numerical differential.
Input velocityAction(const G< N > &X, const Input &u)
static Matrix3 Hat(const Vector3 &xi)
Hat maps from tangent vector to Lie algebra.
void update(const Measurement &y)
void eigensolver(const MatrixType &m)
Matrix blockDiag(const Matrix &A, const Matrix &B)
Create a block diagonal matrix from two matrices.
static Vector3 Vee(const Matrix3 &X)
Vee maps from Lie algebra to tangent vector.
Represents a 3D point on a unit sphere.
Vector3 outputAction(const G< N > &X, const Unit3 &y, int idx)
void propagation(const Input &u, double dt)
A non-templated config holding any types of Manifold-group elements.
gtsam
Author(s):
autogenerated on Wed May 28 2025 03:00:48