ABC_EQF.h
Go to the documentation of this file.
1 
12 #ifndef ABC_EQF_H
13 #define ABC_EQF_H
14 #pragma once
15 #include <gtsam/base/Matrix.h>
16 #include <gtsam/base/Vector.h>
17 #include <gtsam/geometry/Rot3.h>
18 #include <gtsam/geometry/Unit3.h>
19 #include <gtsam/inference/Symbol.h>
21 #include <gtsam/nonlinear/Values.h>
22 #include <gtsam/slam/dataset.h>
23 
24 #include <chrono>
25 #include <cmath>
26 #include <fstream>
27 #include <functional>
28 #include <iostream>
29 #include <numeric> // For std::accumulate
30 #include <string>
31 #include <vector>
32 
33 #include "ABC.h"
34 
35 // All implementations are wrapped in this namespace to avoid conflicts
36 namespace gtsam {
37 namespace abc_eqf_lib {
38 
39 using namespace std;
40 using namespace gtsam;
41 
42 //========================================================================
43 // Helper Functions for EqF
44 //========================================================================
45 
47 
48 Matrix numericalDifferential(std::function<Vector(const Vector&)> f,
49  const Vector& x);
50 
57 template <size_t N>
58 Vector lift(const State<N>& xi, const Input& u);
59 
66 template <size_t N>
67 State<N> operator*(const G<N>& X, const State<N>& xi);
68 
75 template <size_t N>
76 Input velocityAction(const G<N>& X, const Input& u);
77 
85 template <size_t N>
86 Vector3 outputAction(const G<N>& X, const Unit3& y, int idx);
87 
93 template <size_t N>
95 
96 //========================================================================
97 // Equivariant Filter (EqF)
98 //========================================================================
99 
101 template <size_t N>
102 class EqF {
103  private:
104  int dof; // Degrees of freedom
105  G<N> X_hat; // Filter state
106  Matrix Sigma; // Error covariance
107  State<N> xi_0; // Origin state
108  Matrix Dphi0; // Differential of phi at origin
109  Matrix InnovationLift; // Innovation lift matrix
110 
116  Matrix stateMatrixA(const Input& u) const;
117 
124  Matrix stateTransitionMatrix(const Input& u, double dt) const;
125 
130  Matrix inputMatrixBt() const;
131 
138  Matrix measurementMatrixC(const Unit3& d, int idx) const;
139 
145  Matrix outputMatrixDt(int idx) const;
146 
147  public:
153  EqF(const Matrix& Sigma, int m);
154 
159  State<N> stateEstimate() const;
160 
166  void propagation(const Input& u, double dt);
167 
172  void update(const Measurement& y);
173 };
174 
175 //========================================================================
176 // Helper Functions Implementation
177 //========================================================================
178 
186 template <size_t N>
187 Vector lift(const State<N>& xi, const Input& u) {
188  Vector L = Vector::Zero(6 + 3 * N);
189 
190  // First 3 elements
191  L.head<3>() = u.w - xi.b;
192 
193  // Next 3 elements
194  L.segment<3>(3) = -u.W() * xi.b;
195 
196  // Remaining elements
197  for (size_t i = 0; i < N; i++) {
198  L.segment<3>(6 + 3 * i) = xi.S[i].inverse().matrix() * L.head<3>();
199  }
200 
201  return L;
202 }
216 template <size_t N>
217 State<N> operator*(const G<N>& X, const State<N>& xi) {
218  std::array<Rot3, N> new_S;
219 
220  for (size_t i = 0; i < N; i++) {
221  new_S[i] = X.A.inverse() * xi.S[i] * X.B[i];
222  }
223 
224  return State<N>(xi.R * X.A, X.A.inverse().matrix() * (xi.b - Rot3::Vee(X.a)),
225  new_S);
226 }
235 template <size_t N>
236 Input velocityAction(const G<N>& X, const Input& u) {
237  return Input{X.A.inverse().matrix() * (u.w - Rot3::Vee(X.a)), u.Sigma};
238 }
247 template <size_t N>
248 Vector3 outputAction(const G<N>& X, const Unit3& y, int idx) {
249  if (idx == -1) {
250  return X.A.inverse().matrix() * y.unitVector();
251  } else {
252  if (idx >= static_cast<int>(N)) {
253  throw std::out_of_range("Calibration index out of range");
254  }
255  return X.B[idx].inverse().matrix() * y.unitVector();
256  }
257 }
258 
266 Matrix numericalDifferential(std::function<Vector(const Vector&)> f,
267  const Vector& x) {
268  double h = 1e-6;
269  Vector fx = f(x);
270  int n = fx.size();
271  int m = x.size();
272  Matrix Df = Matrix::Zero(n, m);
273 
274  for (int j = 0; j < m; j++) {
275  Vector ej = Vector::Zero(m);
276  ej(j) = 1.0;
277 
278  Vector fplus = f(x + h * ej);
279  Vector fminus = f(x - h * ej);
280 
281  Df.col(j) = (fplus - fminus) / (2 * h);
282  }
283 
284  return Df;
285 }
286 
295 template <size_t N>
297  std::function<Vector(const Vector&)> coordsAction = [&xi](const Vector& U) {
298  G<N> groupElement = G<N>::exp(U);
299  State<N> transformed = groupElement * xi;
300  return xi.localCoordinates(transformed);
301  };
302 
303  Vector zeros = Vector::Zero(6 + 3 * N);
304  Matrix differential = numericalDifferential(coordsAction, zeros);
305  return differential;
306 }
307 
308 //========================================================================
309 // Equivariant Filter (EqF) Implementation
310 //========================================================================
319 template <size_t N>
320 EqF<N>::EqF(const Matrix& Sigma, int m)
321  : dof(6 + 3 * N),
322  X_hat(G<N>::identity(N)),
323  Sigma(Sigma),
324  xi_0(State<N>::identity()) {
325  if (Sigma.rows() != dof || Sigma.cols() != dof) {
326  throw std::invalid_argument(
327  "Initial covariance dimensions must match the degrees of freedom");
328  }
329 
330  // Check positive semi-definite
332  if (eigensolver.eigenvalues().minCoeff() < -1e-10) {
333  throw std::invalid_argument(
334  "Covariance matrix must be semi-positive definite");
335  }
336 
337  if (N < 0) {
338  throw std::invalid_argument(
339  "Number of calibration states must be non-negative");
340  }
341 
342  if (m <= 1) {
343  throw std::invalid_argument(
344  "Number of direction sensors must be at least 2");
345  }
346 
347  // Compute differential of phi
349  InnovationLift = Dphi0.completeOrthogonalDecomposition().pseudoInverse();
350 }
355 template <size_t N>
357  return X_hat * xi_0;
358 }
367 template <size_t N>
368 void EqF<N>::propagation(const Input& u, double dt) {
369  State<N> state_est = stateEstimate();
370  Vector L = lift(state_est, u);
371 
372  Matrix Phi_DT = stateTransitionMatrix(u, dt);
373  Matrix Bt = inputMatrixBt();
374 
375  Matrix tempSigma = blockDiag(u.Sigma, repBlock(1e-9 * I_3x3, N));
376  Matrix M_DT = (Bt * tempSigma * Bt.transpose()) * dt;
377 
378  X_hat = X_hat * G<N>::exp(L * dt);
379  Sigma = Phi_DT * Sigma * Phi_DT.transpose() + M_DT;
380 }
388 template <size_t N>
390  if (y.cal_idx > static_cast<int>(N)) {
391  throw std::invalid_argument("Calibration index out of range");
392  }
393 
394  // Get vector representations for checking
395  Vector3 y_vec = y.y.unitVector();
396  Vector3 d_vec = y.d.unitVector();
397 
398  // Skip update if any NaN values are present
399  if (std::isnan(y_vec[0]) || std::isnan(y_vec[1]) || std::isnan(y_vec[2]) ||
400  std::isnan(d_vec[0]) || std::isnan(d_vec[1]) || std::isnan(d_vec[2])) {
401  return; // Skip this measurement
402  }
403 
404  Matrix Ct = measurementMatrixC(y.d, y.cal_idx);
405  Vector3 action_result = outputAction(X_hat.inv(), y.y, y.cal_idx);
406  Vector3 delta_vec = Rot3::Hat(y.d.unitVector()) * action_result;
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;
411  X_hat = G<N>::exp(Delta) * X_hat;
412  Sigma = (Matrix::Identity(dof, dof) - K * Ct) * Sigma;
413 }
420 template <size_t N>
422  Matrix3 W0 = velocityAction(X_hat.inv(), u).W();
423  Matrix A1 = Matrix::Zero(6, 6);
424  A1.block<3, 3>(0, 3) = -I_3x3;
425  A1.block<3, 3>(3, 3) = W0;
426  Matrix A2 = repBlock(W0, N);
427  return blockDiag(A1, A2);
428 }
429 
436 template <size_t N>
437 Matrix EqF<N>::stateTransitionMatrix(const Input& u, double dt) const {
438  Matrix3 W0 = velocityAction(X_hat.inv(), u).W();
439  Matrix Phi1 = Matrix::Zero(6, 6);
440 
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;
443 
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;
447  Matrix Phi2 = repBlock(Phi22, N);
448  return blockDiag(Phi1, Phi2);
449 }
455 template <size_t N>
457  Matrix B1 = blockDiag(X_hat.A.matrix(), X_hat.A.matrix());
458  Matrix B2(3 * N, 3 * N);
459 
460  for (size_t i = 0; i < N; ++i) {
461  B2.block<3, 3>(3 * i, 3 * i) = X_hat.B[i].matrix();
462  }
463 
464  return blockDiag(B1, B2);
465 }
474 template <size_t N>
475 Matrix EqF<N>::measurementMatrixC(const Unit3& d, int idx) const {
476  Matrix Cc = Matrix::Zero(3, 3 * N);
477 
478  // If the measurement is related to a sensor that has a calibration state
479  if (idx >= 0) {
480  // Set the correct 3x3 block in Cc
481  Cc.block<3, 3>(0, 3 * idx) = Rot3::Hat(d.unitVector());
482  }
483 
484  Matrix3 wedge_d = Rot3::Hat(d.unitVector());
485 
486  // Create the combined matrix
487  Matrix temp(3, 6 + 3 * N);
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;
491 
492  return wedge_d * temp;
493 }
499 template <size_t N>
501  // If the measurement is related to a sensor that has a calibration state
502  if (idx >= 0) {
503  if (idx >= static_cast<int>(N)) {
504  throw std::out_of_range("Calibration index out of range");
505  }
506  return X_hat.B[idx].matrix();
507  } else {
508  return X_hat.A.matrix();
509  }
510 }
511 
512 } // namespace abc_eqf_lib
513 
514 template <size_t N>
515 struct traits<abc_eqf_lib::EqF<N>>
516  : internal::LieGroupTraits<abc_eqf_lib::EqF<N>> {};
517 } // namespace gtsam
518 
519 #endif // ABC_EQF_H
gtsam::abc_eqf_lib::EqF
Equivariant Filter (EqF) implementation.
Definition: ABC_EQF.h:102
gtsam::abc_eqf_lib::EqF::stateEstimate
State< N > stateEstimate() const
Definition: ABC_EQF.h:356
gtsam::abc_eqf_lib::EqF::outputMatrixDt
Matrix outputMatrixDt(int idx) const
Definition: ABC_EQF.h:500
relicense.update
def update(text)
Definition: relicense.py:46
Vector.h
typedef and functions to augment Eigen's VectorXd
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
screwPose2::xi
Vector xi
Definition: testPose2.cpp:169
gtsam::abc_eqf_lib::Input::Sigma
Matrix Sigma
Angular velocity (3-vector)
Definition: ABC.h:111
fx
const double fx
Definition: testSmartStereoFactor_iSAM2.cpp:47
Matrix.h
typedef and functions to augment Eigen's MatrixXd
gtsam::abc_eqf_lib::EqF::inputMatrixBt
Matrix inputMatrixBt() const
Definition: ABC_EQF.h:456
gtsam::abc_eqf_lib::State
State class representing the state of the Biased Attitude System.
Definition: ABC.h:128
x
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
Definition: gnuplot_common_settings.hh:12
dt
const double dt
Definition: testVelocityConstraint.cpp:15
gtsam::abc_eqf_lib::stateActionDiff
Matrix stateActionDiff(const State< N > &xi)
Definition: ABC_EQF.h:296
ABC.h
Core components for Attitude-Bias-Calibration systems.
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
X
#define X
Definition: icosphere.cpp:20
gtsam::abc_eqf_lib::operator*
State< N > operator*(const G< N > &X, const State< N > &xi)
Definition: ABC_EQF.h:217
isnan
#define isnan(X)
Definition: main.h:93
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::abc_eqf_lib::EqF::EqF
EqF(const Matrix &Sigma, int m)
Definition: ABC_EQF.h:320
h
const double h
Definition: testSimpleHelicopter.cpp:19
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::abc_eqf_lib::EqF::stateTransitionMatrix
Matrix stateTransitionMatrix(const Input &u, double dt) const
Definition: ABC_EQF.h:437
Unit3.h
Rot3.h
3D rotation represented as a rotation matrix or quaternion
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam::abc_eqf_lib::EqF::stateMatrixA
Matrix stateMatrixA(const Input &u) const
Definition: ABC_EQF.h:421
gtsam::abc_eqf_lib::lift
Vector lift(const State< N > &xi, const Input &u)
Definition: ABC_EQF.h:187
gtsam::abc_eqf_lib::Input::W
Matrix3 W() const
Random input.
Definition: ABC.h:113
dataset.h
utility functions for loading datasets
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
Eigen::SelfAdjointEigenSolver
Computes eigenvalues and eigenvectors of selfadjoint matrices.
Definition: SelfAdjointEigenSolver.h:76
gtsam::abc_eqf_lib::EqF::measurementMatrixC
Matrix measurementMatrixC(const Unit3 &d, int idx) const
Definition: ABC_EQF.h:475
A2
static const double A2[]
Definition: expn.h:7
L
MatrixXd L
Definition: LLT_example.cpp:6
Symbol.h
gtsam::abc_eqf_lib::repBlock
Matrix repBlock(const Matrix &A, int n)
Repeat a block matrix n times along the diagonal.
Definition: ABC.h:93
gtsam::abc_eqf_lib::EqF::Sigma
Matrix Sigma
Definition: ABC_EQF.h:106
gtsam::internal::LieGroupTraits
Definition: Lie.h:174
gtsam::abc_eqf_lib::Input
Input struct for the Biased Attitude System.
Definition: ABC.h:109
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
gtsam::abc_eqf_lib::Input::w
Vector3 w
Definition: ABC.h:110
gtsam::abc_eqf_lib::EqF::InnovationLift
Matrix InnovationLift
Definition: ABC_EQF.h:109
gtsam::abc_eqf_lib::G::exp
static G exp(const Vector &x)
Exponential map of the tangent space elements to the group.
Definition: ABC.h:233
y
Scalar * y
Definition: level1_cplx_impl.h:124
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
ImuBias.h
gtsam::abc_eqf_lib::EqF::X_hat
G< N > X_hat
Definition: ABC_EQF.h:105
State
Definition: testKalmanFilter.cpp:31
gtsam::abc_eqf_lib::numericalDifferential
Matrix numericalDifferential(std::function< Vector(const Vector &)> f, const Vector &x)
Calculate numerical differential.
Definition: ABC_EQF.h:266
gtsam::abc_eqf_lib::velocityAction
Input velocityAction(const G< N > &X, const Input &u)
Definition: ABC_EQF.h:236
gtsam
traits
Definition: ABC.h:17
gtsam::abc_eqf_lib::EqF::dof
int dof
Definition: ABC_EQF.h:104
gtsam::Rot3::Hat
static Matrix3 Hat(const Vector3 &xi)
Hat maps from tangent vector to Lie algebra.
Definition: Rot3.h:406
gtsam::abc_eqf_lib::EqF::update
void update(const Measurement &y)
Definition: ABC_EQF.h:389
gtsam::traits
Definition: Group.h:36
K
#define K
Definition: igam.h:8
std
Definition: BFloat16.h:88
eigensolver
void eigensolver(const MatrixType &m)
Definition: eigensolver_complex.cpp:72
A1
static const double A1[]
Definition: expn.h:6
gtsam::abc_eqf_lib::blockDiag
Matrix blockDiag(const Matrix &A, const Matrix &B)
Create a block diagonal matrix from two matrices.
Definition: ABC.h:73
gtsam::abc_eqf_lib::Measurement
Measurement struct.
Definition: ABC.h:119
U
@ U
Definition: testDecisionTree.cpp:342
gtsam::abc_eqf_lib::EqF::xi_0
State< N > xi_0
Definition: ABC_EQF.h:107
gtsam::Rot3::Vee
static Vector3 Vee(const Matrix3 &X)
Vee maps from Lie algebra to tangent vector.
Definition: Rot3.h:409
N
#define N
Definition: igam.h:9
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
gtsam::abc_eqf_lib::G
Definition: ABC.h:196
gtsam::abc_eqf_lib::outputAction
Vector3 outputAction(const G< N > &X, const Unit3 &y, int idx)
Definition: ABC_EQF.h:248
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::abc_eqf_lib::EqF::propagation
void propagation(const Input &u, double dt)
Definition: ABC_EQF.h:368
Values.h
A non-templated config holding any types of Manifold-group elements.
gtsam::abc_eqf_lib::EqF::Dphi0
Matrix Dphi0
Definition: ABC_EQF.h:108
S
DiscreteKey S(1, 2)


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:00:48