1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 06:15:16 +03:00

Add Galileo support to GPS

This commit is contained in:
Miguel Angel Mulero Martinez 2018-05-30 09:38:35 +02:00
parent eecb59db45
commit f43b36ce19
3 changed files with 31 additions and 1 deletions

View file

@ -686,6 +686,7 @@ const clivalue_t valueTable[] = {
{ "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_SBAS_MODE }, PG_GPS_CONFIG, offsetof(gpsConfig_t, sbasMode) }, { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_SBAS_MODE }, PG_GPS_CONFIG, offsetof(gpsConfig_t, sbasMode) },
{ "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, autoConfig) }, { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, autoConfig) },
{ "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, autoBaud) }, { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, autoBaud) },
{ "gps_ublox_use_galileo", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, gps_ublox_use_galileo) },
#ifdef USE_GPS_RESCUE #ifdef USE_GPS_RESCUE
// PG_GPS_RESCUE // PG_GPS_RESCUE

View file

@ -204,6 +204,21 @@ static const ubloxSbas_t ubloxSbas[] = {
{ SBAS_MSAS, { 0x00, 0x02, 0x02, 0x00, 0x35, 0xEF}}, { SBAS_MSAS, { 0x00, 0x02, 0x02, 0x00, 0x35, 0xEF}},
{ SBAS_GAGAN, { 0x80, 0x01, 0x00, 0x00, 0xB2, 0xE8}} { SBAS_GAGAN, { 0x80, 0x01, 0x00, 0x00, 0xB2, 0xE8}}
}; };
// Remove QZSS and add Galileo (only 3 GNSS systems supported simultaneously)
// Frame captured from uCenter
static const uint8_t ubloxGalileoInit[] = {
0xB5, 0x62, 0x06, 0x3E, 0x3C, // UBX-CGF-GNSS
0x00, 0x00, 0x20, 0x20, 0x07, // GNSS
0x00, 0x08, 0x10, 0x00, 0x01, 0x00, 0x01, 0x01, // GPS
0x01, 0x01, 0x03, 0x00, 0x01, 0x00, 0x01, 0x01, // SBAS
0x02, 0x04, 0x08, 0x00, 0x01, 0x00, 0x01, 0x01, // Galileo
0x03, 0x08, 0x10, 0x00, 0x00, 0x00, 0x01, 0x01, // BeiDou
0x04, 0x00, 0x08, 0x00, 0x00, 0x00, 0x01, 0x03, // IMES
0x05, 0x00, 0x03, 0x00, 0x00, 0x00, 0x01, 0x05, // QZSS
0x06, 0x08, 0x0E, 0x00, 0x01, 0x00, 0x01, 0x01, // GLONASS
0x55, 0x47
};
#endif // USE_GPS_UBLOX #endif // USE_GPS_UBLOX
typedef enum { typedef enum {
@ -224,7 +239,8 @@ PG_RESET_TEMPLATE(gpsConfig_t, gpsConfig,
.provider = GPS_NMEA, .provider = GPS_NMEA,
.sbasMode = SBAS_AUTO, .sbasMode = SBAS_AUTO,
.autoConfig = GPS_AUTOCONFIG_ON, .autoConfig = GPS_AUTOCONFIG_ON,
.autoBaud = GPS_AUTOBAUD_OFF .autoBaud = GPS_AUTOBAUD_OFF,
.gps_ublox_use_galileo = false
); );
static void shiftPacketLog(void) static void shiftPacketLog(void)
@ -422,6 +438,17 @@ void gpsInitUblox(void)
serialWrite(gpsPort, ubloxSbas[gpsConfig()->sbasMode].message[gpsData.state_position - UBLOX_SBAS_PREFIX_LENGTH]); serialWrite(gpsPort, ubloxSbas[gpsConfig()->sbasMode].message[gpsData.state_position - UBLOX_SBAS_PREFIX_LENGTH]);
gpsData.state_position++; gpsData.state_position++;
} else { } else {
gpsData.state_position = 0;
gpsData.messageState++;
}
}
if (gpsData.messageState == GPS_MESSAGE_STATE_GALILEO) {
if ((gpsConfig()->gps_ublox_use_galileo) && (gpsData.state_position < sizeof(ubloxGalileoInit))) {
serialWrite(gpsPort, ubloxGalileoInit[gpsData.state_position]);
gpsData.state_position++;
} else {
gpsData.state_position = 0;
gpsData.messageState++; gpsData.messageState++;
} }
} }

View file

@ -72,6 +72,7 @@ typedef struct gpsConfig_s {
sbasMode_e sbasMode; sbasMode_e sbasMode;
gpsAutoConfig_e autoConfig; gpsAutoConfig_e autoConfig;
gpsAutoBaud_e autoBaud; gpsAutoBaud_e autoBaud;
uint8_t gps_ublox_use_galileo;
} gpsConfig_t; } gpsConfig_t;
PG_DECLARE(gpsConfig_t, gpsConfig); PG_DECLARE(gpsConfig_t, gpsConfig);
@ -101,6 +102,7 @@ typedef enum {
GPS_MESSAGE_STATE_IDLE = 0, GPS_MESSAGE_STATE_IDLE = 0,
GPS_MESSAGE_STATE_INIT, GPS_MESSAGE_STATE_INIT,
GPS_MESSAGE_STATE_SBAS, GPS_MESSAGE_STATE_SBAS,
GPS_MESSAGE_STATE_GALILEO,
GPS_MESSAGE_STATE_ENTRY_COUNT GPS_MESSAGE_STATE_ENTRY_COUNT
} gpsMessageState_e; } gpsMessageState_e;