Function navtk::navutils::discretize_second_order
Defined in File navigation.hpp
Function Documentation
-
std::pair<Matrix, Matrix> navtk::navutils::discretize_second_order(const Matrix &f, const Matrix &q, double dt)
Converts from continuous-time dynamic system representation to discrete-time representation using second order algorithm.
See
discretize_first_order()for variable definitions.This function calculates \(\pmb{\Phi}\) using the second order calculation
\(\pmb{\Phi}_2 \approx \textbf{I} + \textbf{F}\Delta t + \frac{1}{2}\textbf{F}^2\Delta t^2\)
and
\(\textbf{Q}_{d_2} \approx \frac{\pmb{\Phi}\textbf{Q}\pmb{\Phi}^T + \textbf{Q}}{2}\Delta t\)
See also
See also
- Parameters
f – Continuous-time dynamics matrix \(\textbf{F}\)
q – Continuous-time process noise \(\textbf{Q}\)
dt – Time (seconds) over which propagation is to take place ( \(\Delta t\))
- Returns
(
Phi,Qd) The discrete-time matrices as an std::pair. First isPhi\(=\pmb{\Phi}_2\), second isQd\(=\textbf{Q}_{d_2}\).