diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 9b97c417be21c473c82514d9ae093afafb3154cf..9010834163ed2f9492d7c0140e3e7697d3f9d577 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -673,6 +673,7 @@ INCLUDEPATH += \
HEADERS += \
src/FactSystem/Fact.h \
+ src/FactSystem/FactGroup.h \
src/FactSystem/FactControls/FactPanelController.h \
src/FactSystem/FactMetaData.h \
src/FactSystem/FactSystem.h \
@@ -682,6 +683,7 @@ HEADERS += \
SOURCES += \
src/FactSystem/Fact.cc \
+ src/FactSystem/FactGroup.cc \
src/FactSystem/FactControls/FactPanelController.cc \
src/FactSystem/FactMetaData.cc \
src/FactSystem/FactSystem.cc \
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index e9247708a569974497d6ace58a1d5e0896c36b93..021575ad7792fe6cc4be272e592a89673b86caf9 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -148,5 +148,8 @@
src/FirmwarePlugin/PX4/MavCmdInfoCommon.json
src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json
src/FirmwarePlugin/PX4/MavCmdInfoMultiRotor.json
+ src/Vehicle/VehicleFact.json
+ src/Vehicle/BatteryFact.json
+ src/Vehicle/GPSFact.json
diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc
index 645904a153b42e2dc0c9aa746e72c1894ed01bb1..bda502d4e7afabf17077fd0871e393818172b0cb 100644
--- a/src/FactSystem/Fact.cc
+++ b/src/FactSystem/Fact.cc
@@ -35,6 +35,8 @@ Fact::Fact(QObject* parent)
, _rawValue(0)
, _type(FactMetaData::valueTypeInt32)
, _metaData(NULL)
+ , _sendValueChangedSignals(true)
+ , _deferredValueChangeSignal(false)
{
FactMetaData* metaData = new FactMetaData(_type, this);
setMetaData(metaData);
@@ -47,6 +49,8 @@ Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObjec
, _rawValue(0)
, _type(type)
, _metaData(NULL)
+ , _sendValueChangedSignals(true)
+ , _deferredValueChangeSignal(false)
{
FactMetaData* metaData = new FactMetaData(_type, this);
setMetaData(metaData);
@@ -60,11 +64,13 @@ Fact::Fact(const Fact& other, QObject* parent)
const Fact& Fact::operator=(const Fact& other)
{
- _name = other._name;
- _componentId = other._componentId;
- _rawValue = other._rawValue;
- _type = other._type;
-
+ _name = other._name;
+ _componentId = other._componentId;
+ _rawValue = other._rawValue;
+ _type = other._type;
+ _sendValueChangedSignals = other._sendValueChangedSignals;
+ _deferredValueChangeSignal = other._deferredValueChangeSignal;
+
if (_metaData && other._metaData) {
*_metaData = *other._metaData;
} else {
@@ -82,7 +88,7 @@ void Fact::forceSetRawValue(const QVariant& value)
if (_metaData->convertAndValidateRaw(value, true /* convertOnly */, typedValue, errorString)) {
_rawValue.setValue(typedValue);
- emit valueChanged(cookedValue());
+ _sendValueChangedSignal(cookedValue());
emit _containerRawValueChanged(rawValue());
}
} else {
@@ -99,7 +105,7 @@ void Fact::setRawValue(const QVariant& value)
if (_metaData->convertAndValidateRaw(value, true /* convertOnly */, typedValue, errorString)) {
if (typedValue != _rawValue) {
_rawValue.setValue(typedValue);
- emit valueChanged(cookedValue());
+ _sendValueChangedSignal(cookedValue());
emit _containerRawValueChanged(rawValue());
}
}
@@ -141,7 +147,7 @@ void Fact::setEnumIndex(int index)
void Fact::_containerSetRawValue(const QVariant& value)
{
_rawValue = value;
- emit valueChanged(cookedValue());
+ _sendValueChangedSignal(cookedValue());
emit vehicleUpdated(_rawValue);
}
@@ -492,3 +498,29 @@ bool Fact::rebootRequired(void) const
return false;
}
}
+
+void Fact::setSendValueChangedSignals (bool sendValueChangedSignals)
+{
+ if (sendValueChangedSignals != _sendValueChangedSignals) {
+ _sendValueChangedSignals = sendValueChangedSignals;
+ emit sendValueChangedSignalsChanged(_sendValueChangedSignals);
+ }
+}
+
+void Fact::_sendValueChangedSignal(QVariant value)
+{
+ if (_sendValueChangedSignals) {
+ emit valueChanged(value);
+ _deferredValueChangeSignal = false;
+ } else {
+ _deferredValueChangeSignal = true;
+ }
+}
+
+void Fact::sendDeferredValueChangedSignal(void)
+{
+ if (_deferredValueChangeSignal) {
+ _deferredValueChangeSignal = false;
+ emit valueChanged(cookedValue());
+ }
+}
diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h
index 8e3eaa5190f9af1384d1218e40ddc4aaf765f02b..93a6330a33facebf0fafe5a5681ef5ea5fee6c74 100644
--- a/src/FactSystem/Fact.h
+++ b/src/FactSystem/Fact.h
@@ -117,6 +117,15 @@ public:
void setEnumIndex (int index);
void setEnumStringValue (const QString& value);
+ // The following methods allow you to defer sending of the valueChanged signals in order to implement
+ // rate limited signalling for ui performance. Used by FactGroup for example.
+
+ void setSendValueChangedSignals (bool sendValueChangedSignals);
+ bool sendValueChangedSignals (void) const { return _sendValueChangedSignals; }
+ bool deferredValueChangeSignal(void) const { return _deferredValueChangeSignal; }
+ void clearDeferredValueChangeSignal(void) { _deferredValueChangeSignal = false; }
+ void sendDeferredValueChangedSignal(void);
+
// C++ methods
/// Sets and sends new value to vehicle even if value is the same
@@ -129,12 +138,14 @@ public:
/// Generally you should not change the name of a fact. But if you know what you are doing, you can.
void _setName(const QString& name) { _name = name; }
+
signals:
void bitmaskStringsChanged(void);
void bitmaskValuesChanged(void);
void enumStringsChanged(void);
void enumValuesChanged(void);
+ void sendValueChangedSignalsChanged(bool sendValueChangedSignals);
/// QObject Property System signal for value property changes
///
@@ -151,12 +162,15 @@ signals:
protected:
QString _variantToString(const QVariant& variant) const;
+ void _sendValueChangedSignal(QVariant value);
QString _name;
int _componentId;
QVariant _rawValue;
FactMetaData::ValueType_t _type;
FactMetaData* _metaData;
+ bool _sendValueChangedSignals;
+ bool _deferredValueChangeSignal;
};
#endif
diff --git a/src/FactSystem/FactGroup.cc b/src/FactSystem/FactGroup.cc
new file mode 100644
index 0000000000000000000000000000000000000000..9407a0f9877fc5c2f5c6182450864805fa239c54
--- /dev/null
+++ b/src/FactSystem/FactGroup.cc
@@ -0,0 +1,217 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+#include "FactGroup.h"
+#include "JsonHelper.h"
+
+#include
+#include
+#include
+#include
+#include
+
+QGC_LOGGING_CATEGORY(FactGroupLog, "FactGroupLog")
+
+const char* FactGroup::_decimalPlacesJsonKey = "decimalPlaces";
+const char* FactGroup::_nameJsonKey = "name";
+const char* FactGroup::_propertiesJsonKey = "properties";
+const char* FactGroup::_versionJsonKey = "version";
+const char* FactGroup::_typeJsonKey = "type";
+const char* FactGroup::_shortDescriptionJsonKey = "shortDescription";
+const char* FactGroup::_unitsJsonKey = "units";
+
+FactGroup::FactGroup(int updateRateMsecs, const QString& metaDataFile, QObject* parent)
+ : QObject(parent)
+ , _updateRateMSecs(updateRateMsecs)
+{
+ if (_updateRateMSecs > 0) {
+ connect(&_updateTimer, &QTimer::timeout, this, &FactGroup::_updateAllValues);
+ _updateTimer.setSingleShot(false);
+ _updateTimer.start(_updateRateMSecs);
+ }
+
+ _loadMetaData(metaDataFile);
+}
+
+Fact* FactGroup::getFact(const QString& name)
+{
+ if (_nameToFactMap.contains(name)) {
+ return _nameToFactMap[name];
+ } else {
+ qWarning() << "Unknown Fact" << name;
+ }
+
+ return NULL;
+}
+
+FactGroup* FactGroup::getFactGroup(const QString& name)
+{
+ if (_nameToFactGroupMap.contains(name)) {
+ return _nameToFactGroupMap[name];
+ } else {
+ qWarning() << "Unknown FactGroup" << name;
+ }
+
+ // FIXME: Return bogus fact
+ return NULL;
+}
+
+void FactGroup::_addFact(Fact* fact, const QString& name)
+{
+ if (_nameToFactMap.contains(name)) {
+ qWarning() << "Duplicate Fact" << name;
+ return;
+ }
+
+ fact->setSendValueChangedSignals(_updateRateMSecs == 0);
+ if (_nameToFactMetaDataMap.contains(name)) {
+ fact->setMetaData(_nameToFactMetaDataMap[name]);
+ }
+ _nameToFactMap[name] = fact;
+}
+
+void FactGroup::_addFactGroup(FactGroup* factGroup, const QString& name)
+{
+ if (_nameToFactGroupMap.contains(name)) {
+ qWarning() << "Duplicate FactGroup" << name;
+ return;
+ }
+
+ _nameToFactGroupMap[name] = factGroup;
+}
+
+void FactGroup::_updateAllValues(void)
+{
+ foreach(Fact* fact, _nameToFactMap) {
+ fact->sendDeferredValueChangedSignal();
+ }
+}
+
+void FactGroup::_loadMetaData(const QString& jsonFilename)
+{
+ if (jsonFilename.isEmpty()) {
+ return;
+ }
+
+ qCDebug(FactGroupLog) << "Loading" << jsonFilename;
+
+ QFile jsonFile(jsonFilename);
+ if (!jsonFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
+ qWarning() << "Unable to open file" << jsonFilename << jsonFile.errorString();
+ return;
+ }
+
+ QByteArray bytes = jsonFile.readAll();
+ jsonFile.close();
+ QJsonParseError jsonParseError;
+ QJsonDocument doc = QJsonDocument::fromJson(bytes, &jsonParseError);
+ if (jsonParseError.error != QJsonParseError::NoError) {
+ qWarning() << "Unable to open json document" << jsonFilename << jsonParseError.errorString();
+ return;
+ }
+
+ QJsonObject json = doc.object();
+
+ int version = json.value(_versionJsonKey).toInt();
+ if (version != 1) {
+ qWarning() << "Invalid version" << version;
+ return;
+ }
+
+ QJsonValue jsonValue = json.value(_propertiesJsonKey);
+ if (!jsonValue.isArray()) {
+ qWarning() << "properties object not array";
+ return;
+ }
+
+ QJsonArray jsonArray = jsonValue.toArray();
+ foreach(QJsonValue property, jsonArray) {
+ if (!property.isObject()) {
+ qWarning() << "properties object should contain only objects";
+ return;
+ }
+ QJsonObject jsonObject = property.toObject();
+
+ // Make sure we have the required keys
+ QString errorString;
+ QStringList requiredKeys;
+ requiredKeys << _nameJsonKey << _decimalPlacesJsonKey << _typeJsonKey << _shortDescriptionJsonKey;
+ if (!JsonHelper::validateRequiredKeys(jsonObject, requiredKeys, errorString)) {
+ qWarning() << errorString;
+ return;
+ }
+
+ // Validate key types
+
+ QStringList keys;
+ QList types;
+ keys << _nameJsonKey << _decimalPlacesJsonKey;
+ types << QJsonValue::String << QJsonValue::Double;
+ if (!JsonHelper::validateKeyTypes(jsonObject, keys, types, errorString)) {
+ qWarning() << errorString;
+ return;
+ }
+
+ QString name = jsonObject.value(_nameJsonKey).toString();
+ if (_nameToFactMetaDataMap.contains(name)) {
+ qWarning() << "Duplicate property name" << name;
+ continue;
+ }
+
+ bool unknownType;
+ FactMetaData::ValueType_t type = FactMetaData::stringToType(jsonObject.value(_typeJsonKey).toString(), unknownType);
+ if (unknownType) {
+ qWarning() << "Unknown type" << jsonObject.value(_typeJsonKey).toString();
+ return;
+ }
+
+ QStringList enumValues, enumStrings;
+ if (!JsonHelper::parseEnum(jsonObject, enumStrings, enumValues, errorString)) {
+ qWarning() << errorString;
+ return;
+ }
+
+ FactMetaData* metaData = new FactMetaData(type, this);
+
+ metaData->setDecimalPlaces(jsonObject.value(_decimalPlacesJsonKey).toInt());
+ metaData->setShortDescription(jsonObject.value(_shortDescriptionJsonKey).toString());
+ metaData->setRawUnits(jsonObject.value(_unitsJsonKey).toString());
+
+ for (int i=0; iconvertAndValidateRaw(enumValues[i], false /* validate */, enumVariant, errorString)) {
+ metaData->addEnumInfo(enumStrings[i], enumVariant);
+ } else {
+ qWarning() << "Invalid enum value, name:" << metaData->name()
+ << " type:" << metaData->type() << " value:" << enumValues[i]
+ << " error:" << errorString;
+ delete metaData;
+ return;
+ }
+ }
+
+ _nameToFactMetaDataMap[name] = metaData;
+ }
+}
diff --git a/src/FactSystem/FactGroup.h b/src/FactSystem/FactGroup.h
new file mode 100644
index 0000000000000000000000000000000000000000..5135d9e5c3a1a4ff49508abca2340c45f7e00e34
--- /dev/null
+++ b/src/FactSystem/FactGroup.h
@@ -0,0 +1,83 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+#ifndef FactGroup_H
+#define FactGroup_H
+
+#include "Fact.h"
+#include "QGCLoggingCategory.h"
+
+#include
+#include
+#include
+
+Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
+
+/// Used to group Facts together into an object hierarachy.
+class FactGroup : public QObject
+{
+ Q_OBJECT
+
+public:
+ FactGroup(int updateRateMsecs, const QString& metaDataFile, QObject* parent = NULL);
+
+ Q_PROPERTY(QStringList factNames READ factNames CONSTANT)
+ Q_PROPERTY(QStringList factGroupNames READ factGroupNames CONSTANT)
+
+ /// @return Fact for specified name, NULL if not found
+ Q_INVOKABLE Fact* getFact(const QString& name);
+
+ /// @return FactGroup for specified name, NULL if not found
+ Q_INVOKABLE FactGroup* getFactGroup(const QString& name);
+
+ QStringList factNames(void) const { return _nameToFactMap.keys(); }
+ QStringList factGroupNames(void) const { return _nameToFactGroupMap.keys(); }
+
+protected:
+ void _addFact(Fact* fact, const QString& name);
+ void _addFactGroup(FactGroup* factGroup, const QString& name);
+
+ int _updateRateMSecs; ///< Update rate for Fact::valueChanged signals, 0: immediate update
+
+private slots:
+ void _updateAllValues(void);
+
+private:
+ void _loadMetaData(const QString& filename);
+
+ QMap _nameToFactMap;
+ QMap _nameToFactGroupMap;
+ QMap _nameToFactMetaDataMap;
+
+ QTimer _updateTimer;
+
+ static const char* _propertiesJsonKey;
+ static const char* _nameJsonKey;
+ static const char* _decimalPlacesJsonKey;
+ static const char* _typeJsonKey;
+ static const char* _versionJsonKey;
+ static const char* _shortDescriptionJsonKey;
+ static const char* _unitsJsonKey;
+};
+
+#endif
diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc
index 18ab974b1bc5ed45df3eac93f18ab04397806947..dc79a8fb7dd74172080e8e320cc7b8977946361d 100644
--- a/src/FactSystem/FactMetaData.cc
+++ b/src/FactSystem/FactMetaData.cc
@@ -398,3 +398,39 @@ void FactMetaData::setRawUnits(const QString& rawUnits)
_setBuiltInTranslator();
}
+
+FactMetaData::ValueType_t FactMetaData::stringToType(const QString& typeString, bool& unknownType)
+{
+ QStringList knownTypeStrings;
+ QList knownTypes;
+
+ unknownType = false;
+
+ knownTypeStrings << QStringLiteral("Uint8")
+ << QStringLiteral("Int8")
+ << QStringLiteral("Uint16")
+ << QStringLiteral("Int16")
+ << QStringLiteral("Uint32")
+ << QStringLiteral("Int32")
+ << QStringLiteral("Float")
+ << QStringLiteral("Double");
+
+ knownTypes << valueTypeUint8
+ << valueTypeInt8
+ << valueTypeUint16
+ << valueTypeInt16
+ << valueTypeUint32
+ << valueTypeInt32
+ << valueTypeFloat
+ << valueTypeDouble;
+
+ for (int i=0; i
#include "FactSystem.h"
+#include "FactGroup.h"
#include "FactPanelController.h"
#include
@@ -41,6 +42,7 @@ void FactSystem::setToolbox(QGCToolbox *toolbox)
{
QGCTool::setToolbox(toolbox);
- qmlRegisterType(_factSystemQmlUri, 1, 0, "Fact");
+ qmlRegisterType (_factSystemQmlUri, 1, 0, "Fact");
+ qmlRegisterType (_factSystemQmlUri, 1, 0, "FactGroup");
qmlRegisterType(_factSystemQmlUri, 1, 0, "FactPanelController");
}
diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml
index 36f29eb2ecb3cde7a07a75349aaa742fd5c90ac0..6c0d84569399aa8edd3432fdaf49ef74b03755f4 100644
--- a/src/FlightDisplay/FlightDisplayView.qml
+++ b/src/FlightDisplay/FlightDisplayView.qml
@@ -36,6 +36,7 @@ import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Controllers 1.0
+import QGroundControl.FactSystem 1.0
/// Flight Display View
Item {
@@ -55,7 +56,6 @@ Item {
readonly property real _defaultAltitudeWGS84: 0
readonly property real _defaultGroundSpeed: 0
readonly property real _defaultAirSpeed: 0
- readonly property real _defaultClimbRate: 0
readonly property string _mapName: "FlightDisplayView"
readonly property string _showMapBackgroundKey: "/showMapBackground"
@@ -65,14 +65,15 @@ Item {
property bool _mainIsMap: QGroundControl.loadBoolGlobalSetting(_mainIsMapKey, true)
property bool _isPipVisible: QGroundControl.loadBoolGlobalSetting(_PIPVisibleKey, true)
- property real _roll: _activeVehicle ? (isNaN(_activeVehicle.roll) ? _defaultRoll : _activeVehicle.roll) : _defaultRoll
- property real _pitch: _activeVehicle ? (isNaN(_activeVehicle.pitch) ? _defaultPitch : _activeVehicle.pitch) : _defaultPitch
- property real _heading: _activeVehicle ? (isNaN(_activeVehicle.heading) ? _defaultHeading : _activeVehicle.heading) : _defaultHeading
+ property real _roll: _activeVehicle ? _activeVehicle.roll.value : _defaultRoll
+ property real _pitch: _activeVehicle ? _activeVehicle.pitch.value : _defaultPitch
+ property real _heading: _activeVehicle ? _activeVehicle.heading.value : _defaultHeading
- property real _altitudeWGS84: _activeVehicle ? _activeVehicle.altitudeWGS84 : _defaultAltitudeWGS84
- property real _groundSpeed: _activeVehicle ? _activeVehicle.groundSpeed : _defaultGroundSpeed
- property real _airSpeed: _activeVehicle ? _activeVehicle.airSpeed : _defaultAirSpeed
- property real _climbRate: _activeVehicle ? _activeVehicle.climbRate : _defaultClimbRate
+
+ property Fact _emptyFact: Fact { }
+ property Fact _groundSpeedFact: _activeVehicle ? _activeVehicle.groundSpeed : _emptyFact
+ property Fact _airSpeedFact: _activeVehicle ? _activeVehicle.airSpeed : _emptyFact
+ property Fact _altitudeWGS84Fact: _activeVehicle ? _activeVehicle.altitudeWGS84 : _emptyFact
property bool activeVehicleJoystickEnabled: _activeVehicle ? _activeVehicle.joystickEnabled : false
diff --git a/src/FlightDisplay/FlightDisplayViewWidgets.qml b/src/FlightDisplay/FlightDisplayViewWidgets.qml
index 3bef36c6e3c030226459ec8bb0b00029529c3acd..0a2d0171d6ddb218348a41cc8094c47d23a301cf 100644
--- a/src/FlightDisplay/FlightDisplayViewWidgets.qml
+++ b/src/FlightDisplay/FlightDisplayViewWidgets.qml
@@ -39,7 +39,8 @@ Item {
readonly property string _InstrumentVisibleKey: "IsInstrumentPanelVisible"
- property bool _isInstrumentVisible: QGroundControl.loadBoolGlobalSetting(_InstrumentVisibleKey, true)
+ property bool _isInstrumentVisible: QGroundControl.loadBoolGlobalSetting(_InstrumentVisibleKey, true)
+ property var _activeVehicle: multiVehicleManager.activeVehicle
QGCMapPalette { id: mapPal; lightColors: !isBackgroundDark }
@@ -101,9 +102,9 @@ Item {
heading: _heading
rollAngle: _roll
pitchAngle: _pitch
- altitude: _altitudeWGS84
- groundSpeed: _groundSpeed
- airSpeed: _airSpeed
+ altitudeFact: _altitudeWGS84Fact
+ groundSpeedFact: _groundSpeedFact
+ airSpeedFact: _airSpeedFact
isSatellite: _mainIsMap ? _flightMap ? _flightMap.isSatelliteMap : true : true
z: QGroundControl.zOrderWidgets
onClicked: {
@@ -127,7 +128,7 @@ Item {
spacing: ScreenTools.defaultFontPixelSize * 0.33
anchors.verticalCenter: parent.verticalCenter
QGCLabel {
- text: "Altitude (m)"
+ text: _altitudeWGS84Fact.shortDescription + "(" + _altitudeWGS84Fact.units + ")"
font.pixelSize: ScreenTools.defaultFontPixelSize * 0.75
width: parent.width
height: ScreenTools.defaultFontPixelSize * 0.75
@@ -135,7 +136,7 @@ Item {
horizontalAlignment: TextEdit.AlignHCenter
}
QGCLabel {
- text: _altitudeWGS84 < 10000 ? _altitudeWGS84.toFixed(1) : _altitudeWGS84.toFixed(0)
+ text: _altitudeWGS84Fact.valueString
font.pixelSize: ScreenTools.defaultFontPixelSize * 1.5
font.weight: Font.DemiBold
width: parent.width
@@ -143,7 +144,7 @@ Item {
horizontalAlignment: TextEdit.AlignHCenter
}
QGCLabel {
- text: "Ground Speed (km/h)"
+ text: _groundSpeedFact.shortDescription + "(" + _groundSpeedFact.units + ")"
font.pixelSize: ScreenTools.defaultFontPixelSize * 0.75
width: parent.width
height: ScreenTools.defaultFontPixelSize * 0.75
@@ -151,7 +152,7 @@ Item {
horizontalAlignment: TextEdit.AlignHCenter
}
QGCLabel {
- text: (_groundSpeed * 3.6).toFixed(1)
+ text: _groundSpeedFact.valueString
font.pixelSize: ScreenTools.defaultFontPixelSize
font.weight: Font.DemiBold
width: parent.width
diff --git a/src/FlightMap/MapItems/VehicleMapItem.qml b/src/FlightMap/MapItems/VehicleMapItem.qml
index d00f03531f9aaaeed53d84959365420d801c70f9..b29559707f801168b3a2eaaa20ea2d73120921a2 100644
--- a/src/FlightMap/MapItems/VehicleMapItem.qml
+++ b/src/FlightMap/MapItems/VehicleMapItem.qml
@@ -51,7 +51,7 @@ MapQuickItem {
transform: Rotation {
origin.x: vehicleIcon.width / 2
origin.y: vehicleIcon.height / 2
- angle: vehicle ? vehicle.heading : 0
+ angle: vehicle ? vehicle.heading.value : 0
}
}
}
diff --git a/src/FlightMap/Widgets/QGCInstrumentWidget.qml b/src/FlightMap/Widgets/QGCInstrumentWidget.qml
index d2575e6884ae501cf5dc37210bb083c27a90a6a4..636a743257dfcc0972717a24b3421b5ad34b43bb 100644
--- a/src/FlightMap/Widgets/QGCInstrumentWidget.qml
+++ b/src/FlightMap/Widgets/QGCInstrumentWidget.qml
@@ -29,8 +29,9 @@ This file is part of the QGROUNDCONTROL project
import QtQuick 2.4
-import QGroundControl.Controls 1.0
-import QGroundControl.ScreenTools 1.0
+import QGroundControl.Controls 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.FactSystem 1.0
Item {
id: root
@@ -41,13 +42,15 @@ Item {
property alias heading: compass.heading
property alias rollAngle: attitude.rollAngle
property alias pitchAngle: attitude.pitchAngle
- property real altitude: 0
- property real groundSpeed: 0
- property real airSpeed: 0
property real size: _defaultSize
property bool isSatellite: false
property bool active: false
+ property Fact _emptyFact: Fact { }
+ property Fact groundSpeedFact: _emptyFact
+ property Fact airSpeedFact: _emptyFact
+ property Fact altitudeFact: _emptyFact
+
property real _defaultSize: ScreenTools.defaultFontPixelSize * (9)
property real _sizeRatio: ScreenTools.isTinyScreen ? (size / _defaultSize) * 0.5 : size / _defaultSize
@@ -84,7 +87,7 @@ Item {
anchors.horizontalCenter: parent.horizontalCenter
}
QGCLabel {
- text: "Altitude (m)"
+ text: altitudeFact.shortDescription + " (" + altitudeFact.units + ")"
font.pixelSize: _labelFontSize
width: parent.width
height: _labelFontSize
@@ -92,7 +95,7 @@ Item {
horizontalAlignment: TextEdit.AlignHCenter
}
QGCLabel {
- text: altitude < 10000 ? altitude.toFixed(1) : altitude.toFixed(0)
+ text: altitudeFact.valueString
font.pixelSize: _bigFontSize
font.weight: Font.DemiBold
width: parent.width
@@ -105,25 +108,25 @@ Item {
width: parent.width * 0.9
color: isSatellite ? Qt.rgba(0,0,0,0.25) : Qt.rgba(1,1,1,0.25)
anchors.horizontalCenter: parent.horizontalCenter
- visible: airSpeed <= 0 && !ScreenTools.isTinyScreen
+ visible: airSpeedFact.value <= 0 && !ScreenTools.isTinyScreen
}
QGCLabel {
- text: "Ground Speed (km/h)"
+ text: groundSpeedFact.shortDescription + " (" + groundSpeedFact.units + ")"
font.pixelSize: _labelFontSize
width: parent.width
height: _labelFontSize
color: isSatellite ? "black" : "white"
horizontalAlignment: TextEdit.AlignHCenter
- visible: airSpeed <= 0 && !ScreenTools.isTinyScreen
+ visible: airSpeedFact.value <= 0 && !ScreenTools.isTinyScreen
}
QGCLabel {
- text: (groundSpeed * 3.6).toFixed(1)
+ text: groundSpeedFact.valueString
font.pixelSize: _normalFontSize
font.weight: Font.DemiBold
width: parent.width
color: isSatellite ? "black" : "white"
horizontalAlignment: TextEdit.AlignHCenter
- visible: airSpeed <= 0 && !ScreenTools.isTinyScreen
+ visible: airSpeedFact.value <= 0 && !ScreenTools.isTinyScreen
}
//-- Air Speed
Rectangle {
@@ -131,24 +134,24 @@ Item {
width: parent.width * 0.9
color: isSatellite ? Qt.rgba(0,0,0,0.25) : Qt.rgba(1,1,1,0.25)
anchors.horizontalCenter: parent.horizontalCenter
- visible: airSpeed > 0 && !ScreenTools.isTinyScreen
+ visible: airSpeedFact.value > 0 && !ScreenTools.isTinyScreen
}
QGCLabel {
- text: "Air Speed (km/h)"
+ text: airSpeedFact.shortDescription + " (" + airSpeedFact.units + ")"
font.pixelSize: _labelFontSize
width: parent.width
height: _labelFontSize
color: isSatellite ? "black" : "white"
- visible: airSpeed > 0 && !ScreenTools.isTinyScreen
+ visible: airSpeedFact.value > 0 && !ScreenTools.isTinyScreen
horizontalAlignment: TextEdit.AlignHCenter
}
QGCLabel {
- text: (airSpeed * 3.6).toFixed(1)
+ text: airSpeedFact.valueString
font.pixelSize: _normalFontSize
font.weight: Font.DemiBold
width: parent.width
color: isSatellite ? "black" : "white"
- visible: airSpeed > 0 && !ScreenTools.isTinyScreen
+ visible: airSpeedFact.value > 0 && !ScreenTools.isTinyScreen
horizontalAlignment: TextEdit.AlignHCenter
}
//-- Compass
diff --git a/src/JsonHelper.cc b/src/JsonHelper.cc
index 2d927cc12e8acdbc9f72c20e9ba9b912bce16305..a22846b64bc451c898a353321dfcf1476fae405d 100644
--- a/src/JsonHelper.cc
+++ b/src/JsonHelper.cc
@@ -24,6 +24,9 @@ This file is part of the QGROUNDCONTROL project
#include
+const char* JsonHelper::_enumStringsJsonKey = "enumStrings";
+const char* JsonHelper::_enumValuesJsonKey = "enumValues";
+
bool JsonHelper::validateRequiredKeys(const QJsonObject& jsonObject, const QStringList& keys, QString& errorString)
{
QString missingKeys;
@@ -71,3 +74,30 @@ bool JsonHelper::toQGeoCoordinate(const QJsonValue& jsonValue, QGeoCoordinate& c
return true;
}
+
+bool JsonHelper::validateKeyTypes(QJsonObject& jsonObject, const QStringList& keys, const QList& types, QString& errorString)
+{
+ for (int i=0; i& types, QString& errorString);
static bool toQGeoCoordinate(const QJsonValue& jsonValue, QGeoCoordinate& coordinate, bool altitudeRequired, QString& errorString);
+ static bool parseEnum(QJsonObject& jsonObject, QStringList& enumStrings, QStringList& enumValues, QString& errorString);
+
+ static const char* _enumStringsJsonKey;
+ static const char* _enumValuesJsonKey;
};
#endif
diff --git a/src/Vehicle/BatteryFact.json b/src/Vehicle/BatteryFact.json
new file mode 100644
index 0000000000000000000000000000000000000000..c739c5f0e20d8fc6a8eac405ae2991a8d0eb81d6
--- /dev/null
+++ b/src/Vehicle/BatteryFact.json
@@ -0,0 +1,69 @@
+{
+ "version": 1,
+
+ "properties": [
+ {
+ "name": "roll",
+ "shortDescription": "Roll",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "degrees"
+ },
+ {
+ "name": "pitch",
+ "shortDescription": "Pitch",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "degrees"
+ },
+ {
+ "name": "heading",
+ "shortDescription": "Heading",
+ "type": "double",
+ "decimalPlaces": 0,
+ "units": "degrees"
+ },
+ {
+ "name": "groundSpeed",
+ "shortDescription": "Ground Speed",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "m/s"
+ },
+ {
+ "name": "airSpeed",
+ "shortDescription": "Air Speed",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "m/s"
+ },
+ {
+ "name": "climbRate",
+ "shortDescription": "Climb Rate",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "m/s"
+ },
+ {
+ "name": "altitudeRelative",
+ "shortDescription": "Altitude",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "m"
+ },
+ {
+ "name": "altitudeQGS84",
+ "shortDescription": "Altitude",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "m"
+ },
+ {
+ "name": "altitudeAMSL",
+ "shortDescription": "Altitude",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "m"
+ }
+ ]
+}
diff --git a/src/Vehicle/GPSFact.json b/src/Vehicle/GPSFact.json
new file mode 100644
index 0000000000000000000000000000000000000000..73046fb2f4ac3db04b6bc4d065b41e41d87e6229
--- /dev/null
+++ b/src/Vehicle/GPSFact.json
@@ -0,0 +1,39 @@
+{
+ "version": 1,
+
+ "properties": [
+ {
+ "name": "hdop",
+ "shortDescription": "HDOP",
+ "type": "double",
+ "decimalPlaces": 1
+ },
+ {
+ "name": "vdop",
+ "shortDescription": "VDOP",
+ "type": "double",
+ "decimalPlaces": 1
+ },
+ {
+ "name": "courseOverGround",
+ "shortDescription": "Course Over Ground",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "degrees"
+ },
+ {
+ "name": "lock",
+ "shortDescription": "GPS Lock",
+ "type": "uint32",
+ "enumStrings": "None,None,2D Lock,3D Lock,3D DGPS Lock,3D RTK GPS Lock",
+ "enumValues": "0,1,2,3,4,5",
+ "decimalPlaces": 0
+ },
+ {
+ "name": "count",
+ "shortDescription": "Sat Count",
+ "type": "double",
+ "decimalPlaces": 0
+ }
+ ]
+}
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index f8a4a2a57dd47b6790a5b7cef62a763b43101b63..37b49b6e7dafdc65991c02fd6a012c20f2a3afc6 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -46,6 +46,23 @@ const char* Vehicle::_settingsGroup = "Vehicle%1"; // %1 re
const char* Vehicle::_joystickModeSettingsKey = "JoystickMode";
const char* Vehicle::_joystickEnabledSettingsKey = "JoystickEnabled";
+const char* Vehicle::_rollFactName = "roll";
+const char* Vehicle::_pitchFactName = "pitch";
+const char* Vehicle::_headingFactName = "heading";
+const char* Vehicle::_airSpeedFactName = "airSpeed";
+const char* Vehicle::_groundSpeedFactName = "groundSpeed";
+const char* Vehicle::_climbRateFactName = "climbRate";
+const char* Vehicle::_altitudeRelativeFactName = "altitudeRelative";
+const char* Vehicle::_altitudeWGS84FactName = "altitudeWGS84";
+const char* Vehicle::_altitudeAMSLFactName = "altitudeAMSL";
+const char* Vehicle::_gpsFactGroupName = "gps";
+
+const char* VehicleGPSFactGroup::_hdopFactName = "hdop";
+const char* VehicleGPSFactGroup::_vdopFactName = "vdop";
+const char* VehicleGPSFactGroup::_courseOverGroundFactName = "courseOverGround";
+const char* VehicleGPSFactGroup::_countFactName = "count";
+const char* VehicleGPSFactGroup::_lockFactName = "lock";
+
Vehicle::Vehicle(LinkInterface* link,
int vehicleId,
MAV_AUTOPILOT firmwareType,
@@ -53,7 +70,8 @@ Vehicle::Vehicle(LinkInterface* link,
FirmwarePluginManager* firmwarePluginManager,
AutoPilotPluginManager* autopilotPluginManager,
JoystickManager* joystickManager)
- : _id(vehicleId)
+ : FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json")
+ , _id(vehicleId)
, _active(false)
, _firmwareType(firmwareType)
, _vehicleType(vehicleType)
@@ -72,15 +90,6 @@ Vehicle::Vehicle(LinkInterface* link,
, _currentWarningCount(0)
, _currentNormalCount(0)
, _currentMessageType(MessageNone)
- , _roll(0.0f)
- , _pitch(0.0f)
- , _heading(0.0f)
- , _altitudeAMSL(0.0f)
- , _altitudeWGS84(0.0f)
- , _altitudeRelative(0.0f)
- , _groundSpeed(0.0f)
- , _airSpeed(0.0f)
- , _climbRate(0.0f)
, _navigationAltitudeError(0.0f)
, _navigationSpeedError(0.0f)
, _navigationCrosstrackError(0.0f)
@@ -89,11 +98,6 @@ Vehicle::Vehicle(LinkInterface* link,
, _batteryVoltage(-1.0f)
, _batteryPercent(0.0)
, _batteryConsumed(-1.0)
- , _satelliteCount(-1)
- , _satRawHDOP(1e10f)
- , _satRawVDOP(1e10f)
- , _satRawCOG(0.0)
- , _satelliteLock(0)
, _updateCount(0)
, _rcRSSI(0)
, _rcRSSIstore(100.0)
@@ -118,6 +122,16 @@ Vehicle::Vehicle(LinkInterface* link,
, _messageSeq(0)
, _compID(0)
, _heardFrom(false)
+ , _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble)
+ , _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble)
+ , _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble)
+ , _groundSpeedFact (0, _groundSpeedFactName, FactMetaData::valueTypeDouble)
+ , _airSpeedFact (0, _airSpeedFactName, FactMetaData::valueTypeDouble)
+ , _climbRateFact (0, _climbRateFactName, FactMetaData::valueTypeDouble)
+ , _altitudeRelativeFact (0, _altitudeRelativeFactName, FactMetaData::valueTypeDouble)
+ , _altitudeWGS84Fact (0, _altitudeWGS84FactName, FactMetaData::valueTypeDouble)
+ , _altitudeAMSLFact (0, _altitudeAMSLFactName, FactMetaData::valueTypeDouble)
+ , _gpsFactGroup(this)
{
_addLink(link);
@@ -155,15 +169,6 @@ Vehicle::Vehicle(LinkInterface* link,
connect(&_connectionLostTimer, &QTimer::timeout, this, &Vehicle::_connectionLostTimeout);
_mav = uas();
- // Reset satellite data (no GPS)
- _satelliteCount = -1;
- _satRawHDOP = 1e10f;
- _satRawVDOP = 1e10f;
- _satRawCOG = 0.0;
- emit satRawHDOPChanged();
- emit satRawVDOPChanged();
- emit satRawCOGChanged();
- emit satelliteCountChanged();
// Listen for system messages
connect(qgcApp()->toolbox()->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged, this, &Vehicle::_handleTextMessage);
@@ -179,15 +184,6 @@ Vehicle::Vehicle(LinkInterface* link,
connect(_mav, &UASInterface::NavigationControllerDataChanged, this, &Vehicle::_updateNavigationControllerData);
connect(_mav, &UASInterface::batteryChanged, this, &Vehicle::_updateBatteryRemaining);
connect(_mav, &UASInterface::batteryConsumedChanged, this, &Vehicle::_updateBatteryConsumedChanged);
- connect(_mav, &UASInterface::localizationChanged, this, &Vehicle::_setSatLoc);
- UAS* pUas = dynamic_cast(_mav);
- if(pUas) {
- _setSatelliteCount(pUas->getSatelliteCount(), QString(""));
- connect(pUas, &UAS::satelliteCountChanged, this, &Vehicle::_setSatelliteCount);
- connect(pUas, &UAS::satRawHDOPChanged, this, &Vehicle::_setSatRawHDOP);
- connect(pUas, &UAS::satRawVDOPChanged, this, &Vehicle::_setSatRawVDOP);
- connect(pUas, &UAS::satRawCOGChanged, this, &Vehicle::_setSatRawCOG);
- }
_loadSettings();
@@ -205,6 +201,21 @@ Vehicle::Vehicle(LinkInterface* link,
_mapTrajectoryTimer.setInterval(_mapTrajectoryMsecsBetweenPoints);
connect(&_mapTrajectoryTimer, &QTimer::timeout, this, &Vehicle::_addNewMapTrajectoryPoint);
+
+ // Build FactGroup object model
+
+ _addFact(&_rollFact, _rollFactName);
+ _addFact(&_pitchFact, _pitchFactName);
+ _addFact(&_headingFact, _headingFactName);
+ _addFact(&_groundSpeedFact, _groundSpeedFactName);
+ _addFact(&_airSpeedFact, _airSpeedFactName);
+ _addFact(&_climbRateFact, _climbRateFactName);
+ _addFact(&_altitudeRelativeFact, _altitudeRelativeFactName);
+ _addFact(&_altitudeWGS84Fact, _altitudeWGS84FactName);
+ _addFact(&_altitudeAMSLFact, _altitudeAMSLFactName);
+
+ _addFactGroup(&_gpsFactGroup, _gpsFactGroupName);
+ _gpsFactGroup.setVehicle(this);
}
Vehicle::~Vehicle()
@@ -564,50 +575,21 @@ void Vehicle::setLongitude(double longitude){
void Vehicle::_updateAttitude(UASInterface*, double roll, double pitch, double yaw, quint64)
{
if (isinf(roll)) {
- _roll = std::numeric_limits::quiet_NaN();
+ _rollFact.setRawValue(0);
} else {
- float rolldeg = _oneDecimal(roll * (180.0 / M_PI));
- if (fabs(roll - rolldeg) > 0.25) {
- _roll = rolldeg;
- if(_refreshTimer->isActive()) {
- emit rollChanged();
- }
- }
- if(_roll != rolldeg) {
- _roll = rolldeg;
- _addChange(ROLL_CHANGED);
- }
+ _rollFact.setRawValue(roll * (180.0 / M_PI));
}
if (isinf(pitch)) {
- _pitch = std::numeric_limits::quiet_NaN();
+ _pitchFact.setRawValue(0);
} else {
- float pitchdeg = _oneDecimal(pitch * (180.0 / M_PI));
- if (fabs(pitch - pitchdeg) > 0.25) {
- _pitch = pitchdeg;
- if(_refreshTimer->isActive()) {
- emit pitchChanged();
- }
- }
- if(_pitch != pitchdeg) {
- _pitch = pitchdeg;
- _addChange(PITCH_CHANGED);
- }
+ _pitchFact.setRawValue(pitch * (180.0 / M_PI));
}
if (isinf(yaw)) {
- _heading = std::numeric_limits::quiet_NaN();
+ _headingFact.setRawValue(0);
} else {
- yaw = _oneDecimal(yaw * (180.0 / M_PI));
+ yaw = yaw * (180.0 / M_PI);
if (yaw < 0) yaw += 360;
- if (fabs(_heading - yaw) > 0.25) {
- _heading = yaw;
- if(_refreshTimer->isActive()) {
- emit headingChanged();
- }
- }
- if(_heading != yaw) {
- _heading = yaw;
- _addChange(HEADING_CHANGED);
- }
+ _headingFact.setRawValue(yaw);
}
}
@@ -618,75 +600,15 @@ void Vehicle::_updateAttitude(UASInterface* uas, int, double roll, double pitch,
void Vehicle::_updateSpeed(UASInterface*, double groundSpeed, double airSpeed, quint64)
{
- groundSpeed = _oneDecimal(groundSpeed);
- if (fabs(_groundSpeed - groundSpeed) > 0.5) {
- _groundSpeed = groundSpeed;
- if(_refreshTimer->isActive()) {
- emit groundSpeedChanged();
- }
- }
- airSpeed = _oneDecimal(airSpeed);
- if (fabs(_airSpeed - airSpeed) > 0.5) {
- _airSpeed = airSpeed;
- if(_refreshTimer->isActive()) {
- emit airSpeedChanged();
- }
- }
- if(_groundSpeed != groundSpeed) {
- _groundSpeed = groundSpeed;
- _addChange(GROUNDSPEED_CHANGED);
- }
- if(_airSpeed != airSpeed) {
- _airSpeed = airSpeed;
- _addChange(AIRSPEED_CHANGED);
- }
+ _groundSpeedFact.setRawValue(groundSpeed);
+ _airSpeedFact.setRawValue(airSpeed);
}
void Vehicle::_updateAltitude(UASInterface*, double altitudeAMSL, double altitudeWGS84, double altitudeRelative, double climbRate, quint64) {
- altitudeAMSL = _oneDecimal(altitudeAMSL);
- if (fabs(_altitudeAMSL - altitudeAMSL) > 0.5) {
- _altitudeAMSL = altitudeAMSL;
- if(_refreshTimer->isActive()) {
- emit altitudeAMSLChanged();
- }
- }
- altitudeWGS84 = _oneDecimal(altitudeWGS84);
- if (fabs(_altitudeWGS84 - altitudeWGS84) > 0.5) {
- _altitudeWGS84 = altitudeWGS84;
- if(_refreshTimer->isActive()) {
- emit altitudeWGS84Changed();
- }
- }
- altitudeRelative = _oneDecimal(altitudeRelative);
- if (fabs(_altitudeRelative - altitudeRelative) > 0.5) {
- _altitudeRelative = altitudeRelative;
- if(_refreshTimer->isActive()) {
- emit altitudeRelativeChanged();
- }
- }
- climbRate = _oneDecimal(climbRate);
- if (fabs(_climbRate - climbRate) > 0.5) {
- _climbRate = climbRate;
- if(_refreshTimer->isActive()) {
- emit climbRateChanged();
- }
- }
- if(_altitudeAMSL != altitudeAMSL) {
- _altitudeAMSL = altitudeAMSL;
- _addChange(ALTITUDEAMSL_CHANGED);
- }
- if(_altitudeWGS84 != altitudeWGS84) {
- _altitudeWGS84 = altitudeWGS84;
- _addChange(ALTITUDEWGS84_CHANGED);
- }
- if(_altitudeRelative != altitudeRelative) {
- _altitudeRelative = altitudeRelative;
- _addChange(ALTITUDERELATIVE_CHANGED);
- }
- if(_climbRate != climbRate) {
- _climbRate = climbRate;
- _addChange(CLIMBRATE_CHANGED);
- }
+ _altitudeAMSLFact.setRawValue(altitudeAMSL);
+ _altitudeWGS84Fact.setRawValue(altitudeWGS84);
+ _altitudeRelativeFact.setRawValue(altitudeRelative);
+ _climbRateFact.setRawValue(climbRate);
}
void Vehicle::_updateNavigationControllerErrors(UASInterface*, double altitudeError, double speedError, double xtrackError) {
@@ -705,19 +627,6 @@ void Vehicle::_updateNavigationControllerData(UASInterface *uas, float, float, f
* Internal
*/
-void Vehicle::_addChange(int id)
-{
- if(!_changes.contains(id)) {
- _changes.append(id);
- }
-}
-
-float Vehicle::_oneDecimal(float value)
-{
- int i = (value * 10);
- return (float)i / 10.0;
-}
-
void Vehicle::_checkUpdate()
{
// Update current location
@@ -729,49 +638,6 @@ void Vehicle::_checkUpdate()
setLongitude(_mav->getLongitude());
}
}
- // The timer rate is 20Hz for the coordinates above. These below we only check
- // twice a second.
- if(++_updateCount > 9) {
- _updateCount = 0;
- // Check for changes
- // Significant changes, that is, whole number changes, are updated immediatelly.
- // For every message however, we set a flag for what changed and this timer updates
- // them to bring everything up-to-date. This prevents an avalanche of UI updates.
- foreach(int i, _changes) {
- switch (i) {
- case ROLL_CHANGED:
- emit rollChanged();
- break;
- case PITCH_CHANGED:
- emit pitchChanged();
- break;
- case HEADING_CHANGED:
- emit headingChanged();
- break;
- case GROUNDSPEED_CHANGED:
- emit groundSpeedChanged();
- break;
- case AIRSPEED_CHANGED:
- emit airSpeedChanged();
- break;
- case CLIMBRATE_CHANGED:
- emit climbRateChanged();
- break;
- case ALTITUDERELATIVE_CHANGED:
- emit altitudeRelativeChanged();
- break;
- case ALTITUDEWGS84_CHANGED:
- emit altitudeWGS84Changed();
- break;
- case ALTITUDEAMSL_CHANGED:
- emit altitudeAMSLChanged();
- break;
- default:
- break;
- }
- }
- _changes.clear();
- }
}
QString Vehicle::getMavIconColor()
@@ -837,54 +703,6 @@ void Vehicle::_updateState(UASInterface*, QString name, QString)
}
}
-void Vehicle::_setSatelliteCount(double val, QString)
-{
- // I'm assuming that a negative value or over 99 means there is no GPS
- if(val < 0.0) val = -1.0;
- if(val > 99.0) val = -1.0;
- if(_satelliteCount != (int)val) {
- _satelliteCount = (int)val;
- emit satelliteCountChanged();
- }
-}
-
-void Vehicle::_setSatRawHDOP(double val)
-{
- if(_satRawHDOP != val) {
- _satRawHDOP = val;
- emit satRawHDOPChanged();
- }
-}
-
-void Vehicle::_setSatRawVDOP(double val)
-{
- if(_satRawVDOP != val) {
- _satRawVDOP = val;
- emit satRawVDOPChanged();
- }
-}
-
-void Vehicle::_setSatRawCOG(double val)
-{
- if(_satRawCOG != val) {
- _satRawCOG = val;
- emit satRawCOGChanged();
- }
-}
-
-void Vehicle::_setSatLoc(UASInterface*, int fix)
-{
- // fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D lock, 3: 3D lock
- if(_satelliteLock != fix) {
- if (fix > 2) {
- _coordinateValid = true;
- emit coordinateValidChanged(true);
- }
- _satelliteLock = fix;
- emit satelliteLockChanged();
- }
-}
-
void Vehicle::_handleTextMessage(int newCount)
{
// Reset?
@@ -1358,3 +1176,86 @@ bool Vehicle::multiRotor(void) const
return false;
}
}
+
+void Vehicle::_setCoordinateValid(bool coordinateValid)
+{
+ if (coordinateValid != _coordinateValid) {
+ _coordinateValid = coordinateValid;
+ emit coordinateValidChanged(_coordinateValid);
+ }
+}
+
+
+VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent)
+ : FactGroup(1000, ":/json/Vehicle/GPSFact.json", parent)
+ , _vehicle(NULL)
+ , _hdopFact (0, _hdopFactName, FactMetaData::valueTypeDouble)
+ , _vdopFact (0, _vdopFactName, FactMetaData::valueTypeDouble)
+ , _courseOverGroundFact (0, _courseOverGroundFactName, FactMetaData::valueTypeDouble)
+ , _countFact (0, _countFactName, FactMetaData::valueTypeInt32)
+ , _lockFact (0, _lockFactName, FactMetaData::valueTypeInt32)
+{
+ // Build FactGroup object model
+
+ _addFact(&_hdopFact, _hdopFactName);
+ _addFact(&_vdopFact, _vdopFactName);
+ _addFact(&_courseOverGroundFact, _courseOverGroundFactName);
+ _addFact(&_lockFact, _lockFactName);
+ _addFact(&_countFact, _countFactName);
+}
+
+void VehicleGPSFactGroup::setVehicle(Vehicle* vehicle)
+{
+ _vehicle = vehicle;
+
+#if 0
+ // Reset satellite data (no GPS)
+ _satelliteCount = -1;
+ _satRawHDOP = 1e10f;
+ _satRawVDOP = 1e10f;
+ _satRawCOG = 0.0;
+#endif
+
+ connect(_vehicle->uas(), &UASInterface::localizationChanged, this, &VehicleGPSFactGroup::_setSatLoc);
+
+ UAS* pUas = dynamic_cast(_vehicle->uas());
+ connect(pUas, &UAS::satelliteCountChanged, this, &VehicleGPSFactGroup::_setSatelliteCount);
+ connect(pUas, &UAS::satRawHDOPChanged, this, &VehicleGPSFactGroup::_setSatRawHDOP);
+ connect(pUas, &UAS::satRawVDOPChanged, this, &VehicleGPSFactGroup::_setSatRawVDOP);
+ connect(pUas, &UAS::satRawCOGChanged, this, &VehicleGPSFactGroup::_setSatRawCOG);
+}
+
+void VehicleGPSFactGroup::_setSatelliteCount(double val, QString)
+{
+ // I'm assuming that a negative value or over 99 means there is no GPS
+ if(val < 0.0) val = -1.0;
+ if(val > 99.0) val = -1.0;
+
+ _countFact.setRawValue(val);
+}
+
+void VehicleGPSFactGroup::_setSatRawHDOP(double val)
+{
+ _hdopFact.setRawValue(val);
+}
+
+void VehicleGPSFactGroup::_setSatRawVDOP(double val)
+{
+ _vdopFact.setRawValue(val);
+}
+
+void VehicleGPSFactGroup::_setSatRawCOG(double val)
+{
+ _courseOverGroundFact.setRawValue(val);
+}
+
+void VehicleGPSFactGroup::_setSatLoc(UASInterface*, int fix)
+{
+ _lockFact.setRawValue(fix);
+
+ // fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D lock, 3: 3D lock
+ if (fix > 2) {
+ _vehicle->_setCoordinateValid(true);
+ }
+}
+
diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h
index 0e299ac79b97461ad96a73d4b6a112543c119c0e..d2d0f91711e666912909263b32f8d5d341834e74 100644
--- a/src/Vehicle/Vehicle.h
+++ b/src/Vehicle/Vehicle.h
@@ -30,6 +30,7 @@
#include
#include
+#include "FactGroup.h"
#include "LinkInterface.h"
#include "QGCMAVLink.h"
#include "MissionItem.h"
@@ -50,7 +51,52 @@ class UASMessage;
Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
-class Vehicle : public QObject
+class Vehicle;
+
+class VehicleGPSFactGroup : public FactGroup
+{
+ Q_OBJECT
+
+public:
+ VehicleGPSFactGroup(QObject* parent = NULL);
+
+ Q_PROPERTY(Fact* hdop READ hdop CONSTANT)
+ Q_PROPERTY(Fact* vdop READ vdop CONSTANT)
+ Q_PROPERTY(Fact* courseOverGround READ courseOverGround CONSTANT)
+ Q_PROPERTY(Fact* count READ count CONSTANT)
+ Q_PROPERTY(Fact* lock READ lock CONSTANT)
+
+ Fact* hdop(void) { return &_hdopFact; }
+ Fact* vdop(void) { return &_vdopFact; }
+ Fact* courseOverGround(void) { return &_courseOverGroundFact; }
+ Fact* count(void) { return &_countFact; }
+ Fact* lock(void) { return &_lockFact; }
+
+ void setVehicle(Vehicle* vehicle);
+
+private slots:
+ void _setSatelliteCount(double val, QString);
+ void _setSatRawHDOP(double val);
+ void _setSatRawVDOP(double val);
+ void _setSatRawCOG(double val);
+ void _setSatLoc(UASInterface*, int fix);
+
+private:
+ Vehicle* _vehicle;
+ Fact _hdopFact;
+ Fact _vdopFact;
+ Fact _courseOverGroundFact;
+ Fact _countFact;
+ Fact _lockFact;
+
+ static const char* _hdopFactName;
+ static const char* _vdopFactName;
+ static const char* _courseOverGroundFactName;
+ static const char* _countFactName;
+ static const char* _lockFactName;
+};
+
+class Vehicle : public FactGroup
{
Q_OBJECT
@@ -78,26 +124,12 @@ public:
Q_PROPERTY(bool hilMode READ hilMode WRITE setHilMode NOTIFY hilModeChanged)
Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged)
Q_PROPERTY(QmlObjectListModel* trajectoryPoints READ trajectoryPoints CONSTANT)
- Q_PROPERTY(float roll READ roll NOTIFY rollChanged)
- Q_PROPERTY(float pitch READ pitch NOTIFY pitchChanged)
- Q_PROPERTY(float heading READ heading NOTIFY headingChanged)
- Q_PROPERTY(float groundSpeed READ groundSpeed NOTIFY groundSpeedChanged)
- Q_PROPERTY(float airSpeed READ airSpeed NOTIFY airSpeedChanged)
- Q_PROPERTY(float climbRate READ climbRate NOTIFY climbRateChanged)
- Q_PROPERTY(float altitudeRelative READ altitudeRelative NOTIFY altitudeRelativeChanged)
- Q_PROPERTY(float altitudeWGS84 READ altitudeWGS84 NOTIFY altitudeWGS84Changed)
- Q_PROPERTY(float altitudeAMSL READ altitudeAMSL NOTIFY altitudeAMSLChanged)
Q_PROPERTY(float latitude READ latitude NOTIFY coordinateChanged)
Q_PROPERTY(float longitude READ longitude NOTIFY coordinateChanged)
Q_PROPERTY(double batteryVoltage READ batteryVoltage NOTIFY batteryVoltageChanged)
Q_PROPERTY(double batteryPercent READ batteryPercent NOTIFY batteryPercentChanged)
Q_PROPERTY(double batteryConsumed READ batteryConsumed NOTIFY batteryConsumedChanged)
- Q_PROPERTY(int satelliteCount READ satelliteCount NOTIFY satelliteCountChanged)
- Q_PROPERTY(double satRawHDOP READ satRawHDOP NOTIFY satRawHDOPChanged)
- Q_PROPERTY(double satRawVDOP READ satRawVDOP NOTIFY satRawVDOPChanged)
- Q_PROPERTY(double satRawCOG READ satRawCOG NOTIFY satRawCOGChanged)
Q_PROPERTY(QString currentState READ currentState NOTIFY currentStateChanged)
- Q_PROPERTY(int satelliteLock READ satelliteLock NOTIFY satelliteLockChanged)
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItemsModel CONSTANT)
Q_PROPERTY(bool messageTypeNone READ messageTypeNone NOTIFY messageTypeChanged)
Q_PROPERTY(bool messageTypeNormal READ messageTypeNormal NOTIFY messageTypeChanged)
@@ -126,6 +158,20 @@ public:
Q_PROPERTY(bool multiRotor READ multiRotor CONSTANT)
Q_PROPERTY(bool autoDisconnect MEMBER _autoDisconnect NOTIFY autoDisconnectChanged)
+ // FactGroup object model properties
+
+ Q_PROPERTY(Fact* roll READ roll CONSTANT)
+ Q_PROPERTY(Fact* pitch READ pitch CONSTANT)
+ Q_PROPERTY(Fact* heading READ heading CONSTANT)
+ Q_PROPERTY(Fact* groundSpeed READ groundSpeed CONSTANT)
+ Q_PROPERTY(Fact* airSpeed READ airSpeed CONSTANT)
+ Q_PROPERTY(Fact* climbRate READ climbRate CONSTANT)
+ Q_PROPERTY(Fact* altitudeRelative READ altitudeRelative CONSTANT)
+ Q_PROPERTY(Fact* altitudeWGS84 READ altitudeWGS84 CONSTANT)
+ Q_PROPERTY(Fact* altitudeAMSL READ altitudeAMSL CONSTANT)
+
+ Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT)
+
/// Resets link status counters
Q_INVOKABLE void resetCounters ();
@@ -147,6 +193,7 @@ public:
QGeoCoordinate coordinate(void) { return _coordinate; }
bool coordinateValid(void) { return _coordinateValid; }
+ void _setCoordinateValid(bool coordinateValid);
QmlObjectListModel* missionItemsModel(void);
typedef enum {
@@ -239,18 +286,6 @@ public:
MessageError
} MessageType_t;
- enum {
- ROLL_CHANGED,
- PITCH_CHANGED,
- HEADING_CHANGED,
- GROUNDSPEED_CHANGED,
- AIRSPEED_CHANGED,
- CLIMBRATE_CHANGED,
- ALTITUDERELATIVE_CHANGED,
- ALTITUDEWGS84_CHANGED,
- ALTITUDEAMSL_CHANGED
- };
-
bool messageTypeNone () { return _currentMessageType == MessageNone; }
bool messageTypeNormal () { return _currentMessageType == MessageNormal; }
bool messageTypeWarning () { return _currentMessageType == MessageWarning; }
@@ -260,27 +295,13 @@ public:
QString formatedMessages ();
QString formatedMessage () { return _formatedMessage; }
QString latestError () { return _latestError; }
- float roll () { return _roll; }
- float pitch () { return _pitch; }
- float heading () { return _heading; }
- float groundSpeed () { return _groundSpeed; }
- float airSpeed () { return _airSpeed; }
- float climbRate () { return _climbRate; }
- float altitudeRelative () { return _altitudeRelative; }
- float altitudeWGS84 () { return _altitudeWGS84; }
- float altitudeAMSL () { return _altitudeAMSL; }
float latitude () { return _coordinate.latitude(); }
float longitude () { return _coordinate.longitude(); }
bool mavPresent () { return _mav != NULL; }
- int satelliteCount () { return _satelliteCount; }
- double satRawHDOP () { return _satRawHDOP; }
- double satRawVDOP () { return _satRawVDOP; }
- double satRawCOG () { return _satRawCOG; }
double batteryVoltage () { return _batteryVoltage; }
double batteryPercent () { return _batteryPercent; }
double batteryConsumed () { return _batteryConsumed; }
QString currentState () { return _currentState; }
- int satelliteLock () { return _satelliteLock; }
int rcRSSI () { return _rcRSSI; }
bool px4Firmware () { return _firmwareType == MAV_AUTOPILOT_PX4; }
bool apmFirmware () { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
@@ -291,6 +312,18 @@ public:
uint messagesSent () { return _messagesSent; }
uint messagesLost () { return _messagesLost; }
+ Fact* roll (void) { return &_rollFact; }
+ Fact* heading (void) { return &_headingFact; }
+ Fact* pitch (void) { return &_pitchFact; }
+ Fact* airSpeed (void) { return &_airSpeedFact; }
+ Fact* groundSpeed (void) { return &_groundSpeedFact; }
+ Fact* climbRate (void) { return &_climbRateFact; }
+ Fact* altitudeRelative (void) { return &_altitudeRelativeFact; }
+ Fact* altitudeWGS84 (void) { return &_altitudeWGS84Fact; }
+ Fact* altitudeAMSL (void) { return &_altitudeAMSLFact; }
+
+ FactGroup* gpsFactGroup(void) { return &_gpsFactGroup; }
+
void setConnectionLostEnabled(bool connectionLostEnabled);
ParameterLoader* getParameterLoader(void);
@@ -335,26 +368,12 @@ signals:
void formatedMessagesChanged();
void formatedMessageChanged ();
void latestErrorChanged ();
- void rollChanged ();
- void pitchChanged ();
- void headingChanged ();
- void groundSpeedChanged ();
- void airSpeedChanged ();
- void climbRateChanged ();
- void altitudeRelativeChanged();
- void altitudeWGS84Changed ();
- void altitudeAMSLChanged ();
void longitudeChanged ();
void batteryVoltageChanged ();
void batteryPercentChanged ();
void batteryConsumedChanged ();
void currentConfigChanged ();
- void satelliteCountChanged ();
- void satRawHDOPChanged ();
- void satRawVDOPChanged ();
- void satRawCOGChanged ();
void currentStateChanged ();
- void satelliteLockChanged ();
void flowImageIndexChanged ();
void rcRSSIChanged (int rcRSSI);
@@ -395,11 +414,6 @@ private slots:
void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int);
void _updateBatteryConsumedChanged (UASInterface*, double current_consumed);
void _updateState (UASInterface* system, QString name, QString description);
- void _setSatelliteCount (double val, QString name);
- void _setSatRawHDOP (double val);
- void _setSatRawVDOP (double val);
- void _setSatRawCOG (double val);
- void _setSatLoc (UASInterface* uas, int fix);
/** @brief A new camera image has arrived */
void _imageReady (UASInterface* uas);
void _connectionLostTimeout(void);
@@ -420,9 +434,6 @@ private:
void _connectionActive(void);
void _say(const QString& text, int severity);
- void _addChange (int id);
- float _oneDecimal (float value);
-
private:
int _id; ///< Mavlink system id
bool _active;
@@ -454,30 +465,15 @@ private:
int _currentNormalCount;
MessageType_t _currentMessageType;
QString _latestError;
- float _roll;
- float _pitch;
- float _heading;
- float _altitudeAMSL;
- float _altitudeWGS84;
- float _altitudeRelative;
- float _groundSpeed;
- float _airSpeed;
- float _climbRate;
float _navigationAltitudeError;
float _navigationSpeedError;
float _navigationCrosstrackError;
float _navigationTargetBearing;
QTimer* _refreshTimer;
- QList _changes;
double _batteryVoltage;
double _batteryPercent;
double _batteryConsumed;
QString _currentState;
- int _satelliteCount;
- double _satRawHDOP;
- double _satRawVDOP;
- double _satRawCOG;
- int _satelliteLock;
int _updateCount;
QString _formatedMessage;
int _rcRSSI;
@@ -534,9 +530,37 @@ private:
uint8_t _compID;
bool _heardFrom;
+ // FactGroup facts
+
+ Fact _rollFact;
+ Fact _pitchFact;
+ Fact _headingFact;
+ Fact _groundSpeedFact;
+ Fact _airSpeedFact;
+ Fact _climbRateFact;
+ Fact _altitudeRelativeFact;
+ Fact _altitudeWGS84Fact;
+ Fact _altitudeAMSLFact;
+
+ VehicleGPSFactGroup _gpsFactGroup;
+
+ static const char* _rollFactName;
+ static const char* _pitchFactName;
+ static const char* _headingFactName;
+ static const char* _groundSpeedFactName;
+ static const char* _airSpeedFactName;
+ static const char* _climbRateFactName;
+ static const char* _altitudeRelativeFactName;
+ static const char* _altitudeWGS84FactName;
+ static const char* _altitudeAMSLFactName;
+ static const char* _gpsFactGroupName;
+
+ static const int _vehicleUIUpdateRateMSecs = 100;
+
// Settings keys
static const char* _settingsGroup;
static const char* _joystickModeSettingsKey;
static const char* _joystickEnabledSettingsKey;
+
};
#endif
diff --git a/src/Vehicle/VehicleFact.json b/src/Vehicle/VehicleFact.json
new file mode 100644
index 0000000000000000000000000000000000000000..9eae17280137a7ab1e98e6e3f2f8b647cf6138db
--- /dev/null
+++ b/src/Vehicle/VehicleFact.json
@@ -0,0 +1,69 @@
+{
+ "version": 1,
+
+ "properties": [
+ {
+ "name": "roll",
+ "shortDescription": "Roll",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "degrees"
+ },
+ {
+ "name": "pitch",
+ "shortDescription": "Pitch",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "degrees"
+ },
+ {
+ "name": "heading",
+ "shortDescription": "Heading",
+ "type": "double",
+ "decimalPlaces": 0,
+ "units": "degrees"
+ },
+ {
+ "name": "groundSpeed",
+ "shortDescription": "Ground Speed",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "m/s"
+ },
+ {
+ "name": "airSpeed",
+ "shortDescription": "Air Speed",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "m/s"
+ },
+ {
+ "name": "climbRate",
+ "shortDescription": "Climb Rate",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "m/s"
+ },
+ {
+ "name": "altitudeRelative",
+ "shortDescription": "Altitude",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "m"
+ },
+ {
+ "name": "altitudeWGS84",
+ "shortDescription": "Altitude",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "m"
+ },
+ {
+ "name": "altitudeAMSL",
+ "shortDescription": "Altitude",
+ "type": "double",
+ "decimalPlaces": 1,
+ "units": "m"
+ }
+ ]
+}
diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc
index 5c7e512ac1b4b3c5721a2e93978e17b68570b2ec..487f5b2ea6556c670642a87611e2fc534c8c35be 100644
--- a/src/comm/QGCXPlaneLink.cc
+++ b/src/comm/QGCXPlaneLink.cc
@@ -933,16 +933,16 @@ void QGCXPlaneLink::setRandomPosition()
double offLon = rand() / static_cast(RAND_MAX) / 500.0 + 1.0/500.0;
double offAlt = rand() / static_cast(RAND_MAX) * 200.0 + 100.0;
- if (_vehicle->altitudeAMSL() + offAlt < 0)
+ if (_vehicle->altitudeAMSL()->rawValue().toDouble() + offAlt < 0)
{
offAlt *= -1.0;
}
setPositionAttitude(_vehicle->latitude() + offLat,
_vehicle->longitude() + offLon,
- _vehicle->altitudeAMSL() + offAlt,
- _vehicle->roll(),
- _vehicle->pitch(),
+ _vehicle->altitudeAMSL()->rawValue().toDouble() + offAlt,
+ _vehicle->roll()->rawValue().toDouble(),
+ _vehicle->pitch()->rawValue().toDouble(),
_vehicle->uas()->getYaw());
}
@@ -957,7 +957,7 @@ void QGCXPlaneLink::setRandomAttitude()
setPositionAttitude(_vehicle->latitude(),
_vehicle->longitude(),
- _vehicle->altitudeAMSL(),
+ _vehicle->altitudeAMSL()->rawValue().toDouble(),
roll,
pitch,
yaw);
diff --git a/src/ui/toolbar/MainToolBar.qml b/src/ui/toolbar/MainToolBar.qml
index 1215c8130f82a522522f7086ff0184cacc0b9da8..4fb6be3c9a91eb914cb4565236728b9477ef1892 100644
--- a/src/ui/toolbar/MainToolBar.qml
+++ b/src/ui/toolbar/MainToolBar.qml
@@ -188,28 +188,6 @@ Rectangle {
return colorRed;
}
- function getGpsLockStatus() {
- if(activeVehicle) {
- if(activeVehicle.satelliteLock < 2) {
- return "No Satellite Lock"
- }
- if(activeVehicle.satelliteLock == 2) {
- return "2D Lock"
- }
- if(activeVehicle.satelliteLock == 3) {
- return "3D Lock"
- }
- if(activeVehicle.satelliteLock == 4) {
- return "3D DGPS Lock"
- }
- if(activeVehicle.satelliteLock == 5) {
- return "3D RTK GPS Lock"
- }
- return "Unkown Lock Type (" + activeVehicle.satelliteLock + ")"
- }
- return "N/A"
- }
-
Component.onCompleted: {
//-- TODO: Get this from the actual state
flyButton.checked = true
@@ -232,14 +210,14 @@ Rectangle {
anchors.centerIn: parent
QGCLabel {
id: gpsLabel
- text: (activeVehicle && activeVehicle.satelliteCount >= 0) ? "GPS Status" : "GPS Data Unavailable"
+ text: (activeVehicle && activeVehicle.gps.count.value >= 0) ? "GPS Status" : "GPS Data Unavailable"
font.weight:Font.DemiBold
color: colorWhite
anchors.horizontalCenter: parent.horizontalCenter
}
GridLayout {
id: gpsGrid
- visible: (activeVehicle && activeVehicle.satelliteCount >= 0)
+ visible: (activeVehicle && activeVehicle.gps.count.value >= 0)
anchors.margins: ScreenTools.defaultFontPixelHeight
columnSpacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter
@@ -249,7 +227,7 @@ Rectangle {
color: colorWhite
}
QGCLabel {
- text: activeVehicle ? (activeVehicle.satelliteCount) : "N/A"
+ text: activeVehicle ? activeVehicle.gps.count.valueString : "N/A"
color: colorWhite
}
QGCLabel {
@@ -257,7 +235,7 @@ Rectangle {
color: colorWhite
}
QGCLabel {
- text: getGpsLockStatus()
+ text: activeVehicle ? activeVehicle.gps.lock.enumStringValue : "N/A"
color: colorWhite
}
QGCLabel {
@@ -265,7 +243,7 @@ Rectangle {
color: colorWhite
}
QGCLabel {
- text: activeVehicle ? (activeVehicle.satRawHDOP < 10000 ? activeVehicle.satRawHDOP.toFixed(0) : "N/A") : "N/A"
+ text: activeVehicle ? (activeVehicle.gps.hdop.value < 10000 ? activeVehicle.gps.hdop.valueString : "N/A") : "N/A"
color: colorWhite
}
QGCLabel {
@@ -273,7 +251,7 @@ Rectangle {
color: colorWhite
}
QGCLabel {
- text: activeVehicle ? (activeVehicle.satRawVDOP < 10000 ? activeVehicle.satRawVDOP.toFixed(0) : "N/A") : "N/A"
+ text: activeVehicle ? (activeVehicle.gps.vdop.value < 10000 ? activeVehicle.gps.vdop.valueString : "N/A") : "N/A"
color: colorWhite
}
QGCLabel {
@@ -281,7 +259,7 @@ Rectangle {
color: colorWhite
}
QGCLabel {
- text: activeVehicle ? (activeVehicle.satRawCOG).toFixed(2) : "N/A"
+ text: activeVehicle ? activeVehicle.gps.courseOverGround.valueString : "N/A"
color: colorWhite
}
}
diff --git a/src/ui/toolbar/MainToolBarIndicators.qml b/src/ui/toolbar/MainToolBarIndicators.qml
index 11eb06b7d9730be88c646eb0543ef5bdf1fb371c..92a0d40379868d7115fa69bdb4ef27679ea901b8 100644
--- a/src/ui/toolbar/MainToolBarIndicators.qml
+++ b/src/ui/toolbar/MainToolBarIndicators.qml
@@ -176,18 +176,18 @@ Row {
smooth: true
width: mainWindow.tbCellHeight * 0.65
height: mainWindow.tbCellHeight * 0.5
- opacity: (activeVehicle && activeVehicle.satelliteCount >= 0) ? 1 : 0.5
+ opacity: (activeVehicle && activeVehicle.gps.count.value >= 0) ? 1 : 0.5
anchors.verticalCenter: parent.verticalCenter
}
SignalStrength {
size: mainWindow.tbCellHeight * 0.5
- percent: activeVehicle ? getSatStrength(activeVehicle.satRawHDOP) : ""
+ percent: activeVehicle ? getSatStrength(activeVehicle.gps.hdop.value) : ""
anchors.verticalCenter: parent.verticalCenter
}
}
QGCLabel {
- text: (activeVehicle && activeVehicle.satelliteCount >= 0) ? activeVehicle.satelliteCount : ""
- visible: (activeVehicle && activeVehicle.satelliteCount >= 0)
+ text: (activeVehicle && activeVehicle.gps.count.value >= 0) ? activeVehicle.gps.count.valueString : ""
+ visible: (activeVehicle && activeVehicle.gps.count.value >= 0)
font.pixelSize: tbFontSmall
color: colorWhite
anchors.top: parent.top