EqF.py
Go to the documentation of this file.
1 """
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
5 
6 This module is Alessandro Fornasier's equivariant filter code (https://github.com/aau-cns/ABC-EqF)
7 converted to use GTSAM's libraries.
8 
9 Authors: Jennifer Oum & Darshan Rajasekaran
10 """
11 
12 import numpy as np
13 import gtsam
14 from gtsam import Rot3, Unit3
15 from dataclasses import dataclass
16 from typing import List
17 
18 coordinate = "EXPONENTIAL"
19 
20 
21 def checkNorm(x: np.ndarray, tol: float = 1e-3):
22  """Check norm of a vector being 1 or nan
23 
24  :param x: A numpy array
25  :param tol: tollerance, default 1e-3
26  :return: Boolean true if norm is 1 or nan
27  """
28  return abs(np.linalg.norm(x) - 1) < tol or np.isnan(np.linalg.norm(x))
29 
30 
31 class State:
32  """Define the state of the Biased Attitude System
33  ----------
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
37  ----------
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]
42  ----------
43  """
44 
45  # Attitude rotation matrix R
46  R: Rot3
47 
48  # Gyroscope bias b
49  b: np.ndarray
50 
51  # Sensor calibrations S
52  S: List[Rot3]
53 
54  def __init__(
55  self,
56  R: Rot3 = Rot3.Identity(),
57  b: np.ndarray = np.zeros(3),
58  S: List[Rot3] = None,
59  ):
60  """Initialize State
61 
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
66  """
67 
68  if not isinstance(R, gtsam.Rot3):
69 
70  raise TypeError(
71  "the attitude rotation matrix R has to be of type SO3 but type is",
72  type(R),
73  )
74  self.R = R
75 
76  if not (isinstance(b, np.ndarray) and b.size == 3):
77  raise TypeError(
78  "The gyroscope bias has to be probvided as numpy array with size 3"
79  )
80  self.b = b
81 
82  if S is None:
83  self.S = []
84  else:
85  if not isinstance(S, list):
86  raise TypeError("Calibration states has to be provided as a list")
87  for calibration in S:
88  if not isinstance(calibration, Rot3):
89  raise TypeError(
90  "Elements of the list of calibration states have to be of type SO3"
91  )
92  self.S = S
93 
94  @staticmethod
95  def identity(n: int):
96  """Return a identity state with n calibration states
97 
98  :param n: number of elements in list B associated with calibration states
99  :return: The identity element of the State
100  """
101 
102  return State(Rot3.Identity(), np.zeros(3), [Rot3.Identity() for _ in range(n)])
103 
104 
105 class Input:
106  """Define the input space of the Biased Attitude System
107  ----------
108  w is a 3-vector representing the angular velocity measured by a gyroscope
109  ----------
110  """
111 
112  # Angular velocity
113  w: np.ndarray
114 
115  # Noise covariance of angular velocity
116  Sigma: np.ndarray
117 
118  def __init__(self, w: np.ndarray, Sigma: np.ndarray):
119  """Initialize Input
120 
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
124  """
125 
126  if not (isinstance(w, np.ndarray) and w.size == 3):
127  raise TypeError(
128  "Angular velocity has to be provided as a numpy array with size 3"
129  )
130  if not (
131  isinstance(Sigma, np.ndarray) and Sigma.shape[0] == Sigma.shape[1] == 6
132  ):
133  raise TypeError(
134  "Input measurement noise covariance has to be provided as a numpy array with shape (6. 6)"
135  )
136  if not np.all(np.linalg.eigvals(Sigma) >= 0):
137  raise TypeError("Covariance matrix has to be semi-positive definite")
138 
139  self.w = w
140  self.Sigma = Sigma
141 
142  @staticmethod
143  def random() -> "Input":
144  """Return a random angular velocity
145 
146  :return: A random angular velocity as a Input element
147  """
148 
149  return Input(np.random.randn(3), np.eye(6))
150 
151  def W(self) -> np.ndarray:
152  """Return the Input as a skew-symmetric matrix
153 
154  :return: self.w as a skew-symmetric matrix
155  """
156 
157  return Rot3.Hat(self.w)
158 
159 
160 class G:
161  """Symmetry group (SO(3) |x so(3)) x SO(3) x ... x SO(3)
162  ----------
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
169  ----------
170  """
171 
172  A: Rot3
173  a: np.ndarray
174  B: List[Rot3]
175 
176  def __init__(
177  self,
178  A: Rot3 = Rot3.Identity(),
179  a: np.ndarray = np.zeros((3, 3)),
180  B: List[Rot3] = None,
181  ):
182  """Initialize the symmetry group G
183 
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
187  """
188 
189  if not isinstance(A, Rot3):
190  raise TypeError("A has to be of type SO3")
191  self.A = A
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)")
194  self.a = a
195  if B is None:
196  self.B = []
197  else:
198  for b in B:
199  if not isinstance(b, Rot3):
200  raise TypeError("Elements of B have to be of type SO3")
201  self.B = B
202 
203  def __mul__(self, other: "G") -> "G":
204  """Define the group operation
205 
206  :param other: G
207  :return: A element of the group G given by the "multiplication" of self and other
208  """
209 
210  assert isinstance(other, G)
211  assert len(self.B) == len(other.B)
212  return G(
213  self.A * other.A,
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))],
216  )
217 
218  @staticmethod
219  def identity(n: int):
220  """Return the identity of the symmetry group with n elements of SO3 related to sensor calibration states
221 
222  :param n: number of elements in list B associated with calibration states
223  :return: The identity of the group G
224  """
225 
226  return G(Rot3.Identity(), np.zeros((3, 3)), [Rot3.Identity() for _ in range(n)])
227 
228  @staticmethod
229  def Rot3LeftJacobian(arr: np.ndarray) -> np.ndarray:
230  """Return the SO(3) Left Jacobian
231  :param arr: A numpy array with size 3
232  :return: The left Jacobian of SO(3)
233  """
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)
237  # Near |phi|==0, use first order Taylor expansion
238  if np.isclose(angle, 0.0):
239  return np.eye(3) + 0.5 * Rot3.Hat(arr)
240  axis = arr / angle
241  s = np.sin(angle)
242  c = np.cos(angle)
243  return (
244  (s / angle) * np.eye(3)
245  + (1 - (s / angle)) * np.outer(axis, axis)
246  + ((1 - c) / angle) * Rot3.Hat(axis)
247  )
248 
249  def exp(x: np.ndarray) -> "G":
250  """Return a group element X given by X = exp(x) where x is a numpy array
251 
252  :param x: A numpy array
253  :return: A element of the group G given by the exponential of x
254  """
255 
256  if not (isinstance(x, np.ndarray) and x.size >= 6):
257  raise ValueError(
258  "Wrong shape, a numpy array with size 3n has to be provided"
259  )
260  if (x.size % 3) != 0:
261  raise ValueError(
262  "Wrong size, a numpy array with size multiple of 3 has to be provided"
263  )
264 
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)]
269 
270  return G(A, a, B)
271 
272  def inv(self) -> "G":
273  """Return the inverse element of the symmetry group
274 
275  :return: A element of the group G given by the inverse of self
276  """
277 
278  return G(
279  self.A.inverse(),
280  -Rot3.Hat(self.A.inverse().matrix() @ Rot3.Vee(self.a)),
281  [B.inverse() for B in self.B],
282  )
283 
284 
285 class Direction:
286  """Define a direction as a S2 element"""
287 
288  # Direction
289  d: Unit3
290 
291  def __init__(self, d: np.ndarray):
292  """Initialize direction
293 
294  :param d: A numpy array with size 3 and norm 1 representing the direction
295  """
296 
297  if not (isinstance(d, np.ndarray) and d.size == 3 and checkNorm(d)):
298  raise TypeError("Direction has to be provided as a 3 vector")
299  self.d = Unit3(d)
300 
301 
302 def blockDiag(A: np.ndarray, B: np.ndarray) -> np.ndarray:
303  """Create a lock diagonal matrix from blocks A and B
304 
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
308  """
309 
310  if A is None:
311  return B
312  elif B is None:
313  return A
314  else:
315  return np.block(
316  [
317  [A, np.zeros((A.shape[0], B.shape[1]))],
318  [np.zeros((B.shape[0], A.shape[1])), B],
319  ]
320  )
321 
322 
323 def repBlock(A: np.ndarray, n: int) -> np.ndarray:
324  """Create a block diagonal matrix repeating the A block n times
325 
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
329  """
330 
331  res = None
332  for _ in range(n):
333  res = blockDiag(res, A)
334  return res
335 
336 
337 def numericalDifferential(f, x) -> np.ndarray:
338  """Compute the numerical derivative via central difference"""
339 
340  if isinstance(x, float):
341  x = np.reshape([x], (1, 1))
342  h = 1e-6
343  fx = f(x)
344  n = fx.shape[0]
345  m = x.shape[0]
346  Df = np.zeros((n, m))
347  for j in range(m):
348  ej = np.zeros(m)
349  ej[j] = 1.0
350  Df[:, j : j + 1] = (f(x + h * ej) - f(x - h * ej)).reshape(m, 1) / (2 * h)
351  return Df
352 
353 
354 def lift(xi: State, u: Input) -> np.ndarray:
355  """The Lift of the system (Theorem 3.8, Equation 7)
356 
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
360  """
361 
362  n = len(xi.S)
363  L = np.zeros(6 + 3 * n)
364  L[0:3] = u.w - xi.b
365  L[3:6] = -u.W() @ xi.b
366  for i in range(n):
367  L[(6 + 3 * i) : (9 + 3 * i)] = xi.S[i].inverse().matrix() @ L[0:3]
368 
369  return L
370 
371 
372 def checkNorm(x: np.ndarray, tol: float = 1e-3):
373  """Check norm of a vector being 1 or nan
374 
375  :param x: A numpy array
376  :param tol: tollerance, default 1e-3
377  :return: Boolean true if norm is 1 or nan
378  """
379  return abs(np.linalg.norm(x) - 1) < tol or np.isnan(np.linalg.norm(x))
380 
381 
382 def stateAction(X: G, xi: State) -> State:
383  """Action of the symmetry group on the state space, return phi(X, xi) (Equation 4)
384 
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
388  """
389 
390  if len(xi.S) != len(X.B):
391  raise ValueError(
392  "the number of calibration states and B elements of the symmetry group has to match"
393  )
394 
395  return State(
396  xi.R * X.A,
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))],
399  )
400 
401 
402 def velocityAction(X: G, u: Input) -> Input:
403  """Action of the symmetry group on the input space, return psi(X, u) (Equation 5)
404 
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
408  """
409 
410  return Input(X.A.inverse().matrix() @ (u.w - Rot3.Vee(X.a)), u.Sigma)
411 
412 
413 def outputAction(X: G, y: Direction, idx: int = -1) -> np.ndarray:
414  """Action of the symmetry group on the output space, return rho(X, y) (Equation 6)
415 
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
420  """
421 
422  if idx == -1:
423  return X.A.inverse().matrix() @ y.d.unitVector()
424  else:
425  return X.B[idx].inverse().matrix() @ y.d.unitVector()
426 
427 
428 def local_coords(e: State) -> np.ndarray:
429  """Local coordinates assuming __xi_0 = identity (Equation 9)
430 
431  :param e: A element of the State representing the equivariant error
432  :return: Local coordinates assuming __xi_0 = identity
433  """
434 
435  if coordinate == "EXPONENTIAL":
436  tmp = [Rot3.Logmap(S) for S in e.S]
437  eps = np.concatenate(
438  (
439  Rot3.Logmap(e.R),
440  e.b,
441  np.asarray(tmp).reshape(
442  3 * len(tmp),
443  ),
444  )
445  )
446  elif coordinate == "NORMAL":
447  raise ValueError("Normal coordinate representation is not implemented yet")
448  # X = G(e.R, -SO3.Rot3.Hat(e.R @ e.b), e.S)
449  # eps = G.log(X)
450  else:
451  raise ValueError("Invalid coordinate representation")
452 
453  return eps
454 
455 
456 def local_coords_inv(eps: np.ndarray) -> "State":
457  """Local coordinates inverse assuming __xi_0 = identity
458 
459  :param eps: A numpy array representing the equivariant error in local coordinates
460  :return: Local coordinates inverse assuming __xi_0 = identity
461  """
462 
463  X = G.exp(eps) # G
464  if coordinate == "EXPONENTIAL":
465  e = State(X.A, eps[3:6, :], X.B) # State
466  elif coordinate == "NORMAL":
467  raise ValueError("Normal coordinate representation is not implemented yet")
468  # stateAction(X, State(SO3.identity(), np.zeros(3), [SO3.identity() for _ in range(len(X.B))]))
469  else:
470  raise ValueError("Invalid coordinate representation")
471 
472  return e
473 
474 
475 def stateActionDiff(xi: State) -> np.ndarray:
476  """Differential of the phi action phi(xi, E) at E = Id in local coordinates (can be found within equation 23)
477 
478  :param xi: A element of the State
479  :return: (Dtheta) * (Dphi(xi, E) at E = Id)
480  """
481  coordsAction = lambda U: local_coords(stateAction(G.exp(U), xi))
482  differential = numericalDifferential(coordsAction, np.zeros(6 + 3 * len(xi.S)))
483  return differential
484 
485 
487  """Define a measurement
488  ----------
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
494  ----------
495  """
496 
497  # measurement
498  y: Direction
499 
500  # Known direction in global frame
501  d: Direction
502 
503  # Covariance matrix of the measurement
504  Sigma: np.ndarray
505 
506  # Calibration index
507  cal_idx: int = -1
508 
509  def __init__(self, y: np.ndarray, d: np.ndarray, Sigma: np.ndarray, i: int = -1):
510  """Initialize measurement
511 
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
516  """
517 
518  if not (isinstance(y, np.ndarray) and y.size == 3 and checkNorm(y)):
519  raise TypeError("Measurement has to be provided as a (3, 1) vector")
520  if not (isinstance(d, np.ndarray) and d.size == 3 and checkNorm(d)):
521  raise TypeError("Direction has to be provided as a (3, 1) vector")
522  if not (
523  isinstance(Sigma, np.ndarray) and Sigma.shape[0] == Sigma.shape[1] == 3
524  ):
525  raise TypeError(
526  "Direction measurement noise covariance has to be provided as a numpy array with shape (3. 3)"
527  )
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")
532 
533  self.y = Direction(y)
534  self.d = Direction(d)
535  self.Sigma = Sigma
536  self.cal_idx = i
537 
538 
539 @dataclass
540 class Data:
541  """Define ground-truth, input and output data"""
542 
543  # Ground-truth state
544  xi: State
545  n_cal: int
546 
547  # Input measurements
548  u: Input
549 
550  # Output measurements as a list of Measurement
551  y: list
552  n_meas: int
553 
554  # Time
555  t: float
556  dt: float
557 
558 
559 class EqF:
560  def __init__(self, Sigma: np.ndarray, n: int, m: int):
561  """Initialize EqF
562 
563  :param Sigma: Initial covariance
564  :param n: Number of calibration states
565  :param m: Total number of available sensor
566  """
567 
568  self.__dof = 6 + 3 * n
569  self.__n_cal = n
570  self.__n_sensor = m
571 
572  if not (
573  isinstance(Sigma, np.ndarray)
574  and (Sigma.shape[0] == Sigma.shape[1] == self.__dof)
575  ):
576  raise TypeError(
577  f"Initial covariance has to be provided as a numpy array with shape ({self.__dof}, {self.__dof})"
578  )
579  if not np.all(np.linalg.eigvals(Sigma) >= 0):
580  raise TypeError("Covariance matrix has to be semi-positive definite")
581  if not (isinstance(n, int) and n >= 0):
582  raise TypeError("Number of calibration state has to be unsigned")
583  if not (isinstance(m, int) and m > 1):
584  raise TypeError("Number of direction sensor has to be grater-equal than 2")
585 
586  self.__X_hat = G.identity(n)
587  self.__Sigma = Sigma
588  self.__xi_0 = State.identity(n)
589  self.__Dphi0 = stateActionDiff(self.__xi_0) # Within equation 23
590  self.__InnovationLift = np.linalg.pinv(self.__Dphi0) # Within equation 23
591 
592  def stateEstimate(self) -> State:
593  """Return estimated state
594 
595  :return: Estimated state
596  """
597  return stateAction(self.__X_hat, self.__xi_0)
598 
599  def propagation(self, u: Input, dt: float):
600  """Propagate the filter state
601 
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
604  """
605 
606  if not isinstance(u, Input):
607  raise TypeError(
608  "angular velocity measurement has to be provided as a Input element"
609  )
610 
611  L = lift(self.stateEstimate(), u) # Equation 7
612 
613  Phi_DT = self.__stateTransitionMatrix(u, dt) # Equation 17
614  # Equivalent
615  # A0t = self.__stateMatrixA(u) # Equation 14a
616  # Phi_DT = expm(A0t * dt)
617 
618  Bt = self.__inputMatrixBt() # Equation 27
619  M_DT = (
620  Bt @ blockDiag(u.Sigma, repBlock(1e-9 * np.eye(3), self.__n_cal)) @ Bt.T
621  ) * dt
622 
623  self.__X_hat = self.__X_hat * G.exp(L * dt) # Equation 18
624  self.__Sigma = Phi_DT @ self.__Sigma @ Phi_DT.T + M_DT # Equation 19
625 
626  def update(self, y: Measurement):
627  """Update the filter state
628 
629  :param y: A measurement
630  """
631 
632  # Cross-check calibration
633  assert y.cal_idx <= self.__n_cal
634 
635  Ct = self.__measurementMatrixC(y.d, y.cal_idx) # Equation 14b
636  delta = Rot3.Hat(y.d.d.unitVector()) @ outputAction(
637  self.__X_hat.inv(), y.y, y.cal_idx
638  )
639  Dt = self.__outputMatrixDt(y.cal_idx)
640  S = Ct @ self.__Sigma @ Ct.T + Dt @ y.Sigma @ Dt.T # Equation 21
641  K = self.__Sigma @ Ct.T @ np.linalg.inv(S) # Equation 22
642  Delta = self.__InnovationLift @ K @ delta # Equation 23
643  self.__X_hat = G.exp(Delta) * self.__X_hat # Equation 24
644  self.__Sigma = (np.eye(self.__dof) - K @ Ct) @ self.__Sigma # Equation 25
645 
646  def __stateMatrixA(self, u: Input) -> np.ndarray:
647  """Return the state matrix A0t (Equation 14a)
648 
649  :param u: Input
650  :return: numpy array representing the state matrix A0t
651  """
652 
653  W0 = velocityAction(self.__X_hat.inv(), u).W()
654  A1 = np.zeros((6, 6))
655 
656  if coordinate == "EXPONENTIAL":
657  A1[0:3, 3:6] = -np.eye(3)
658  A1[3:6, 3:6] = W0
659  A2 = repBlock(W0, self.__n_cal)
660  elif coordinate == "NORMAL":
661  raise ValueError("Normal coordinate representation is not implemented yet")
662  else:
663  raise ValueError("Invalid coordinate representation")
664 
665  return blockDiag(A1, A2)
666 
667  def __stateTransitionMatrix(self, u: Input, dt: float) -> np.ndarray:
668  """Return the state transition matrix Phi (Equation 17)
669 
670  :param u: Input
671  :param dt: Delta time
672  :return: numpy array representing the state transition matrix Phi
673  """
674 
675  W0 = velocityAction(self.__X_hat.inv(), u).W()
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
679 
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
684  Phi2 = repBlock(Phi22, self.__n_cal)
685  elif coordinate == "NORMAL":
686  raise ValueError("Normal coordinate representation is not implemented yet")
687  else:
688  raise ValueError("Invalid coordinate representation")
689 
690  return blockDiag(Phi1, Phi2)
691 
692  def __inputMatrixBt(self) -> np.ndarray:
693  """Return the Input matrix Bt
694 
695  :return: numpy array representing the state matrix Bt
696  """
697 
698  if coordinate == "EXPONENTIAL":
699  B1 = blockDiag(self.__X_hat.A.matrix(), self.__X_hat.A.matrix())
700  B2 = None
701  for B in self.__X_hat.B:
702  B2 = blockDiag(B2, B.matrix())
703  elif coordinate == "NORMAL":
704  raise ValueError("Normal coordinate representation is not implemented yet")
705  else:
706  raise ValueError("Invalid coordinate representation")
707 
708  return blockDiag(B1, B2)
709 
710  def __measurementMatrixC(self, d: Direction, idx: int) -> np.ndarray:
711  """Return the measurement matrix C0 (Equation 14b)
712 
713  :param d: Known direction
714  :param idx: index of the related calibration state
715  :return: numpy array representing the measurement matrix C0
716  """
717 
718  Cc = np.zeros((3, 3 * self.__n_cal))
719 
720  # If the measurement is related to a sensor that has a calibration state
721  if idx >= 0:
722  Cc[(3 * idx) : (3 + 3 * idx), :] = Rot3.Hat(d.d.unitVector())
723 
724  return Rot3.Hat(d.d.unitVector()) @ np.hstack(
725  (Rot3.Hat(d.d.unitVector()), np.zeros((3, 3)), Cc)
726  )
727 
728  def __outputMatrixDt(self, idx: int) -> np.ndarray:
729  """Return the measurement output matrix Dt
730 
731  :param idx: index of the related calibration state
732  :return: numpy array representing the output matrix Dt
733  """
734 
735  # If the measurement is related to a sensor that has a calibration state
736  if idx >= 0:
737  return self.__X_hat.B[idx].matrix()
738  else:
739  return self.__X_hat.A.matrix()
gtsam.examples.EqF.EqF.__inputMatrixBt
np.ndarray __inputMatrixBt(self)
Definition: EqF.py:692
gtsam.examples.EqF.G.identity
def identity(int n)
Definition: EqF.py:219
gtsam.examples.DogLegOptimizerExample.int
int
Definition: DogLegOptimizerExample.py:111
gtsam.examples.EqF.G.inv
"G" inv(self)
Definition: EqF.py:272
gtsam.examples.EqF.Input.W
np.ndarray W(self)
Definition: EqF.py:151
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
gtsam.examples.EqF.numericalDifferential
np.ndarray numericalDifferential(f, x)
Definition: EqF.py:337
gtsam.examples.EqF.Measurement.cal_idx
cal_idx
Definition: EqF.py:536
gtsam.examples.EqF.State.R
R
Definition: EqF.py:69
gtsam.examples.EqF.EqF.__n_cal
__n_cal
Definition: EqF.py:569
gtsam.examples.EqF.G.a
a
Definition: EqF.py:189
gtsam.examples.EqF.Direction.d
d
Definition: EqF.py:299
gtsam.examples.EqF.EqF.__init__
def __init__(self, np.ndarray Sigma, int n, int m)
Definition: EqF.py:560
gtsam.examples.EqF.Input.Sigma
Sigma
Definition: EqF.py:140
gtsam.examples.EqF.State.identity
def identity(int n)
Definition: EqF.py:95
gtsam.examples.EqF.EqF.__xi_0
__xi_0
Definition: EqF.py:588
gtsam.examples.EqF.G.__mul__
"G" __mul__(self, "G" other)
Definition: EqF.py:203
type
Definition: pytypes.h:1527
gtsam.examples.EqF.EqF.__Dphi0
__Dphi0
Definition: EqF.py:589
gtsam.examples.EqF.State.S
S
Definition: EqF.py:78
gtsam.examples.EqF.velocityAction
Input velocityAction(G X, Input u)
Definition: EqF.py:402
gtsam::reshape
Reshape< OutM, OutN, OutOptions, InM, InN, InOptions >::ReshapedType reshape(const Eigen::Matrix< double, InM, InN, InOptions > &m)
Definition: base/Matrix.h:262
gtsam.examples.EqF.EqF.__n_sensor
__n_sensor
Definition: EqF.py:570
gtsam::range
Double_ range(const Point2_ &p, const Point2_ &q)
Definition: slam/expressions.h:30
gtsam.examples.EqF.Measurement.__init__
def __init__(self, np.ndarray y, np.ndarray d, np.ndarray Sigma, int i=-1)
Definition: EqF.py:509
gtsam.examples.EqF.blockDiag
np.ndarray blockDiag(np.ndarray A, np.ndarray B)
Definition: EqF.py:302
gtsam.examples.EqF.EqF.__stateTransitionMatrix
np.ndarray __stateTransitionMatrix(self, Input u, float dt)
Definition: EqF.py:667
gtsam.examples.EqF.local_coords_inv
"State" local_coords_inv(np.ndarray eps)
Definition: EqF.py:456
isinstance
bool isinstance(handle obj)
Definition: pytypes.h:842
gtsam.examples.EqF.G.A
A
Definition: EqF.py:186
gtsam.examples.EqF.outputAction
np.ndarray outputAction(G X, Direction y, int idx=-1)
Definition: EqF.py:413
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam.examples.EqF.Direction.__init__
def __init__(self, np.ndarray d)
Definition: EqF.py:291
gtsam.examples.EqF.Measurement.d
d
Definition: EqF.py:534
gtsam.examples.EqF.local_coords
np.ndarray local_coords(State e)
Definition: EqF.py:428
gtsam.examples.EqF.EqF.propagation
def propagation(self, Input u, float dt)
Definition: EqF.py:599
gtsam.examples.EqF.stateAction
State stateAction(G X, State xi)
Definition: EqF.py:382
gtsam.examples.EqF.checkNorm
def checkNorm(np.ndarray x, float tol=1e-3)
Definition: EqF.py:21
gtsam.examples.EqF.EqF.__stateMatrixA
np.ndarray __stateMatrixA(self, Input u)
Definition: EqF.py:646
gtsam.examples.EqF.Input
Definition: EqF.py:105
gtsam.examples.EqF.EqF.__X_hat
__X_hat
Definition: EqF.py:586
gtsam.examples.EqF.EqF.__measurementMatrixC
np.ndarray __measurementMatrixC(self, Direction d, int idx)
Definition: EqF.py:710
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: gtsam/3rdparty/Eigen/blas/common.h:110
gtsam.examples.EqF.G.B
B
Definition: EqF.py:191
gtsam.examples.EqF.EqF.__InnovationLift
__InnovationLift
Definition: EqF.py:590
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam.examples.EqF.repBlock
np.ndarray repBlock(np.ndarray A, int n)
Definition: EqF.py:323
gtsam.examples.EqF.G.exp
"G" exp(np.ndarray x)
Definition: EqF.py:249
gtsam.examples.EqF.G.__init__
def __init__(self, Rot3 A=Rot3.Identity(), np.ndarray a=np.zeros((3, 3)), List[Rot3] B=None)
Definition: EqF.py:176
gtsam.examples.EqF.State
Definition: EqF.py:31
gtsam.examples.EqF.stateActionDiff
np.ndarray stateActionDiff(State xi)
Definition: EqF.py:475
gtsam.examples.EqF.Measurement.y
y
Definition: EqF.py:533
gtsam.examples.EqF.EqF.__Sigma
__Sigma
Definition: EqF.py:587
gtsam.examples.EqF.EqF.stateEstimate
State stateEstimate(self)
Definition: EqF.py:592
gtsam.examples.EqF.State.__init__
def __init__(self, Rot3 R=Rot3.Identity(), np.ndarray b=np.zeros(3), List[Rot3] S=None)
Definition: EqF.py:54
gtsam::symbol_shorthand::W
Key W(std::uint64_t j)
Definition: inference/Symbol.h:170
gtsam.examples.EqF.G.Rot3LeftJacobian
np.ndarray Rot3LeftJacobian(np.ndarray arr)
Definition: EqF.py:229
gtsam.examples.EqF.Input.random
"Input" random()
Definition: EqF.py:143
gtsam.examples.EqF.Direction
Definition: EqF.py:285
gtsam.examples.EqF.EqF.__dof
__dof
Definition: EqF.py:568
gtsam.examples.EqF.Measurement
Definition: EqF.py:486
gtsam.examples.EqF.lift
np.ndarray lift(State xi, Input u)
Definition: EqF.py:354
gtsam.examples.EqF.G
Definition: EqF.py:160
gtsam.examples.EqF.EqF.__outputMatrixDt
np.ndarray __outputMatrixDt(self, int idx)
Definition: EqF.py:728
gtsam.examples.EqF.Data
Definition: EqF.py:540
abs
#define abs(x)
Definition: datatypes.h:17
len
size_t len(handle h)
Get the length of a Python object.
Definition: pytypes.h:2448
gtsam.examples.EqF.State.b
b
Definition: EqF.py:75
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
gtsam.examples.EqF.Input.w
w
Definition: EqF.py:139
gtsam.examples.EqF.Input.__init__
def __init__(self, np.ndarray w, np.ndarray Sigma)
Definition: EqF.py:118
gtsam.examples.EqF.Measurement.Sigma
Sigma
Definition: EqF.py:535
gtsam.examples.EqF.EqF.update
def update(self, Measurement y)
Definition: EqF.py:626
gtsam.examples.EqF.EqF
Definition: EqF.py:559


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:01:38