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

General process Noise definitions. More...

Go to the source code of this file.

Functions

Eigen::Matrix3d NAV::G_GaussMarkov1 (const Eigen::Vector3d &sigma2, const Eigen::Vector3d &beta)
 Submatrix 𝐆_a of the noise input matrix 𝐆
 
Eigen::Matrix3d NAV::G_RandomWalk (const Eigen::Vector3d &sigma2)
 Random walk noise input matrix 𝐆
 
Eigen::Matrix3d NAV::ie_Q_dr_df (const Eigen::Vector3d &S_bad, const Eigen::Matrix3d &ie_Dcm_b, const double &tau_s)
 Submatrix 𝐐_34 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::ie_Q_dr_domega (const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ie_F_21, const Eigen::Matrix3d &ie_Dcm_b, const double &tau_s)
 Submatrix 𝐐_35 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::ie_Q_dr_dr (const Eigen::Vector3d &S_ra, const Eigen::Vector3d &S_bad, const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ie_F_21, const double &tau_s)
 Submatrix 𝐐_33 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::ie_Q_dr_dv (const Eigen::Vector3d &S_ra, const Eigen::Vector3d &S_bad, const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ie_F_21, const double &tau_s)
 Submatrix 𝐐_32 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::ie_Q_dr_psi (const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ie_F_21, const double &tau_s)
 Submatrix 𝐐_31 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::ien_Q_dv_domega (const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ien_F_21, const Eigen::Matrix3d &ien_Dcm_b, const double &tau_s)
 Submatrix 𝐐_25 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::ien_Q_dv_dv (const Eigen::Vector3d &S_ra, const Eigen::Vector3d &S_bad, const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ien_F_21, const double &tau_s)
 Submatrix 𝐐_22 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::ien_Q_dv_psi (const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &ien_F_21, const double &tau_s)
 Submatrix 𝐐_21 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::n_Q_dr_df (const Eigen::Vector3d &S_bad, const Eigen::Matrix3d &T_rn_p, const Eigen::Matrix3d &n_Dcm_b, const double &tau_s)
 Submatrix 𝐐_34 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::n_Q_dr_domega (const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &n_F_21, const Eigen::Matrix3d &T_rn_p, const Eigen::Matrix3d &n_Dcm_b, const double &tau_s)
 Submatrix 𝐐_35 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::n_Q_dr_dr (const Eigen::Vector3d &S_ra, const Eigen::Vector3d &S_bad, const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &n_F_21, const Eigen::Matrix3d &T_rn_p, const double &tau_s)
 Submatrix 𝐐_33 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::n_Q_dr_dv (const Eigen::Vector3d &S_ra, const Eigen::Vector3d &S_bad, const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &n_F_21, const Eigen::Matrix3d &T_rn_p, const double &tau_s)
 Submatrix 𝐐_32 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::n_Q_dr_psi (const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &n_F_21, const Eigen::Matrix3d &T_rn_p, const double &tau_s)
 Submatrix 𝐐_31 of the system noise covariance matrix 𝐐
 
Eigen::Vector3d NAV::psdBiasGaussMarkov (const Eigen::Vector3d &sigma2_bd, const Eigen::Vector3d &tau_bd)
 u_bias Power Spectral Density of the bias for a Gauss-Markov random process
 
Eigen::Matrix3d NAV::Q_df_df (const Eigen::Vector3d &S_bad, const double &tau_s)
 Submatrix 𝐐_44 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::Q_df_dv (const Eigen::Vector3d &S_bad, const Eigen::Matrix3d &b_Dcm_ien, const double &tau_s)
 Submatrix 𝐐_42 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::Q_domega_domega (const Eigen::Vector3d &S_bgd, const double &tau_s)
 Submatrix 𝐐_55 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::Q_domega_psi (const Eigen::Vector3d &S_bgd, const Eigen::Matrix3d &b_Dcm_ien, const double &tau_s)
 Submatrix 𝐐_51 of the system noise covariance matrix 𝐐
 
Eigen::Matrix2d NAV::Q_gnss (const double &S_cPhi, const double &S_cf, const double &tau_s)
 Submatrix 𝐐_66 of the system noise covariance matrix 𝐐
 
Eigen::Matrix3d NAV::Q_psi_psi (const Eigen::Vector3d &S_rg, const Eigen::Vector3d &S_bgd, const double &tau_s)
 Submatrix 𝐐_11 of the system noise covariance matrix 𝐐
 

Detailed Description

General process Noise definitions.

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

Function Documentation

◆ G_GaussMarkov1()

Eigen::Matrix3d NAV::G_GaussMarkov1 ( const Eigen::Vector3d & sigma2,
const Eigen::Vector3d & beta )

Submatrix 𝐆_a of the noise input matrix 𝐆

Parameters
[in]sigma2Variance of the noise on the measurements
[in]betaGauss-Markov constant 𝛽 = 1 / 𝜏 (𝜏 correlation length)
Note
See T. Hobiger (2021) Inertialnavigation V06 - equation (6.3)

◆ G_RandomWalk()

Eigen::Matrix3d NAV::G_RandomWalk ( const Eigen::Vector3d & sigma2)

Random walk noise input matrix 𝐆

Parameters
[in]sigma2Variance of the noise on the measurements
Note
See T. Hobiger (2021) Inertialnavigation V06 - equation (6.3)

◆ ie_Q_dr_df()

Eigen::Matrix3d NAV::ie_Q_dr_df ( const Eigen::Vector3d & S_bad,
const Eigen::Matrix3d & ie_Dcm_b,
const double & tau_s )

Submatrix 𝐐_34 of the system noise covariance matrix 𝐐

Parameters
[in]S_badPower Spectral Density of the accelerometer bias variation
[in]ie_Dcm_bDirection Cosine Matrix from body to {i,e} coordinates
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_34
Note
See Groves (2013) equation (14.81)

◆ ie_Q_dr_domega()

Eigen::Matrix3d NAV::ie_Q_dr_domega ( const Eigen::Vector3d & S_bgd,
const Eigen::Matrix3d & ie_F_21,
const Eigen::Matrix3d & ie_Dcm_b,
const double & tau_s )

Submatrix 𝐐_35 of the system noise covariance matrix 𝐐

Parameters
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]ie_F_21Submatrix 𝐅_21 of the system matrix 𝐅
[in]ie_Dcm_bDirection Cosine Matrix from body to {i,e} coordinates
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_35
Note
See Groves (2013) equation (14.81)

◆ ie_Q_dr_dr()

Eigen::Matrix3d NAV::ie_Q_dr_dr ( const Eigen::Vector3d & S_ra,
const Eigen::Vector3d & S_bad,
const Eigen::Vector3d & S_rg,
const Eigen::Vector3d & S_bgd,
const Eigen::Matrix3d & ie_F_21,
const double & tau_s )

Submatrix 𝐐_33 of the system noise covariance matrix 𝐐

Parameters
[in]S_raPower Spectral Density of the accelerometer random noise
[in]S_badPower Spectral Density of the accelerometer bias variation
[in]S_rgPower Spectral Density of the gyroscope random noise
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]ie_F_21Submatrix 𝐅_21 of the system matrix 𝐅 in {i,e} frame
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_33
Note
See Groves (2013) equation (14.81)

◆ ie_Q_dr_dv()

Eigen::Matrix3d NAV::ie_Q_dr_dv ( const Eigen::Vector3d & S_ra,
const Eigen::Vector3d & S_bad,
const Eigen::Vector3d & S_rg,
const Eigen::Vector3d & S_bgd,
const Eigen::Matrix3d & ie_F_21,
const double & tau_s )

Submatrix 𝐐_32 of the system noise covariance matrix 𝐐

Parameters
[in]S_raPower Spectral Density of the accelerometer random noise
[in]S_badPower Spectral Density of the accelerometer bias variation
[in]S_rgPower Spectral Density of the gyroscope random noise
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]ie_F_21Submatrix 𝐅_21 of the system matrix 𝐅 in {i,e} frame
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_32
Note
See Groves (2013) equation (14.81)

◆ ie_Q_dr_psi()

Eigen::Matrix3d NAV::ie_Q_dr_psi ( const Eigen::Vector3d & S_rg,
const Eigen::Vector3d & S_bgd,
const Eigen::Matrix3d & ie_F_21,
const double & tau_s )

Submatrix 𝐐_31 of the system noise covariance matrix 𝐐

Parameters
[in]S_rgPower Spectral Density of the gyroscope random noise
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]ie_F_21Submatrix 𝐅_21 of the system matrix 𝐅 in {i,e} frame
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_31
Note
See Groves (2013) equation (14.81)

◆ ien_Q_dv_domega()

Eigen::Matrix3d NAV::ien_Q_dv_domega ( const Eigen::Vector3d & S_bgd,
const Eigen::Matrix3d & ien_F_21,
const Eigen::Matrix3d & ien_Dcm_b,
const double & tau_s )

Submatrix 𝐐_25 of the system noise covariance matrix 𝐐

Parameters
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]ien_F_21Submatrix 𝐅_21 of the system matrix 𝐅
[in]ien_Dcm_bDirection Cosine Matrix from body to {i,e,n} frame
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_25
Note
See Groves (2013) equation (14.80)

◆ ien_Q_dv_dv()

Eigen::Matrix3d NAV::ien_Q_dv_dv ( const Eigen::Vector3d & S_ra,
const Eigen::Vector3d & S_bad,
const Eigen::Vector3d & S_rg,
const Eigen::Vector3d & S_bgd,
const Eigen::Matrix3d & ien_F_21,
const double & tau_s )

Submatrix 𝐐_22 of the system noise covariance matrix 𝐐

Parameters
[in]S_raPower Spectral Density of the accelerometer random noise
[in]S_badPower Spectral Density of the accelerometer bias variation
[in]S_rgPower Spectral Density of the gyroscope random noise
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]ien_F_21Submatrix 𝐅_21 of the system matrix 𝐅 in {i,e,n} frame
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_22
Note
See Groves (2013) equation (14.81)

◆ ien_Q_dv_psi()

Eigen::Matrix3d NAV::ien_Q_dv_psi ( const Eigen::Vector3d & S_rg,
const Eigen::Vector3d & S_bgd,
const Eigen::Matrix3d & ien_F_21,
const double & tau_s )

Submatrix 𝐐_21 of the system noise covariance matrix 𝐐

Parameters
[in]S_rgPower Spectral Density of the gyroscope random noise
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]ien_F_21Submatrix 𝐅_21 of the system matrix 𝐅 in {i,e,n} frame
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_21
Note
See Groves (2013) equation (14.81)

◆ n_Q_dr_df()

Eigen::Matrix3d NAV::n_Q_dr_df ( const Eigen::Vector3d & S_bad,
const Eigen::Matrix3d & T_rn_p,
const Eigen::Matrix3d & n_Dcm_b,
const double & tau_s )

Submatrix 𝐐_34 of the system noise covariance matrix 𝐐

Parameters
[in]S_badPower Spectral Density of the accelerometer bias variation
[in]T_rn_pConversion matrix between cartesian and curvilinear perturbations to the position
[in]n_Dcm_bDirection Cosine Matrix from body to navigation coordinates
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_34
Note
See Groves (2013) equation (14.81)

◆ n_Q_dr_domega()

Eigen::Matrix3d NAV::n_Q_dr_domega ( const Eigen::Vector3d & S_bgd,
const Eigen::Matrix3d & n_F_21,
const Eigen::Matrix3d & T_rn_p,
const Eigen::Matrix3d & n_Dcm_b,
const double & tau_s )

Submatrix 𝐐_35 of the system noise covariance matrix 𝐐

Parameters
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]n_F_21Submatrix 𝐅_21 of the system matrix 𝐅
[in]T_rn_pConversion matrix between cartesian and curvilinear perturbations to the position
[in]n_Dcm_bDirection Cosine Matrix from body to navigation coordinates
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_35
Note
See Groves (2013) equation (14.81)

◆ n_Q_dr_dr()

Eigen::Matrix3d NAV::n_Q_dr_dr ( const Eigen::Vector3d & S_ra,
const Eigen::Vector3d & S_bad,
const Eigen::Vector3d & S_rg,
const Eigen::Vector3d & S_bgd,
const Eigen::Matrix3d & n_F_21,
const Eigen::Matrix3d & T_rn_p,
const double & tau_s )

Submatrix 𝐐_33 of the system noise covariance matrix 𝐐

Parameters
[in]S_raPower Spectral Density of the accelerometer random noise
[in]S_badPower Spectral Density of the accelerometer bias variation
[in]S_rgPower Spectral Density of the gyroscope random noise
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]n_F_21Submatrix 𝐅_21 of the system matrix 𝐅
[in]T_rn_pConversion matrix between cartesian and curvilinear perturbations to the position
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_33
Note
See Groves (2013) equation (14.81)

◆ n_Q_dr_dv()

Eigen::Matrix3d NAV::n_Q_dr_dv ( const Eigen::Vector3d & S_ra,
const Eigen::Vector3d & S_bad,
const Eigen::Vector3d & S_rg,
const Eigen::Vector3d & S_bgd,
const Eigen::Matrix3d & n_F_21,
const Eigen::Matrix3d & T_rn_p,
const double & tau_s )

Submatrix 𝐐_32 of the system noise covariance matrix 𝐐

Parameters
[in]S_raPower Spectral Density of the accelerometer random noise
[in]S_badPower Spectral Density of the accelerometer bias variation
[in]S_rgPower Spectral Density of the gyroscope random noise
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]n_F_21Submatrix 𝐅_21 of the system matrix 𝐅
[in]T_rn_pConversion matrix between cartesian and curvilinear perturbations to the position
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_32
Note
See Groves (2013) equation (14.81)

◆ n_Q_dr_psi()

Eigen::Matrix3d NAV::n_Q_dr_psi ( const Eigen::Vector3d & S_rg,
const Eigen::Vector3d & S_bgd,
const Eigen::Matrix3d & n_F_21,
const Eigen::Matrix3d & T_rn_p,
const double & tau_s )

Submatrix 𝐐_31 of the system noise covariance matrix 𝐐

Parameters
[in]S_rgPower Spectral Density of the gyroscope random noise
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]n_F_21Submatrix 𝐅_21 of the system matrix 𝐅
[in]T_rn_pConversion matrix between cartesian and curvilinear perturbations to the position
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_31
Note
See Groves (2013) equation (14.81)

◆ psdBiasGaussMarkov()

Eigen::Vector3d NAV::psdBiasGaussMarkov ( const Eigen::Vector3d & sigma2_bd,
const Eigen::Vector3d & tau_bd )

u_bias Power Spectral Density of the bias for a Gauss-Markov random process

Parameters
[in]sigma2_bd𝜎²_bd standard deviation of the bias noise
[in]tau_bd𝜏 Correlation length in [s]
Note
See Brown & Hwang (2011) - Introduction to Random Signals and Applied Kalman Filtering (example 9.6)

◆ Q_df_df()

Eigen::Matrix3d NAV::Q_df_df ( const Eigen::Vector3d & S_bad,
const double & tau_s )

Submatrix 𝐐_44 of the system noise covariance matrix 𝐐

Parameters
[in]S_badPower Spectral Density of the accelerometer bias variation
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_44
Note
See Groves (2013) equation (14.80)

◆ Q_df_dv()

Eigen::Matrix3d NAV::Q_df_dv ( const Eigen::Vector3d & S_bad,
const Eigen::Matrix3d & b_Dcm_ien,
const double & tau_s )

Submatrix 𝐐_42 of the system noise covariance matrix 𝐐

Parameters
[in]S_badPower Spectral Density of the accelerometer bias variation
[in]b_Dcm_ienDirection Cosine Matrix from {i,e,n} to body coordinates
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_42
Note
See Groves (2013) equation (14.80)

◆ Q_domega_domega()

Eigen::Matrix3d NAV::Q_domega_domega ( const Eigen::Vector3d & S_bgd,
const double & tau_s )

Submatrix 𝐐_55 of the system noise covariance matrix 𝐐

Parameters
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_55
Note
See Groves (2013) equation (14.80)

◆ Q_domega_psi()

Eigen::Matrix3d NAV::Q_domega_psi ( const Eigen::Vector3d & S_bgd,
const Eigen::Matrix3d & b_Dcm_ien,
const double & tau_s )

Submatrix 𝐐_51 of the system noise covariance matrix 𝐐

Parameters
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]b_Dcm_ienDirection Cosine Matrix from {i,e,n} to body coordinates
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_51
Note
See Groves (2013) equation (14.80)

◆ Q_gnss()

Eigen::Matrix2d NAV::Q_gnss ( const double & S_cPhi,
const double & S_cf,
const double & tau_s )

Submatrix 𝐐_66 of the system noise covariance matrix 𝐐

Parameters
[in]S_cPhiPower Spectral Density of the receiver clock phase drift in [m^2 s^-1]
[in]S_cfPower Spectral Density of the receiver clock frequency-drift [m^2 s^-3]
[in]tau_sTime interval in [s]
Returns
See Groves (2013) equation (9.152)

◆ Q_psi_psi()

Eigen::Matrix3d NAV::Q_psi_psi ( const Eigen::Vector3d & S_rg,
const Eigen::Vector3d & S_bgd,
const double & tau_s )

Submatrix 𝐐_11 of the system noise covariance matrix 𝐐

Parameters
[in]S_rgPower Spectral Density of the gyroscope random noise
[in]S_bgdPower Spectral Density of the gyroscope bias variation
[in]tau_sTime interval in [s]
Returns
The 3x3 matrix 𝐐_11
Note
See Groves (2013) equation (14.81)