Commit 2c0db7c4 authored by Don Gagne's avatar Don Gagne

Add new FactGroup support

Plumb through initial object mode on Vehicle
parent c51923ef
...@@ -673,6 +673,7 @@ INCLUDEPATH += \ ...@@ -673,6 +673,7 @@ INCLUDEPATH += \
HEADERS += \ HEADERS += \
src/FactSystem/Fact.h \ src/FactSystem/Fact.h \
src/FactSystem/FactGroup.h \
src/FactSystem/FactControls/FactPanelController.h \ src/FactSystem/FactControls/FactPanelController.h \
src/FactSystem/FactMetaData.h \ src/FactSystem/FactMetaData.h \
src/FactSystem/FactSystem.h \ src/FactSystem/FactSystem.h \
...@@ -682,6 +683,7 @@ HEADERS += \ ...@@ -682,6 +683,7 @@ HEADERS += \
SOURCES += \ SOURCES += \
src/FactSystem/Fact.cc \ src/FactSystem/Fact.cc \
src/FactSystem/FactGroup.cc \
src/FactSystem/FactControls/FactPanelController.cc \ src/FactSystem/FactControls/FactPanelController.cc \
src/FactSystem/FactMetaData.cc \ src/FactSystem/FactMetaData.cc \
src/FactSystem/FactSystem.cc \ src/FactSystem/FactSystem.cc \
......
...@@ -148,5 +148,8 @@ ...@@ -148,5 +148,8 @@
<file alias="PX4/MavCmdInfoCommon.json">src/FirmwarePlugin/PX4/MavCmdInfoCommon.json</file> <file alias="PX4/MavCmdInfoCommon.json">src/FirmwarePlugin/PX4/MavCmdInfoCommon.json</file>
<file alias="PX4/MavCmdInfoFixedWing.json">src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json</file> <file alias="PX4/MavCmdInfoFixedWing.json">src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json</file>
<file alias="PX4/MavCmdInfoMultiRotor.json">src/FirmwarePlugin/PX4/MavCmdInfoMultiRotor.json</file> <file alias="PX4/MavCmdInfoMultiRotor.json">src/FirmwarePlugin/PX4/MavCmdInfoMultiRotor.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/GPSFact.json">src/Vehicle/GPSFact.json</file>
</qresource> </qresource>
</RCC> </RCC>
...@@ -35,6 +35,8 @@ Fact::Fact(QObject* parent) ...@@ -35,6 +35,8 @@ Fact::Fact(QObject* parent)
, _rawValue(0) , _rawValue(0)
, _type(FactMetaData::valueTypeInt32) , _type(FactMetaData::valueTypeInt32)
, _metaData(NULL) , _metaData(NULL)
, _sendValueChangedSignals(true)
, _deferredValueChangeSignal(false)
{ {
FactMetaData* metaData = new FactMetaData(_type, this); FactMetaData* metaData = new FactMetaData(_type, this);
setMetaData(metaData); setMetaData(metaData);
...@@ -47,6 +49,8 @@ Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObjec ...@@ -47,6 +49,8 @@ Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObjec
, _rawValue(0) , _rawValue(0)
, _type(type) , _type(type)
, _metaData(NULL) , _metaData(NULL)
, _sendValueChangedSignals(true)
, _deferredValueChangeSignal(false)
{ {
FactMetaData* metaData = new FactMetaData(_type, this); FactMetaData* metaData = new FactMetaData(_type, this);
setMetaData(metaData); setMetaData(metaData);
...@@ -60,11 +64,13 @@ Fact::Fact(const Fact& other, QObject* parent) ...@@ -60,11 +64,13 @@ Fact::Fact(const Fact& other, QObject* parent)
const Fact& Fact::operator=(const Fact& other) const Fact& Fact::operator=(const Fact& other)
{ {
_name = other._name; _name = other._name;
_componentId = other._componentId; _componentId = other._componentId;
_rawValue = other._rawValue; _rawValue = other._rawValue;
_type = other._type; _type = other._type;
_sendValueChangedSignals = other._sendValueChangedSignals;
_deferredValueChangeSignal = other._deferredValueChangeSignal;
if (_metaData && other._metaData) { if (_metaData && other._metaData) {
*_metaData = *other._metaData; *_metaData = *other._metaData;
} else { } else {
...@@ -82,7 +88,7 @@ void Fact::forceSetRawValue(const QVariant& value) ...@@ -82,7 +88,7 @@ void Fact::forceSetRawValue(const QVariant& value)
if (_metaData->convertAndValidateRaw(value, true /* convertOnly */, typedValue, errorString)) { if (_metaData->convertAndValidateRaw(value, true /* convertOnly */, typedValue, errorString)) {
_rawValue.setValue(typedValue); _rawValue.setValue(typedValue);
emit valueChanged(cookedValue()); _sendValueChangedSignal(cookedValue());
emit _containerRawValueChanged(rawValue()); emit _containerRawValueChanged(rawValue());
} }
} else { } else {
...@@ -99,7 +105,7 @@ void Fact::setRawValue(const QVariant& value) ...@@ -99,7 +105,7 @@ void Fact::setRawValue(const QVariant& value)
if (_metaData->convertAndValidateRaw(value, true /* convertOnly */, typedValue, errorString)) { if (_metaData->convertAndValidateRaw(value, true /* convertOnly */, typedValue, errorString)) {
if (typedValue != _rawValue) { if (typedValue != _rawValue) {
_rawValue.setValue(typedValue); _rawValue.setValue(typedValue);
emit valueChanged(cookedValue()); _sendValueChangedSignal(cookedValue());
emit _containerRawValueChanged(rawValue()); emit _containerRawValueChanged(rawValue());
} }
} }
...@@ -141,7 +147,7 @@ void Fact::setEnumIndex(int index) ...@@ -141,7 +147,7 @@ void Fact::setEnumIndex(int index)
void Fact::_containerSetRawValue(const QVariant& value) void Fact::_containerSetRawValue(const QVariant& value)
{ {
_rawValue = value; _rawValue = value;
emit valueChanged(cookedValue()); _sendValueChangedSignal(cookedValue());
emit vehicleUpdated(_rawValue); emit vehicleUpdated(_rawValue);
} }
...@@ -492,3 +498,29 @@ bool Fact::rebootRequired(void) const ...@@ -492,3 +498,29 @@ bool Fact::rebootRequired(void) const
return false; 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());
}
}
...@@ -117,6 +117,15 @@ public: ...@@ -117,6 +117,15 @@ public:
void setEnumIndex (int index); void setEnumIndex (int index);
void setEnumStringValue (const QString& value); 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 // C++ methods
/// Sets and sends new value to vehicle even if value is the same /// Sets and sends new value to vehicle even if value is the same
...@@ -129,12 +138,14 @@ public: ...@@ -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. /// 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; } void _setName(const QString& name) { _name = name; }
signals: signals:
void bitmaskStringsChanged(void); void bitmaskStringsChanged(void);
void bitmaskValuesChanged(void); void bitmaskValuesChanged(void);
void enumStringsChanged(void); void enumStringsChanged(void);
void enumValuesChanged(void); void enumValuesChanged(void);
void sendValueChangedSignalsChanged(bool sendValueChangedSignals);
/// QObject Property System signal for value property changes /// QObject Property System signal for value property changes
/// ///
...@@ -151,12 +162,15 @@ signals: ...@@ -151,12 +162,15 @@ signals:
protected: protected:
QString _variantToString(const QVariant& variant) const; QString _variantToString(const QVariant& variant) const;
void _sendValueChangedSignal(QVariant value);
QString _name; QString _name;
int _componentId; int _componentId;
QVariant _rawValue; QVariant _rawValue;
FactMetaData::ValueType_t _type; FactMetaData::ValueType_t _type;
FactMetaData* _metaData; FactMetaData* _metaData;
bool _sendValueChangedSignals;
bool _deferredValueChangeSignal;
}; };
#endif #endif
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
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 <http://www.gnu.org/licenses/>.
======================================================================*/
#include "FactGroup.h"
#include "JsonHelper.h"
#include <QJsonDocument>
#include <QJsonParseError>
#include <QJsonArray>
#include <QDebug>
#include <QFile>
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<QJsonValue::Type> 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; i<enumValues.count(); i++) {
QVariant enumVariant;
QString errorString;
if (metaData->convertAndValidateRaw(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;
}
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
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 <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef FactGroup_H
#define FactGroup_H
#include "Fact.h"
#include "QGCLoggingCategory.h"
#include <QStringList>
#include <QMap>
#include <QTimer>
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<QString, Fact*> _nameToFactMap;
QMap<QString, FactGroup*> _nameToFactGroupMap;
QMap<QString, FactMetaData*> _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
...@@ -398,3 +398,39 @@ void FactMetaData::setRawUnits(const QString& rawUnits) ...@@ -398,3 +398,39 @@ void FactMetaData::setRawUnits(const QString& rawUnits)
_setBuiltInTranslator(); _setBuiltInTranslator();
} }
FactMetaData::ValueType_t FactMetaData::stringToType(const QString& typeString, bool& unknownType)
{
QStringList knownTypeStrings;
QList<ValueType_t> 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<knownTypeStrings.count(); i++) {
if (knownTypeStrings[i].compare(typeString, Qt::CaseInsensitive) == 0) {
return knownTypes[i];
}
}
unknownType = true;
return valueTypeDouble;
}
...@@ -120,6 +120,8 @@ public: ...@@ -120,6 +120,8 @@ public:
static const int defaultDecimalPlaces = 3; static const int defaultDecimalPlaces = 3;
static ValueType_t stringToType(const QString& typeString, bool& unknownType);
private: private:
QVariant _minForType(void) const; QVariant _minForType(void) const;
QVariant _maxForType(void) const; QVariant _maxForType(void) const;
......
...@@ -25,6 +25,7 @@ ...@@ -25,6 +25,7 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "FactSystem.h" #include "FactSystem.h"
#include "FactGroup.h"
#include "FactPanelController.h" #include "FactPanelController.h"
#include <QtQml> #include <QtQml>
...@@ -41,6 +42,7 @@ void FactSystem::setToolbox(QGCToolbox *toolbox) ...@@ -41,6 +42,7 @@ void FactSystem::setToolbox(QGCToolbox *toolbox)
{ {
QGCTool::setToolbox(toolbox); QGCTool::setToolbox(toolbox);
qmlRegisterType<Fact>(_factSystemQmlUri, 1, 0, "Fact"); qmlRegisterType<Fact> (_factSystemQmlUri, 1, 0, "Fact");
qmlRegisterType<Fact> (_factSystemQmlUri, 1, 0, "FactGroup");
qmlRegisterType<FactPanelController>(_factSystemQmlUri, 1, 0, "FactPanelController"); qmlRegisterType<FactPanelController>(_factSystemQmlUri, 1, 0, "FactPanelController");
} }
...@@ -36,6 +36,7 @@ import QGroundControl.Controls 1.0 ...@@ -36,6 +36,7 @@ import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
import QGroundControl.Vehicle 1.0 import QGroundControl.Vehicle 1.0
import QGroundControl.Controllers 1.0 import QGroundControl.Controllers 1.0
import QGroundControl.FactSystem 1.0
/// Flight Display View /// Flight Display View
Item { Item {
...@@ -55,7 +56,6 @@ Item { ...@@ -55,7 +56,6 @@ Item {
readonly property real _defaultAltitudeWGS84: 0 readonly property real _defaultAltitudeWGS84: 0
readonly property real _defaultGroundSpeed: 0 readonly property real _defaultGroundSpeed: 0
readonly property real _defaultAirSpeed: 0 readonly property real _defaultAirSpeed: 0
readonly property real _defaultClimbRate: 0
readonly property string _mapName: "FlightDisplayView" readonly property string _mapName: "FlightDisplayView"
readonly property string _showMapBackgroundKey: "/showMapBackground" readonly property string _showMapBackgroundKey: "/showMapBackground"
...@@ -65,14 +65,15 @@ Item { ...@@ -65,14 +65,15 @@ Item {
property bool _mainIsMap: QGroundControl.loadBoolGlobalSetting(_mainIsMapKey, true) property bool _mainIsMap: QGroundControl.loadBoolGlobalSetting(_mainIsMapKey, true)
property bool _isPipVisible: QGroundControl.loadBoolGlobalSetting(_PIPVisibleKey, true) property bool _isPipVisible: QGroundControl.loadBoolGlobalSetting(_PIPVisibleKey, true)
property real _roll: _activeVehicle ? (isNaN(_activeVehicle.roll) ? _defaultRoll : _activeVehicle.roll) : _defaultRoll property real _roll: _activeVehicle ? _activeVehicle.roll.value : _defaultRoll
property real _pitch: _activeVehicle ? (isNaN(_activeVehicle.pitch) ? _defaultPitch : _activeVehicle.pitch) : _defaultPitch property real _pitch: _activeVehicle ? _activeVehicle.pitch.value : _defaultPitch
property real _heading: _activeVehicle ? (isNaN(_activeVehicle.heading) ? _defaultHeading : _activeVehicle.heading) : _defaultHeading property real _heading: _activeVehicle ? _activeVehicle.heading.value : _defaultHeading
property real _altitudeWGS84: _activeVehicle ? _activeVehicle.altitudeWGS84 : _defaultAltitudeWGS84
property real _groundSpeed: _activeVehicle ? _activeVehicle.groundSpeed : _defaultGroundSpeed property Fact _emptyFact: Fact { }
property real _airSpeed: _activeVehicle ? _activeVehicle.airSpeed : _defaultAirSpeed property Fact _groundSpeedFact: _activeVehicle ? _activeVehicle.groundSpeed : _emptyFact
property real _climbRate: _activeVehicle ? _activeVehicle.climbRate : _defaultClimbRate property Fact _airSpeedFact: _activeVehicle ? _activeVehicle.airSpeed : _emptyFact
property Fact _altitudeWGS84Fact: _activeVehicle ? _activeVehicle.altitudeWGS84 : _emptyFact
property bool activeVehicleJoystickEnabled: _activeVehicle ? _activeVehicle.joystickEnabled : false property bool activeVehicleJoystickEnabled: _activeVehicle ? _activeVehicle.joystickEnabled : false
......
...@@ -39,7 +39,8 @@ Item { ...@@ -39,7 +39,8 @@ Item {
readonly property string _InstrumentVisibleKey: "IsInstrumentPanelVisible" 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 } QGCMapPalette { id: mapPal; lightColors: !isBackgroundDark }
...@@ -101,9 +102,9 @@ Item { ...@@ -101,9 +102,9 @@ Item {
heading: _heading heading: _heading
rollAngle: _roll rollAngle: _roll
pitchAngle: _pitch pitchAngle: _pitch
altitude: _altitudeWGS84 altitudeFact: _altitudeWGS84Fact
groundSpeed: _groundSpeed groundSpeedFact: _groundSpeedFact
airSpeed: _airSpeed airSpeedFact: _airSpeedFact
isSatellite: _mainIsMap ? _flightMap ? _flightMap.isSatelliteMap : true : true isSatellite: _mainIsMap ? _flightMap ? _flightMap.isSatelliteMap : true : true
z: QGroundControl.zOrderWidgets z: QGroundControl.zOrderWidgets
onClicked: { onClicked: {
...@@ -127,7 +128,7 @@ Item { ...@@ -127,7 +128,7 @@ Item {
spacing: ScreenTools.defaultFontPixelSize * 0.33 spacing: ScreenTools.defaultFontPixelSize * 0.33
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
QGCLabel { QGCLabel {
text: "Altitude (m)" text: _altitudeWGS84Fact.shortDescription + "(" + _altitudeWGS84Fact.units + ")"
font.pixelSize: ScreenTools.defaultFontPixelSize * 0.75 font.pixelSize: ScreenTools.defaultFontPixelSize * 0.75
width: parent.width width: parent.width
height: ScreenTools.defaultFontPixelSize * 0.75 height: ScreenTools.defaultFontPixelSize * 0.75
...@@ -135,7 +136,7 @@ Item { ...@@ -135,7 +136,7 @@ Item {
horizontalAlignment: TextEdit.AlignHCenter horizontalAlignment: TextEdit.AlignHCenter
} }
QGCLabel { QGCLabel {
text: _altitudeWGS84 < 10000 ? _altitudeWGS84.toFixed(1) : _altitudeWGS84.toFixed(0) text: _altitudeWGS84Fact.valueString
font.pixelSize: ScreenTools.defaultFontPixelSize * 1.5 font.pixelSize: ScreenTools.defaultFontPixelSize * 1.5
font.weight: Font.DemiBold font.weight: Font.DemiBold
width: parent.width width: parent.width
...@@ -143,7 +144,7 @@ Item { ...@@ -143,7 +144,7 @@ Item {
horizontalAlignment: TextEdit.AlignHCenter horizontalAlignment: TextEdit.AlignHCenter
} }
QGCLabel { QGCLabel {
text: "Ground Speed (km/h)" text: _groundSpeedFact.shortDescription + "(" + _groundSpeedFact.units + ")"
font.pixelSize: ScreenTools.defaultFontPixelSize * 0.75 font.pixelSize: ScreenTools.defaultFontPixelSize * 0.75
width: parent.width width: parent.width
height: ScreenTools.defaultFontPixelSize * 0.75 height: ScreenTools.defaultFontPixelSize * 0.75
...@@ -151,7 +152,7 @@ Item { ...@@ -151,7 +152,7 @@ Item {
horizontalAlignment: TextEdit.AlignHCenter horizontalAlignment: TextEdit.AlignHCenter
} }
QGCLabel { QGCLabel {
text: (_groundSpeed * 3.6).toFixed(1) text: _groundSpeedFact.valueString
font.pixelSize: ScreenTools.defaultFontPixelSize font.pixelSize: ScreenTools.defaultFontPixelSize
font.weight: Font.DemiBold font.weight: Font.DemiBold
width: parent.width width: parent.width
......
...@@ -51,7 +51,7 @@ MapQuickItem { ...@@ -51,7 +51,7 @@ MapQuickItem {
transform: Rotation { transform: Rotation {
origin.x: vehicleIcon.width / 2 origin.x: vehicleIcon.width / 2
origin.y: vehicleIcon.height / 2 origin.y: vehicleIcon.height / 2
angle: vehicle ? vehicle.heading : 0 angle: vehicle ? vehicle.heading.value : 0
} }
} }
} }
...@@ -29,8 +29,9 @@ This file is part of the QGROUNDCONTROL project ...@@ -29,8 +29,9 @@ This file is part of the QGROUNDCONTROL project
import QtQuick 2.4 import QtQuick 2.4
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.FactSystem 1.0
Item { Item {
id: root id: root
...@@ -41,13 +42,15 @@ Item { ...@@ -41,13 +42,15 @@ Item {
property alias heading: compass.heading property alias heading: compass.heading
property alias rollAngle: attitude.rollAngle property alias rollAngle: attitude.rollAngle
property alias pitchAngle: attitude.pitchAngle property alias pitchAngle: attitude.pitchAngle
property real altitude: 0
property real groundSpeed: 0
property real airSpeed: 0
property real size: _defaultSize property real size: _defaultSize
property bool isSatellite: false property bool isSatellite: false
property bool active: 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 _defaultSize: ScreenTools.defaultFontPixelSize * (9)
property real _sizeRatio: ScreenTools.isTinyScreen ? (size / _defaultSize) * 0.5 : size / _defaultSize property real _sizeRatio: ScreenTools.isTinyScreen ? (size / _defaultSize) * 0.5 : size / _defaultSize
...@@ -84,7 +87,7 @@ Item { ...@@ -84,7 +87,7 @@ Item {
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
} }
QGCLabel { QGCLabel {
text: "Altitude (m)" text: altitudeFact.shortDescription + " (" + altitudeFact.units + ")"
font.pixelSize: _labelFontSize font.pixelSize: _labelFontSize
width: parent.width width: parent.width
height: _labelFontSize height: _labelFontSize
...@@ -92,7 +95,7 @@ Item { ...@@ -92,7 +95,7 @@ Item {
horizontalAlignment: TextEdit.AlignHCenter horizontalAlignment: TextEdit.AlignHCenter
} }
QGCLabel { QGCLabel {
text: altitude < 10000 ? altitude.toFixed(1) : altitude.toFixed(0) text: altitudeFact.valueString
font.pixelSize: _bigFontSize font.pixelSize: _bigFontSize
font.weight: Font.DemiBold font.weight: Font.DemiBold
width: parent.width width: parent.width
...@@ -105,25 +108,25 @@ Item { ...@@ -105,25 +108,25 @@ Item {
width: parent.width * 0.9 width: parent.width * 0.9
color: isSatellite ? Qt.rgba(0,0,0,0.25) : Qt.rgba(1,1,1,0.25) color: isSatellite ? Qt.rgba(0,0,0,0.25) : Qt.rgba(1,1,1,0.25)
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
visible: airSpeed <= 0 && !ScreenTools.isTinyScreen visible: airSpeedFact.value <= 0 && !ScreenTools.isTinyScreen
} }
QGCLabel { QGCLabel {
text: "Ground Speed (km/h)" text: groundSpeedFact.shortDescription + " (" + groundSpeedFact.units + ")"
font.pixelSize: _labelFontSize font.pixelSize: _labelFontSize
width: parent.width width: parent.width
height: _labelFontSize height: _labelFontSize
color: isSatellite ? "black" : "white" color: isSatellite ? "black" : "white"
horizontalAlignment: TextEdit.AlignHCenter horizontalAlignment: TextEdit.AlignHCenter
visible: airSpeed <= 0 && !ScreenTools.isTinyScreen visible: airSpeedFact.value <= 0 && !ScreenTools.isTinyScreen
} }
QGCLabel { QGCLabel {
text: (groundSpeed * 3.6).toFixed(1) text: groundSpeedFact.valueString
font.pixelSize: _normalFontSize font.pixelSize: _normalFontSize
font.weight: Font.DemiBold font.weight: Font.DemiBold
width: parent.width width: parent.width
color: isSatellite ? "black" : "white" color: isSatellite ? "black" : "white"
horizontalAlignment: TextEdit.AlignHCenter horizontalAlignment: TextEdit.AlignHCenter
visible: airSpeed <= 0 && !ScreenTools.isTinyScreen visible: airSpeedFact.value <= 0 && !ScreenTools.isTinyScreen
} }
//-- Air Speed //-- Air Speed
Rectangle { Rectangle {
...@@ -131,24 +134,24 @@ Item { ...@@ -131,24 +134,24 @@ Item {
width: parent.width * 0.9 width: parent.width * 0.9
color: isSatellite ? Qt.rgba(0,0,0,0.25) : Qt.rgba(1,1,1,0.25) color: isSatellite ? Qt.rgba(0,0,0,0.25) : Qt.rgba(1,1,1,0.25)
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
visible: airSpeed > 0 && !ScreenTools.isTinyScreen visible: airSpeedFact.value > 0 && !ScreenTools.isTinyScreen
} }
QGCLabel { QGCLabel {
text: "Air Speed (km/h)" text: airSpeedFact.shortDescription + " (" + airSpeedFact.units + ")"
font.pixelSize: _labelFontSize font.pixelSize: _labelFontSize
width: parent.width width: parent.width
height: _labelFontSize height: _labelFontSize
color: isSatellite ? "black" : "white" color: isSatellite ? "black" : "white"
visible: airSpeed > 0 && !ScreenTools.isTinyScreen visible: airSpeedFact.value > 0 && !ScreenTools.isTinyScreen
horizontalAlignment: TextEdit.AlignHCenter horizontalAlignment: TextEdit.AlignHCenter
} }
QGCLabel { QGCLabel {
text: (airSpeed * 3.6).toFixed(1) text: airSpeedFact.valueString
font.pixelSize: _normalFontSize font.pixelSize: _normalFontSize
font.weight: Font.DemiBold font.weight: Font.DemiBold
width: parent.width width: parent.width
color: isSatellite ? "black" : "white" color: isSatellite ? "black" : "white"
visible: airSpeed > 0 && !ScreenTools.isTinyScreen visible: airSpeedFact.value > 0 && !ScreenTools.isTinyScreen
horizontalAlignment: TextEdit.AlignHCenter horizontalAlignment: TextEdit.AlignHCenter
} }
//-- Compass //-- Compass
......
...@@ -24,6 +24,9 @@ This file is part of the QGROUNDCONTROL project ...@@ -24,6 +24,9 @@ This file is part of the QGROUNDCONTROL project
#include <QJsonArray> #include <QJsonArray>
const char* JsonHelper::_enumStringsJsonKey = "enumStrings";
const char* JsonHelper::_enumValuesJsonKey = "enumValues";
bool JsonHelper::validateRequiredKeys(const QJsonObject& jsonObject, const QStringList& keys, QString& errorString) bool JsonHelper::validateRequiredKeys(const QJsonObject& jsonObject, const QStringList& keys, QString& errorString)
{ {
QString missingKeys; QString missingKeys;
...@@ -71,3 +74,30 @@ bool JsonHelper::toQGeoCoordinate(const QJsonValue& jsonValue, QGeoCoordinate& c ...@@ -71,3 +74,30 @@ bool JsonHelper::toQGeoCoordinate(const QJsonValue& jsonValue, QGeoCoordinate& c
return true; return true;
} }
bool JsonHelper::validateKeyTypes(QJsonObject& jsonObject, const QStringList& keys, const QList<QJsonValue::Type>& types, QString& errorString)
{
for (int i=0; i<keys.count(); i++) {
if (jsonObject.contains(keys[i])) {
if (jsonObject.value(keys[i]).type() != types[i]) {
errorString = QString("Incorrect type key:type:expected %1 %2 %3").arg(keys[i]).arg(jsonObject.value(keys[i]).type()).arg(types[i]);
return false;
}
}
}
return true;
}
bool JsonHelper::parseEnum(QJsonObject& jsonObject, QStringList& enumStrings, QStringList& enumValues, QString& errorString)
{
enumStrings = jsonObject.value(_enumStringsJsonKey).toString().split(",", QString::SkipEmptyParts);
enumValues = jsonObject.value(_enumValuesJsonKey).toString().split(",", QString::SkipEmptyParts);
if (enumStrings.count() != enumValues.count()) {
errorString = QString("enum strings/values count mismatch: %1");
return false;
}
return true;
}
...@@ -31,7 +31,12 @@ class JsonHelper ...@@ -31,7 +31,12 @@ class JsonHelper
{ {
public: public:
static bool validateRequiredKeys(const QJsonObject& jsonObject, const QStringList& keys, QString& errorString); static bool validateRequiredKeys(const QJsonObject& jsonObject, const QStringList& keys, QString& errorString);
static bool validateKeyTypes(QJsonObject& jsonObject, const QStringList& keys, const QList<QJsonValue::Type>& types, QString& errorString);
static bool toQGeoCoordinate(const QJsonValue& jsonValue, QGeoCoordinate& coordinate, bool altitudeRequired, 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 #endif
{
"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"
}
]
}
{
"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
}
]
}
This diff is collapsed.
This diff is collapsed.
{
"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"
}
]
}
...@@ -933,16 +933,16 @@ void QGCXPlaneLink::setRandomPosition() ...@@ -933,16 +933,16 @@ void QGCXPlaneLink::setRandomPosition()
double offLon = rand() / static_cast<double>(RAND_MAX) / 500.0 + 1.0/500.0; double offLon = rand() / static_cast<double>(RAND_MAX) / 500.0 + 1.0/500.0;
double offAlt = rand() / static_cast<double>(RAND_MAX) * 200.0 + 100.0; double offAlt = rand() / static_cast<double>(RAND_MAX) * 200.0 + 100.0;
if (_vehicle->altitudeAMSL() + offAlt < 0) if (_vehicle->altitudeAMSL()->rawValue().toDouble() + offAlt < 0)
{ {
offAlt *= -1.0; offAlt *= -1.0;
} }
setPositionAttitude(_vehicle->latitude() + offLat, setPositionAttitude(_vehicle->latitude() + offLat,
_vehicle->longitude() + offLon, _vehicle->longitude() + offLon,
_vehicle->altitudeAMSL() + offAlt, _vehicle->altitudeAMSL()->rawValue().toDouble() + offAlt,
_vehicle->roll(), _vehicle->roll()->rawValue().toDouble(),
_vehicle->pitch(), _vehicle->pitch()->rawValue().toDouble(),
_vehicle->uas()->getYaw()); _vehicle->uas()->getYaw());
} }
...@@ -957,7 +957,7 @@ void QGCXPlaneLink::setRandomAttitude() ...@@ -957,7 +957,7 @@ void QGCXPlaneLink::setRandomAttitude()
setPositionAttitude(_vehicle->latitude(), setPositionAttitude(_vehicle->latitude(),
_vehicle->longitude(), _vehicle->longitude(),
_vehicle->altitudeAMSL(), _vehicle->altitudeAMSL()->rawValue().toDouble(),
roll, roll,
pitch, pitch,
yaw); yaw);
......
...@@ -188,28 +188,6 @@ Rectangle { ...@@ -188,28 +188,6 @@ Rectangle {
return colorRed; 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: { Component.onCompleted: {
//-- TODO: Get this from the actual state //-- TODO: Get this from the actual state
flyButton.checked = true flyButton.checked = true
...@@ -232,14 +210,14 @@ Rectangle { ...@@ -232,14 +210,14 @@ Rectangle {
anchors.centerIn: parent anchors.centerIn: parent
QGCLabel { QGCLabel {
id: gpsLabel 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 font.weight:Font.DemiBold
color: colorWhite color: colorWhite
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
} }
GridLayout { GridLayout {
id: gpsGrid id: gpsGrid
visible: (activeVehicle && activeVehicle.satelliteCount >= 0) visible: (activeVehicle && activeVehicle.gps.count.value >= 0)
anchors.margins: ScreenTools.defaultFontPixelHeight anchors.margins: ScreenTools.defaultFontPixelHeight
columnSpacing: ScreenTools.defaultFontPixelWidth columnSpacing: ScreenTools.defaultFontPixelWidth
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
...@@ -249,7 +227,7 @@ Rectangle { ...@@ -249,7 +227,7 @@ Rectangle {
color: colorWhite color: colorWhite
} }
QGCLabel { QGCLabel {
text: activeVehicle ? (activeVehicle.satelliteCount) : "N/A" text: activeVehicle ? activeVehicle.gps.count.valueString : "N/A"
color: colorWhite color: colorWhite
} }
QGCLabel { QGCLabel {
...@@ -257,7 +235,7 @@ Rectangle { ...@@ -257,7 +235,7 @@ Rectangle {
color: colorWhite color: colorWhite
} }
QGCLabel { QGCLabel {
text: getGpsLockStatus() text: activeVehicle ? activeVehicle.gps.lock.enumStringValue : "N/A"
color: colorWhite color: colorWhite
} }
QGCLabel { QGCLabel {
...@@ -265,7 +243,7 @@ Rectangle { ...@@ -265,7 +243,7 @@ Rectangle {
color: colorWhite color: colorWhite
} }
QGCLabel { 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 color: colorWhite
} }
QGCLabel { QGCLabel {
...@@ -273,7 +251,7 @@ Rectangle { ...@@ -273,7 +251,7 @@ Rectangle {
color: colorWhite color: colorWhite
} }
QGCLabel { 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 color: colorWhite
} }
QGCLabel { QGCLabel {
...@@ -281,7 +259,7 @@ Rectangle { ...@@ -281,7 +259,7 @@ Rectangle {
color: colorWhite color: colorWhite
} }
QGCLabel { QGCLabel {
text: activeVehicle ? (activeVehicle.satRawCOG).toFixed(2) : "N/A" text: activeVehicle ? activeVehicle.gps.courseOverGround.valueString : "N/A"
color: colorWhite color: colorWhite
} }
} }
......
...@@ -176,18 +176,18 @@ Row { ...@@ -176,18 +176,18 @@ Row {
smooth: true smooth: true
width: mainWindow.tbCellHeight * 0.65 width: mainWindow.tbCellHeight * 0.65
height: mainWindow.tbCellHeight * 0.5 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 anchors.verticalCenter: parent.verticalCenter
} }
SignalStrength { SignalStrength {
size: mainWindow.tbCellHeight * 0.5 size: mainWindow.tbCellHeight * 0.5
percent: activeVehicle ? getSatStrength(activeVehicle.satRawHDOP) : "" percent: activeVehicle ? getSatStrength(activeVehicle.gps.hdop.value) : ""
anchors.verticalCenter: parent.verticalCenter anchors.verticalCenter: parent.verticalCenter
} }
} }
QGCLabel { QGCLabel {
text: (activeVehicle && activeVehicle.satelliteCount >= 0) ? activeVehicle.satelliteCount : "" text: (activeVehicle && activeVehicle.gps.count.value >= 0) ? activeVehicle.gps.count.valueString : ""
visible: (activeVehicle && activeVehicle.satelliteCount >= 0) visible: (activeVehicle && activeVehicle.gps.count.value >= 0)
font.pixelSize: tbFontSmall font.pixelSize: tbFontSmall
color: colorWhite color: colorWhite
anchors.top: parent.top anchors.top: parent.top
......
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