diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 521595b8a31879682174de30585c1fe9611aefda..05f62700201a01c7a661b2f5165b65d9ce376ba9 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -225,6 +225,8 @@ src/FlightDisplay/PreFlightSensorsHealthCheck.qml src/FlightDisplay/PreFlightSoundCheck.qml src/FlightDisplay/PreFlightCheckListShowAction.qml + src/FlightDisplay/ProximityRadarValues.qml + src/FlightDisplay/ProximityRadarVideoView.qml src/FlightDisplay/TerrainProgress.qml src/FlightDisplay/TelemetryValuesBar.qml src/FlightDisplay/VehicleWarnings.qml @@ -244,6 +246,7 @@ src/FlightMap/Widgets/PhotoVideoControl.qml src/FlightMap/MapItems/PlanMapItems.qml src/FlightMap/MapItems/PolygonEditor.qml + src/FlightMap/MapItems/ProximityRadarMapView.qml src/FlightMap/Widgets/QGCArtificialHorizon.qml src/FlightMap/Widgets/QGCAttitudeHUD.qml src/FlightMap/Widgets/QGCAttitudeWidget.qml @@ -271,8 +274,6 @@ src/AnalyzeView/VibrationPage.qml src/FlightDisplay/VirtualJoystick.qml src/PlanView/VTOLLandingPatternEditor.qml - src/FlightMap/MapItems/ProximityRadarMapView.qml - src/FlightDisplay/ProximityRadarVideoView.qml src/FirstRunPromptDialogs/UnitsFirstRunPrompt.qml diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index d080b9f5e3296c2103ec0a85067231e50fcff24a..08de95abcda9c156ad75c4d41c815db616a86e58 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -546,7 +546,7 @@ QString Fact::group(void) const void Fact::setMetaData(FactMetaData* metaData, bool setDefaultFromMetaData) { _metaData = metaData; - if (setDefaultFromMetaData) { + if (setDefaultFromMetaData && metaData->defaultValueAvailable()) { setRawValue(rawDefaultValue()); } emit valueChanged(cookedValue()); diff --git a/src/FactSystem/FactGroup.cc b/src/FactSystem/FactGroup.cc index edb4e8f241a57dee7edc2cabdf4ad25d7c2b819f..436f9d0e0253aec84bc7711f7dfbfffddb2b0a7f 100644 --- a/src/FactSystem/FactGroup.cc +++ b/src/FactSystem/FactGroup.cc @@ -25,6 +25,7 @@ FactGroup::FactGroup(int updateRateMsecs, const QString& metaDataFile, QObject* { _setupTimer(); _nameToFactMetaDataMap = FactMetaData::createMapFromJsonFile(metaDataFile, this); + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); } FactGroup::FactGroup(int updateRateMsecs, QObject* parent, bool ignoreCamelCase) @@ -33,6 +34,7 @@ FactGroup::FactGroup(int updateRateMsecs, QObject* parent, bool ignoreCamelCase) , _ignoreCamelCase(ignoreCamelCase) { _setupTimer(); + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); } void FactGroup::_loadFromJsonArray(const QJsonArray jsonArray) @@ -129,7 +131,7 @@ void FactGroup::_addFact(Fact* fact, const QString& name) fact->setSendValueChangedSignals(_updateRateMSecs == 0); if (_nameToFactMetaDataMap.contains(name)) { - fact->setMetaData(_nameToFactMetaDataMap[name]); + fact->setMetaData(_nameToFactMetaDataMap[name], true /* setDefaultFromMetaData */); } _nameToFactMap[name] = fact; _factNames.append(name); @@ -182,3 +184,11 @@ void FactGroup::handleMessage(Vehicle* /* vehicle */, mavlink_message_t& /* mess { // Default implementation does nothing } + +void FactGroup::_setTelemetryAvailable (bool telemetryAvailable) +{ + if (telemetryAvailable != _telemetryAvailable) { + _telemetryAvailable = telemetryAvailable; + emit telemetryAvailableChanged(_telemetryAvailable); + } +} diff --git a/src/FactSystem/FactGroup.h b/src/FactSystem/FactGroup.h index 6ece49957eb724b1ef4aa1767d4151f204fb3ecd..114fb44f4e0dfd82322082438f0528052a17411f 100644 --- a/src/FactSystem/FactGroup.h +++ b/src/FactSystem/FactGroup.h @@ -28,8 +28,9 @@ public: FactGroup(int updateRateMsecs, const QString& metaDataFile, QObject* parent = nullptr, bool ignoreCamelCase = false); FactGroup(int updateRateMsecs, QObject* parent = nullptr, bool ignoreCamelCase = false); - Q_PROPERTY(QStringList factNames READ factNames NOTIFY factNamesChanged) - Q_PROPERTY(QStringList factGroupNames READ factGroupNames NOTIFY factGroupNamesChanged) + Q_PROPERTY(QStringList factNames READ factNames NOTIFY factNamesChanged) + Q_PROPERTY(QStringList factGroupNames READ factGroupNames NOTIFY factGroupNamesChanged) + Q_PROPERTY(bool telemetryAvailable READ telemetryAvailable NOTIFY telemetryAvailableChanged) ///< false: No telemetry for these values has been received /// @ return true: if the fact exists in the group Q_INVOKABLE bool factExists(const QString& name); @@ -45,23 +46,26 @@ public: /// Turning on live updates will allow value changes to flow through as they are received. Q_INVOKABLE void setLiveUpdates(bool liveUpdates); - QStringList factNames(void) const { return _factNames; } - QStringList factGroupNames(void) const { return _nameToFactGroupMap.keys(); } + QStringList factNames (void) const { return _factNames; } + QStringList factGroupNames (void) const { return _nameToFactGroupMap.keys(); } + bool telemetryAvailable (void) const { return _telemetryAvailable; } /// Allows a FactGroup to parse incoming messages and fill in values virtual void handleMessage(Vehicle* vehicle, mavlink_message_t& message); signals: - void factNamesChanged (void); - void factGroupNamesChanged (void); + void factNamesChanged (void); + void factGroupNamesChanged (void); + void telemetryAvailableChanged (bool telemetryAvailable); protected slots: virtual void _updateAllValues(void); protected: - void _addFact (Fact* fact, const QString& name); - void _addFactGroup (FactGroup* factGroup, const QString& name); - void _loadFromJsonArray (const QJsonArray jsonArray); + void _addFact (Fact* fact, const QString& name); + void _addFactGroup (FactGroup* factGroup, const QString& name); + void _loadFromJsonArray (const QJsonArray jsonArray); + void _setTelemetryAvailable (bool telemetryAvailable); int _updateRateMSecs; ///< Update rate for Fact::valueChanged signals, 0: immediate update @@ -74,6 +78,7 @@ private: void _setupTimer (void); QString _camelCase (const QString& text); - bool _ignoreCamelCase = false; + bool _ignoreCamelCase = false; QTimer _updateTimer; + bool _telemetryAvailable = false; }; diff --git a/src/FlightDisplay/FlyViewVideo.qml b/src/FlightDisplay/FlyViewVideo.qml index 0fa32bd115b6e810c571498bc3b07c0728500f46..4a00d2b9422313ccca64cc721b0e7d1d7f3e39df 100644 --- a/src/FlightDisplay/FlyViewVideo.qml +++ b/src/FlightDisplay/FlyViewVideo.qml @@ -70,7 +70,7 @@ Item { } ProximityRadarVideoView{ - anchors.fill: parent - vehicle: QGroundControl.multiVehicleManager.activeVehicle + anchors.fill: parent + vehicle: QGroundControl.multiVehicleManager.activeVehicle } } diff --git a/src/FlightDisplay/ProximityRadarValues.qml b/src/FlightDisplay/ProximityRadarValues.qml new file mode 100644 index 0000000000000000000000000000000000000000..226f5a2c4d0c154146c41c6d034749abde983c70 --- /dev/null +++ b/src/FlightDisplay/ProximityRadarValues.qml @@ -0,0 +1,54 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +import QtQuick 2.12 + +/// Object which exposes vehicle distanceSensors FactGroup information for use in UI +QtObject { + property var vehicle + + property bool telemetryAvailable: vehicle && vehicle.distanceSensors.telemetryAvailable + + signal rotationValueChanged ///< Signalled when any available rotation value changes + + property real rotationNoneValue: _distanceSensors ? _distanceSensors.rotationNone.value : NaN + property real rotationYaw45Value: _distanceSensors ? _distanceSensors.rotationYaw45.value : NaN + property real rotationYaw90Value: _distanceSensors ? _distanceSensors.rotationYaw90.value : NaN + property real rotationYaw135Value: _distanceSensors ? _distanceSensors.rotationYaw135.value : NaN + property real rotationYaw180Value: _distanceSensors ? _distanceSensors.rotationYaw180.value : NaN + property real rotationYaw225Value: _distanceSensors ? _distanceSensors.rotationYaw225.value : NaN + property real rotationYaw270Value: _distanceSensors ? _distanceSensors.rotationYaw270.value : NaN + property real rotationYaw315Value: _distanceSensors ? _distanceSensors.rotationYaw315.value : NaN + property real maxDistance: _distanceSensors ? _distanceSensors.maxDistance.value : NaN + + property string rotationNoneValueString: _distanceSensors ? _distanceSensors.rotationNone.valueString : _noValueStr + property string rotationYaw45ValueString: _distanceSensors ? _distanceSensors.rotationYaw45.valueString : _noValueStr + property string rotationYaw90ValueString: _distanceSensors ? _distanceSensors.rotationYaw90.valueString : _noValueStr + property string rotationYaw135ValueString: _distanceSensors ? _distanceSensors.rotationYaw135.valueString : _noValueStr + property string rotationYaw180ValueString: _distanceSensors ? _distanceSensors.rotationYaw180.valueString : _noValueStr + property string rotationYaw225ValueString: _distanceSensors ? _distanceSensors.rotationYaw225.valueString : _noValueStr + property string rotationYaw270ValueString: _distanceSensors ? _distanceSensors.rotationYaw270.valueString : _noValueStr + property string rotationYaw315ValueString: _distanceSensors ? _distanceSensors.rotationYaw315.valueString : _noValueStr + + property var rgRotationValues: [ rotationNoneValue, rotationYaw45Value, rotationYaw90Value, rotationYaw135Value, rotationYaw180Value, rotationYaw225Value, rotationYaw270Value, rotationYaw315Value ] + property var rgRotationValueStrings: [ rotationNoneValueString, rotationYaw45ValueString, rotationYaw90ValueString, rotationYaw135ValueString, rotationYaw180ValueString, rotationYaw225ValueString, rotationYaw270ValueString, rotationYaw315ValueString ] + + property var _distanceSensors: vehicle ? vehicle.distanceSensors : null + property string _noValueStr: qsTr("--.--") + + onRotationNoneValueChanged: rotationValueChanged() + onRotationYaw45ValueChanged: rotationValueChanged() + onRotationYaw90ValueChanged: rotationValueChanged() + onRotationYaw135ValueChanged: rotationValueChanged() + onRotationYaw180ValueChanged: rotationValueChanged() + onRotationYaw225ValueChanged: rotationValueChanged() + onRotationYaw270ValueChanged: rotationValueChanged() + onRotationYaw315ValueChanged: rotationValueChanged() +} + diff --git a/src/FlightDisplay/ProximityRadarVideoView.qml b/src/FlightDisplay/ProximityRadarVideoView.qml index ea5d0e71c4c0773a2a818cda649105b5fe2e2a36..84d03119de404d916c7c8bc12d08fba0bbb2ec0c 100644 --- a/src/FlightDisplay/ProximityRadarVideoView.qml +++ b/src/FlightDisplay/ProximityRadarVideoView.qml @@ -16,93 +16,76 @@ import QGroundControl 1.0 import QGroundControl.ScreenTools 1.0 import QGroundControl.Vehicle 1.0 import QGroundControl.Controls 1.0 -//import QGroundControl.Controllers 1.0 +import QGroundControl.FlightDisplay 1.0 - - -/// Marker for displaying a vehicle location on the map Item { id: _root - anchors.fill: parent - - property var vehicle /// Vehicle object, undefined for ADSB vehicle - property var range - - property var _distanceSensor: vehicle?vehicle.distanceSensors:null - property var _range: range?range:6 // default 6m view + anchors.fill: parent + visible: proximityValues.telemetryAvailable - property var _rotationNone: _distanceSensor?_distanceSensor.rotationNone.value:0 - property var _rotationYaw45: _distanceSensor?_distanceSensor.rotationYaw45.value:0 - property var _rotationYaw90: _distanceSensor?_distanceSensor.rotationYaw90.value:0 - property var _rotationYaw135: _distanceSensor?_distanceSensor.rotationYaw135.value:0 - property var _rotationYaw180: _distanceSensor?_distanceSensor.rotationYaw180.value:0 - property var _rotationYaw225: _distanceSensor?_distanceSensor.rotationYaw225.value:0 - property var _rotationYaw270: _distanceSensor?_distanceSensor.rotationYaw270.value:0 - property var _rotationYaw315: _distanceSensor?_distanceSensor.rotationYaw315.value:0 - property var _rottab: [_rotationNone,_rotationYaw45,_rotationYaw90,_rotationYaw135,_rotationYaw180,_rotationYaw225,_rotationYaw270,_rotationYaw315] + property var vehicle ///< Vehicle object, undefined for ADSB vehicle + property real range: 6 ///< Default 6m view -// on_RottabChanged: _sectorViewEllipsoid.requestPaint() - on_RotationNoneChanged: _sectorViewEllipsoid.requestPaint() - on_RotationYaw45Changed: _sectorViewEllipsoid.requestPaint() - on_RotationYaw90Changed: _sectorViewEllipsoid.requestPaint() - on_RotationYaw135Changed: _sectorViewEllipsoid.requestPaint() - on_RotationYaw180Changed: _sectorViewEllipsoid.requestPaint() - on_RotationYaw225Changed: _sectorViewEllipsoid.requestPaint() - on_RotationYaw270Changed: _sectorViewEllipsoid.requestPaint() - on_RotationYaw315Changed: _sectorViewEllipsoid.requestPaint() + property var _minlength: Math.min(_root.width,_root.height) + property var _ratio: (_minlength / 2) / _root.range - property var _minlength: Math.min(_root.width,_root.height) - property var _ratio: (_minlength/2)/_root._range + ProximityRadarValues { + id: proximityValues + vehicle: _root.vehicle + onRotationValueChanged: _sectorViewEllipsoid.requestPaint() + } Canvas{ - id:_sectorViewEllipsoid - anchors.fill: _root - opacity: 0.5 - visible: _distanceSensor?true:false + id: _sectorViewEllipsoid + anchors.fill: _root + opacity: 0.5 + onPaint: { - if(_distanceSensor) { - var ctx = getContext("2d"); - ctx.reset(); - ctx.translate(width/2,height/2) - ctx.strokeStyle = Qt.rgba(1, 0, 0, 1); - ctx.lineWidth = width/100; - ctx.scale(_root.width / _minlength,_root.height / _minlength); - ctx.rotate(-Math.PI/2-Math.PI/8); - for(var i=0; i< _rottab.length; i++) - { - var a=Math.PI/4*i; - ctx.beginPath(); - ctx.arc(0,0,_rottab[i]*_ratio,0+a+Math.PI/50,Math.PI/4+a-Math.PI/50,false); - ctx.stroke(); - } + var ctx = getContext("2d"); + ctx.reset(); + ctx.translate(width/2, height/2) + ctx.strokeStyle = Qt.rgba(1, 0, 0, 1); + ctx.lineWidth = width/100; + ctx.scale(_root.width / _minlength, _root.height / _minlength); + ctx.rotate(-Math.PI/2 - Math.PI/8); + for (var i=0; i 1 - property real _ratio: 1 - - property var _distanceSensor: vehicle?vehicle.distanceSensors:null - property var _maxSensor: _distanceSensor?_distanceSensor.maxDistance.value:1 //need to change in cc - property var _rotationNone: _distanceSensor?_distanceSensor.rotationNone.value:0 - property var _rotationYaw45: _distanceSensor?_distanceSensor.rotationYaw45.value:0 - property var _rotationYaw90: _distanceSensor?_distanceSensor.rotationYaw90.value:0 - property var _rotationYaw135: _distanceSensor?_distanceSensor.rotationYaw135.value:0 - property var _rotationYaw180: _distanceSensor?_distanceSensor.rotationYaw180.value:0 - property var _rotationYaw225: _distanceSensor?_distanceSensor.rotationYaw225.value:0 - property var _rotationYaw270: _distanceSensor?_distanceSensor.rotationYaw270.value:0 - property var _rotationYaw315: _distanceSensor?_distanceSensor.rotationYaw315.value:0 - property var _rottab: [_rotationNone,_rotationYaw45,_rotationYaw90,_rotationYaw135,_rotationYaw180,_rotationYaw225,_rotationYaw270,_rotationYaw315] - - function calcSize(){ - if(_map) { - var scaleLinePixelLength = 100 - var leftCoord = _map.toCoordinate(Qt.point(0, 0), false /* clipToViewPort */) - var rightCoord = _map.toCoordinate(Qt.point(scaleLinePixelLength, 0), false /* clipToViewPort */) - var scaleLineMeters = Math.round(leftCoord.distanceTo(rightCoord)) - } - _ratio=scaleLinePixelLength/scaleLineMeters; - } - on_RotationNoneChanged: vehicleSensors.requestPaint() - on_RotationYaw45Changed: vehicleSensors.requestPaint() - on_RotationYaw90Changed: vehicleSensors.requestPaint() - on_RotationYaw135Changed: vehicleSensors.requestPaint() - on_RotationYaw180Changed: vehicleSensors.requestPaint() - on_RotationYaw225Changed: vehicleSensors.requestPaint() - on_RotationYaw270Changed: vehicleSensors.requestPaint() - on_RotationYaw315Changed: vehicleSensors.requestPaint() + property real _ratio: 1 + property real _maxDistance: isNaN(proximityValues.maxDistance) + function calcSize() { + var scaleLinePixelLength = 100 + var leftCoord = map.toCoordinate(Qt.point(0, 0), false /* clipToViewPort */) + var rightCoord = map.toCoordinate(Qt.point(scaleLinePixelLength, 0), false /* clipToViewPort */) + var scaleLineMeters = Math.round(leftCoord.distanceTo(rightCoord)) + _ratio = scaleLinePixelLength / scaleLineMeters; + } + ProximityRadarValues { + id: proximityValues + vehicle: _root.vehicle + onRotationValueChanged: vehicleSensors.requestPaint() + } Connections { target: map @@ -91,48 +67,52 @@ MapQuickItem { height: detectionLimitCircle.height opacity: 0.5 + Component.onCompleted: calcSize() + Canvas{ id: vehicleSensors anchors.fill: detectionLimitCircle + transform: Rotation { origin.x: detectionLimitCircle.width / 2 origin.y: detectionLimitCircle.height / 2 angle: isNaN(heading) ? 0 : heading } - function deg2rad(degrees) - { - var pi = Math.PI; - return degrees * (pi/180); + + function deg2rad(degrees) { + var pi = Math.PI; + return degrees * (pi/180); } + onPaint: { - if(_distanceSensor) - { - var ctx = getContext("2d"); - ctx.reset(); - ctx.translate(width/2,height/2) - ctx.rotate(-Math.PI/2); - ctx.lineWidth = 5; - ctx.strokeStyle = Qt.rgba(1, 0, 0, 1); - for(var i=0; i<_rottab.length;i++){ - var a=deg2rad(360-22.5)+Math.PI/4*i; - ctx.beginPath(); - ctx.arc(0,0,_rottab[i]*_ratio, a,a+Math.PI/4,false); - ctx.stroke(); - } - - } + var ctx = getContext("2d"); + ctx.reset(); + ctx.translate(width/2, height/2) + ctx.rotate(-Math.PI/2); + ctx.lineWidth = 5; + ctx.strokeStyle = Qt.rgba(1, 0, 0, 1); + for(var i=0; ipercentRemaining()->setRawValue(highLatency.battery_remaining == UINT8_MAX ? qQNaN() : highLatency.battery_remaining); + group->_setTelemetryAvailable(true); } void VehicleBatteryFactGroup::_handleHighLatency2(Vehicle* vehicle, mavlink_message_t& message) @@ -119,6 +120,7 @@ void VehicleBatteryFactGroup::_handleHighLatency2(Vehicle* vehicle, mavlink_mess VehicleBatteryFactGroup* group = _findOrAddBatteryGroupById(vehicle, 0); group->percentRemaining()->setRawValue(highLatency2.battery == -1 ? qQNaN() : highLatency2.battery); + group->_setTelemetryAvailable(true); } void VehicleBatteryFactGroup::_handleBatteryStatus(Vehicle* vehicle, mavlink_message_t& message) @@ -151,6 +153,7 @@ void VehicleBatteryFactGroup::_handleBatteryStatus(Vehicle* vehicle, mavlink_mes group->timeRemaining()->setRawValue (batteryStatus.time_remaining == 0 ? qQNaN() : batteryStatus.time_remaining); group->chargeState()->setRawValue (batteryStatus.charge_state); group->instantPower()->setRawValue (totalVoltage * group->current()->rawValue().toDouble()); + group->_setTelemetryAvailable(true); } VehicleBatteryFactGroup* VehicleBatteryFactGroup::_findOrAddBatteryGroupById(Vehicle* vehicle, uint8_t batteryId) diff --git a/src/Vehicle/VehicleClockFactGroup.cc b/src/Vehicle/VehicleClockFactGroup.cc index ab771f458175b345fa96042542fb95a6d4cfdd49..c2c8d1a94d16dda8d0f0193ffc8895281b95e330 100644 --- a/src/Vehicle/VehicleClockFactGroup.cc +++ b/src/Vehicle/VehicleClockFactGroup.cc @@ -30,6 +30,7 @@ void VehicleClockFactGroup::_updateAllValues() { _currentTimeFact.setRawValue(QTime::currentTime().toString()); _currentDateFact.setRawValue(QDateTime::currentDateTime().toString(QLocale::system().dateFormat(QLocale::ShortFormat))); + _setTelemetryAvailable(true); FactGroup::_updateAllValues(); } diff --git a/src/Vehicle/VehicleDistanceSensorFactGroup.cc b/src/Vehicle/VehicleDistanceSensorFactGroup.cc index c4c46f18fbec564d9b2ba6da02b240df045ae0f7..40217af81d67ad3b5c884ece1bf59bf3b8ee349f 100644 --- a/src/Vehicle/VehicleDistanceSensorFactGroup.cc +++ b/src/Vehicle/VehicleDistanceSensorFactGroup.cc @@ -20,6 +20,7 @@ const char* VehicleDistanceSensorFactGroup::_rotationYaw270FactName = "rotatio const char* VehicleDistanceSensorFactGroup::_rotationYaw315FactName = "rotationYaw315"; const char* VehicleDistanceSensorFactGroup::_rotationPitch90FactName = "rotationPitch90"; const char* VehicleDistanceSensorFactGroup::_rotationPitch270FactName = "rotationPitch270"; +const char* VehicleDistanceSensorFactGroup::_minDistanceFactName = "minDistance"; const char* VehicleDistanceSensorFactGroup::_maxDistanceFactName = "maxDistance"; VehicleDistanceSensorFactGroup::VehicleDistanceSensorFactGroup(QObject* parent) @@ -34,6 +35,7 @@ VehicleDistanceSensorFactGroup::VehicleDistanceSensorFactGroup(QObject* parent) , _rotationYaw315Fact (0, _rotationYaw315FactName, FactMetaData::valueTypeDouble) , _rotationPitch90Fact (0, _rotationPitch90FactName, FactMetaData::valueTypeDouble) , _rotationPitch270Fact (0, _rotationPitch270FactName, FactMetaData::valueTypeDouble) + , _minDistanceFact (0, _minDistanceFactName, FactMetaData::valueTypeDouble) , _maxDistanceFact (0, _maxDistanceFactName, FactMetaData::valueTypeDouble) { _addFact(&_rotationNoneFact, _rotationNoneFactName); @@ -46,19 +48,8 @@ VehicleDistanceSensorFactGroup::VehicleDistanceSensorFactGroup(QObject* parent) _addFact(&_rotationYaw315Fact, _rotationYaw315FactName); _addFact(&_rotationPitch90Fact, _rotationPitch90FactName); _addFact(&_rotationPitch270Fact, _rotationPitch270FactName); + _addFact(&_minDistanceFact, _minDistanceFactName); _addFact(&_maxDistanceFact, _maxDistanceFactName); - - // Start out as not available "--.--" - _rotationNoneFact.setRawValue(qQNaN()); - _rotationYaw45Fact.setRawValue(qQNaN()); - _rotationYaw135Fact.setRawValue(qQNaN()); - _rotationYaw90Fact.setRawValue(qQNaN()); - _rotationYaw180Fact.setRawValue(qQNaN()); - _rotationYaw225Fact.setRawValue(qQNaN()); - _rotationYaw270Fact.setRawValue(qQNaN()); - _rotationPitch90Fact.setRawValue(qQNaN()); - _rotationPitch270Fact.setRawValue(qQNaN()); - _maxDistanceFact.setRawValue(qQNaN()); } void VehicleDistanceSensorFactGroup::handleMessage(Vehicle* /* vehicle */, mavlink_message_t& message) @@ -95,6 +86,8 @@ void VehicleDistanceSensorFactGroup::handleMessage(Vehicle* /* vehicle */, mavli if (orientation2Fact.orientation == distanceSensor.orientation) { orientation2Fact.fact->setRawValue(distanceSensor.current_distance / 100.0); // cm to meters } - maxDistance()->setRawValue(distanceSensor.max_distance/100.0); } + + maxDistance()->setRawValue(distanceSensor.max_distance / 100.0); + _setTelemetryAvailable(true); } diff --git a/src/Vehicle/VehicleDistanceSensorFactGroup.h b/src/Vehicle/VehicleDistanceSensorFactGroup.h index dfc219ed1adc690cee405d7d8a105da71eb8c05f..d3659f4cea32f7583ba2c1175de6dbd77248e452 100644 --- a/src/Vehicle/VehicleDistanceSensorFactGroup.h +++ b/src/Vehicle/VehicleDistanceSensorFactGroup.h @@ -31,6 +31,7 @@ public: Q_PROPERTY(Fact* rotationYaw315 READ rotationYaw315 CONSTANT) Q_PROPERTY(Fact* rotationPitch90 READ rotationPitch90 CONSTANT) Q_PROPERTY(Fact* rotationPitch270 READ rotationPitch270 CONSTANT) + Q_PROPERTY(Fact* minDistance READ minDistance CONSTANT) Q_PROPERTY(Fact* maxDistance READ maxDistance CONSTANT) Fact* rotationNone () { return &_rotationNoneFact; } @@ -43,6 +44,7 @@ public: Fact* rotationYaw315 () { return &_rotationYaw315Fact; } Fact* rotationPitch90 () { return &_rotationPitch90Fact; } Fact* rotationPitch270 () { return &_rotationPitch270Fact; } + Fact* minDistance () { return &_minDistanceFact; } Fact* maxDistance () { return &_maxDistanceFact; } // Overrides from FactGroup @@ -58,6 +60,7 @@ public: static const char* _rotationYaw315FactName; static const char* _rotationPitch90FactName; static const char* _rotationPitch270FactName; + static const char* _minDistanceFactName; static const char* _maxDistanceFactName; private: @@ -71,5 +74,6 @@ private: Fact _rotationYaw315Fact; Fact _rotationPitch90Fact; Fact _rotationPitch270Fact; + Fact _minDistanceFact; Fact _maxDistanceFact; }; diff --git a/src/Vehicle/VehicleEstimatorStatusFactGroup.cc b/src/Vehicle/VehicleEstimatorStatusFactGroup.cc index 516b085f79e59ae70743236e2c6b2d6801ee7fc9..03d633a0230bf86e95d9e874dbb9c8b711b280ab 100644 --- a/src/Vehicle/VehicleEstimatorStatusFactGroup.cc +++ b/src/Vehicle/VehicleEstimatorStatusFactGroup.cc @@ -105,4 +105,6 @@ void VehicleEstimatorStatusFactGroup::handleMessage(Vehicle* /* vehicle */, mavl tasRatio()->setRawValue (estimatorStatus.tas_ratio); horizPosAccuracy()->setRawValue (estimatorStatus.pos_horiz_accuracy); vertPosAccuracy()->setRawValue (estimatorStatus.pos_vert_accuracy); + + _setTelemetryAvailable(true); } diff --git a/src/Vehicle/VehicleSetpointFactGroup.cc b/src/Vehicle/VehicleSetpointFactGroup.cc index 993f0e2d59ecc7531727d1d26cf0309023e7b7c4..3456400ccb1cf34071385493f2aeaf9556f22498 100644 --- a/src/Vehicle/VehicleSetpointFactGroup.cc +++ b/src/Vehicle/VehicleSetpointFactGroup.cc @@ -64,4 +64,6 @@ void VehicleSetpointFactGroup::handleMessage(Vehicle* /* vehicle */, mavlink_mes rollRate()->setRawValue (qRadiansToDegrees(attitudeTarget.body_roll_rate)); pitchRate()->setRawValue(qRadiansToDegrees(attitudeTarget.body_pitch_rate)); yawRate()->setRawValue (qRadiansToDegrees(attitudeTarget.body_yaw_rate)); + + _setTelemetryAvailable(true); } diff --git a/src/Vehicle/VehicleTemperatureFactGroup.cc b/src/Vehicle/VehicleTemperatureFactGroup.cc index 96cef80261ea3037d8b1039421a093f34f5bb4f3..17efafadff27b42f5fcafc3112e33b1baa5a2df9 100644 --- a/src/Vehicle/VehicleTemperatureFactGroup.cc +++ b/src/Vehicle/VehicleTemperatureFactGroup.cc @@ -58,6 +58,7 @@ void VehicleTemperatureFactGroup::_handleHighLatency(mavlink_message_t& message) mavlink_high_latency_t highLatency; mavlink_msg_high_latency_decode(&message, &highLatency); temperature1()->setRawValue(highLatency.temperature_air); + _setTelemetryAvailable(true); } void VehicleTemperatureFactGroup::_handleHighLatency2(mavlink_message_t& message) @@ -65,6 +66,7 @@ void VehicleTemperatureFactGroup::_handleHighLatency2(mavlink_message_t& message mavlink_high_latency2_t highLatency2; mavlink_msg_high_latency2_decode(&message, &highLatency2); temperature1()->setRawValue(highLatency2.temperature_air); + _setTelemetryAvailable(true); } void VehicleTemperatureFactGroup::_handleScaledPressure(mavlink_message_t& message) @@ -72,6 +74,7 @@ void VehicleTemperatureFactGroup::_handleScaledPressure(mavlink_message_t& messa mavlink_scaled_pressure_t pressure; mavlink_msg_scaled_pressure_decode(&message, &pressure); temperature1()->setRawValue(pressure.temperature / 100.0); + _setTelemetryAvailable(true); } void VehicleTemperatureFactGroup::_handleScaledPressure2(mavlink_message_t& message) @@ -79,6 +82,7 @@ void VehicleTemperatureFactGroup::_handleScaledPressure2(mavlink_message_t& mess mavlink_scaled_pressure2_t pressure; mavlink_msg_scaled_pressure2_decode(&message, &pressure); temperature2()->setRawValue(pressure.temperature / 100.0); + _setTelemetryAvailable(true); } void VehicleTemperatureFactGroup::_handleScaledPressure3(mavlink_message_t& message) @@ -86,4 +90,5 @@ void VehicleTemperatureFactGroup::_handleScaledPressure3(mavlink_message_t& mess mavlink_scaled_pressure3_t pressure; mavlink_msg_scaled_pressure3_decode(&message, &pressure); temperature3()->setRawValue(pressure.temperature / 100.0); + _setTelemetryAvailable(true); } diff --git a/src/Vehicle/VehicleVibrationFactGroup.cc b/src/Vehicle/VehicleVibrationFactGroup.cc index 76cda6431eb8126db6eb427d520964f62a1a9658..f82eb4bcdcd9c800bb44ca8fa19fa7fea3afae0f 100644 --- a/src/Vehicle/VehicleVibrationFactGroup.cc +++ b/src/Vehicle/VehicleVibrationFactGroup.cc @@ -54,5 +54,6 @@ void VehicleVibrationFactGroup::handleMessage(Vehicle* /* vehicle */, mavlink_me clipCount1()->setRawValue(vibration.clipping_0); clipCount2()->setRawValue(vibration.clipping_1); clipCount3()->setRawValue(vibration.clipping_2); + _setTelemetryAvailable(true); } diff --git a/src/Vehicle/VehicleWindFactGroup.cc b/src/Vehicle/VehicleWindFactGroup.cc index 3c84c39a4b626c4c68325de8328d4805f49e90fe..58d81f64c52bf7ed426c8fe37497ee67938893e6 100644 --- a/src/Vehicle/VehicleWindFactGroup.cc +++ b/src/Vehicle/VehicleWindFactGroup.cc @@ -59,6 +59,7 @@ void VehicleWindFactGroup::_handleHighLatency(mavlink_message_t& message) mavlink_high_latency_t highLatency; mavlink_msg_high_latency_decode(&message, &highLatency); speed()->setRawValue((double)highLatency.airspeed / 5.0); + _setTelemetryAvailable(true); } void VehicleWindFactGroup::_handleHighLatency2(mavlink_message_t& message) @@ -67,6 +68,7 @@ void VehicleWindFactGroup::_handleHighLatency2(mavlink_message_t& message) mavlink_msg_high_latency2_decode(&message, &highLatency2); direction()->setRawValue((double)highLatency2.wind_heading * 2.0); speed()->setRawValue((double)highLatency2.windspeed / 5.0); + _setTelemetryAvailable(true); } void VehicleWindFactGroup::_handleWindCov(mavlink_message_t& message) @@ -84,6 +86,7 @@ void VehicleWindFactGroup::_handleWindCov(mavlink_message_t& message) this->direction()->setRawValue(direction); this->speed()->setRawValue(speed); verticalSpeed()->setRawValue(0); + _setTelemetryAvailable(true); } #if !defined(NO_ARDUPILOT_DIALECT) @@ -100,5 +103,6 @@ void VehicleWindFactGroup::_handleWind(mavlink_message_t& message) this->direction()->setRawValue(direction); speed()->setRawValue(wind.speed); verticalSpeed()->setRawValue(wind.speed_z); + _setTelemetryAvailable(true); } #endif