1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 01:35:35 +03:00

Merge pull request #9219 from iNavFlight/mmosca-gps-autobaud-more-speeds

Restore autobaud for m8 gps
This commit is contained in:
Marcelo Bezerra 2023-08-06 17:15:04 +02:00 committed by GitHub
commit e39f3e5841
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
5 changed files with 37 additions and 5 deletions

View file

@ -1372,6 +1372,16 @@ Automatic configuration of GPS baudrate(The specified baudrate in configured in
---
### gps_auto_baud_max_supported
Max baudrate supported by GPS unit. This is used during autobaud. M8 supports up to 460400, M10 supports up to 921600 and 230400 is the value used before INAV 7.0
| Default | Min | Max |
| --- | --- | --- |
| 230400 | | |
---
### gps_auto_config
Enable automatic configuration of UBlox GPS receivers.

View file

@ -190,6 +190,9 @@ tables:
- name: nav_fw_wp_turn_smoothing
values: ["OFF", "ON", "ON-CUT"]
enum: wpFwTurnSmoothing_e
- name: gps_auto_baud_max
values: [ '115200', '57600', '38400', '19200', '9600', '230400', '460800', '921600']
enum: gpsBaudRate_e
constants:
RPYL_PID_MIN: 0
@ -1501,6 +1504,7 @@ groups:
min: 1
max: 3000
- name: PG_GPS_CONFIG
headers: [ "io/gps.h" ]
type: gpsConfig_t
condition: USE_GPS
members:
@ -1532,6 +1536,12 @@ groups:
default_value: ON
field: autoBaud
type: bool
- name: gps_auto_baud_max_supported
description: "Max baudrate supported by GPS unit. This is used during autobaud. M8 supports up to 460400, M10 supports up to 921600 and 230400 is the value used before INAV 7.0"
default_value: "230400"
table: gps_auto_baud_max
field: autoBaudMax
type: uint8_t
- name: gps_ublox_use_galileo
description: "Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]."
default_value: OFF

View file

@ -113,7 +113,7 @@ static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = {
};
PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 3);
PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 4);
PG_RESET_TEMPLATE(gpsConfig_t, gpsConfig,
.provider = SETTING_GPS_PROVIDER_DEFAULT,
@ -125,13 +125,13 @@ PG_RESET_TEMPLATE(gpsConfig_t, gpsConfig,
.ubloxUseGalileo = SETTING_GPS_UBLOX_USE_GALILEO_DEFAULT,
.ubloxUseBeidou = SETTING_GPS_UBLOX_USE_BEIDOU_DEFAULT,
.ubloxUseGlonass = SETTING_GPS_UBLOX_USE_GLONASS_DEFAULT,
.ubloxNavHz = SETTING_GPS_UBLOX_NAV_HZ_DEFAULT
.ubloxNavHz = SETTING_GPS_UBLOX_NAV_HZ_DEFAULT,
.autoBaudMax = SETTING_GPS_AUTO_BAUD_MAX_SUPPORTED_DEFAULT
);
int getGpsBaudrate(void)
int gpsBaudRateToInt(gpsBaudRate_e baudrate)
{
switch(gpsState.baudrateIndex)
switch(baudrate)
{
case GPS_BAUDRATE_115200:
return 115200;
@ -154,6 +154,11 @@ int getGpsBaudrate(void)
}
}
int getGpsBaudrate(void)
{
return gpsBaudRateToInt(gpsState.baudrateIndex);
}
const char *getGpsHwVersion(void)
{
switch(gpsState.hwVersion)

View file

@ -99,6 +99,7 @@ typedef struct gpsConfig_s {
bool ubloxUseGlonass;
uint8_t gpsMinSats;
uint8_t ubloxNavHz;
gpsBaudRate_e autoBaudMax;
} gpsConfig_t;
PG_DECLARE(gpsConfig_t, gpsConfig);
@ -175,6 +176,7 @@ uint8_t getGpsProtoMajorVersion(void);
uint8_t getGpsProtoMinorVersion(void);
int getGpsBaudrate(void);
int gpsBaudRateToInt(gpsBaudRate_e baudrate);
#if defined(USE_GPS_FAKE)
void gpsFakeSet(

View file

@ -997,6 +997,11 @@ STATIC_PROTOTHREAD(gpsProtocolStateThread)
// Try sending baud rate switch command at all common baud rates
gpsSetProtocolTimeout((GPS_BAUD_CHANGE_DELAY + 50) * (GPS_BAUDRATE_COUNT));
for (gpsState.autoBaudrateIndex = 0; gpsState.autoBaudrateIndex < GPS_BAUDRATE_COUNT; gpsState.autoBaudrateIndex++) {
if (gpsBaudRateToInt(gpsState.autoBaudrateIndex) > gpsBaudRateToInt(gpsState.gpsConfig->autoBaudMax)) {
// trying higher baud rates fails on m8 gps
// autoBaudRateIndex is not sorted by baud rate
continue;
}
// 2. Set serial port to baud rate and send an $UBX command to switch the baud rate specified by portConfig [baudrateIndex]
serialSetBaudRate(gpsState.gpsPort, baudRates[gpsToSerialBaudRate[gpsState.autoBaudrateIndex]]);
serialPrint(gpsState.gpsPort, baudInitDataNMEA[gpsState.baudrateIndex]);