diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.h b/libraries/AP_NavEKF3/AP_NavEKF3.h index d4b70b3e14..ccd0a6e2f1 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3.h @@ -413,7 +413,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 diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp index 7dc38b8578..e4ed3c232e 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp @@ -342,7 +342,7 @@ void NavEKF3_core::SelectVelPosFusion() // store the time of the reset lastPosReset_ms = imuSampleTime_ms; - // If we are alseo using GPS as the height reference, reset the height + // If we are also using GPS as the height reference, reset the height if (activeHgtSource == HGT_SOURCE_GPS) { // Store the position before the reset so that we can record the reset delta posResetD = stateStruct.position.z; @@ -435,7 +435,7 @@ void NavEKF3_core::FuseVelPosNED() // Use different errors if operating without external aiding using an assumed position or velocity of zero if (PV_AidingMode == AID_NONE) { if (tiltAlignComplete && motorsArmed) { - // This is a compromise between corrections for gyro errors and reducing effect of manoeuvre accelerations on tilt estimate + // This is a compromise between corrections for gyro errors and reducing effect of manoeuvre accelerations on tilt estimate R_OBS[0] = sq(constrain_float(frontend->_noaidHorizNoise, 0.5f, 50.0f)); } else { // Use a smaller value to give faster initial alignment