mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_NavEKF2: minor comment fixes
This commit is contained in:
parent
43c9e13372
commit
990313371d
@ -396,7 +396,7 @@ private:
|
||||
AP_Float _gyroBiasProcessNoise; // gyro bias state process noise : rad/s
|
||||
AP_Float _accelBiasProcessNoise;// accel bias state process noise : m/s^2
|
||||
AP_Int16 _hgtDelay_ms; // effective average delay of Height measurements relative to inertial measurements (msec)
|
||||
AP_Int8 _fusionModeGPS; // 0 = use 3D velocity, 1 = use 2D velocity, 2 = use no velocity
|
||||
AP_Int8 _fusionModeGPS; // 0 = use 3D velocity, 1 = use 2D velocity, 2 = use no velocity, 3 = do not use GPS
|
||||
AP_Int16 _gpsVelInnovGate; // Percentage number of standard deviations applied to GPS velocity innovation consistency check
|
||||
AP_Int16 _gpsPosInnovGate; // Percentage number of standard deviations applied to GPS position innovation consistency check
|
||||
AP_Int16 _hgtInnovGate; // Percentage number of standard deviations applied to height innovation consistency check
|
||||
|
@ -113,7 +113,7 @@ void NavEKF2_core::controlMagYawReset()
|
||||
// the new quaternion uses the old roll/pitch and new yaw angle
|
||||
stateStruct.quat.from_euler(eulerAnglesOld.x, eulerAnglesOld.y, eulerAnglesNew.z);
|
||||
|
||||
// calculate the change in the quaternion state and apply it to the ouput history buffer
|
||||
// calculate the change in the quaternion state and apply it to the output history buffer
|
||||
prevQuat = stateStruct.quat/prevQuat;
|
||||
StoreQuatRotate(prevQuat);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user