0.2.0
Loading...
Searching...
No Matches
VanLoan.hpp File Reference

Van Loan Method [46]. More...

Go to the source code of this file.

Functions

template<typename DerivedF , typename DerivedG , typename DerivedW >
std::pair< typename DerivedF::PlainObject, typename DerivedF::PlainObject > NAV::calcPhiAndQWithVanLoanMethod (const Eigen::MatrixBase< DerivedF > &F, const Eigen::MatrixBase< DerivedG > &G, const Eigen::MatrixBase< DerivedW > &W, typename DerivedF::Scalar dt)
 Numerical Method to calculate the State transition matrix 𝚽 and System/Process noise covariance matrix 𝐐
 

Detailed Description

Van Loan Method [46].

Author
T. Topp (topp@.nosp@m.ins..nosp@m.uni-s.nosp@m.tutt.nosp@m.gart..nosp@m.de)
Date
2022-01-11

Function Documentation

◆ calcPhiAndQWithVanLoanMethod()

template<typename DerivedF , typename DerivedG , typename DerivedW >
std::pair< typename DerivedF::PlainObject, typename DerivedF::PlainObject > NAV::calcPhiAndQWithVanLoanMethod ( const Eigen::MatrixBase< DerivedF > & F,
const Eigen::MatrixBase< DerivedG > & G,
const Eigen::MatrixBase< DerivedW > & W,
typename DerivedF::Scalar dt )

Numerical Method to calculate the State transition matrix 𝚽 and System/Process noise covariance matrix 𝐐

Template Parameters
DerivedFMatrix type of the F matrix
DerivedGMatrix type of the G matrix
DerivedWMatrix type of the W matrix
Parameters
[in]FSystem model matrix
[in]GNoise model matrix
[in]WNoise scale factors
[in]dtTime step in [s]
Returns
A pair with the matrices {𝚽, 𝐐}
  1. Form a \( 2n \times 2n \) matrix called \( \mathbf{A} \) ( \( n \) is the dimension of \( \mathbf{x} \) and \( \mathbf{W} \) is the power spectral density of the noise \( W(t) \))

    \begin{equation} \label{eq:eq-Loan-A} \mathbf{A} = \begin{bmatrix} -\mathbf{F} & \mathbf{G} \mathbf{W} \mathbf{G} \\ \mathbf{0} & \mathbf{F}^T \end{bmatrix} \Delta t \end{equation}

  2. Calculate the exponential of \( \mathbf{A} \)

    \begin{equation} \label{eq:eq-Loan-B} \mathbf{B} = \text{expm}(\mathbf{A}) = \left[ \begin{array}{c;{2pt/2pt}c} \dots & \mathbf{\Phi}^{-1} \mathbf{Q} \\[2mm] \hdashline[2pt/2pt] & \\[-2mm] \mathbf{0} & \mathbf{\Phi}^T \end{array} \right] = \begin{bmatrix} \mathbf{B}_{11} & \mathbf{B}_{12} \\ \mathbf{B}_{21} & \mathbf{B}_{22} \end{bmatrix} \end{equation}

  3. Calculate the state transition matrix \( \mathbf{\Phi} \) as

    \begin{equation} \label{eq:eq-Loan-Phi} \mathbf{\Phi} = \mathbf{B}_{22}^T \end{equation}

  4. Calculate the process noise covariance matrix \( \mathbf{Q} \) as

    \begin{equation} \label{eq:eq-Loan-Q} \mathbf{Q} = \mathbf{\Phi} \mathbf{B}_{12} \end{equation}

Note
See C.F. van Loan (1978) - Computing Integrals Involving the Matrix Exponential [46]