Classes | Functions | Variables
gtsam.examples.EqF Namespace Reference

Classes

class  Data
 
class  Direction
 
class  EqF
 
class  G
 
class  Input
 
class  Measurement
 
class  State
 

Functions

np.ndarray blockDiag (np.ndarray A, np.ndarray B)
 
def checkNorm (np.ndarray x, float tol=1e-3)
 
np.ndarray lift (State xi, Input u)
 
np.ndarray local_coords (State e)
 
"State" local_coords_inv (np.ndarray eps)
 
np.ndarray numericalDifferential (f, x)
 
np.ndarray outputAction (G X, Direction y, int idx=-1)
 
np.ndarray repBlock (np.ndarray A, int n)
 
State stateAction (G X, State xi)
 
np.ndarray stateActionDiff (State xi)
 
Input velocityAction (G X, Input u)
 

Variables

string coordinate = "EXPONENTIAL"
 

Detailed Description

Implementation of Attitude-Bias-Calibration EqF form:
"Overcoming Bias: Equivariant Filter Design for Biased Attitude Estimation with Online Calibration"
https://ieeexplore.ieee.org/document/9905914

This module is Alessandro Fornasier's equivariant filter code (https://github.com/aau-cns/ABC-EqF) 
converted to use GTSAM's libraries.

Authors: Jennifer Oum & Darshan Rajasekaran

Function Documentation

◆ blockDiag()

np.ndarray gtsam.examples.EqF.blockDiag ( np.ndarray  A,
np.ndarray  B 
)
Create a lock diagonal matrix from blocks A and B

:param A: numpy array
:param B: numpy array
:return: numpy array representing a block diagonal matrix composed of blocks A and B

Definition at line 302 of file EqF.py.

◆ checkNorm()

def gtsam.examples.EqF.checkNorm ( np.ndarray  x,
float   tol = 1e-3 
)
Check norm of a vector being 1 or nan

:param x: A numpy array
:param tol: tollerance, default 1e-3
:return: Boolean true if norm is 1 or nan

Definition at line 21 of file EqF.py.

◆ lift()

np.ndarray gtsam.examples.EqF.lift ( State  xi,
Input  u 
)
The Lift of the system (Theorem 3.8, Equation 7)

:param xi: A element of the State
:param u: A element of the Input space
:return: A numpy array representing the Lift

Definition at line 354 of file EqF.py.

◆ local_coords()

np.ndarray gtsam.examples.EqF.local_coords ( State  e)
Local coordinates assuming __xi_0 = identity (Equation 9)

:param e: A element of the State representing the equivariant error
:return: Local coordinates assuming __xi_0 = identity

Definition at line 428 of file EqF.py.

◆ local_coords_inv()

"State" gtsam.examples.EqF.local_coords_inv ( np.ndarray  eps)
Local coordinates inverse assuming __xi_0 = identity

:param eps: A numpy array representing the equivariant error in local coordinates
:return: Local coordinates inverse assuming __xi_0 = identity

Definition at line 456 of file EqF.py.

◆ numericalDifferential()

np.ndarray gtsam.examples.EqF.numericalDifferential (   f,
  x 
)
Compute the numerical derivative via central difference

Definition at line 337 of file EqF.py.

◆ outputAction()

np.ndarray gtsam.examples.EqF.outputAction ( G  X,
Direction  y,
int   idx = -1 
)
Action of the symmetry group on the output space, return rho(X, y) (Equation 6)

:param X: A element of the group G
:param y: A direction measurement
:param idx: indicate the index of the B element in the list, -1 in case no B element exist
:return: A numpy array given by the action of rho of G in the Output space

Definition at line 413 of file EqF.py.

◆ repBlock()

np.ndarray gtsam.examples.EqF.repBlock ( np.ndarray  A,
int  n 
)
Create a block diagonal matrix repeating the A block n times

:param A: numpy array representing the block A
:param n: number of times to repeat A
:return: numpy array representing a block diagonal matrix composed of n-times the blocks A

Definition at line 323 of file EqF.py.

◆ stateAction()

State gtsam.examples.EqF.stateAction ( G  X,
State  xi 
)
Action of the symmetry group on the state space, return phi(X, xi) (Equation 4)

:param X: A element of the group G
:param xi: A element of the State
:return: A new element of the state given by the action of phi of G in the State space

Definition at line 382 of file EqF.py.

◆ stateActionDiff()

np.ndarray gtsam.examples.EqF.stateActionDiff ( State  xi)
Differential of the phi action phi(xi, E) at E = Id in local coordinates (can be found within equation 23)

:param xi: A element of the State
:return: (Dtheta) * (Dphi(xi, E) at E = Id)

Definition at line 475 of file EqF.py.

◆ velocityAction()

Input gtsam.examples.EqF.velocityAction ( G  X,
Input  u 
)
Action of the symmetry group on the input space, return psi(X, u) (Equation 5)

:param X: A element of the group G
:param u: A element of the Input
:return: A new element of the Input given by the action of psi of G in the Input space

Definition at line 402 of file EqF.py.

Variable Documentation

◆ coordinate

string gtsam.examples.EqF.coordinate = "EXPONENTIAL"

Definition at line 18 of file EqF.py.



gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:15:49