mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: remove dead GPS_MINDGPS variable
This commit is contained in:
parent
e72a39353e
commit
21a01c5587
|
@ -229,7 +229,6 @@ GPS_DELAY_MS2,0
|
|||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_DGPS,100
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
GPS_POS1_X,0.000000000000000000
|
||||
|
|
|
@ -227,7 +227,6 @@ GPS_DELAY_MS2,0
|
|||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_DGPS,100
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
GPS_POS1_X,0.0
|
||||
|
|
|
@ -223,7 +223,6 @@ GPS_DELAY_MS2,0
|
|||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_DGPS,100
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
GPS_POS1_X,0.0
|
||||
|
|
|
@ -263,7 +263,6 @@ GPS_DELAY_MS2,0
|
|||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_DGPS,100
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
GPS_POS1_X,0.0
|
||||
|
@ -828,4 +827,5 @@ WPNAV_SPEED,500.0
|
|||
WPNAV_SPEED_DN,150.0
|
||||
WPNAV_SPEED_UP,250.0
|
||||
WP_YAW_BEHAVIOR,4
|
||||
XTRACK_ANG_LIM,45
|
||||
XTRACK_ANG_LIM,45
|
||||
|
||||
|
|
|
@ -227,7 +227,6 @@ GPS_DELAY_MS2,0
|
|||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_DGPS,100
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
GPS_POS1_X,0.000000000000000000
|
||||
|
|
|
@ -223,7 +223,6 @@ GPS_DELAY_MS2,0
|
|||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_DGPS,100
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
GPS_POS1_X,0.0
|
||||
|
|
|
@ -263,7 +263,6 @@ GPS_DELAY_MS2,0
|
|||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_DGPS,100
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
GPS_POS1_X,0.0
|
||||
|
|
|
@ -227,7 +227,6 @@ GPS_DELAY_MS2,0
|
|||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_DGPS,100
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
GPS_POS1_X,0
|
||||
|
|
|
@ -158,13 +158,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
|||
AP_GROUPINFO("_AUTO_SWITCH", 3, AP_GPS, _auto_switch, (int8_t)GPSAutoSwitch::USE_BEST),
|
||||
#endif
|
||||
|
||||
// @Param: _MIN_DGPS
|
||||
// @DisplayName: Minimum Lock Type Accepted for DGPS
|
||||
// @Description: Sets the minimum type of differential GPS corrections required before allowing to switch into DGPS mode.
|
||||
// @Values: 0:Any,50:FloatRTK,100:IntegerRTK
|
||||
// @User: Advanced
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("_MIN_DGPS", 4, AP_GPS, _min_dgps, 100),
|
||||
// 4 was _MIN_GPS, removed Feb 2024
|
||||
|
||||
// @Param: _SBAS_MODE
|
||||
// @DisplayName: SBAS Mode
|
||||
|
|
|
@ -592,7 +592,6 @@ protected:
|
|||
AP_Int8 _type[GPS_MAX_RECEIVERS];
|
||||
AP_Int8 _navfilter;
|
||||
AP_Int8 _auto_switch;
|
||||
AP_Int8 _min_dgps;
|
||||
AP_Int16 _sbp_logmask;
|
||||
AP_Int8 _inject_to;
|
||||
uint32_t _last_instance_swap_ms;
|
||||
|
|
|
@ -176,7 +176,6 @@ GPS_DELAY_MS2,0
|
|||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_DGPS,100
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
GPS_POS1_X,0
|
||||
|
|
|
@ -180,7 +180,6 @@ GPS_DELAY_MS2,0
|
|||
GPS_GNSS_MODE,0
|
||||
GPS_GNSS_MODE2,0
|
||||
GPS_INJECT_TO,127
|
||||
GPS_MIN_DGPS,100
|
||||
GPS_MIN_ELEV,-100
|
||||
GPS_NAVFILTER,8
|
||||
GPS_POS1_X,0
|
||||
|
|
Loading…
Reference in New Issue