mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-30 15:52:12 +01:00
LP-452 Added Galileo as a GNSS configuration option to the GCS.
System -> Settings -> GPSSettings -> UbxGNSSMode The options GPS+Galileo and GPS+GLONASS+Galileo have been added. Also corrected PRN mask for EGNOS SBAS information. Active PRN: 120 & 136 , 123 Ref: https://egnos-user-support.essp-sas.eu/new_egnos_ops/index.php
This commit is contained in:
parent
58e15feb08
commit
e5ca71052a
@ -727,31 +727,49 @@ void updateGpsSettings(__attribute__((unused)) UAVObjEvent *ev)
|
||||
newconfig.enableGPS = true;
|
||||
newconfig.enableGLONASS = true;
|
||||
newconfig.enableBeiDou = false;
|
||||
newconfig.enableGalileo = false;
|
||||
break;
|
||||
case GPSSETTINGS_UBXGNSSMODE_GLONASS:
|
||||
newconfig.enableGPS = false;
|
||||
newconfig.enableGLONASS = true;
|
||||
newconfig.enableBeiDou = false;
|
||||
newconfig.enableGalileo = false;
|
||||
break;
|
||||
case GPSSETTINGS_UBXGNSSMODE_GPS:
|
||||
newconfig.enableGPS = true;
|
||||
newconfig.enableGLONASS = false;
|
||||
newconfig.enableBeiDou = false;
|
||||
newconfig.enableGalileo = false;
|
||||
break;
|
||||
case GPSSETTINGS_UBXGNSSMODE_GPSBEIDOU:
|
||||
newconfig.enableGPS = true;
|
||||
newconfig.enableGLONASS = false;
|
||||
newconfig.enableBeiDou = true;
|
||||
newconfig.enableGalileo = false;
|
||||
break;
|
||||
case GPSSETTINGS_UBXGNSSMODE_GLONASSBEIDOU:
|
||||
newconfig.enableGPS = false;
|
||||
newconfig.enableGLONASS = true;
|
||||
newconfig.enableBeiDou = true;
|
||||
newconfig.enableGalileo = false;
|
||||
break;
|
||||
case GPSSETTINGS_UBXGNSSMODE_GPSGALILEO:
|
||||
newconfig.enableGPS = true;
|
||||
newconfig.enableGLONASS = false;
|
||||
newconfig.enableBeiDou = false;
|
||||
newconfig.enableGalileo = true;
|
||||
break;
|
||||
case GPSSETTINGS_UBXGNSSMODE_GPSGLONASSGALILEO:
|
||||
newconfig.enableGPS = true;
|
||||
newconfig.enableGLONASS = true;
|
||||
newconfig.enableBeiDou = false;
|
||||
newconfig.enableGalileo = true;
|
||||
break;
|
||||
default:
|
||||
newconfig.enableGPS = false;
|
||||
newconfig.enableGLONASS = false;
|
||||
newconfig.enableBeiDou = false;
|
||||
newconfig.enableGalileo = false;
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -460,8 +460,8 @@ struct UBX_CFG_CFG {
|
||||
// ------------------------------------10987654321098765432109876543210
|
||||
// WAAS 122, 133, 134, 135, 138---------|---------|---------|---------|
|
||||
#define UBX_CFG_SBAS_SCANMODE1_WAAS 0b00000000000001001110000000000100
|
||||
// EGNOS 120, 124, 126, 131-------------|---------|---------|---------|
|
||||
#define UBX_CFG_SBAS_SCANMODE1_EGNOS 0b00000000000000000000100001010001
|
||||
// EGNOS 120, 123, 136------------------|---------|---------|---------|
|
||||
#define UBX_CFG_SBAS_SCANMODE1_EGNOS 0b00000000000000010000000000001001
|
||||
// MSAS 129, 137------------------------|---------|---------|---------|
|
||||
#define UBX_CFG_SBAS_SCANMODE1_MSAS 0b00000000000000100000001000000000
|
||||
// GAGAN 127, 128-----------------------|---------|---------|---------|
|
||||
@ -485,6 +485,7 @@ struct UBX_CFG_SBAS {
|
||||
#define UBX_CFG_GNSS_FLAGS_QZSS_L1CA 0x010000
|
||||
#define UBX_CFG_GNSS_FLAGS_QZSS_L1SAIF 0x040000
|
||||
#define UBX_CFG_GNSS_FLAGS_GLONASS_L1OF 0x010000
|
||||
#define UBX_CFG_GNSS_FLAGS_GALILEO_E1 0x010000
|
||||
|
||||
#define UBX_CFG_GNSS_NUMCH_VER7 22
|
||||
#define UBX_CFG_GNSS_NUMCH_VER8 32
|
||||
|
@ -102,6 +102,7 @@ typedef struct {
|
||||
bool enableGPS;
|
||||
bool enableGLONASS;
|
||||
bool enableBeiDou;
|
||||
bool enableGalileo;
|
||||
} ubx_autoconfig_settings_t;
|
||||
|
||||
// Sent messages for configuration support
|
||||
|
@ -397,6 +397,13 @@ static void config_gnss(uint16_t *bytes_to_send)
|
||||
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].resTrkCh = 8;
|
||||
}
|
||||
break;
|
||||
case UBX_GNSS_ID_GALILEO:
|
||||
if (status->currentSettings.enableGalileo) {
|
||||
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].flags = UBX_CFG_GNSS_FLAGS_ENABLED | UBX_CFG_GNSS_FLAGS_GALILEO_E1;
|
||||
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].maxTrkCh = 10;
|
||||
status->working_packet.message.payload.cfg_gnss.cfgBlocks[i].resTrkCh = 8;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
@ -18,7 +18,7 @@
|
||||
<field name="UbxSBASChannelsUsed" units="" type="uint8" elements="1" defaultvalue="3"/>
|
||||
<field name="UbxSBASSats" units="" type="enum" elements="1" options="AutoScan,WAAS,EGNOS,MSAS,GAGAN,SDCM" defaultvalue="AutoScan" />
|
||||
<!-- Ubx GNSS configuration, only applies to Ublox generation 7+ and concurrent GNSS only to generation 8 -->
|
||||
<field name="UbxGNSSMode" units="" type="enum" elements="1" options="Default,GPS,GLONASS,GPS+GLONASS,GPS+BeiDou,GLONASS+BeiDou" defaultvalue="Default" />
|
||||
<field name="UbxGNSSMode" units="" type="enum" elements="1" options="Default,GPS,GLONASS,GPS+GLONASS,GPS+BeiDou,GLONASS+BeiDou,GPS+GALILEO,GPS+GLONASS+GALILEO" defaultvalue="Default" />
|
||||
<field name="UbxAssistNowAutonomous" units="" type="enum" elements="1" options="False,True" defaultvalue="True"
|
||||
description="Enable or disable the AssistNow Autonomous feature"/>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user