0.2.0
|
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 𝐐 | |
Van Loan Method [46].
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 𝐐
DerivedF | Matrix type of the F matrix |
DerivedG | Matrix type of the G matrix |
DerivedW | Matrix type of the W matrix |
[in] | F | System model matrix |
[in] | G | Noise model matrix |
[in] | W | Noise scale factors |
[in] | dt | Time step in [s] |
\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}
\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}
\begin{equation} \label{eq:eq-Loan-Phi} \mathbf{\Phi} = \mathbf{B}_{22}^T \end{equation}
\begin{equation} \label{eq:eq-Loan-Q} \mathbf{Q} = \mathbf{\Phi} \mathbf{B}_{12} \end{equation}