Commit 098a0204 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #5296 from mavlink/rtk_status

[WIP] First stab at GPS RTK indicator
parents 83537695 46c8ae23
......@@ -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 \
......
......@@ -6,6 +6,7 @@
<file alias="ArmedIndicator.qml">src/ui/toolbar/ArmedIndicator.qml</file>
<file alias="BatteryIndicator.qml">src/ui/toolbar/BatteryIndicator.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="ModeIndicator.qml">src/ui/toolbar/ModeIndicator.qml</file>
<file alias="RCRSSIIndicator.qml">src/ui/toolbar/RCRSSIIndicator.qml</file>
......@@ -210,6 +211,7 @@
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.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/GPSRTKFact.json">src/Vehicle/GPSRTKFact.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/TemperatureFact.json">src/Vehicle/TemperatureFact.json</file>
......
......@@ -334,6 +334,7 @@ const QVariantList &FirmwarePlugin::toolBarIndicators(const Vehicle* vehicle)
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/BatteryIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ModeIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ArmedIndicator.qml")));
_toolBarIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPSRTKIndicator.qml")));
}
return _toolBarIndicatorList;
}
......
......@@ -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()
......
......@@ -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);
......
......@@ -172,6 +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 surveyInStatus(status->duration, status->mean_accuracy, (int)(status->flags & 1), (int)((status->flags>>1) & 1));
}
break;
......
......@@ -40,6 +40,7 @@ signals:
void positionUpdate(GPSPositionMessage message);
void satelliteInfoUpdate(GPSSatelliteMessage message);
void RTCMDataUpdate(QByteArray message);
void surveyInStatus(float duration, float accuracyMM, bool valid, bool active);
protected:
void run();
......
......@@ -62,6 +62,16 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
_corePlugin = toolbox->corePlugin();
_firmwarePluginManager = toolbox->firmwarePluginManager();
_settingsManager = toolbox->settingsManager();
#ifndef __mobile__
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);
}
#endif /* __mobile__ */
}
void QGroundControlQmlGlobal::saveGlobalSetting (const QString& key, const QString& value)
......@@ -230,3 +240,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);
}
......@@ -22,6 +22,10 @@
#include "SimulatedPosition.h"
#include "QGCLoggingCategory.h"
#include "AppSettings.h"
#ifndef __mobile__
#include "GPS/GPSManager.h"
#endif /* __mobile__ */
#include "GPSRTKFactGroup.h"
#ifdef QT_DEBUG
#include "MockLink.h"
......@@ -48,6 +52,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 +141,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 +183,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 +201,7 @@ private:
QGCCorePlugin* _corePlugin;
FirmwarePluginManager* _firmwarePluginManager;
SettingsManager* _settingsManager;
GPSRTKFactGroup _gpsRtkFactGroup;
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) 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.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
//-------------------------------------------------------------------------
//-- GPS Indicator
Item {
id: satelitte
width: (gpsValuesColumn.x + gpsValuesColumn.width) * 1.1
anchors.top: parent.top
anchors.bottom: parent.bottom
visible: QGroundControl.gpsRtk.connected.value
Component {
id: gpsInfo
Rectangle {
width: gpsCol.width + ScreenTools.defaultFontPixelWidth * 3
height: gpsCol.height + ScreenTools.defaultFontPixelHeight * 2
radius: ScreenTools.defaultFontPixelHeight * 0.5
color: qgcPal.window
border.color: qgcPal.text
Column {
id: gpsCol
spacing: ScreenTools.defaultFontPixelHeight * 0.5
width: Math.max(gpsGrid.width, gpsLabel.width)
anchors.margins: ScreenTools.defaultFontPixelHeight
anchors.centerIn: parent
QGCLabel {
id: gpsLabel
text: (QGroundControl.gpsRtk.active.value) ? qsTr("Survey-in Active") : qsTr("RTK Streaming")
font.family: ScreenTools.demiboldFontFamily
anchors.horizontalCenter: parent.horizontalCenter
}
GridLayout {
id: gpsGrid
visible: true
anchors.margins: ScreenTools.defaultFontPixelHeight
columnSpacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
columns: 2
QGCLabel {
text: qsTr("Duration:")
visible: QGroundControl.gpsRtk.active.value
}
QGCLabel {
text: QGroundControl.gpsRtk.currentDuration.value + ' s'
visible: QGroundControl.gpsRtk.active.value
}
QGCLabel {
// during survey-in show the current accuracy, after that show the final accuracy
text: QGroundControl.gpsRtk.valid.value ? qsTr("Accuracy:") : qsTr("Current Accuracy:")
}
QGCLabel {
text: (QGroundControl.gpsRtk.currentAccuracy.value/1000).toFixed(1) + ' m'
}
QGCLabel { text: qsTr("Satellites:") }
QGCLabel { text: QGroundControl.gpsRtk.numSatellites.value }
}
}
Component.onCompleted: {
var pos = mapFromItem(toolBar, centerX - (width / 2), toolBar.height)
x = pos.x
y = pos.y + ScreenTools.defaultFontPixelHeight
}
}
}
QGCColoredImage {
id: gpsIcon
width: height
anchors.top: parent.top
anchors.bottom: parent.bottom
source: "/qmlimages/Gps.svg"
fillMode: Image.PreserveAspectFit
sourceSize.height: height
opacity: 1
color: QGroundControl.gpsRtk.active.value ? qgcPal.colorRed : qgcPal.buttonText
}
Column {
id: gpsValuesColumn
anchors.verticalCenter: parent.verticalCenter
anchors.leftMargin: ScreenTools.defaultFontPixelWidth / 2
anchors.left: gpsIcon.right
QGCLabel {
anchors.horizontalCenter: numSatValue.horizontalCenter
color: qgcPal.buttonText
text: QGroundControl.gpsRtk.numSatellites.value
}
QGCLabel {
id: numSatValue
color: qgcPal.buttonText
text: qsTr("RTK")
}
}
MouseArea {
anchors.fill: parent
onClicked: {
var centerX = mapToItem(toolBar, x, y).x + (width / 2)
mainWindow.showPopUp(gpsInfo, centerX)
}
}
}
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