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

Inertial Navigation Mechanization Functions in ECEF frame. More...

Go to the source code of this file.

Functions

template<typename DerivedA , typename DerivedB >
Eigen::Vector4< typename DerivedA::Scalar > NAV::calcTimeDerivativeFor_e_Quat_b (const Eigen::MatrixBase< DerivedA > &b_omega_eb, const Eigen::MatrixBase< DerivedB > &e_Quat_b_coeffs)
 Calculates the time derivative of the quaternion e_Quat_b.
 
template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Vector< Scalar, 10 > NAV::e_calcPosVelAttDerivative (const Eigen::Vector< Scalar, 10 > &y, const Eigen::Vector< Scalar, 6 > &z, const PosVelAttDerivativeConstants< Scalar > &c, Scalar=0.0)
 Calculates the derivative of the quaternion, velocity and position in ECEF coordinates.
 
template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::e_calcTimeDerivativeForPosition (const Eigen::MatrixBase< Derived > &e_velocity)
 Calculates the time derivative of the ECEF position.
 
template<typename DerivedA , typename DerivedB , typename DerivedC , typename DerivedD >
Eigen::Vector3< typename DerivedA::Scalar > NAV::e_calcTimeDerivativeForVelocity (const Eigen::MatrixBase< DerivedA > &e_measuredForce, const Eigen::MatrixBase< DerivedB > &e_coriolisAcceleration, const Eigen::MatrixBase< DerivedC > &e_gravitation, const Eigen::MatrixBase< DerivedD > &e_centrifugalAcceleration)
 Calculates the time derivative of the velocity in ECEF frame coordinates.
 

Detailed Description

Inertial Navigation Mechanization Functions in ECEF frame.

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

Function Documentation

◆ calcTimeDerivativeFor_e_Quat_b()

template<typename DerivedA , typename DerivedB >
Eigen::Vector4< typename DerivedA::Scalar > NAV::calcTimeDerivativeFor_e_Quat_b ( const Eigen::MatrixBase< DerivedA > & b_omega_eb,
const Eigen::MatrixBase< DerivedB > & e_Quat_b_coeffs )

Calculates the time derivative of the quaternion e_Quat_b.

\begin{equation} \label{eq:eq-INS-Mechanization-e_Quat_b-dot} \mathbf{\dot{q}}_b^e = \begin{bmatrix} \dot{w} \\ \dot{x} \\ \dot{y} \\ \dot{z} \end{bmatrix} = \frac{1}{2} \begin{bmatrix} 0 & -\omega_{eb,x}^b & -\omega_{eb,y}^b & -\omega_{eb,z}^b \\ \omega_{eb,x}^b & 0 & \omega_{eb,z}^b & -\omega_{eb,y}^b \\ \omega_{eb,y}^b & -\omega_{eb,z}^b & 0 & \omega_{eb,x}^b \\ \omega_{eb,z}^b & \omega_{eb,y}^b & -\omega_{eb,x}^b & 0 \end{bmatrix} \begin{bmatrix} w \\ x \\ y \\ z \end{bmatrix} \end{equation}

Parameters
[in]b_omega_ebω_eb_b Body rate with respect to the ECEF frame, expressed in the body frame
[in]e_Quat_b_coeffsCoefficients of the quaternion e_Quat_b in order w, x, y, z (q = w + ix + jy + kz)
Returns
The time derivative of the coefficients of the quaternion e_Quat_b in order w, x, y, z (q = w + ix + jy + kz)
Note
See Propagation of quaternion with time equation eq-ImuIntegrator-Mechanization-e-Attitude-Quaternion-matrix

◆ e_calcPosVelAttDerivative()

template<typename Scalar , typename = std::enable_if_t<std::is_floating_point_v<Scalar>>>
Eigen::Vector< Scalar, 10 > NAV::e_calcPosVelAttDerivative ( const Eigen::Vector< Scalar, 10 > & y,
const Eigen::Vector< Scalar, 6 > & z,
const PosVelAttDerivativeConstants< Scalar > & c,
Scalar = 0.0 )

Calculates the derivative of the quaternion, velocity and position in ECEF coordinates.

Parameters
[in]y[w, x, y, z, v_x, v_y, v_z, x, y, z]^T
[in]z[fx, fy, fz, ωx, ωy, ωz]^T
[in]cConstant values needed to calculate the derivatives
Returns
The derivative ∂/∂t [w, x, y, z, v_x, v_y, v_z, x, y, z]^T

◆ e_calcTimeDerivativeForPosition()

template<typename Derived >
Eigen::Vector3< typename Derived::Scalar > NAV::e_calcTimeDerivativeForPosition ( const Eigen::MatrixBase< Derived > & e_velocity)

Calculates the time derivative of the ECEF position.

\begin{equation} \label{eq:eq-INS-Mechanization-x_e-dot} \boldsymbol{\dot{x}}^e = \boldsymbol{v}^e \end{equation}

Parameters
[in]e_velocityVelocity with respect to the Earth in ECEF frame coordinates [m/s]
Returns
The time derivative of the ECEF position
Note
See Position equation eq-ImuIntegrator-Mechanization-e-Position

◆ e_calcTimeDerivativeForVelocity()

template<typename DerivedA , typename DerivedB , typename DerivedC , typename DerivedD >
Eigen::Vector3< typename DerivedA::Scalar > NAV::e_calcTimeDerivativeForVelocity ( const Eigen::MatrixBase< DerivedA > & e_measuredForce,
const Eigen::MatrixBase< DerivedB > & e_coriolisAcceleration,
const Eigen::MatrixBase< DerivedC > & e_gravitation,
const Eigen::MatrixBase< DerivedD > & e_centrifugalAcceleration )

Calculates the time derivative of the velocity in ECEF frame coordinates.

\begin{equation} \label{eq:eq-INS-Mechanization-v_e-dot} \boldsymbol{\dot{v}}^e = \overbrace{\boldsymbol{f}^e}^{\text{measured}} -\ \underbrace{2 \boldsymbol{\omega}_{ie}^e \times \boldsymbol{v}^e}_{\text{coriolis acceleration}} +\ \overbrace{\mathbf{g}^e}^{\text{gravitation}} -\ \underbrace{\left(\boldsymbol{\omega}_{ie}^e \times [ \boldsymbol{\omega}_{ie}^e \times \mathbf{x}^e ] \right)}_{\text{centrifugal acceleration}} \end{equation}

Parameters
[in]e_measuredForcef_e Specific force vector as measured by a triad of accelerometers and resolved into ECEF frame coordinates
[in]e_coriolisAccelerationCoriolis acceleration in ECEF coordinates in [m/s^2]
[in]e_gravitationLocal gravitation vector (caused by effects of mass attraction) in ECEF frame coordinates [m/s^2]
[in]e_centrifugalAccelerationCentrifugal acceleration in ECEF coordinates in [m/s^2]
Returns
The time derivative of the velocity in ECEF frame coordinates
Note
See Velocity equation eq-ImuIntegrator-Mechanization-e-Velocity