Attitude System Model.  
 More...
 | 
| template<typename Derived>  | 
| std::pair< KeyedMatrix4d< StateKeyType >, KeyedMatrix4d< StateKeyType > >  | calcPhiAndQ (double dt, const double &latitude, const double &longitude, const Eigen::QuaternionBase< Derived > &n_quat_b) | 
|   | Calculates the state transition matrix (𝚽) and the process noise covariance matrix (𝐐)  
  | 
| void  | initialize () | 
|   | Initializes the attitude model.  
  | 
| bool  | ShowGui (float itemWidth, float unitWidth, const char *id) | 
|   | Shows a GUI.  
  | 
| template<typename Scalar, int Size, typename Derived>  | 
| void  | updatePhiAndQ (KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &Phi, KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &Q, double dt, const double &latitude, const double &longitude, const Eigen::QuaternionBase< Derived > &n_quat_b) | 
|   | Updates the provided Phi, Q and G matrix.  
  | 
 | 
| template<typename Derived>  | 
| KeyedMatrix4d< StateKeyType >  | calcProcessNoiseMatrix (double dt, double latitude, double longitude, const Eigen::QuaternionBase< Derived > &n_quat_b) const | 
|   | Calculates the process noise matrix Q.  
  | 
template<typename StateKeyType>
class NAV::AttitudeModel< StateKeyType >
Attitude System Model. 
Definition at line 34 of file AttitudeModel.hpp.
 
◆ calcPhiAndQ()
template<typename StateKeyType> 
template<typename Derived> 
  
  
      
        
          | std::pair< KeyedMatrix4d< StateKeyType >, KeyedMatrix4d< StateKeyType > > NAV::AttitudeModel< StateKeyType >::calcPhiAndQ  | 
          ( | 
          double |           dt,  | 
         
        
           | 
           | 
          const double & |           latitude,  | 
         
        
           | 
           | 
          const double & |           longitude,  | 
         
        
           | 
           | 
          const Eigen::QuaternionBase< Derived > & |           n_quat_b ) | 
         
       
   | 
  
inlinenodiscard   | 
  
 
Calculates the state transition matrix (𝚽) and the process noise covariance matrix (𝐐) 
- Parameters
 - 
  
    | [in] | dt | Time step size in [s]  | 
    | [in] | latitude | Latitude [rad]  | 
    | [in] | longitude | Longitude [rad]  | 
    | [in] | n_quat_b | Quaternion body to navigation frame  | 
  
   
- Returns
 - Phi and Q matrix 
 
Definition at line 73 of file AttitudeModel.hpp.
 
 
◆ calcProcessNoiseMatrix()
template<typename StateKeyType> 
template<typename Derived> 
  
  
      
        
          | KeyedMatrix4d< StateKeyType > NAV::AttitudeModel< StateKeyType >::calcProcessNoiseMatrix  | 
          ( | 
          double |           dt,  | 
         
        
           | 
           | 
          double |           latitude,  | 
         
        
           | 
           | 
          double |           longitude,  | 
         
        
           | 
           | 
          const Eigen::QuaternionBase< Derived > & |           n_quat_b ) const | 
         
       
   | 
  
inlinenodiscardprivate   | 
  
 
Calculates the process noise matrix Q. 
- Parameters
 - 
  
    | [in] | dt | Time step [s]  | 
    | [in] | latitude | Latitude [rad]  | 
    | [in] | longitude | Longitude [rad]  | 
    | [in] | n_quat_b | Quaternion body to navigation frame  | 
  
   
Definition at line 122 of file AttitudeModel.hpp.
 
 
◆ initialize()
template<typename StateKeyType> 
 
 
◆ ShowGui()
template<typename StateKeyType> 
  
  
      
        
          | bool NAV::AttitudeModel< StateKeyType >::ShowGui  | 
          ( | 
          float |           itemWidth,  | 
         
        
           | 
           | 
          float |           unitWidth,  | 
         
        
           | 
           | 
          const char * |           id ) | 
         
       
   | 
  
inline   | 
  
 
Shows a GUI. 
- Parameters
 - 
  
    | [in] | itemWidth | Width of the space for the config items  | 
    | [in] | unitWidth | Width of the units  | 
    | [in] | id | Unique id for ImGui  | 
  
   
- Returns
 - True if something was changed 
 
Definition at line 87 of file AttitudeModel.hpp.
 
 
◆ updatePhiAndQ()
template<typename StateKeyType> 
template<typename Scalar, int Size, typename Derived> 
  
  
      
        
          | void NAV::AttitudeModel< StateKeyType >::updatePhiAndQ  | 
          ( | 
          KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > & |           Phi,  | 
         
        
           | 
           | 
          KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > & |           Q,  | 
         
        
           | 
           | 
          double |           dt,  | 
         
        
           | 
           | 
          const double & |           latitude,  | 
         
        
           | 
           | 
          const double & |           longitude,  | 
         
        
           | 
           | 
          const Eigen::QuaternionBase< Derived > & |           n_quat_b ) | 
         
       
   | 
  
inline   | 
  
 
Updates the provided Phi, Q and G matrix. 
- Parameters
 - 
  
    | [in,out] | Phi | State transition matrix  | 
    | [in,out] | Q | System/Process noise covariance matrix  | 
    | [in] | dt | Time step size in [s]  | 
    | [in] | latitude | Latitude [rad]  | 
    | [in] | longitude | Longitude [rad]  | 
    | [in] | n_quat_b | Quaternion body to navigation frame  | 
  
   
Definition at line 54 of file AttitudeModel.hpp.
 
 
◆ from_json
template<typename StateKeyType> 
 
Converts the provided json object into the data object. 
- Parameters
 - 
  
    | [in] | j | Json object with the needed values  | 
    | [out] | data | Object to fill from the json  | 
  
   
Definition at line 157 of file AttitudeModel.hpp.
 
 
◆ to_json
template<typename StateKeyType> 
 
Converts the provided data into a json object. 
- Parameters
 - 
  
    | [out] | j | Json object which gets filled with the info  | 
    | [in] | data | Data to convert into json  | 
  
   
Definition at line 147 of file AttitudeModel.hpp.
 
 
◆ _covarianceAngularVelocity
template<typename StateKeyType> 
 
Covariance of the angular velocity due to user motion (Roll, Pitch, Yaw) [rad²/s]. 
Definition at line 142 of file AttitudeModel.hpp.
 
 
◆ _gui_covarianceAngularVelocity
template<typename StateKeyType> 
 
GUI selection for the Standard deviation of the angular velocity due to user motion (Roll, Pitch, Yaw) 
Definition at line 139 of file AttitudeModel.hpp.
 
 
◆ _gui_covarianceAngularVelocityUnit
template<typename StateKeyType> 
 
Gui selection for the Unit of the input covarianceAngularVelocity. 
Definition at line 137 of file AttitudeModel.hpp.
 
 
◆ Att
template<typename StateKeyType> 
 
 
The documentation for this class was generated from the following file:
- /home/runner/work/INSTINCT/INSTINCT/src/Navigation/GNSS/SystemModel/AttitudeModel.hpp