![]()  | 
              
                  0.5.0
                 
               | 
            
Inertial state and measurements. More...
Data Fields | |
| Eigen::Quaternion< T > | attitude | 
| IMU attitude (e_Quat_b / n_Quat_b)   | |
| InsTime | epoch | 
| Epoch of this state.   | |
| Measurement | m | 
| Inertial measurement.   | |
| Eigen::Quaternion< T > | misalignmentAccel | 
| Misalignment of the accelerometer sensor axes.   | |
| Eigen::Quaternion< T > | misalignmentGyro | 
| Misalignment of the gyroscope sensor axes.   | |
| Eigen::Vector3< T > | p_biasAcceleration | 
| Acceleration bias in platform frame coordinates in [m/s^2].   | |
| Eigen::Vector3< T > | p_biasAngularRate | 
| Angular rate bias in platform frame coordinates in [rad/s].   | |
| Eigen::Vector3< T > | position | 
| IMU position (e_pos / lla_pos)   | |
| Eigen::Vector3< T > | scaleFactorAccel | 
| Scale factor of the accelerometer [-].   | |
| Eigen::Vector3< T > | scaleFactorGyro | 
| Scale factor of the gyroscope [-].   | |
| Eigen::Vector3< T > | velocity | 
| IMU velocity (e_vel / n_vel)   | |
Inertial state and measurements.
Definition at line 74 of file InertialIntegrator.hpp.
| Eigen::Quaternion<T> NAV::InertialIntegrator::GenericState< T >::attitude | 
IMU attitude (e_Quat_b / n_Quat_b)
Definition at line 80 of file InertialIntegrator.hpp.
| InsTime NAV::InertialIntegrator::GenericState< T >::epoch | 
Epoch of this state.
Definition at line 76 of file InertialIntegrator.hpp.
| Measurement NAV::InertialIntegrator::GenericState< T >::m | 
Inertial measurement.
Definition at line 82 of file InertialIntegrator.hpp.
| Eigen::Quaternion<T> NAV::InertialIntegrator::GenericState< T >::misalignmentAccel | 
Misalignment of the accelerometer sensor axes.
Definition at line 90 of file InertialIntegrator.hpp.
| Eigen::Quaternion<T> NAV::InertialIntegrator::GenericState< T >::misalignmentGyro | 
Misalignment of the gyroscope sensor axes.
Definition at line 91 of file InertialIntegrator.hpp.
| Eigen::Vector3<T> NAV::InertialIntegrator::GenericState< T >::p_biasAcceleration | 
Acceleration bias in platform frame coordinates in [m/s^2].
Definition at line 84 of file InertialIntegrator.hpp.
| Eigen::Vector3<T> NAV::InertialIntegrator::GenericState< T >::p_biasAngularRate | 
Angular rate bias in platform frame coordinates in [rad/s].
Definition at line 85 of file InertialIntegrator.hpp.
| Eigen::Vector3<T> NAV::InertialIntegrator::GenericState< T >::position | 
IMU position (e_pos / lla_pos)
Definition at line 78 of file InertialIntegrator.hpp.
| Eigen::Vector3<T> NAV::InertialIntegrator::GenericState< T >::scaleFactorAccel | 
Scale factor of the accelerometer [-].
Definition at line 87 of file InertialIntegrator.hpp.
| Eigen::Vector3<T> NAV::InertialIntegrator::GenericState< T >::scaleFactorGyro | 
Scale factor of the gyroscope [-].
Definition at line 88 of file InertialIntegrator.hpp.
| Eigen::Vector3<T> NAV::InertialIntegrator::GenericState< T >::velocity | 
IMU velocity (e_vel / n_vel)
Definition at line 79 of file InertialIntegrator.hpp.