mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 00:35:34 +03:00
Rename setting to try to fix build
This commit is contained in:
parent
deb688b08a
commit
1ac5f8df27
3 changed files with 3 additions and 3 deletions
|
@ -1422,7 +1422,7 @@ Which SBAS mode to be used
|
|||
|
||||
---
|
||||
|
||||
### gps_ublox7_nav_hz
|
||||
### gps_ublox_nav_hz
|
||||
|
||||
Navigation update rate for UBLOX7 receivers. Some receivers may limit the maximum number of satellites tracked when the value is too high.
|
||||
|
||||
|
|
|
@ -1543,7 +1543,7 @@ groups:
|
|||
field: gpsMinSats
|
||||
min: 5
|
||||
max: 10
|
||||
- name: gps_ublox7_nav_hz
|
||||
- name: gps_ublox_nav_hz
|
||||
description: "Navigation update rate for UBLOX7 receivers. Some receivers may limit the maximum number of satellites tracked when the value is too high."
|
||||
default_value: 10
|
||||
field: ubloxNavHz
|
||||
|
|
|
@ -122,7 +122,7 @@ PG_RESET_TEMPLATE(gpsConfig_t, gpsConfig,
|
|||
.dynModel = SETTING_GPS_DYN_MODEL_DEFAULT,
|
||||
.gpsMinSats = SETTING_GPS_MIN_SATS_DEFAULT,
|
||||
.ubloxUseGalileo = SETTING_GPS_UBLOX_USE_GALILEO_DEFAULT,
|
||||
.ubloxNavHz = SETTING_GPS_UBLOX7_NAV_HZ_DEFAULT
|
||||
.ubloxNavHz = SETTING_GPS_UBLOX_NAV_HZ_DEFAULT
|
||||
);
|
||||
|
||||
void gpsSetState(gpsState_e state)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue