2 Implementation of Attitude-Bias-Calibration EqF form: 
    3 "Overcoming Bias: Equivariant Filter Design for Biased Attitude Estimation with Online Calibration" 
    4 https://ieeexplore.ieee.org/document/9905914 
    6 This module is Alessandro Fornasier's equivariant filter code (https://github.com/aau-cns/ABC-EqF)  
    7 converted to use GTSAM's libraries. 
    9 Authors: Jennifer Oum & Darshan Rajasekaran 
   14 from gtsam 
import Rot3, Unit3
 
   15 from dataclasses 
import dataclass
 
   16 from typing 
import List
 
   18 coordinate = 
"EXPONENTIAL" 
   22     """Check norm of a vector being 1 or nan 
   24     :param x: A numpy array 
   25     :param tol: tollerance, default 1e-3 
   26     :return: Boolean true if norm is 1 or nan 
   28     return abs(np.linalg.norm(x) - 1) < tol 
or np.isnan(np.linalg.norm(x))
 
   32     """Define the state of the Biased Attitude System 
   34     R is a rotation matrix representing the attitude of the body 
   35     b is a 3-vector representing the gyroscope bias 
   36     S is a list of rotation matrix, each representing the calibration of the corresponding direction sensor 
   38     Let's assume we want to use three known direction a, b, and c, where only the sensor that measure b is 
   39     uncalibrated (we'd like to estimate the calibration states). Therefore, the system's d list looks like 
   40     d = [b, a, c], and the S list should look like S = [Sb]. The association between d and S is done via indeces. 
   41     In general S[i] correspond to the calibration state of the sensor that measure the direcion d[i] 
   56         R: Rot3 = Rot3.Identity(),
 
   57         b: np.ndarray = np.zeros(3),
 
   62         :param R: A SO3 element representing the attitude of the system as a rotation matrix 
   63         :param b: A numpy array with size 3 representing the gyroscope bias 
   64         :param S: A list of SO3 elements representing the calibration states for "uncalibrated" sensors, 
   65         if no sensor require a calibration state, than S will be initialized as an empty list 
   71                 "the attitude rotation matrix R has to be of type SO3 but type is",
 
   76         if not (
isinstance(b, np.ndarray) 
and b.size == 3):
 
   78                 "The gyroscope bias has to be probvided as numpy array with size 3" 
   86                 raise TypeError(
"Calibration states has to be provided as a list")
 
   90                         "Elements of the list of calibration states have to be of type SO3" 
   96         """Return a identity state  with n calibration states 
   98         :param n: number of elements in list B associated with calibration states 
   99         :return: The identity element of the State 
  102         return State(Rot3.Identity(), np.zeros(3), [Rot3.Identity() 
for _ 
in range(n)])
 
  106     """Define the input space of the Biased Attitude System 
  108     w is a 3-vector representing the angular velocity measured by a gyroscope 
  118     def __init__(self, w: np.ndarray, Sigma: np.ndarray):
 
  121         :param w: A numpy array with size 3 representing the angular velocity measurement from a gyroscope 
  122         :param Sigma: A numpy array with shape (6, 6) representing the noise covariance of the 
  123         angular velocity measurement and gyro bias random walk 
  126         if not (
isinstance(w, np.ndarray) 
and w.size == 3):
 
  128                 "Angular velocity has to be provided as a numpy array with size 3" 
  131             isinstance(Sigma, np.ndarray) 
and Sigma.shape[0] == Sigma.shape[1] == 6
 
  134                 "Input measurement noise covariance has to be provided as a numpy array with shape (6. 6)" 
  136         if not np.all(np.linalg.eigvals(Sigma) >= 0):
 
  137             raise TypeError(
"Covariance matrix has to be semi-positive definite")
 
  144         """Return a random angular velocity 
  146         :return: A random angular velocity as a Input element 
  149         return Input(np.random.randn(3), np.eye(6))
 
  151     def W(self) -> np.ndarray:
 
  152         """Return the Input as a skew-symmetric matrix 
  154         :return: self.w as a skew-symmetric matrix 
  157         return Rot3.Hat(self.
w)
 
  161     """Symmetry group (SO(3) |x so(3)) x SO(3) x ... x SO(3) 
  163     Each element of the B list is associated with a calibration states in State's S list where the association is done 
  164     via corresponding index. In general B[i] is the SO(3) element of the symmetry group that correspond to the 
  165     state's calibration state S[i]. For example, let's assume we want to use three known direction a, b, and c, where 
  166     only the sensor that measure b is uncalibrated (we'd like to estimate the calibration states). Therefore, 
  167     the system's d list is defined as d = [b, a, c], and the state's S list is defined as S = [Sb]. The symmetry group 
  168     B list should be defined as B = [Bb] where Ba is the SO(3) element of the symmetry group that is related to Sb 
  178         A: Rot3 = Rot3.Identity(),
 
  179         a: np.ndarray = np.zeros((3, 3)),
 
  180         B: List[Rot3] = 
None,
 
  182         """Initialize the symmetry group G 
  184         :param A: SO3 element 
  185         :param a: np.ndarray with shape (3, 3) corresponding to a skew symmetric matrix 
  186         :param B: list of SO3 elements 
  190             raise TypeError(
"A has to be of type SO3")
 
  192         if not (
isinstance(a, np.ndarray) 
and a.shape == (3, 3)):
 
  193             raise TypeError(
"a has to be a numpy array with shape (3, 3)")
 
  200                     raise TypeError(
"Elements of B have to be of type SO3")
 
  204         """Define the group operation 
  207         :return: A element of the group G given by the "multiplication" of self and other 
  211         assert len(self.
B) == 
len(other.B)
 
  214             self.
a + Rot3.Hat(self.
A.
matrix() @ Rot3.Vee(other.a)),
 
  215             [self.
B[i] * other.B[i] 
for i 
in range(
len(self.
B))],
 
  220         """Return the identity of the symmetry group with n elements of SO3 related to sensor calibration states 
  222         :param n: number of elements in list B associated with calibration states 
  223         :return: The identity of the group G 
  226         return G(Rot3.Identity(), np.zeros((3, 3)), [Rot3.Identity() 
for _ 
in range(n)])
 
  230         """Return the SO(3) Left Jacobian 
  231         :param arr: A numpy array with size 3 
  232         :return: The left Jacobian of SO(3) 
  234         if not (
isinstance(arr, np.ndarray) 
and arr.size == 3):
 
  235             raise ValueError(
"A numpy array with size 3 has to be provided")
 
  236         angle = np.linalg.norm(arr)
 
  238         if np.isclose(angle, 0.0):
 
  239             return np.eye(3) + 0.5 * Rot3.Hat(arr)
 
  244             (s / angle) * np.eye(3)
 
  245             + (1 - (s / angle)) * np.outer(axis, axis)
 
  246             + ((1 - c) / angle) * Rot3.Hat(axis)
 
  249     def exp(x: np.ndarray) -> 
"G":
 
  250         """Return a group element X given by X = exp(x) where x is a numpy array 
  252         :param x: A numpy array 
  253         :return: A element of the group G given by the exponential of x 
  256         if not (
isinstance(x, np.ndarray) 
and x.size >= 6):
 
  258                 "Wrong shape, a numpy array with size 3n has to be provided" 
  260         if (x.size % 3) != 0:
 
  262                 "Wrong size, a numpy array with size multiple of 3 has to be provided" 
  265         n = 
int((x.size - 6) / 3)
 
  266         A = Rot3.Expmap(x[0:3])
 
  267         a = Rot3.Hat(G.Rot3LeftJacobian(x[0:3]) @ x[3:6])
 
  268         B = [Rot3.Expmap(x[(6 + 3 * i) : (9 + 3 * i)]) 
for i 
in range(n)]
 
  273         """Return the inverse element of the symmetry group 
  275         :return: A element of the group G given by the inverse of self 
  281             [B.inverse() 
for B 
in self.
B],
 
  286     """Define a direction as a S2 element""" 
  292         """Initialize direction 
  294         :param d: A numpy array with size 3 and norm 1 representing the direction 
  298             raise TypeError(
"Direction has to be provided as a 3 vector")
 
  302 def blockDiag(A: np.ndarray, B: np.ndarray) -> np.ndarray:
 
  303     """Create a lock diagonal matrix from blocks A and B 
  305     :param A: numpy array 
  306     :param B: numpy array 
  307     :return: numpy array representing a block diagonal matrix composed of blocks A and B 
  317                 [A, np.zeros((A.shape[0], B.shape[1]))],
 
  318                 [np.zeros((B.shape[0], A.shape[1])), B],
 
  324     """Create a block diagonal matrix repeating the A block n times 
  326     :param A: numpy array representing the block A 
  327     :param n: number of times to repeat A 
  328     :return: numpy array representing a block diagonal matrix composed of n-times the blocks A 
  338     """Compute the numerical derivative via central difference""" 
  341         x = np.reshape([x], (1, 1))
 
  346     Df = np.zeros((n, m))
 
  350         Df[:, j : j + 1] = (
f(x + h * ej) - 
f(x - h * ej)).
reshape(m, 1) / (2 * h)
 
  354 def lift(xi: State, u: Input) -> np.ndarray:
 
  355     """The Lift of the system (Theorem 3.8, Equation 7) 
  357     :param xi: A element of the State 
  358     :param u: A element of the Input space 
  359     :return: A numpy array representing the Lift 
  363     L = np.zeros(6 + 3 * n)
 
  365     L[3:6] = -u.W() @ xi.b
 
  367         L[(6 + 3 * i) : (9 + 3 * i)] = xi.S[i].
inverse().
matrix() @ L[0:3]
 
  372 def checkNorm(x: np.ndarray, tol: float = 1e-3):
 
  373     """Check norm of a vector being 1 or nan 
  375     :param x: A numpy array 
  376     :param tol: tollerance, default 1e-3 
  377     :return: Boolean true if norm is 1 or nan 
  379     return abs(np.linalg.norm(x) - 1) < tol 
or np.isnan(np.linalg.norm(x))
 
  383     """Action of the symmetry group on the state space, return phi(X, xi) (Equation 4) 
  385     :param X: A element of the group G 
  386     :param xi: A element of the State 
  387     :return: A new element of the state given by the action of phi of G in the State space 
  392             "the number of calibration states and B elements of the symmetry group has to match" 
  397         X.A.inverse().
matrix() @ (xi.b - Rot3.Vee(X.a)),
 
  398         [(X.A.inverse() * xi.S[i] * X.B[i]) 
for i 
in range(
len(X.B))],
 
  403     """Action of the symmetry group on the input space, return psi(X, u) (Equation 5) 
  405     :param X: A element of the group G 
  406     :param u: A element of the Input 
  407     :return: A new element of the Input given by the action of psi of G in the Input space 
  410     return Input(X.A.inverse().
matrix() @ (u.w - Rot3.Vee(X.a)), u.Sigma)
 
  414     """Action of the symmetry group on the output space, return rho(X, y) (Equation 6) 
  416     :param X: A element of the group G 
  417     :param y: A direction measurement 
  418     :param idx: indicate the index of the B element in the list, -1 in case no B element exist 
  419     :return: A numpy array given by the action of rho of G in the Output space 
  423         return X.A.inverse().
matrix() @ y.d.unitVector()
 
  429     """Local coordinates assuming __xi_0 = identity (Equation 9) 
  431     :param e: A element of the State representing the equivariant error 
  432     :return: Local coordinates assuming __xi_0 = identity 
  435     if coordinate == 
"EXPONENTIAL":
 
  436         tmp = [Rot3.Logmap(S) 
for S 
in e.S]
 
  437         eps = np.concatenate(
 
  446     elif coordinate == 
"NORMAL":
 
  447         raise ValueError(
"Normal coordinate representation is not implemented yet")
 
  451         raise ValueError(
"Invalid coordinate representation")
 
  457     """Local coordinates inverse assuming __xi_0 = identity 
  459     :param eps: A numpy array representing the equivariant error in local coordinates 
  460     :return: Local coordinates inverse assuming __xi_0 = identity 
  464     if coordinate == 
"EXPONENTIAL":
 
  465         e = 
State(X.A, eps[3:6, :], X.B)  
 
  466     elif coordinate == 
"NORMAL":
 
  467         raise ValueError(
"Normal coordinate representation is not implemented yet")
 
  470         raise ValueError(
"Invalid coordinate representation")
 
  476     """Differential of the phi action phi(xi, E) at E = Id in local coordinates (can be found within equation 23) 
  478     :param xi: A element of the State 
  479     :return: (Dtheta) * (Dphi(xi, E) at E = Id) 
  487     """Define a measurement 
  489     cal_idx is a index corresponding to the cal_idx-th calibration related to the measurement. Let's consider the case 
  490     of 2 uncalibrated sensor with two associated calibration state in State.S = [S0, S1], and a single calibrated sensor. 
  491     cal_idx = 0 indicates a measurement coming from the sensor that has calibration S0, cal_idx = 1 indicates a 
  492     measurement coming from the sensor that has calibration S1. cal_idx = -1 indicates that the measurement is coming 
  493     from a calibrated sensor 
  509     def __init__(self, y: np.ndarray, d: np.ndarray, Sigma: np.ndarray, i: int = -1):
 
  510         """Initialize measurement 
  512         :param y: A numpy array with size 3 and norm 1 representing the direction measurement in the sensor frame 
  513         :param d: A numpy array with size 3 and norm 1 representing the direction in the global frame 
  514         :param Sigma: A numpy array with shape (3, 3) representing the noise covariance of the direction measurement 
  515         :param i: index of the corresponding calibration state 
  519             raise TypeError(
"Measurement has to be provided as a (3, 1) vector")
 
  521             raise TypeError(
"Direction has to be provided as a (3, 1) vector")
 
  523             isinstance(Sigma, np.ndarray) 
and Sigma.shape[0] == Sigma.shape[1] == 3
 
  526                 "Direction measurement noise covariance has to be provided as a numpy array with shape (3. 3)" 
  528         if not np.all(np.linalg.eigvals(Sigma) >= 0):
 
  529             raise TypeError(
"Covariance matrix has to be semi-positive definite")
 
  530         if not (
isinstance(i, int) 
or i == -1 
or i > 0):
 
  531             raise TypeError(
"calibration index is a positive integer or -1")
 
  541     """Define ground-truth, input and output data""" 
  560     def __init__(self, Sigma: np.ndarray, n: int, m: int):
 
  563         :param Sigma: Initial covariance 
  564         :param n: Number of calibration states 
  565         :param m: Total number of available sensor 
  574             and (Sigma.shape[0] == Sigma.shape[1] == self.
__dof)
 
  577                 f
"Initial covariance has to be provided as a numpy array with shape ({self.__dof}, {self.__dof})" 
  579         if not np.all(np.linalg.eigvals(Sigma) >= 0):
 
  580             raise TypeError(
"Covariance matrix has to be semi-positive definite")
 
  582             raise TypeError(
"Number of calibration state has to be unsigned")
 
  584             raise TypeError(
"Number of direction sensor has to be grater-equal than 2")
 
  593         """Return estimated state 
  595         :return: Estimated state 
  600         """Propagate the filter state 
  602         :param u: Angular velocity measurement from IMU 
  603         :param dt: delta time between timestamp of last propagation/update and timestamp of angular velocity measurement 
  608                 "angular velocity measurement has to be provided as a Input element" 
  627         """Update the filter state 
  629         :param y: A  measurement 
  633         assert y.cal_idx <= self.
__n_cal 
  637             self.
__X_hat.inv(), y.y, y.cal_idx
 
  640         S = Ct @ self.
__Sigma @ Ct.T + Dt @ y.Sigma @ Dt.T  
 
  641         K = self.
__Sigma @ Ct.T @ np.linalg.inv(S)  
 
  647         """Return the state matrix A0t (Equation 14a) 
  650         :return: numpy array representing the state matrix A0t 
  654         A1 = np.zeros((6, 6))
 
  656         if coordinate == 
"EXPONENTIAL":
 
  657             A1[0:3, 3:6] = -np.eye(3)
 
  660         elif coordinate == 
"NORMAL":
 
  661             raise ValueError(
"Normal coordinate representation is not implemented yet")
 
  663             raise ValueError(
"Invalid coordinate representation")
 
  668         """Return the state transition matrix Phi (Equation 17) 
  671         :param dt: Delta time 
  672         :return: numpy array representing the state transition matrix Phi 
  676         Phi1 = np.zeros((6, 6))
 
  677         Phi12 = -dt * (np.eye(3) + (dt / 2) * W0 + ((dt**2) / 6) * W0 * W0)
 
  678         Phi22 = np.eye(3) + dt * W0 + ((dt**2) / 2) * W0 * W0
 
  680         if coordinate == 
"EXPONENTIAL":
 
  681             Phi1[0:3, 0:3] = np.eye(3)
 
  682             Phi1[0:3, 3:6] = Phi12
 
  683             Phi1[3:6, 3:6] = Phi22
 
  685         elif coordinate == 
"NORMAL":
 
  686             raise ValueError(
"Normal coordinate representation is not implemented yet")
 
  688             raise ValueError(
"Invalid coordinate representation")
 
  693         """Return the Input matrix Bt 
  695         :return: numpy array representing the state matrix Bt 
  698         if coordinate == 
"EXPONENTIAL":
 
  703         elif coordinate == 
"NORMAL":
 
  704             raise ValueError(
"Normal coordinate representation is not implemented yet")
 
  706             raise ValueError(
"Invalid coordinate representation")
 
  711         """Return the measurement matrix C0 (Equation 14b) 
  713         :param d: Known direction 
  714         :param idx: index of the related calibration state 
  715         :return: numpy array representing the measurement matrix C0 
  718         Cc = np.zeros((3, 3 * self.
__n_cal))
 
  722             Cc[(3 * idx) : (3 + 3 * idx), :] = Rot3.Hat(d.d.unitVector())
 
  724         return Rot3.Hat(d.d.unitVector()) @ np.hstack(
 
  725             (Rot3.Hat(d.d.unitVector()), np.zeros((3, 3)), Cc)
 
  729         """Return the measurement output matrix Dt 
  731         :param idx: index of the related calibration state 
  732         :return: numpy array representing the output matrix Dt