diff --git a/ChangeLog.md b/ChangeLog.md index 527403c9163b1748ede7713852849dbaa721afd9..87b4933c5ffbf865a92f54375753cabe6e4fe985 100644 --- a/ChangeLog.md +++ b/ChangeLog.md @@ -7,13 +7,15 @@ Note: This file only contains high level features or important fixes. * Support mavlink terrain protocol which queries gcs for terrain height information. Allows planning missions with TERRAIN\_FRAME. * Fly: New instrument values display/editing support * Plan: Added new VTOL Landing Pattern support +* Plan: Much better conversion of missions to KML for 3d visualization/verification of missions ## 4.0 ### 4.0.6 - Not yet released -* Plan: Much better conversion of missions to KML for 3d visualization/verification of missions * Analyze/Log Download - Fix download on mobile versions of QGC +* Fly: Fix problems where Continue Mission and Change Altitude were not available after a Mission Pause. +* PX4 Flow: Fix video display problem ### 4.0.5 - Stable diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index efe625f51700b66eaf689bf2dcc003f9f28b8150..e000ac8c29413a471f09e94a21c3e59a60a2cccf 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -912,6 +912,11 @@ void APMFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu return; } + if (abs(altitudeChange) < 0.01) { + // This prevents unecessary changes to Guided mode when the users selects pause and doesn't really touch the altitude slider + return; + } + setGuidedMode(vehicle, true); mavlink_message_t msg; diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml index 92644b07cb6f1f4328d7b836726de725318a5e45..1b5844b725a32a669949b62678b2fb059fe5576b 100644 --- a/src/FlightDisplay/FlightDisplayView.qml +++ b/src/FlightDisplay/FlightDisplayView.qml @@ -639,8 +639,7 @@ Item { { name: qsTr("Action"), iconSource: "/res/action.svg", - buttonVisible: !_guidedController.showPause, - buttonEnabled: _anyActionAvailable, + buttonVisible: _anyActionAvailable, action: -1 } ] diff --git a/src/FlightDisplay/GuidedActionsController.qml b/src/FlightDisplay/GuidedActionsController.qml index b3027d3605e159ee38868c90e30150c0885b7887..1507646aa06455cb5dc5d1749b24aba9a4ea028e 100644 --- a/src/FlightDisplay/GuidedActionsController.qml +++ b/src/FlightDisplay/GuidedActionsController.qml @@ -203,7 +203,12 @@ Item { } _outputState() } - // End of hack + onShowChangeAltChanged: { + if (_corePlugin.guidedActionsControllerLogging()) { + console.log("showChangeAlt", showChangeAlt) + } + _outputState() + } on_VehicleFlyingChanged: { _outputState() diff --git a/src/FlightDisplay/PreFlightCheckList.qml b/src/FlightDisplay/PreFlightCheckList.qml index 6115e3f7bc8842248392e5571608e20ddee409f8..1a81e0672888afdbaae78bd1e42f447cd0f31cf6 100644 --- a/src/FlightDisplay/PreFlightCheckList.qml +++ b/src/FlightDisplay/PreFlightCheckList.qml @@ -31,6 +31,11 @@ Rectangle { } property bool allChecksPassed: false + property var vehicleCopy: activeVehicle + + onVehicleCopyChanged: { + checkListRepeater.model.reset() + } onAllChecksPassedChanged: { if (allChecksPassed) { diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 1ab8d80cffdb955b8124508f3bf1bacc2e9e16ea..822fd38cddd9adbfc0892f86c08899dfe068049b 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -27,6 +27,7 @@ #include #include #include +#include #ifdef QGC_ENABLE_BLUETOOTH #include @@ -102,6 +103,7 @@ #include "TrajectoryPoints.h" #include "ValuesWidgetController.h" #include "RCToParamDialogController.h" +#include "QGCImageProvider.h" #if defined(QGC_ENABLE_PAIRING) #include "PairingManager.h" @@ -573,6 +575,10 @@ bool QGCApplication::_initForNormalAppBoot() _qmlAppEngine = toolbox()->corePlugin()->createRootWindow(this); + // Image provider for PX4 Flow + QQuickImageProvider* pImgProvider = dynamic_cast(qgcApp()->toolbox()->imageProvider()); + _qmlAppEngine->addImageProvider(QStringLiteral("QGCImages"), pImgProvider); + QQuickWindow* rootWindow = (QQuickWindow*)qgcApp()->mainRootWindow(); if (rootWindow) { diff --git a/src/Settings/AppSettings.cc b/src/Settings/AppSettings.cc index 5c83d5c70413274a8a9aec0735a15fa84c7ec673..a77836e5e9e43d407bb5aad8acfdbed25f8b1491 100644 --- a/src/Settings/AppSettings.cc +++ b/src/Settings/AppSettings.cc @@ -43,7 +43,13 @@ DECLARE_SETTINGGROUP(App, "") SettingsFact* savePathFact = qobject_cast(savePath()); QString appName = qgcApp()->applicationName(); +#ifdef __mobile__ + // Mobile builds always use the runtime generated location for savePath. The reason is that for example on iOS the save path includes + // a UID for the app in it. When you then update the app that UID could change which in turn makes any saved value invalid. + if (true) { +#else if (savePathFact->rawValue().toString().isEmpty() && _nameToMetaDataMap[savePathName]->rawDefaultValue().toString().isEmpty()) { +#endif #ifdef __mobile__ #ifdef __ios__ QDir rootDir = QDir(QStandardPaths::writableLocation(QStandardPaths::AppDataLocation)); diff --git a/src/Settings/Video.SettingsGroup.json b/src/Settings/Video.SettingsGroup.json index 4b5a6cc99159fc9f5f1b3ad30a19b26886969c98..c9cd28a0407e4290250394e2c70abca56880acfb 100644 --- a/src/Settings/Video.SettingsGroup.json +++ b/src/Settings/Video.SettingsGroup.json @@ -117,5 +117,12 @@ "longDescription": "Disable Video Stream when disarmed.", "type": "bool", "defaultValue": false +}, +{ + "name": "lowLatencyMode", + "shortDescription": "Tweaks video for lower latency", + "longDescription": "If this option is enabled, the rtpjitterbuffer is removed and the video sink is set to assynchronous mode, reducing the latency by about 200 ms.", + "type": "bool", + "defaultValue": false } ] diff --git a/src/Settings/VideoSettings.cc b/src/Settings/VideoSettings.cc index 7e2689c05314444d01a0591492e591c031299c92..c42d46cf5752065fbde04b9a9dd64f5b061a2b67 100644 --- a/src/Settings/VideoSettings.cc +++ b/src/Settings/VideoSettings.cc @@ -82,6 +82,7 @@ DECLARE_SETTINGSFACT(VideoSettings, enableStorageLimit) DECLARE_SETTINGSFACT(VideoSettings, rtspTimeout) DECLARE_SETTINGSFACT(VideoSettings, streamEnabled) DECLARE_SETTINGSFACT(VideoSettings, disableWhenDisarmed) +DECLARE_SETTINGSFACT(VideoSettings, lowLatencyMode) DECLARE_SETTINGSFACT_NO_FUNC(VideoSettings, videoSource) { diff --git a/src/Settings/VideoSettings.h b/src/Settings/VideoSettings.h index 38da7691681a97bf1838c4097674384d1ace3698..1e927889d337f11ba7551c30c9d86d5530bbcc2e 100644 --- a/src/Settings/VideoSettings.h +++ b/src/Settings/VideoSettings.h @@ -34,6 +34,7 @@ public: DEFINE_SETTINGFACT(rtspTimeout) DEFINE_SETTINGFACT(streamEnabled) DEFINE_SETTINGFACT(disableWhenDisarmed) + DEFINE_SETTINGFACT(lowLatencyMode) Q_PROPERTY(bool streamConfigured READ streamConfigured NOTIFY streamConfiguredChanged) Q_PROPERTY(QString rtspVideoSource READ rtspVideoSource CONSTANT) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index a3b551805acb9fbbc805195b7d8483c4b27c6ec2..97b724c6494b604508cdd4b4987224670374f7c2 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -538,6 +538,7 @@ void Vehicle::_commonInit() // Set video stream to udp if running ArduSub and Video is disabled if (sub() && _settingsManager->videoSettings()->videoSource()->rawValue() == VideoSettings::videoDisabled) { _settingsManager->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDPH264); + _settingsManager->videoSettings()->lowLatencyMode()->setRawValue(true); } //-- Airspace Management diff --git a/src/VideoManager/VideoManager.cc b/src/VideoManager/VideoManager.cc index 1305bde709e2cd5a4f123b9deedb4b948d059e09..f30fcc13fa4ed83c1d7e08b89eb0636c6d4ac2d3 100644 --- a/src/VideoManager/VideoManager.cc +++ b/src/VideoManager/VideoManager.cc @@ -89,6 +89,7 @@ VideoManager::setToolbox(QGCToolbox *toolbox) connect(_videoSettings->rtspUrl(), &Fact::rawValueChanged, this, &VideoManager::_rtspUrlChanged); connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_tcpUrlChanged); connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::_aspectRatioChanged); + connect(_videoSettings->lowLatencyMode(),&Fact::rawValueChanged, this, &VideoManager::_lowLatencyModeChanged); MultiVehicleManager *pVehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); connect(pVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle); @@ -422,6 +423,13 @@ VideoManager::_tcpUrlChanged() _restartVideo(); } +//----------------------------------------------------------------------------- +void +VideoManager::_lowLatencyModeChanged() +{ + restartVideo(); +} + //----------------------------------------------------------------------------- bool VideoManager::hasVideo() diff --git a/src/VideoManager/VideoManager.h b/src/VideoManager/VideoManager.h index f5c3192918d866d9f44c60552c62b7b2bee76c36..58b60dd33e8b599c33e07d8a0fc971db21ff848f 100644 --- a/src/VideoManager/VideoManager.h +++ b/src/VideoManager/VideoManager.h @@ -105,6 +105,7 @@ protected slots: void _udpPortChanged (); void _rtspUrlChanged (); void _tcpUrlChanged (); + void _lowLatencyModeChanged (); void _updateUVC (); void _setActiveVehicle (Vehicle* vehicle); void _aspectRatioChanged (); diff --git a/src/ui/preferences/GeneralSettings.qml b/src/ui/preferences/GeneralSettings.qml index 865e4fa19f11c4c5a526e672dbdb767fcd09087d..213202b432a815d79978063dad1baf0291adae09 100644 --- a/src/ui/preferences/GeneralSettings.qml +++ b/src/ui/preferences/GeneralSettings.qml @@ -1033,6 +1033,16 @@ Rectangle { fact: QGroundControl.settingsManager.videoSettings.disableWhenDisarmed visible: _isGst && QGroundControl.settingsManager.videoSettings.disableWhenDisarmed.visible } + + QGCLabel { + text: qsTr("Low Latency Mode") + visible: _isGst && QGroundControl.settingsManager.videoSettings.lowLatencyMode.visible + } + FactCheckBox { + text: "" + fact: QGroundControl.settingsManager.videoSettings.lowLatencyMode + visible: _isGst && QGroundControl.settingsManager.videoSettings.lowLatencyMode.visible + } } }