mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-11-29 07:24:13 +01:00
Merged in Oblivium/librepilot/LP-452_Implement_and_verify_Galileo_support_for_ublox_8 (pull request #368)
LP-452 Support the Galileo GNSS on U-blox NEO M8N receiver.
This commit is contained in:
commit
9ad736d7c8
@ -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;
|
||||
}
|
||||
|
@ -118,7 +118,7 @@ void GpsConstellationWidget::updateSat(int index, int prn, int elevation, int az
|
||||
}
|
||||
|
||||
// TODO: add range checking
|
||||
satellites[index][0] = prn;
|
||||
satellites[index][0] = prn; // UBX SVID
|
||||
satellites[index][1] = elevation;
|
||||
satellites[index][2] = azimuth;
|
||||
satellites[index][3] = snr;
|
||||
@ -129,7 +129,13 @@ void GpsConstellationWidget::updateSat(int index, int prn, int elevation, int az
|
||||
-satIcons[index]->boundingRect().center().y());
|
||||
satIcons[index]->setTransform(QTransform::fromTranslate(opd.x(), opd.y()), false);
|
||||
|
||||
// Show normal GPS, SBAS/QZSS (120-158,193-197 range), BeiDou (33-64, 159-163) or GLONASS (65-96, 255 if unidentified)
|
||||
// Show satellite constellations in a separate color
|
||||
// The UBX SVID numbers are defined in appendix A of u-blox8-M8_ReceiverDescrProtSpec_(UBX-13003221)_Public.pdf
|
||||
// GPS = default
|
||||
// SBAS 120-158, QZSS 193-197
|
||||
// BeiDou 33-64, 159-163
|
||||
// GLONASS 65-96, 255 if unidentified
|
||||
// Galileo 211-246
|
||||
if ((prn > 119 && prn < 159) || (prn > 192 && prn < 198)) {
|
||||
if (snr) {
|
||||
satIcons[index]->setElementId("satellite-sbas");
|
||||
@ -148,6 +154,12 @@ void GpsConstellationWidget::updateSat(int index, int prn, int elevation, int az
|
||||
} else {
|
||||
satIcons[index]->setElementId("sat-beidou-notSeen");
|
||||
}
|
||||
} else if (prn > 210 && prn < 247) {
|
||||
if (snr) {
|
||||
satIcons[index]->setElementId("satellite-galileo");
|
||||
} else {
|
||||
satIcons[index]->setElementId("sat-galileo-notSeen");
|
||||
}
|
||||
} else {
|
||||
if (snr) {
|
||||
satIcons[index]->setElementId("satellite");
|
||||
|
@ -127,7 +127,7 @@
|
||||
</palette>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>Displays the SNR for each detected sat. GPS satellites are shown in green, GLONASS in cyan, BeiDou in red and SBAS/QZSS in orange. Satellite number (PRN) is displayed inside the bar. Sat SNR is displayed above (in dBHz)</p></body></html></string>
|
||||
<string><html><head/><body><p>Displays the SNR for each detected sat. GPS satellites are shown in green, GLONASS in cyan, BeiDou in red, Galileo in magenta and SBAS/QZSS in orange. Satellite number (PRN) is displayed inside the bar. Sat SNR is displayed above (in dBHz)</p></body></html></string>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
|
@ -104,14 +104,21 @@ void GpsSnrWidget::drawSat(int index)
|
||||
|
||||
QRectF boxRect = boxes[index]->boundingRect();
|
||||
|
||||
// Change color for SBAS & QZSS 120-158, 193-197 range
|
||||
// GLONASS range 65-96 or 255, BeiDou 33-64 or 159-163
|
||||
// Show satellite constellations in a separate color
|
||||
// The UBX SVID numbers are defined in appendix A of u-blox8-M8_ReceiverDescrProtSpec_(UBX-13003221)_Public.pdf
|
||||
// GPS = default
|
||||
// SBAS 120-158, QZSS 193-197
|
||||
// BeiDou 33-64, 159-163
|
||||
// GLONASS 65-96, 255 if unidentified
|
||||
// Galileo 211-246
|
||||
if ((prn > 119 && prn < 159) || (prn > 192 && prn < 198)) {
|
||||
boxes[index]->setBrush(QColor("#fd700b"));
|
||||
boxes[index]->setBrush(QColor("#fd700b")); // orange
|
||||
} else if ((prn > 64 && prn < 97) || 255 == prn) {
|
||||
boxes[index]->setBrush(QColor("Cyan"));
|
||||
} else if ((prn > 32 && prn < 65) || (prn > 158 && prn < 164)) {
|
||||
boxes[index]->setBrush(QColor("Red"));
|
||||
} else if (prn > 210 && prn < 247) {
|
||||
boxes[index]->setBrush(QColor("#e162f3")); // magenta
|
||||
} else {
|
||||
boxes[index]->setBrush(QColor("Green"));
|
||||
}
|
||||
|
@ -14,10 +14,21 @@
|
||||
height="691.54303"
|
||||
id="svg2"
|
||||
version="1.1"
|
||||
inkscape:version="0.48.4 r9939"
|
||||
inkscape:version="0.91 r13725"
|
||||
sodipodi:docname="gpsEarth.svg">
|
||||
<defs
|
||||
id="defs4">
|
||||
<linearGradient
|
||||
id="linearGradient4512">
|
||||
<stop
|
||||
id="stop4514"
|
||||
offset="0"
|
||||
style="stop-color:#ce00e0;stop-opacity:1" />
|
||||
<stop
|
||||
id="stop4516"
|
||||
offset="1"
|
||||
style="stop-color:#fff954;stop-opacity:0;" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
id="linearGradient4431">
|
||||
@ -1003,6 +1014,46 @@
|
||||
fx="559.92383"
|
||||
fy="182.67093"
|
||||
r="21.496641" />
|
||||
<radialGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient3825"
|
||||
id="radialGradient3907-5-5"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(-0.11243486,0.51064271,-0.68854473,-0.15160586,748.65596,-75.556107)"
|
||||
cx="559.92383"
|
||||
cy="182.67093"
|
||||
fx="559.92383"
|
||||
fy="182.67093"
|
||||
r="21.496641" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4512"
|
||||
id="linearGradient3859-7-2"
|
||||
x1="572.75409"
|
||||
y1="197.75398"
|
||||
x2="599.88422"
|
||||
y2="231.04071"
|
||||
gradientUnits="userSpaceOnUse" />
|
||||
<radialGradient
|
||||
r="21.496641"
|
||||
fy="182.67093"
|
||||
fx="559.92383"
|
||||
cy="182.67093"
|
||||
cx="559.92383"
|
||||
gradientTransform="matrix(-0.11243486,0.51064271,-0.68854473,-0.15160586,748.65596,-75.556107)"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
id="radialGradient4859-3"
|
||||
xlink:href="#linearGradient3825"
|
||||
inkscape:collect="always" />
|
||||
<filter
|
||||
style="color-interpolation-filters:sRGB"
|
||||
inkscape:collect="always"
|
||||
id="filter3997-7-6">
|
||||
<feGaussianBlur
|
||||
inkscape:collect="always"
|
||||
stdDeviation="0.62142855"
|
||||
id="feGaussianBlur3999-1-6" />
|
||||
</filter>
|
||||
</defs>
|
||||
<sodipodi:namedview
|
||||
id="base"
|
||||
@ -1533,6 +1584,46 @@
|
||||
d="m 589.99999,195.93361 c 0,11.44018 -9.2741,20.71428 -20.71428,20.71428 -11.44019,0 -20.71429,-9.2741 -20.71429,-20.71428 0,-11.44018 9.2741,-20.71429 20.71429,-20.71429 11.44018,0 20.71428,9.27411 20.71428,20.71429 z"
|
||||
transform="translate(0.08444218,-2.2540576e-8)" />
|
||||
</g>
|
||||
<g
|
||||
style="display:inline"
|
||||
id="satellite-galileo"
|
||||
transform="matrix(0.93879118,0,0,0.93879118,55.180064,91.285495)"
|
||||
inkscape:label="#g3722">
|
||||
<circle
|
||||
r="20.714285"
|
||||
cy="195.93361"
|
||||
cx="569.28571"
|
||||
transform="translate(0.08444214,2.2540576e-8)"
|
||||
id="path3712-3"
|
||||
style="fill:url(#linearGradient3859-7-2);fill-opacity:1;stroke:#8d029a;stroke-width:1.56471384;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1" />
|
||||
<circle
|
||||
r="20.714285"
|
||||
cy="195.93361"
|
||||
cx="569.28571"
|
||||
style="fill:url(#radialGradient4859-3);fill-opacity:1;stroke:none;filter:url(#filter3997-7-6)"
|
||||
id="path3833-3"
|
||||
transform="translate(0.08444218,2.2540576e-8)" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:label="#g3722"
|
||||
transform="matrix(0.93879118,0,0,0.93879118,123.18007,91.285495)"
|
||||
id="sat-galileo-notSeen"
|
||||
style="display:inline;opacity:0.4">
|
||||
<circle
|
||||
r="20.714285"
|
||||
cy="195.93361"
|
||||
cx="569.28571"
|
||||
style="fill:#ce00e0;fill-opacity:1;stroke:#8d029a;stroke-width:1.56471384;stroke-miterlimit:4;stroke-dasharray:none;stroke-opacity:1"
|
||||
id="path3891-0"
|
||||
transform="translate(0.08444214,2.2540576e-8)" />
|
||||
<circle
|
||||
r="20.714285"
|
||||
cy="195.93361"
|
||||
cx="569.28571"
|
||||
transform="translate(0.08444218,2.2540576e-8)"
|
||||
id="path3897-8"
|
||||
style="fill:url(#radialGradient3907-5-5);fill-opacity:1;stroke:none" />
|
||||
</g>
|
||||
</g>
|
||||
</g>
|
||||
</svg>
|
||||
|
Before Width: | Height: | Size: 85 KiB After Width: | Height: | Size: 88 KiB |
@ -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…
Reference in New Issue
Block a user