Van Loan Method [48].
More...
Go to the source code of this file.
|
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, double dt) |
| Numerical Method to calculate the State transition matrix 𝚽 and System/Process noise covariance matrix 𝐐
|
|
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, double dt, size_t expmOrder) |
| Numerical Method to calculate the State transition matrix 𝚽 and System/Process noise covariance matrix 𝐐
|
|
◆ calcPhiAndQWithVanLoanMethod() [1/2]
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, |
|
|
double | dt ) |
|
nodiscard |
Numerical Method to calculate the State transition matrix 𝚽 and System/Process noise covariance matrix 𝐐
- Template Parameters
-
DerivedF | Matrix type of the F matrix |
DerivedG | Matrix type of the G matrix |
DerivedW | Matrix type of the W matrix |
- Parameters
-
[in] | F | System model matrix |
[in] | G | Noise model matrix |
[in] | W | Noise scale factors |
[in] | dt | Time step in [s] |
- Returns
- A pair with the matrices {𝚽, 𝐐}
◆ calcPhiAndQWithVanLoanMethod() [2/2]
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, |
|
|
double | dt, |
|
|
size_t | expmOrder ) |
|
nodiscard |
Numerical Method to calculate the State transition matrix 𝚽 and System/Process noise covariance matrix 𝐐
- Template Parameters
-
DerivedF | Matrix type of the F matrix |
DerivedG | Matrix type of the G matrix |
DerivedW | Matrix type of the W matrix |
- Parameters
-
[in] | F | System model matrix |
[in] | G | Noise model matrix |
[in] | W | Noise scale factors |
[in] | dt | Time step in [s] |
[in] | expmOrder | Order to use to calculate the exponential matrix |
- Returns
- A pair with the matrices {𝚽, 𝐐}