Commit e3c97d2e authored by Beat Küng's avatar Beat Küng

toolbar: show RTK survey-in status

parent 5211a7a9
...@@ -812,6 +812,7 @@ HEADERS+= \ ...@@ -812,6 +812,7 @@ HEADERS+= \
src/FirmwarePlugin/FirmwarePlugin.h \ src/FirmwarePlugin/FirmwarePlugin.h \
src/FirmwarePlugin/FirmwarePluginManager.h \ src/FirmwarePlugin/FirmwarePluginManager.h \
src/Vehicle/MultiVehicleManager.h \ src/Vehicle/MultiVehicleManager.h \
src/Vehicle/GPSRTKFactGroup.h \
src/Vehicle/Vehicle.h \ src/Vehicle/Vehicle.h \
src/VehicleSetup/VehicleComponent.h \ src/VehicleSetup/VehicleComponent.h \
...@@ -836,6 +837,7 @@ SOURCES += \ ...@@ -836,6 +837,7 @@ SOURCES += \
src/FirmwarePlugin/FirmwarePlugin.cc \ src/FirmwarePlugin/FirmwarePlugin.cc \
src/FirmwarePlugin/FirmwarePluginManager.cc \ src/FirmwarePlugin/FirmwarePluginManager.cc \
src/Vehicle/MultiVehicleManager.cc \ src/Vehicle/MultiVehicleManager.cc \
src/Vehicle/GPSRTKFactGroup.cc \
src/Vehicle/Vehicle.cc \ src/Vehicle/Vehicle.cc \
src/VehicleSetup/VehicleComponent.cc \ src/VehicleSetup/VehicleComponent.cc \
......
...@@ -6,6 +6,7 @@ ...@@ -6,6 +6,7 @@
<file alias="ArmedIndicator.qml">src/ui/toolbar/ArmedIndicator.qml</file> <file alias="ArmedIndicator.qml">src/ui/toolbar/ArmedIndicator.qml</file>
<file alias="BatteryIndicator.qml">src/ui/toolbar/BatteryIndicator.qml</file> <file alias="BatteryIndicator.qml">src/ui/toolbar/BatteryIndicator.qml</file>
<file alias="GPSIndicator.qml">src/ui/toolbar/GPSIndicator.qml</file> <file alias="GPSIndicator.qml">src/ui/toolbar/GPSIndicator.qml</file>
<file alias="GPSRTKIndicator.qml">src/ui/toolbar/GPSRTKIndicator.qml</file>
<file alias="MessageIndicator.qml">src/ui/toolbar/MessageIndicator.qml</file> <file alias="MessageIndicator.qml">src/ui/toolbar/MessageIndicator.qml</file>
<file alias="ModeIndicator.qml">src/ui/toolbar/ModeIndicator.qml</file> <file alias="ModeIndicator.qml">src/ui/toolbar/ModeIndicator.qml</file>
<file alias="RCRSSIIndicator.qml">src/ui/toolbar/RCRSSIIndicator.qml</file> <file alias="RCRSSIIndicator.qml">src/ui/toolbar/RCRSSIIndicator.qml</file>
...@@ -209,6 +210,7 @@ ...@@ -209,6 +210,7 @@
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file> <file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file>
<file alias="Vehicle/BatteryFact.json">src/Vehicle/BatteryFact.json</file> <file alias="Vehicle/BatteryFact.json">src/Vehicle/BatteryFact.json</file>
<file alias="Vehicle/GPSFact.json">src/Vehicle/GPSFact.json</file> <file alias="Vehicle/GPSFact.json">src/Vehicle/GPSFact.json</file>
<file alias="Vehicle/GPSRTKFact.json">src/Vehicle/GPSRTKFact.json</file>
<file alias="Vehicle/WindFact.json">src/Vehicle/WindFact.json</file> <file alias="Vehicle/WindFact.json">src/Vehicle/WindFact.json</file>
<file alias="Vehicle/VibrationFact.json">src/Vehicle/VibrationFact.json</file> <file alias="Vehicle/VibrationFact.json">src/Vehicle/VibrationFact.json</file>
<file alias="Vehicle/TemperatureFact.json">src/Vehicle/TemperatureFact.json</file> <file alias="Vehicle/TemperatureFact.json">src/Vehicle/TemperatureFact.json</file>
......
...@@ -43,7 +43,10 @@ void GPSManager::connectGPS(const QString& device) ...@@ -43,7 +43,10 @@ void GPSManager::connectGPS(const QString& device)
//test: connect to position update //test: connect to position update
connect(_gpsProvider, &GPSProvider::positionUpdate, this, &GPSManager::GPSPositionUpdate); connect(_gpsProvider, &GPSProvider::positionUpdate, this, &GPSManager::GPSPositionUpdate);
connect(_gpsProvider, &GPSProvider::satelliteInfoUpdate, this, &GPSManager::GPSSatelliteUpdate); 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) void GPSManager::GPSPositionUpdate(GPSPositionMessage msg)
...@@ -53,6 +56,7 @@ void GPSManager::GPSPositionUpdate(GPSPositionMessage msg) ...@@ -53,6 +56,7 @@ void GPSManager::GPSPositionUpdate(GPSPositionMessage msg)
void GPSManager::GPSSatelliteUpdate(GPSSatelliteMessage msg) void GPSManager::GPSSatelliteUpdate(GPSSatelliteMessage msg)
{ {
qCDebug(RTKGPSLog) << QString("GPS: got satellite info update, %1 satellites").arg((int)msg.satellite_data.count); 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() void GPSManager::cleanup()
......
...@@ -31,6 +31,12 @@ public: ...@@ -31,6 +31,12 @@ public:
void connectGPS(const QString& device); void connectGPS(const QString& device);
bool connected(void) const { return _gpsProvider && _gpsProvider->isRunning(); } 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: private slots:
void GPSPositionUpdate(GPSPositionMessage msg); void GPSPositionUpdate(GPSPositionMessage msg);
void GPSSatelliteUpdate(GPSSatelliteMessage msg); void GPSSatelliteUpdate(GPSSatelliteMessage msg);
......
...@@ -172,7 +172,7 @@ int GPSProvider::callback(GPSCallbackType type, void *data1, int data2) ...@@ -172,7 +172,7 @@ int GPSProvider::callback(GPSCallbackType type, void *data1, int data2)
{ {
SurveyInStatus* status = (SurveyInStatus*)data1; 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)); 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; break;
......
...@@ -40,7 +40,7 @@ signals: ...@@ -40,7 +40,7 @@ signals:
void positionUpdate(GPSPositionMessage message); void positionUpdate(GPSPositionMessage message);
void satelliteInfoUpdate(GPSSatelliteMessage message); void satelliteInfoUpdate(GPSSatelliteMessage message);
void RTCMDataUpdate(QByteArray 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: protected:
void run(); void run();
......
...@@ -62,6 +62,14 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox) ...@@ -62,6 +62,14 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
_corePlugin = toolbox->corePlugin(); _corePlugin = toolbox->corePlugin();
_firmwarePluginManager = toolbox->firmwarePluginManager(); _firmwarePluginManager = toolbox->firmwarePluginManager();
_settingsManager = toolbox->settingsManager(); _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) void QGroundControlQmlGlobal::saveGlobalSetting (const QString& key, const QString& value)
...@@ -230,3 +238,24 @@ void QGroundControlQmlGlobal::setFlightMapZoom(double zoom) ...@@ -230,3 +238,24 @@ void QGroundControlQmlGlobal::setFlightMapZoom(double zoom)
emit flightMapZoomChanged(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);
}
...@@ -22,6 +22,8 @@ ...@@ -22,6 +22,8 @@
#include "SimulatedPosition.h" #include "SimulatedPosition.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "AppSettings.h" #include "AppSettings.h"
#include "GPS/GPSManager.h"
#include "GPSRTKFactGroup.h"
#ifdef QT_DEBUG #ifdef QT_DEBUG
#include "MockLink.h" #include "MockLink.h"
...@@ -48,6 +50,7 @@ public: ...@@ -48,6 +50,7 @@ public:
Q_PROPERTY(MAVLinkLogManager* mavlinkLogManager READ mavlinkLogManager CONSTANT) Q_PROPERTY(MAVLinkLogManager* mavlinkLogManager READ mavlinkLogManager CONSTANT)
Q_PROPERTY(QGCCorePlugin* corePlugin READ corePlugin CONSTANT) Q_PROPERTY(QGCCorePlugin* corePlugin READ corePlugin CONSTANT)
Q_PROPERTY(SettingsManager* settingsManager READ settingsManager CONSTANT) Q_PROPERTY(SettingsManager* settingsManager READ settingsManager CONSTANT)
Q_PROPERTY(FactGroup* gpsRtk READ gpsRtkFactGroup CONSTANT)
Q_PROPERTY(int supportedFirmwareCount READ supportedFirmwareCount CONSTANT) Q_PROPERTY(int supportedFirmwareCount READ supportedFirmwareCount CONSTANT)
...@@ -136,6 +139,7 @@ public: ...@@ -136,6 +139,7 @@ public:
MAVLinkLogManager* mavlinkLogManager () { return _mavlinkLogManager; } MAVLinkLogManager* mavlinkLogManager () { return _mavlinkLogManager; }
QGCCorePlugin* corePlugin () { return _corePlugin; } QGCCorePlugin* corePlugin () { return _corePlugin; }
SettingsManager* settingsManager () { return _settingsManager; } SettingsManager* settingsManager () { return _settingsManager; }
FactGroup* gpsRtkFactGroup () { return &_gpsRtkFactGroup; }
static QGeoCoordinate flightMapPosition (); static QGeoCoordinate flightMapPosition ();
static double flightMapZoom (); static double flightMapZoom ();
...@@ -177,6 +181,12 @@ signals: ...@@ -177,6 +181,12 @@ signals:
void flightMapZoomChanged (double flightMapZoom); void flightMapZoomChanged (double flightMapZoom);
void skipSetupPageChanged (); void skipSetupPageChanged ();
private slots:
void _onGPSConnect();
void _onGPSDisconnect();
void _GPSSurveyInStatus(float duration, float accuracyMM, bool valid, bool active);
void _GPSNumSatellites(int numSatellites);
private: private:
double _flightMapInitialZoom; double _flightMapInitialZoom;
LinkManager* _linkManager; LinkManager* _linkManager;
...@@ -189,6 +199,7 @@ private: ...@@ -189,6 +199,7 @@ private:
QGCCorePlugin* _corePlugin; QGCCorePlugin* _corePlugin;
FirmwarePluginManager* _firmwarePluginManager; FirmwarePluginManager* _firmwarePluginManager;
SettingsManager* _settingsManager; SettingsManager* _settingsManager;
GPSRTKFactGroup _gpsRtkFactGroup;
bool _skipSetupPage; bool _skipSetupPage;
......
[
{
"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"
}
]
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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);
}
/****************************************************************************
*
* (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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
};
/**************************************************************************** /****************************************************************************
* *
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> * (c) 2017 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
* *
* QGroundControl is licensed according to the terms in the file * QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory. * COPYING.md in the root of the source code directory.
...@@ -14,7 +14,6 @@ import QtQuick.Layouts 1.2 ...@@ -14,7 +14,6 @@ import QtQuick.Layouts 1.2
import QGroundControl 1.0 import QGroundControl 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import QGroundControl.MultiVehicleManager 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
...@@ -45,7 +44,7 @@ Item { ...@@ -45,7 +44,7 @@ Item {
QGCLabel { QGCLabel {
id: gpsLabel 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 font.family: ScreenTools.demiboldFontFamily
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
} }
...@@ -58,16 +57,14 @@ Item { ...@@ -58,16 +57,14 @@ Item {
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
columns: 2 columns: 2
QGCLabel { text: qsTr("GPS Count:") } QGCLabel { text: qsTr("GPS connected:") }
QGCLabel { text: activeVehicle ? activeVehicle.gps.count.valueString : qsTr("N/A", "No data to display") } QGCLabel { text: QGroundControl.gpsRtk.connected.value }
QGCLabel { text: qsTr("GPS Lock:") } QGCLabel { text: qsTr("Survey-in Duration:") }
QGCLabel { text: activeVehicle ? activeVehicle.gps.lock.enumStringValue : qsTr("N/A", "No data to display") } QGCLabel { text: QGroundControl.gpsRtk.currentDuration.value }
QGCLabel { text: qsTr("HDOP:") } QGCLabel { text: qsTr("Survey-in Accuracy:") }
QGCLabel { text: activeVehicle ? activeVehicle.gps.hdop.valueString : qsTr("--.--", "No data to display") } QGCLabel { text: QGroundControl.gpsRtk.currentAccuracy.value }
QGCLabel { text: qsTr("VDOP:") } QGCLabel { text: qsTr("Number of Satellites:") }
QGCLabel { text: activeVehicle ? activeVehicle.gps.vdop.valueString : qsTr("--.--", "No data to display") } QGCLabel { text: QGroundControl.gpsRtk.numSatellites.value }
QGCLabel { text: qsTr("Course Over Ground:") }
QGCLabel { text: activeVehicle ? activeVehicle.gps.courseOverGround.valueString : qsTr("--.--", "No data to display") }
} }
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment