diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 382aca4f55422ad2692dd802386b2b595aa08b0d..c80a217786fad03222a8ac46edc850d074331402 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -812,6 +812,7 @@ HEADERS+= \
src/FirmwarePlugin/FirmwarePlugin.h \
src/FirmwarePlugin/FirmwarePluginManager.h \
src/Vehicle/MultiVehicleManager.h \
+ src/Vehicle/GPSRTKFactGroup.h \
src/Vehicle/Vehicle.h \
src/VehicleSetup/VehicleComponent.h \
@@ -836,6 +837,7 @@ SOURCES += \
src/FirmwarePlugin/FirmwarePlugin.cc \
src/FirmwarePlugin/FirmwarePluginManager.cc \
src/Vehicle/MultiVehicleManager.cc \
+ src/Vehicle/GPSRTKFactGroup.cc \
src/Vehicle/Vehicle.cc \
src/VehicleSetup/VehicleComponent.cc \
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 312d45503aaf934410bae786ae1dc5949128bba2..9b10333c4ee06631a2d9b2c88446688e80402c69 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -6,6 +6,7 @@
src/ui/toolbar/ArmedIndicator.qml
src/ui/toolbar/BatteryIndicator.qml
src/ui/toolbar/GPSIndicator.qml
+ src/ui/toolbar/GPSRTKIndicator.qml
src/ui/toolbar/MessageIndicator.qml
src/ui/toolbar/ModeIndicator.qml
src/ui/toolbar/RCRSSIIndicator.qml
@@ -209,6 +210,7 @@
src/Vehicle/VehicleFact.json
src/Vehicle/BatteryFact.json
src/Vehicle/GPSFact.json
+ src/Vehicle/GPSRTKFact.json
src/Vehicle/WindFact.json
src/Vehicle/VibrationFact.json
src/Vehicle/TemperatureFact.json
diff --git a/src/GPS/GPSManager.cc b/src/GPS/GPSManager.cc
index 0d1a28fb2e3ba00d53d65a6661af29c35bf31b5f..bf155c9bc813024809de89b0522a8c56fab9f558 100644
--- a/src/GPS/GPSManager.cc
+++ b/src/GPS/GPSManager.cc
@@ -43,7 +43,10 @@ void GPSManager::connectGPS(const QString& device)
//test: connect to position update
connect(_gpsProvider, &GPSProvider::positionUpdate, this, &GPSManager::GPSPositionUpdate);
connect(_gpsProvider, &GPSProvider::satelliteInfoUpdate, this, &GPSManager::GPSSatelliteUpdate);
+ connect(_gpsProvider, &GPSProvider::finished, this, &GPSManager::onDisconnect);
+ connect(_gpsProvider, &GPSProvider::surveyInStatus, this, &GPSManager::surveyInStatus);
+ emit onConnect();
}
void GPSManager::GPSPositionUpdate(GPSPositionMessage msg)
@@ -53,6 +56,7 @@ void GPSManager::GPSPositionUpdate(GPSPositionMessage msg)
void GPSManager::GPSSatelliteUpdate(GPSSatelliteMessage msg)
{
qCDebug(RTKGPSLog) << QString("GPS: got satellite info update, %1 satellites").arg((int)msg.satellite_data.count);
+ emit satelliteUpdate(msg.satellite_data.count);
}
void GPSManager::cleanup()
diff --git a/src/GPS/GPSManager.h b/src/GPS/GPSManager.h
index d28bbaa117c8c856c329f244bd5b67b89e315de8..87936730cd02aee0bbb8e19cd6ed262a5bb02813 100644
--- a/src/GPS/GPSManager.h
+++ b/src/GPS/GPSManager.h
@@ -31,6 +31,12 @@ public:
void connectGPS(const QString& device);
bool connected(void) const { return _gpsProvider && _gpsProvider->isRunning(); }
+signals:
+ void onConnect();
+ void onDisconnect();
+ void surveyInStatus(float duration, float accuracyMM, bool valid, bool active);
+ void satelliteUpdate(int numSats);
+
private slots:
void GPSPositionUpdate(GPSPositionMessage msg);
void GPSSatelliteUpdate(GPSSatelliteMessage msg);
diff --git a/src/GPS/GPSProvider.cc b/src/GPS/GPSProvider.cc
index ec9d9289ceb673e5ff4d6ff7279d9001e07996f6..8e77aa0b774d37a4b859837c765452b4052c3d97 100644
--- a/src/GPS/GPSProvider.cc
+++ b/src/GPS/GPSProvider.cc
@@ -172,7 +172,7 @@ int GPSProvider::callback(GPSCallbackType type, void *data1, int data2)
{
SurveyInStatus* status = (SurveyInStatus*)data1;
qCDebug(RTKGPSLog) << QString("Survey-in status: %1s cur accuracy: %2mm valid: %3 active: %4").arg(status->duration).arg(status->mean_accuracy).arg((int)(status->flags & 1)).arg((int)((status->flags>>1) & 1));
- emit rtkStatus(status->duration, status->mean_accuracy, (int)(status->flags & 1), (int)((status->flags>>1) & 1));
+ emit surveyInStatus(status->duration, status->mean_accuracy, (int)(status->flags & 1), (int)((status->flags>>1) & 1));
}
break;
diff --git a/src/GPS/GPSProvider.h b/src/GPS/GPSProvider.h
index 6029b38006ca92f642cb874d2eff56c6f3c6feaf..c2b5c7e12cf4e1b2d80c07b33dd405093aecf31f 100644
--- a/src/GPS/GPSProvider.h
+++ b/src/GPS/GPSProvider.h
@@ -40,7 +40,7 @@ signals:
void positionUpdate(GPSPositionMessage message);
void satelliteInfoUpdate(GPSSatelliteMessage message);
void RTCMDataUpdate(QByteArray message);
- void rtkStatus(float duration, float accuracyMM, bool valid, bool active);
+ void surveyInStatus(float duration, float accuracyMM, bool valid, bool active);
protected:
void run();
diff --git a/src/QmlControls/QGroundControlQmlGlobal.cc b/src/QmlControls/QGroundControlQmlGlobal.cc
index 4b8daac79a805367ba189f10d02cc7033a69acf9..24f9d53777a9e861703438dd90f7b5cbe7e1ad05 100644
--- a/src/QmlControls/QGroundControlQmlGlobal.cc
+++ b/src/QmlControls/QGroundControlQmlGlobal.cc
@@ -62,6 +62,14 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
_corePlugin = toolbox->corePlugin();
_firmwarePluginManager = toolbox->firmwarePluginManager();
_settingsManager = toolbox->settingsManager();
+
+ GPSManager *gpsManager = toolbox->gpsManager();
+ if (gpsManager) {
+ connect(gpsManager, &GPSManager::onConnect, this, &QGroundControlQmlGlobal::_onGPSConnect);
+ connect(gpsManager, &GPSManager::onDisconnect, this, &QGroundControlQmlGlobal::_onGPSDisconnect);
+ connect(gpsManager, &GPSManager::surveyInStatus, this, &QGroundControlQmlGlobal::_GPSSurveyInStatus);
+ connect(gpsManager, &GPSManager::satelliteUpdate, this, &QGroundControlQmlGlobal::_GPSNumSatellites);
+ }
}
void QGroundControlQmlGlobal::saveGlobalSetting (const QString& key, const QString& value)
@@ -230,3 +238,24 @@ void QGroundControlQmlGlobal::setFlightMapZoom(double zoom)
emit flightMapZoomChanged(zoom);
}
}
+
+void QGroundControlQmlGlobal::_onGPSConnect()
+{
+ _gpsRtkFactGroup.connected()->setRawValue(true);
+}
+void QGroundControlQmlGlobal::_onGPSDisconnect()
+{
+ _gpsRtkFactGroup.connected()->setRawValue(false);
+}
+void QGroundControlQmlGlobal::_GPSSurveyInStatus(float duration, float accuracyMM, bool valid, bool active)
+{
+ _gpsRtkFactGroup.currentDuration()->setRawValue(duration);
+ _gpsRtkFactGroup.currentAccuracy()->setRawValue(accuracyMM);
+ _gpsRtkFactGroup.valid()->setRawValue(valid);
+ _gpsRtkFactGroup.active()->setRawValue(active);
+}
+void QGroundControlQmlGlobal::_GPSNumSatellites(int numSatellites)
+{
+ _gpsRtkFactGroup.numSatellites()->setRawValue(numSatellites);
+}
+
diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h
index b51c2f040c98c0c2554d68a89cba0259bcac2e51..1f57ff9f438eb4807ae70120cf762565925308a7 100644
--- a/src/QmlControls/QGroundControlQmlGlobal.h
+++ b/src/QmlControls/QGroundControlQmlGlobal.h
@@ -22,6 +22,8 @@
#include "SimulatedPosition.h"
#include "QGCLoggingCategory.h"
#include "AppSettings.h"
+#include "GPS/GPSManager.h"
+#include "GPSRTKFactGroup.h"
#ifdef QT_DEBUG
#include "MockLink.h"
@@ -48,6 +50,7 @@ public:
Q_PROPERTY(MAVLinkLogManager* mavlinkLogManager READ mavlinkLogManager CONSTANT)
Q_PROPERTY(QGCCorePlugin* corePlugin READ corePlugin CONSTANT)
Q_PROPERTY(SettingsManager* settingsManager READ settingsManager CONSTANT)
+ Q_PROPERTY(FactGroup* gpsRtk READ gpsRtkFactGroup CONSTANT)
Q_PROPERTY(int supportedFirmwareCount READ supportedFirmwareCount CONSTANT)
@@ -136,6 +139,7 @@ public:
MAVLinkLogManager* mavlinkLogManager () { return _mavlinkLogManager; }
QGCCorePlugin* corePlugin () { return _corePlugin; }
SettingsManager* settingsManager () { return _settingsManager; }
+ FactGroup* gpsRtkFactGroup () { return &_gpsRtkFactGroup; }
static QGeoCoordinate flightMapPosition ();
static double flightMapZoom ();
@@ -177,6 +181,12 @@ signals:
void flightMapZoomChanged (double flightMapZoom);
void skipSetupPageChanged ();
+private slots:
+ void _onGPSConnect();
+ void _onGPSDisconnect();
+ void _GPSSurveyInStatus(float duration, float accuracyMM, bool valid, bool active);
+ void _GPSNumSatellites(int numSatellites);
+
private:
double _flightMapInitialZoom;
LinkManager* _linkManager;
@@ -189,6 +199,7 @@ private:
QGCCorePlugin* _corePlugin;
FirmwarePluginManager* _firmwarePluginManager;
SettingsManager* _settingsManager;
+ GPSRTKFactGroup _gpsRtkFactGroup;
bool _skipSetupPage;
diff --git a/src/Vehicle/GPSRTKFact.json b/src/Vehicle/GPSRTKFact.json
new file mode 100644
index 0000000000000000000000000000000000000000..306781373dc8a74789a64e9932943cedfd50df3b
--- /dev/null
+++ b/src/Vehicle/GPSRTKFact.json
@@ -0,0 +1,36 @@
+[
+{
+ "name": "connected",
+ "shortDescription": "Connected",
+ "type": "bool"
+},
+{
+ "name": "currentAccuracy",
+ "shortDescription": "Current Accuracy",
+ "type": "double",
+ "decimalPlaces": 0,
+ "units": "mm"
+},
+{
+ "name": "currentDuration",
+ "shortDescription": "Current Duration",
+ "type": "double",
+ "decimalPlaces": 0,
+ "units": "s"
+},
+{
+ "name": "valid",
+ "shortDescription": "Survey-in Valid",
+ "type": "bool"
+},
+{
+ "name": "active",
+ "shortDescription": "Survey-in Active",
+ "type": "bool"
+},
+{
+ "name": "numSatellites",
+ "shortDescription": "Number of Satellites",
+ "type": "int32"
+}
+]
diff --git a/src/Vehicle/GPSRTKFactGroup.cc b/src/Vehicle/GPSRTKFactGroup.cc
new file mode 100644
index 0000000000000000000000000000000000000000..3a85cc64b8755b45189f6e7d7e85a2c50d1a5898
--- /dev/null
+++ b/src/Vehicle/GPSRTKFactGroup.cc
@@ -0,0 +1,35 @@
+/****************************************************************************
+ *
+ * (c) 2017 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "GPSRTKFactGroup.h"
+
+const char* GPSRTKFactGroup::_connectedFactName = "connected";
+const char* GPSRTKFactGroup::_currentAccuracyFactName = "currentAccuracy";
+const char* GPSRTKFactGroup::_currentDurationFactName = "currentDuration";
+const char* GPSRTKFactGroup::_validFactName = "valid";
+const char* GPSRTKFactGroup::_activeFactName = "active";
+const char* GPSRTKFactGroup::_numSatellitesFactName = "numSatellites";
+
+GPSRTKFactGroup::GPSRTKFactGroup(QObject* parent)
+ : FactGroup(1000, ":/json/Vehicle/GPSRTKFact.json", parent)
+ , _connected (false, _connectedFactName, FactMetaData::valueTypeBool)
+ , _currentDuration (0, _currentDurationFactName, FactMetaData::valueTypeDouble)
+ , _currentAccuracy (0, _currentAccuracyFactName, FactMetaData::valueTypeDouble)
+ , _valid (false, _validFactName, FactMetaData::valueTypeBool)
+ , _active (false, _activeFactName, FactMetaData::valueTypeBool)
+ , _numSatellites (false, _numSatellitesFactName, FactMetaData::valueTypeInt32)
+{
+ _addFact(&_connected, _connectedFactName);
+ _addFact(&_currentDuration, _currentDurationFactName);
+ _addFact(&_currentAccuracy, _currentAccuracyFactName);
+ _addFact(&_valid, _validFactName);
+ _addFact(&_active, _activeFactName);
+ _addFact(&_numSatellites, _numSatellitesFactName);
+}
+
diff --git a/src/Vehicle/GPSRTKFactGroup.h b/src/Vehicle/GPSRTKFactGroup.h
new file mode 100644
index 0000000000000000000000000000000000000000..251ed3d4ed72b1c228b7198cbbdc9fb60750dbd7
--- /dev/null
+++ b/src/Vehicle/GPSRTKFactGroup.h
@@ -0,0 +1,50 @@
+/****************************************************************************
+ *
+ * (c) 2017 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+
+#pragma once
+
+#include "Vehicle.h"
+
+class GPSRTKFactGroup : public FactGroup
+{
+ Q_OBJECT
+
+public:
+ GPSRTKFactGroup(QObject* parent = NULL);
+
+ Q_PROPERTY(Fact* connected READ connected CONSTANT)
+ Q_PROPERTY(Fact* currentDuration READ currentDuration CONSTANT)
+ Q_PROPERTY(Fact* currentAccuracy READ currentAccuracy CONSTANT)
+ Q_PROPERTY(Fact* valid READ valid CONSTANT)
+ Q_PROPERTY(Fact* active READ active CONSTANT)
+ Q_PROPERTY(Fact* numSatellites READ numSatellites CONSTANT)
+
+ Fact* connected (void) { return &_connected; }
+ Fact* currentDuration (void) { return &_currentDuration; }
+ Fact* currentAccuracy (void) { return &_currentAccuracy; }
+ Fact* valid (void) { return &_valid; }
+ Fact* active (void) { return &_active; }
+ Fact* numSatellites (void) { return &_numSatellites; }
+
+ static const char* _connectedFactName;
+ static const char* _currentDurationFactName;
+ static const char* _currentAccuracyFactName;
+ static const char* _validFactName;
+ static const char* _activeFactName;
+ static const char* _numSatellitesFactName;
+
+private:
+ Fact _connected; ///< is an RTK gps connected?
+ Fact _currentDuration; ///< survey-in status in [s]
+ Fact _currentAccuracy; ///< survey-in accuracy in [mm]
+ Fact _valid; ///< survey-in valid?
+ Fact _active; ///< survey-in active?
+ Fact _numSatellites; ///< number of satellites
+};
diff --git a/src/ui/toolbar/GPSRTKIndicator.qml b/src/ui/toolbar/GPSRTKIndicator.qml
index 709a32884a06488e89c39737444f55a201515e83..1a74ddbf9ca15a0d3cbbc829854cee52553c603f 100644
--- a/src/ui/toolbar/GPSRTKIndicator.qml
+++ b/src/ui/toolbar/GPSRTKIndicator.qml
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ * (c) 2017 QGROUNDCONTROL PROJECT
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
@@ -14,7 +14,6 @@ import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.Controls 1.0
-import QGroundControl.MultiVehicleManager 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
@@ -45,7 +44,7 @@ Item {
QGCLabel {
id: gpsLabel
- text: (activeVehicle && activeVehicle.gps.count.value >= 0) ? qsTr("GPS Status") : qsTr("GPS Data Unavailable")
+ text: (QGroundControl.gpsRtk.active.value) ? qsTr("Survey-in Active") : qsTr("RTK Active")
font.family: ScreenTools.demiboldFontFamily
anchors.horizontalCenter: parent.horizontalCenter
}
@@ -58,16 +57,14 @@ Item {
anchors.horizontalCenter: parent.horizontalCenter
columns: 2
- QGCLabel { text: qsTr("GPS Count:") }
- QGCLabel { text: activeVehicle ? activeVehicle.gps.count.valueString : qsTr("N/A", "No data to display") }
- QGCLabel { text: qsTr("GPS Lock:") }
- QGCLabel { text: activeVehicle ? activeVehicle.gps.lock.enumStringValue : qsTr("N/A", "No data to display") }
- QGCLabel { text: qsTr("HDOP:") }
- QGCLabel { text: activeVehicle ? activeVehicle.gps.hdop.valueString : qsTr("--.--", "No data to display") }
- QGCLabel { text: qsTr("VDOP:") }
- QGCLabel { text: activeVehicle ? activeVehicle.gps.vdop.valueString : qsTr("--.--", "No data to display") }
- QGCLabel { text: qsTr("Course Over Ground:") }
- QGCLabel { text: activeVehicle ? activeVehicle.gps.courseOverGround.valueString : qsTr("--.--", "No data to display") }
+ QGCLabel { text: qsTr("GPS connected:") }
+ QGCLabel { text: QGroundControl.gpsRtk.connected.value }
+ QGCLabel { text: qsTr("Survey-in Duration:") }
+ QGCLabel { text: QGroundControl.gpsRtk.currentDuration.value }
+ QGCLabel { text: qsTr("Survey-in Accuracy:") }
+ QGCLabel { text: QGroundControl.gpsRtk.currentAccuracy.value }
+ QGCLabel { text: qsTr("Number of Satellites:") }
+ QGCLabel { text: QGroundControl.gpsRtk.numSatellites.value }
}
}