mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: remove unused EK3_GSF_DELAY param
This commit is contained in:
parent
78704a2f9c
commit
837df29179
|
@ -614,15 +614,7 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = {
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("GSF_USE_MASK", 58, NavEKF3, _gsfUseMask, 3),
|
AP_GROUPINFO("GSF_USE_MASK", 58, NavEKF3, _gsfUseMask, 3),
|
||||||
|
|
||||||
// @Param: GSF_DELAY
|
// 59 was GSF_DELAY which was never released in a stable version
|
||||||
// @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 EK3_GSF_DELAY milli-seconds, then the EKF3 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 EK3_GSF_USE parameter.
|
|
||||||
// @Range: 500 5000
|
|
||||||
// @Increment: 100
|
|
||||||
// @Units: ms
|
|
||||||
// @User: Advanced
|
|
||||||
// @RebootRequired: True
|
|
||||||
AP_GROUPINFO("GSF_DELAY", 59, NavEKF3, _gsfResetDelay, 1000),
|
|
||||||
|
|
||||||
// @Param: GSF_RST_MAX
|
// @Param: GSF_RST_MAX
|
||||||
// @DisplayName: Maximum number of resets to the EKF-GSF yaw estimate allowed
|
// @DisplayName: Maximum number of resets to the EKF-GSF yaw estimate allowed
|
||||||
|
|
|
@ -417,7 +417,6 @@ private:
|
||||||
AP_Int16 _mag_ef_limit; // limit on difference between WMM tables and learned earth field.
|
AP_Int16 _mag_ef_limit; // limit on difference between WMM tables and learned earth field.
|
||||||
AP_Int8 _gsfRunMask; // mask controlling which EKF3 instances run a separate EKF-GSF yaw estimator
|
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 _gsfUseMask; // mask controlling which EKF3 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 EKF3 is allowed to reset it's yaw to the EKF-GSF estimate
|
||||||
AP_Float _err_thresh; // lanes have to be consistently better than the primary by at least this threshold to reduce their overall relativeCoreError
|
AP_Float _err_thresh; // lanes have to be consistently better than the primary by at least this threshold to reduce their overall relativeCoreError
|
||||||
AP_Int32 _affinity; // bitmask of sensor affinity options
|
AP_Int32 _affinity; // bitmask of sensor affinity options
|
||||||
|
|
Loading…
Reference in New Issue