Function navtk::navutils::calc_van_loan

Function Documentation

Matrix navtk::navutils::calc_van_loan(const Matrix &F, const Matrix &G, const Matrix &Q, double dt)

Calculates the discrete-time system noise covariance matrix from a continuous-time system description.

First, define a continuous-time system as

\( \dot{\textbf{x}} = \textbf{Fx} + \textbf{Gw} \)

\( E[\textbf{w}(t-\tau)\textbf{w}^T(t-\tau)] = \textbf{Q}\delta(\tau) \)

where \( E[] \) is the expectation operator and \( \delta(\tau) \) is the Dirac delta function.

This can be converted to an equivalent discrete-time system

\( \textbf{x}_{t_{k+1}} = \pmb{\Phi}\textbf{x}_{t_k} + \textbf{w}_d \)

where

\( \pmb{\Phi}=e^{\textbf{F}\Delta t} \)

\( \Delta t = t_{k+1} - t_k \)

\( E[\textbf{w}_{t_j}\textbf{w}^T_{t_k}] = \textbf{Q}_d \delta_{kj} \)

and \( \delta_{kj} \) is the Kronecker delta function.

Parameters
  • F – The continuous-time dynamics matrix \(\textbf{F}\), NxN.

  • G – The noise mapping matrix \( \textbf{G} \), NxM.

  • Q – The continuous time noise covariance matrix \( \textbf{Q} \), MxM.

  • dt – The discretization time interval \( \Delta t \)

Returns

The discrete-time system noise covariance matrix \( \textbf{Q}_d \).