From 0fb233ed4b4e3d79b5319a7e287189a4fdaa501d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 23 Apr 2020 10:25:09 +0900 Subject: [PATCH] AP_NavEKF2: minor comment fixes --- libraries/AP_NavEKF2/AP_NavEKF2.h | 6 +++--- libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.h b/libraries/AP_NavEKF2/AP_NavEKF2.h index af3a12eef8..42b1e1ade6 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2.h @@ -432,10 +432,10 @@ private: AP_Int8 _flowUse; // Controls if the optical flow data is fused into the main navigation estimator and/or the terrain estimator. AP_Int16 _mag_ef_limit; // limit on difference between WMM tables and learned earth field. AP_Float _hrt_filt_freq; // frequency of output observer height rate complementary filter in Hz - AP_Int8 _gsfRunMask; // mask controlling which EKF3 instances run a separate EKF-GSF yaw estimator - AP_Int8 _gsfUseMask; // mask controlling which EKF3 instances will use EKF-GSF yaw estimator data to assit with yaw resets + AP_Int8 _gsfRunMask; // mask controlling which EKF2 instances run a separate EKF-GSF yaw estimator + AP_Int8 _gsfUseMask; // mask controlling which EKF2 instances will use EKF-GSF yaw estimator data to assit with yaw resets AP_Int16 _gsfResetDelay; // number of mSec from loss of navigation to requesting a reset using EKF-GSF yaw estimator data - AP_Int8 _gsfResetMaxCount; // maximum number of times the EKF3 is allowed to reset it's yaw to the EKF-GSF estimate + AP_Int8 _gsfResetMaxCount; // maximum number of times the EKF2 is allowed to reset it's yaw to the EKF-GSF estimate // Possible values for _flowUse #define FLOW_USE_NONE 0 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp index 3fb4d47b90..9111df4a86 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp @@ -1216,7 +1216,7 @@ void NavEKF2_core::recordMagReset() // Reset states using yaw from EKF-GSF and velocity and position from GPS bool NavEKF2_core::EKFGSF_resetMainFilterYaw() { - // Don't do a reset unless permitted by the EK3_GSF_USE and EKF3_GSF_RUN parameter masks + // Don't do a reset unless permitted by the EK2_GSF_USE_MASK and EKF@_GSF_RUN_MASK parameter masks if ((yawEstimator == nullptr) || !(frontend->_gsfUseMask & (1U<= frontend->_gsfResetMaxCount) {