Definition at line 559 of file EqF.py.
◆ __init__()
def gtsam.examples.EqF.EqF.__init__ |
( |
|
self, |
|
|
np.ndarray |
Sigma, |
|
|
int |
n, |
|
|
int |
m |
|
) |
| |
Initialize EqF
:param Sigma: Initial covariance
:param n: Number of calibration states
:param m: Total number of available sensor
Definition at line 560 of file EqF.py.
◆ __inputMatrixBt()
np.ndarray gtsam.examples.EqF.EqF.__inputMatrixBt |
( |
|
self | ) |
|
|
private |
Return the Input matrix Bt
:return: numpy array representing the state matrix Bt
Definition at line 692 of file EqF.py.
◆ __measurementMatrixC()
np.ndarray gtsam.examples.EqF.EqF.__measurementMatrixC |
( |
|
self, |
|
|
Direction |
d, |
|
|
int |
idx |
|
) |
| |
|
private |
Return the measurement matrix C0 (Equation 14b)
:param d: Known direction
:param idx: index of the related calibration state
:return: numpy array representing the measurement matrix C0
Definition at line 710 of file EqF.py.
◆ __outputMatrixDt()
np.ndarray gtsam.examples.EqF.EqF.__outputMatrixDt |
( |
|
self, |
|
|
int |
idx |
|
) |
| |
|
private |
Return the measurement output matrix Dt
:param idx: index of the related calibration state
:return: numpy array representing the output matrix Dt
Definition at line 728 of file EqF.py.
◆ __stateMatrixA()
np.ndarray gtsam.examples.EqF.EqF.__stateMatrixA |
( |
|
self, |
|
|
Input |
u |
|
) |
| |
|
private |
Return the state matrix A0t (Equation 14a)
:param u: Input
:return: numpy array representing the state matrix A0t
Definition at line 646 of file EqF.py.
◆ __stateTransitionMatrix()
np.ndarray gtsam.examples.EqF.EqF.__stateTransitionMatrix |
( |
|
self, |
|
|
Input |
u, |
|
|
float |
dt |
|
) |
| |
|
private |
Return the state transition matrix Phi (Equation 17)
:param u: Input
:param dt: Delta time
:return: numpy array representing the state transition matrix Phi
Definition at line 667 of file EqF.py.
◆ propagation()
def gtsam.examples.EqF.EqF.propagation |
( |
|
self, |
|
|
Input |
u, |
|
|
float |
dt |
|
) |
| |
Propagate the filter state
:param u: Angular velocity measurement from IMU
:param dt: delta time between timestamp of last propagation/update and timestamp of angular velocity measurement
Definition at line 599 of file EqF.py.
◆ stateEstimate()
State gtsam.examples.EqF.EqF.stateEstimate |
( |
|
self | ) |
|
Return estimated state
:return: Estimated state
Definition at line 592 of file EqF.py.
◆ update()
def gtsam.examples.EqF.EqF.update |
( |
|
self, |
|
|
Measurement |
y |
|
) |
| |
Update the filter state
:param y: A measurement
Definition at line 626 of file EqF.py.
◆ __dof
gtsam.examples.EqF.EqF.__dof |
|
private |
◆ __Dphi0
gtsam.examples.EqF.EqF.__Dphi0 |
|
private |
◆ __InnovationLift
gtsam.examples.EqF.EqF.__InnovationLift |
|
private |
◆ __n_cal
gtsam.examples.EqF.EqF.__n_cal |
|
private |
◆ __n_sensor
gtsam.examples.EqF.EqF.__n_sensor |
|
private |
◆ __Sigma
gtsam.examples.EqF.EqF.__Sigma |
|
private |
◆ __X_hat
gtsam.examples.EqF.EqF.__X_hat |
|
private |
◆ __xi_0
gtsam.examples.EqF.EqF.__xi_0 |
|
private |
The documentation for this class was generated from the following file: