mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +03:00
Allow GPS SBAS mode to be configurable.
It was noticed that GPS startup time increased when the change was made from using EGNOS by default to using AUTO by default. The default is still AUTO but faster GPS startup times may be achieved by telling the GPS receiver what region you are in. This also removes more unfinished MTK gps provider support.
This commit is contained in:
parent
09a1739ce6
commit
fabd376f41
7 changed files with 67 additions and 28 deletions
28
docs/Gps.md
Normal file
28
docs/Gps.md
Normal file
|
@ -0,0 +1,28 @@
|
||||||
|
# GPS
|
||||||
|
|
||||||
|
Two GPS protocols are supported. NMEA text and UBLOX Binary.
|
||||||
|
|
||||||
|
## GPS Provider
|
||||||
|
|
||||||
|
Set the `gps_provider` appropriately.
|
||||||
|
|
||||||
|
| Value | Meaning |
|
||||||
|
| ----- | -------- |
|
||||||
|
| 0 | NMEA |
|
||||||
|
| 1 | UBLOX |
|
||||||
|
|
||||||
|
## SBAS
|
||||||
|
|
||||||
|
When using a UBLOX GPS the SBAS mode can be configured using `gps_sbas_mode`.
|
||||||
|
|
||||||
|
The default is AUTO.
|
||||||
|
|
||||||
|
| Value | Meaning | Region |
|
||||||
|
| ----- | -------- | ------------- |
|
||||||
|
| 0 | AUTO | Global |
|
||||||
|
| 1 | EGNOS | Europe |
|
||||||
|
| 2 | WAAS | North America |
|
||||||
|
| 3 | MSAS | Asia |
|
||||||
|
| 4 | GAGAN | India |
|
||||||
|
|
||||||
|
If you use a regional specific setting you may achieve a faster GPS lock than using AUTO.
|
|
@ -235,7 +235,8 @@ static void resetConf(void)
|
||||||
masterConfig.servo_pwm_rate = 50;
|
masterConfig.servo_pwm_rate = 50;
|
||||||
|
|
||||||
// gps/nav stuff
|
// gps/nav stuff
|
||||||
masterConfig.gps_provider = GPS_NMEA;
|
masterConfig.gpsConfig.provider = GPS_NMEA;
|
||||||
|
masterConfig.gpsConfig.sbasMode = SBAS_AUTO;
|
||||||
|
|
||||||
resetSerialConfig(&masterConfig.serialConfig);
|
resetSerialConfig(&masterConfig.serialConfig);
|
||||||
|
|
||||||
|
|
|
@ -46,8 +46,7 @@ typedef struct master_t {
|
||||||
airplaneConfig_t airplaneConfig;
|
airplaneConfig_t airplaneConfig;
|
||||||
int8_t fixedwing_althold_dir; // +1 or -1 for pitch/althold gain. later check if need more than just sign
|
int8_t fixedwing_althold_dir; // +1 or -1 for pitch/althold gain. later check if need more than just sign
|
||||||
|
|
||||||
// gps-related stuff
|
gpsConfig_t gpsConfig;
|
||||||
gpsProvider_e gps_provider;
|
|
||||||
|
|
||||||
serialConfig_t serialConfig;
|
serialConfig_t serialConfig;
|
||||||
|
|
||||||
|
|
|
@ -60,7 +60,7 @@ static int16_t nav_rated[2]; // Adding a rate controller to the na
|
||||||
int8_t nav_mode = NAV_MODE_NONE; // Navigation mode
|
int8_t nav_mode = NAV_MODE_NONE; // Navigation mode
|
||||||
|
|
||||||
|
|
||||||
static uint8_t gpsProvider;
|
static gpsConfig_t *gpsConfig;
|
||||||
|
|
||||||
// GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 2.5second)
|
// GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 2.5second)
|
||||||
#define GPS_TIMEOUT (2500)
|
#define GPS_TIMEOUT (2500)
|
||||||
|
@ -113,20 +113,13 @@ static const uint8_t ubloxInit[] = {
|
||||||
// 31.21 CFG-SBAS (0x06 0x16), Page 142/210
|
// 31.21 CFG-SBAS (0x06 0x16), Page 142/210
|
||||||
// A.10 SBAS Configuration (UBX-CFG-SBAS), Page 198/210 - GPS.G6-SW-10018-F
|
// A.10 SBAS Configuration (UBX-CFG-SBAS), Page 198/210 - GPS.G6-SW-10018-F
|
||||||
|
|
||||||
typedef enum {
|
|
||||||
SBAS_AUTO = 0,
|
|
||||||
SBAS_EGNOS,
|
|
||||||
SBAS_WAAS,
|
|
||||||
SBAS_MSAS,
|
|
||||||
SBAS_GAGAN
|
|
||||||
} sbasMode_e;
|
|
||||||
|
|
||||||
#define UBLOX_SBAS_MESSAGE_LENGTH 16
|
#define UBLOX_SBAS_MESSAGE_LENGTH 16
|
||||||
typedef struct ubloxSbas_s {
|
typedef struct ubloxSbas_s {
|
||||||
sbasMode_e mode;
|
sbasMode_e mode;
|
||||||
uint8_t message[UBLOX_SBAS_MESSAGE_LENGTH];
|
uint8_t message[UBLOX_SBAS_MESSAGE_LENGTH];
|
||||||
} ubloxSbas_t;
|
} ubloxSbas_t;
|
||||||
|
|
||||||
|
// Note: these must be defined in the same order is sbasMode_e since no lookup table is used.
|
||||||
static const ubloxSbas_t ubloxSbas[] = {
|
static const ubloxSbas_t ubloxSbas[] = {
|
||||||
{ SBAS_AUTO, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x31, 0xE5}},
|
{ SBAS_AUTO, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x31, 0xE5}},
|
||||||
{ SBAS_EGNOS, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x51, 0x08, 0x00, 0x00, 0x8A, 0x41}},
|
{ SBAS_EGNOS, { 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x51, 0x08, 0x00, 0x00, 0x8A, 0x41}},
|
||||||
|
@ -188,7 +181,7 @@ void gpsUseProfile(gpsProfile_t *gpsProfileToUse)
|
||||||
}
|
}
|
||||||
|
|
||||||
// When using PWM input GPS usage reduces number of available channels by 2 - see pwm_common.c/pwmInit()
|
// When using PWM input GPS usage reduces number of available channels by 2 - see pwm_common.c/pwmInit()
|
||||||
void gpsInit(serialConfig_t *initialSerialConfig, uint8_t initialGpsProvider, gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile)
|
void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig, gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile)
|
||||||
{
|
{
|
||||||
serialConfig = initialSerialConfig;
|
serialConfig = initialSerialConfig;
|
||||||
|
|
||||||
|
@ -201,7 +194,7 @@ void gpsInit(serialConfig_t *initialSerialConfig, uint8_t initialGpsProvider, gp
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
gpsProvider = initialGpsProvider;
|
gpsConfig = initialGpsConfig;
|
||||||
gpsUseProfile(initialGpsProfile);
|
gpsUseProfile(initialGpsProfile);
|
||||||
|
|
||||||
// init gpsData structure. if we're not actually enabled, don't bother doing anything else
|
// init gpsData structure. if we're not actually enabled, don't bother doing anything else
|
||||||
|
@ -212,7 +205,7 @@ void gpsInit(serialConfig_t *initialSerialConfig, uint8_t initialGpsProvider, gp
|
||||||
|
|
||||||
portMode_t mode = MODE_RXTX;
|
portMode_t mode = MODE_RXTX;
|
||||||
// only RX is needed for NMEA-style GPS
|
// only RX is needed for NMEA-style GPS
|
||||||
if (gpsProvider == GPS_NMEA)
|
if (gpsConfig->provider == GPS_NMEA)
|
||||||
mode = MODE_RX;
|
mode = MODE_RX;
|
||||||
|
|
||||||
gpsUsePIDs(pidProfile);
|
gpsUsePIDs(pidProfile);
|
||||||
|
@ -289,9 +282,8 @@ void gpsInitUblox(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gpsData.messageState == GPS_MESSAGE_STATE_SBAS) {
|
if (gpsData.messageState == GPS_MESSAGE_STATE_SBAS) {
|
||||||
uint8_t sbasIndex = SBAS_AUTO; // TODO allow configuration
|
|
||||||
if (gpsData.state_position < UBLOX_SBAS_MESSAGE_LENGTH) {
|
if (gpsData.state_position < UBLOX_SBAS_MESSAGE_LENGTH) {
|
||||||
serialWrite(gpsPort, ubloxSbas[sbasIndex].message[gpsData.state_position]);
|
serialWrite(gpsPort, ubloxSbas[gpsConfig->sbasMode].message[gpsData.state_position]);
|
||||||
gpsData.state_position++;
|
gpsData.state_position++;
|
||||||
} else {
|
} else {
|
||||||
gpsData.messageState++;
|
gpsData.messageState++;
|
||||||
|
@ -308,7 +300,7 @@ void gpsInitUblox(void)
|
||||||
|
|
||||||
void gpsInitHardware(void)
|
void gpsInitHardware(void)
|
||||||
{
|
{
|
||||||
switch (gpsProvider) {
|
switch (gpsConfig->provider) {
|
||||||
case GPS_NMEA:
|
case GPS_NMEA:
|
||||||
gpsInitNmea();
|
gpsInitNmea();
|
||||||
break;
|
break;
|
||||||
|
@ -365,9 +357,8 @@ void gpsThread(void)
|
||||||
|
|
||||||
static bool gpsNewFrame(uint8_t c)
|
static bool gpsNewFrame(uint8_t c)
|
||||||
{
|
{
|
||||||
switch (gpsProvider) {
|
switch (gpsConfig->provider) {
|
||||||
case GPS_NMEA: // NMEA
|
case GPS_NMEA: // NMEA
|
||||||
case GPS_MTK_NMEA: // MTK in NMEA mode
|
|
||||||
return gpsNewFrameNMEA(c);
|
return gpsNewFrameNMEA(c);
|
||||||
case GPS_UBLOX: // UBX binary
|
case GPS_UBLOX: // UBX binary
|
||||||
return gpsNewFrameUBLOX(c);
|
return gpsNewFrameUBLOX(c);
|
||||||
|
|
|
@ -5,20 +5,31 @@
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
GPS_NMEA = 0,
|
GPS_NMEA = 0,
|
||||||
GPS_UBLOX,
|
GPS_UBLOX
|
||||||
GPS_MTK_NMEA,
|
|
||||||
GPS_PROVIDER_MAX = GPS_MTK_NMEA,
|
|
||||||
} gpsProvider_e;
|
} gpsProvider_e;
|
||||||
|
|
||||||
|
#define GPS_PROVIDER_MAX GPS_UBLOX
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
SBAS_AUTO = 0,
|
||||||
|
SBAS_EGNOS,
|
||||||
|
SBAS_WAAS,
|
||||||
|
SBAS_MSAS,
|
||||||
|
SBAS_GAGAN
|
||||||
|
} sbasMode_e;
|
||||||
|
|
||||||
|
#define SBAS_MODE_MAX SBAS_GAGAN
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
GPS_BAUDRATE_115200 = 0,
|
GPS_BAUDRATE_115200 = 0,
|
||||||
GPS_BAUDRATE_57600,
|
GPS_BAUDRATE_57600,
|
||||||
GPS_BAUDRATE_38400,
|
GPS_BAUDRATE_38400,
|
||||||
GPS_BAUDRATE_19200,
|
GPS_BAUDRATE_19200,
|
||||||
GPS_BAUDRATE_9600,
|
GPS_BAUDRATE_9600
|
||||||
GPS_BAUDRATE_MAX = GPS_BAUDRATE_9600
|
|
||||||
} gpsBaudRate_e;
|
} gpsBaudRate_e;
|
||||||
|
|
||||||
|
#define GPS_BAUDRATE_MAX GPS_BAUDRATE_9600
|
||||||
|
|
||||||
// Serial GPS only variables
|
// Serial GPS only variables
|
||||||
// navigation mode
|
// navigation mode
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
@ -37,6 +48,11 @@ typedef struct gpsProfile_s {
|
||||||
uint16_t ap_mode; // Temporarily Disables GPS_HOLD_MODE to be able to make it possible to adjust the Hold-position when moving the sticks, creating a deadspan for GPS
|
uint16_t ap_mode; // Temporarily Disables GPS_HOLD_MODE to be able to make it possible to adjust the Hold-position when moving the sticks, creating a deadspan for GPS
|
||||||
} gpsProfile_t;
|
} gpsProfile_t;
|
||||||
|
|
||||||
|
typedef struct gpsConfig_s {
|
||||||
|
gpsProvider_e provider;
|
||||||
|
sbasMode_e sbasMode;
|
||||||
|
} gpsConfig_t;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
GPS_PASSTHROUGH_ENABLED = 1,
|
GPS_PASSTHROUGH_ENABLED = 1,
|
||||||
GPS_PASSTHROUGH_NO_GPS,
|
GPS_PASSTHROUGH_NO_GPS,
|
||||||
|
|
|
@ -173,6 +173,9 @@ const clivalue_t valueTable[] = {
|
||||||
{ "serial_port_2_scenario", VAR_UINT8, &masterConfig.serialConfig.serial_port_2_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
{ "serial_port_2_scenario", VAR_UINT8, &masterConfig.serialConfig.serial_port_2_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||||
{ "serial_port_3_scenario", VAR_UINT8, &masterConfig.serialConfig.serial_port_3_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
{ "serial_port_3_scenario", VAR_UINT8, &masterConfig.serialConfig.serial_port_3_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||||
{ "serial_port_4_scenario", VAR_UINT8, &masterConfig.serialConfig.serial_port_4_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
{ "serial_port_4_scenario", VAR_UINT8, &masterConfig.serialConfig.serial_port_4_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||||
|
#if (SERIAL_PORT_COUNT > 4)
|
||||||
|
{ "serial_port_5_scenario", VAR_UINT8, &masterConfig.serialConfig.serial_port_5_scenario, 0, SERIAL_PORT_SCENARIO_MAX },
|
||||||
|
#endif
|
||||||
|
|
||||||
{ "reboot_character", VAR_UINT8, &masterConfig.serialConfig.reboot_character, 48, 126 },
|
{ "reboot_character", VAR_UINT8, &masterConfig.serialConfig.reboot_character, 48, 126 },
|
||||||
{ "msp_baudrate", VAR_UINT32, &masterConfig.serialConfig.msp_baudrate, 1200, 115200 },
|
{ "msp_baudrate", VAR_UINT32, &masterConfig.serialConfig.msp_baudrate, 1200, 115200 },
|
||||||
|
@ -180,7 +183,8 @@ const clivalue_t valueTable[] = {
|
||||||
{ "gps_baudrate", VAR_UINT32, &masterConfig.serialConfig.gps_baudrate, 0, 115200 },
|
{ "gps_baudrate", VAR_UINT32, &masterConfig.serialConfig.gps_baudrate, 0, 115200 },
|
||||||
{ "gps_passthrough_baudrate", VAR_UINT32, &masterConfig.serialConfig.gps_passthrough_baudrate, 1200, 115200 },
|
{ "gps_passthrough_baudrate", VAR_UINT32, &masterConfig.serialConfig.gps_passthrough_baudrate, 1200, 115200 },
|
||||||
|
|
||||||
{ "gps_provider", VAR_UINT8, &masterConfig.gps_provider, 0, GPS_PROVIDER_MAX },
|
{ "gps_provider", VAR_UINT8, &masterConfig.gpsConfig.provider, 0, GPS_PROVIDER_MAX },
|
||||||
|
{ "gps_sbas_mode", VAR_UINT8, &masterConfig.gpsConfig.sbasMode, 0, SBAS_MODE_MAX },
|
||||||
|
|
||||||
{ "serialrx_provider", VAR_UINT8, &masterConfig.rxConfig.serialrx_provider, 0, SERIALRX_PROVIDER_MAX },
|
{ "serialrx_provider", VAR_UINT8, &masterConfig.rxConfig.serialrx_provider, 0, SERIALRX_PROVIDER_MAX },
|
||||||
|
|
||||||
|
|
|
@ -62,7 +62,7 @@ failsafe_t* failsafeInit(rxConfig_t *intialRxConfig);
|
||||||
void pwmInit(drv_pwm_config_t *init);
|
void pwmInit(drv_pwm_config_t *init);
|
||||||
void rxInit(rxConfig_t *rxConfig, failsafe_t *failsafe);
|
void rxInit(rxConfig_t *rxConfig, failsafe_t *failsafe);
|
||||||
void buzzerInit(failsafe_t *initialFailsafe);
|
void buzzerInit(failsafe_t *initialFailsafe);
|
||||||
void gpsInit(serialConfig_t *serialConfig, uint8_t initialGpsProvider, gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile);
|
void gpsInit(serialConfig_t *serialConfig, gpsConfig_t *initialGpsConfig, gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile);
|
||||||
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int16_t magDeclinationFromConfig);
|
bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int16_t magDeclinationFromConfig);
|
||||||
void imuInit(void);
|
void imuInit(void);
|
||||||
|
|
||||||
|
@ -183,7 +183,7 @@ void init(void)
|
||||||
if (feature(FEATURE_GPS)) {
|
if (feature(FEATURE_GPS)) {
|
||||||
gpsInit(
|
gpsInit(
|
||||||
&masterConfig.serialConfig,
|
&masterConfig.serialConfig,
|
||||||
masterConfig.gps_provider,
|
&masterConfig.gpsConfig,
|
||||||
¤tProfile.gpsProfile,
|
¤tProfile.gpsProfile,
|
||||||
¤tProfile.pidProfile
|
¤tProfile.pidProfile
|
||||||
);
|
);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue