AP_NavEKF2: remove unused EK2_GSF_DELAY param

This commit is contained in:
Randy Mackay 2021-08-05 12:40:41 +09:00
parent 7b77dd39e0
commit 25af40adde
2 changed files with 1 additions and 10 deletions

View File

@ -584,15 +584,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
// @RebootRequired: True
AP_GROUPINFO("GSF_USE_MASK", 55, NavEKF2, _gsfUseMask, 3),
// @Param: GSF_DELAY
// @DisplayName: Delay from loss of navigation to yaw reset
// @Description: If the inertial navigation calculation stops following the GPS and other positioning sensors for longer than EK2_GSF_DELAY milli-seconds, then the EKF2 code will generate a reset request internally and reset the yaw to the estimate from the EKF-GSF filter and reset the horizontal velocity and position to the GPS. This reset will not be performed unless the use of the EKF-GSF yaw estimate is enabled via the EK2_GSF_USE parameter.
// @Range: 500 5000
// @Increment: 100
// @Units: ms
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("GSF_DELAY", 56, NavEKF2, _gsfResetDelay, 1000),
// 56 was GSF_DELAY which was never released in a stable version
// @Param: GSF_RST_MAX
// @DisplayName: Maximum number of resets to the EKF-GSF yaw estimate allowed

View File

@ -367,7 +367,6 @@ private:
AP_Float _hrt_filt_freq; // frequency of output observer height rate complementary filter in Hz
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 EKF2 is allowed to reset it's yaw to the EKF-GSF estimate
// Possible values for _flowUse