From 9c88c15b52f28ad0f514f465afc23710bdc957d5 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Thu, 14 Nov 2024 00:13:15 +0100 Subject: [PATCH 01/44] resources: add artwork for multi-gcs indicator --- qgcresources.qrc | 4 +++ resources/controlIndicator/gcscontrol_1.svg | 23 ++++++++++++++++++ resources/controlIndicator/gcscontrol_3.svg | 27 +++++++++++++++++++++ 3 files changed, 54 insertions(+) create mode 100644 resources/controlIndicator/gcscontrol_1.svg create mode 100644 resources/controlIndicator/gcscontrol_3.svg diff --git a/qgcresources.qrc b/qgcresources.qrc index 3690875865a0..e64eb0f3b014 100644 --- a/qgcresources.qrc +++ b/qgcresources.qrc @@ -110,4 +110,8 @@ resources/gimbal/payload.svg + + resources/controlIndicator/gcscontrol_1.svg + resources/controlIndicator/gcscontrol_3.svg + diff --git a/resources/controlIndicator/gcscontrol_1.svg b/resources/controlIndicator/gcscontrol_1.svg new file mode 100644 index 000000000000..c14b221002d8 --- /dev/null +++ b/resources/controlIndicator/gcscontrol_1.svg @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/resources/controlIndicator/gcscontrol_3.svg b/resources/controlIndicator/gcscontrol_3.svg new file mode 100644 index 000000000000..809970ad5891 --- /dev/null +++ b/resources/controlIndicator/gcscontrol_3.svg @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + \ No newline at end of file From 8525aad97ec2c63262b251bedf42a1ae023361bd Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 11 May 2025 13:27:56 +0200 Subject: [PATCH 02/44] Vehicle: add support for multi-GCS mavlink protocol --- src/Vehicle/Vehicle.cc | 62 ++++++++++++++++++++++++++++++++++++++++++ src/Vehicle/Vehicle.h | 32 ++++++++++++++++++++++ 2 files changed, 94 insertions(+) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index cd7cf4b1547e..27e6862511e3 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -647,6 +647,12 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes _handleMessageInterval(message); break; } + case MAVLINK_MSG_ID_CONTROL_STATUS: + _handleControlStatus(message); + break; + case MAVLINK_MSG_ID_COMMAND_LONG: + _handleCommandLong(message); + break; } // This must be emitted after the vehicle processes the message. This way the vehicle state is up to date when anyone else @@ -3970,6 +3976,62 @@ void Vehicle::_handleMessageInterval(const mavlink_message_t& message) } } +void Vehicle::requestOperatorControl(bool allowOverride) +{ + sendMavCommand(_defaultComponentId, + MAV_CMD(43005), // MAV_CMD_REQUEST_OPERATOR_CONTROL + true, // show errors + 0, // System ID of GCS requesting control, 0 if it is this GCS + 1, // Action - 0: Release control, 1: Request control. + allowOverride ? 1 : 0); // Allow takeover - Enable automatic granting of ownership on request. 0: Ask current owner and reject request, 1: Allow automatic takeover. +} + +void Vehicle::_handleControlStatus(const mavlink_message_t& message) +{ + mavlink_control_status_t controlStatus; + mavlink_msg_control_status_decode(&message, &controlStatus); + + bool updateControlStatusSignals = false; + if (_gcsControlStatusFlags != controlStatus.flags) { + _gcsControlStatusFlags = controlStatus.flags; + _gcsControlStatusFlags_SystemManager = controlStatus.flags & GCS_CONTROL_STATUS_FLAGS_SYSTEM_MANAGER; + _gcsControlStatusFlags_TakeoverAllowed = controlStatus.flags & GCS_CONTROL_STATUS_FLAGS_TAKEOVER_ALLOWED; + updateControlStatusSignals = true; + } + + if (_sysid_in_control != controlStatus.sysid_in_control) { + _sysid_in_control = controlStatus.sysid_in_control; + updateControlStatusSignals = true; + } + + if (!_firstControlStatusReceived) { + _firstControlStatusReceived = true; + updateControlStatusSignals = true; + } + + if (updateControlStatusSignals) { + emit gcsControlStatusChanged(); + } +} + +void Vehicle::_handleCommandRequestOperatorControl(const mavlink_command_long_t commandLong) +{ + emit requestOperatorControlReceived(commandLong.param1, commandLong.param3); +} + +void Vehicle::_handleCommandLong(const mavlink_message_t& message) +{ + mavlink_command_long_t commandLong; + mavlink_msg_command_long_decode(&message, &commandLong); + // Ignore command if it is not targeted for us + if (commandLong.target_system != MAVLinkProtocol::instance()->getSystemId()) { + return; + } + if (commandLong.command == MAV_CMD(32100)) { // MAV_CMD_REQUEST_OPERATOR_CONTROL + _handleCommandRequestOperatorControl(commandLong); + } +} + void Vehicle::_requestMessageMessageIntervalResultHandler(void* resultHandlerData, MAV_RESULT result, RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t& message) { if((result != MAV_RESULT_ACCEPTED) || (failureCode != RequestMessageNoFailure)) diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index b5141d2d9aa2..142516cb3837 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -974,6 +974,7 @@ private slots: void _handleCameraFeedback (const mavlink_message_t& message); #endif void _handleCameraImageCaptured (const mavlink_message_t& message); + void _handleCommandLong (const mavlink_message_t& message); void _missionManagerError (int errorCode, const QString& errorMsg); void _geoFenceManagerError (int errorCode, const QString& errorMsg); void _rallyPointManagerError (int errorCode, const QString& errorMsg); @@ -1322,6 +1323,37 @@ private slots: /*---------------------------------------------------------------------------*/ /*===========================================================================*/ /* Status Text Handler */ +/* CONTROL STATUS HANDLER */ +/*===========================================================================*/ +public: + Q_INVOKABLE void requestOperatorControl(bool allowOverride); + +private: + void _handleControlStatus(const mavlink_message_t& message); + void _handleCommandRequestOperatorControl(const mavlink_command_long_t commandLong); + + Q_PROPERTY(uint8_t sysidInControl READ sysidInControl NOTIFY gcsControlStatusChanged) + Q_PROPERTY(bool gcsControlStatusFlags_SystemManager READ gcsControlStatusFlags_SystemManager NOTIFY gcsControlStatusChanged) + Q_PROPERTY(bool gcsControlStatusFlags_TakeoverAllowed READ gcsControlStatusFlags_TakeoverAllowed NOTIFY gcsControlStatusChanged) + Q_PROPERTY(bool firstControlStatusReceived READ firstControlStatusReceived NOTIFY gcsControlStatusChanged) + + uint8_t sysidInControl() const { return _sysid_in_control; } + bool gcsControlStatusFlags_SystemManager() const { return _gcsControlStatusFlags_SystemManager; } + bool gcsControlStatusFlags_TakeoverAllowed() const { return _gcsControlStatusFlags_TakeoverAllowed; } + bool firstControlStatusReceived() const { return _firstControlStatusReceived; } + + uint8_t _sysid_in_control = 0; + uint8_t _gcsControlStatusFlags = 0; + bool _gcsControlStatusFlags_SystemManager = 0; + bool _gcsControlStatusFlags_TakeoverAllowed = 0; + bool _firstControlStatusReceived = false; + +signals: + void gcsControlStatusChanged(); + void requestOperatorControlReceived(int sysIdRequestingControl, int allowTakeover); + +/*===========================================================================*/ +/* STATUS TEXT HANDLER */ /*===========================================================================*/ private: Q_PROPERTY(bool messageTypeNone READ messageTypeNone NOTIFY messageTypeChanged) From 3b95164f5ff46070a5e648398d56396b050a6793 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Thu, 14 Nov 2024 00:16:34 +0100 Subject: [PATCH 03/44] FlyviewSettings: add setting for multi-GCS mavlink protocol --- src/Settings/FlyView.SettingsGroup.json | 6 ++++++ src/Settings/FlyViewSettings.cc | 1 + src/Settings/FlyViewSettings.h | 1 + 3 files changed, 8 insertions(+) diff --git a/src/Settings/FlyView.SettingsGroup.json b/src/Settings/FlyView.SettingsGroup.json index 99e0c95bd7b1..3c50e0a0484d 100644 --- a/src/Settings/FlyView.SettingsGroup.json +++ b/src/Settings/FlyView.SettingsGroup.json @@ -74,6 +74,12 @@ "enumStrings": "Integrated Compass & Attitude,Horizontal Compass & Attitude,Large Vertical", "enumValues": "qrc:/qml/IntegratedCompassAttitude.qml,qrc:/qml/HorizontalCompassAttitude.qml,qrc:/qml/VerticalCompassAttitude.qml", "default": "qrc:/qml/IntegratedCompassAttitude.qml" +}, +{ + "name": "requestControlAllowTakeover", + "shortDesc": "When requesting vehicle control, allow other GCS to override control automatically, or require this GCS to accept the request first.", + "type": "bool", + "default": false } ] } diff --git a/src/Settings/FlyViewSettings.cc b/src/Settings/FlyViewSettings.cc index 2ffa1f024255..b2cce774cb3f 100644 --- a/src/Settings/FlyViewSettings.cc +++ b/src/Settings/FlyViewSettings.cc @@ -27,3 +27,4 @@ DECLARE_SETTINGSFACT(FlyViewSettings, showSimpleCameraControl) DECLARE_SETTINGSFACT(FlyViewSettings, showObstacleDistanceOverlay) DECLARE_SETTINGSFACT(FlyViewSettings, updateHomePosition) DECLARE_SETTINGSFACT(FlyViewSettings, instrumentQmlFile) +DECLARE_SETTINGSFACT(FlyViewSettings, requestControlAllowTakeover) diff --git a/src/Settings/FlyViewSettings.h b/src/Settings/FlyViewSettings.h index d949bf7b05ce..a80ed5cdd00c 100644 --- a/src/Settings/FlyViewSettings.h +++ b/src/Settings/FlyViewSettings.h @@ -30,4 +30,5 @@ class FlyViewSettings : public SettingsGroup DEFINE_SETTINGFACT(showObstacleDistanceOverlay) DEFINE_SETTINGFACT(updateHomePosition) DEFINE_SETTINGFACT(instrumentQmlFile) + DEFINE_SETTINGFACT(requestControlAllowTakeover) }; From 21ce3bcd388772325413e688b089fce1a559419d Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Thu, 14 Nov 2024 00:17:32 +0100 Subject: [PATCH 04/44] toolbar: new multi-GCS control top toolbar indicator --- qgroundcontrol.qrc | 1 + src/UI/toolbar/ControlIndicator.qml | 334 ++++++++++++++++++++++++++++ 2 files changed, 335 insertions(+) create mode 100644 src/UI/toolbar/ControlIndicator.qml diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index af1883aa9681..3bf6185a4663 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -12,6 +12,7 @@ src/UI/toolbar/TelemetryRSSIIndicator.qml src/UI/toolbar/APMSupportForwardingIndicator.qml src/UI/toolbar/GimbalIndicator.qml + src/UI/toolbar/ControlIndicator.qml src/FlightDisplay/DefaultChecklist.qml diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml new file mode 100644 index 000000000000..1fc3e895d03b --- /dev/null +++ b/src/UI/toolbar/ControlIndicator.qml @@ -0,0 +1,334 @@ +import QtQuick +import QtQuick.Layouts + +import QGroundControl +import QGroundControl.Controls +import QGroundControl.MultiVehicleManager +import QGroundControl.ScreenTools +import QGroundControl.Palette +import QGroundControl.FactSystem +import QGroundControl.FactControls + +Item { + id: _root + width: controlIndicatorIcon.width * 1.1 + anchors.top: parent.top + anchors.bottom: parent.bottom + + property var activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + property bool showIndicator: activeVehicle && activeVehicle.firstControlStatusReceived + property var sysidInControl: activeVehicle ? activeVehicle.sysidInControl : 0 + property bool gcsControlStatusFlags_SystemManager: activeVehicle ? activeVehicle.gcsControlStatusFlags_SystemManager : false + property bool gcsControlStatusFlags_TakeoverAllowed: activeVehicle ? activeVehicle.gcsControlStatusFlags_TakeoverAllowed : false + property Fact requestControlAllowTakeoverFact: QGroundControl.settingsManager.flyViewSettings.requestControlAllowTakeover + property bool requestControlAllowTakeover: requestControlAllowTakeoverFact.rawValue + property bool isThisGCSinControl: sysidInControl == QGroundControl.mavlinkSystemID + + property var margins: ScreenTools.defaultFontPixelWidth + property var panelRadius: ScreenTools.defaultFontPixelWidth * 0.5 + property var buttonHeight: height * 1.6 + property var squareButtonPadding: ScreenTools.defaultFontPixelWidth + property var separatorHeight: buttonHeight * 0.9 + property var settingsPanelVisible: false + property bool outdoorPalette: qgcPal.globalTheme === QGCPalette.Light + + // Used by control request popup, when other GCS ask us for control + property var receivedRequestTimeoutMs: 6000 + property var requestSysIdRequestingControl: 0 + property var requestAllowTakeover: false + + signal triggerAnimations // Used to trigger animation inside the popup component + + Connections { + target: activeVehicle + // Popup prompting user to accept control from other GCS + onRequestOperatorControlReceived: (sysIdRequestingControl, allowTakeover) => { + // If we don't have the indicator visible ( not receiving CONTROL_STATUS ) don't proceed + if (!_root.showIndicator) { + return + } + requestSysIdRequestingControl = sysIdRequestingControl + requestAllowTakeover = allowTakeover + // First hide current popup, in case the normal control panel is visible + mainWindow.hideIndicatorPopup() + mainWindow.showIndicatorPopup(_root, controlRequestPopup, false) + } + // Animation to blink indicator when any related info changes + onGcsControlStatusChanged: { + backgroundRectangle.doOpacityAnimation() + triggerAnimations() // Needed for animation inside the popup component + } + } + + // Background to have animation when current system in control changes + Rectangle { + id: backgroundRectangle + anchors.centerIn: parent + width: height + height: parent.height * 1.4 + color: isThisGCSinControl ? qgcPal.colorGreen : qgcPal.text + radius: margins + opacity: 0.0 + + function doOpacityAnimation() { opacityAnimation.restart() } + SequentialAnimation on opacity { + id: opacityAnimation + running: false + loops: 1 + PropertyAnimation { to: 0.4; duration: 150 } + PropertyAnimation { to: 0.5; duration: 100 } + PropertyAnimation { to: 0.0; duration: 150 } + } + } + + // Control request popup. Appears when other GCS requests control, so operator on this one can accept or deny it + Component { + id: controlRequestPopup + Item { + id: controlRequestRectangle + width: mainLayout.width + margins * 4 + height: mainLayout.height + margins * 4 + + Rectangle { + anchors.fill: parent + radius: ScreenTools.defaultFontPixelWidth / 2 + color: qgcPal.window + opacity: 0.7 + } + + property var progress: 0 + SequentialAnimation on progress { + id: progressAnimation + running: false + loops: 1 + NumberAnimation { target: controlRequestRectangle; property: "progress"; to: 1; duration: receivedRequestTimeoutMs } + } + + property var progresTimeLabel + property double lastUpdateTime: 0 + onProgressChanged: { + // Only update each 0.2 seconds + const currentTime = Date.now() * 0.001; + if (currentTime - lastUpdateTime < 0.1) { + return + } + var currentCount = (progress * receivedRequestTimeoutMs * 0.001) + progresTimeLabel = (receivedRequestTimeoutMs * 0.001 - currentCount).toFixed(1) + lastUpdateTime = currentTime; + } + + Component.onCompleted: { + requestTimer.restart() + progressAnimation.restart() + } + + Timer { + id: requestTimer + interval: receivedRequestTimeoutMs + repeat: false + running: false + onTriggered: { + // Sanity check, only hide if this panel is visible + if (!controlRequestRectangle.visible) { + return + } + mainWindow.hideIndicatorPopup() + } + } + + GridLayout { + id: mainLayout + anchors.margins: margins * 2 + anchors.top: parent.top + anchors.right: parent.right + columns: 3 + + // Action label + QGCLabel { + font.pointSize: ScreenTools.defaultFontPointSize * 1.1 + text: qsTr("GCS ") + requestSysIdRequestingControl + qsTr(" is requesting control") + font.bold: true + Layout.columnSpan: 2 + } + QGCButton { + text: qsTr("Allow
takeover") + Layout.rowSpan: 2 + Layout.leftMargin: margins * 2 + Layout.alignment: Qt.AlignBottom + Layout.fillHeight: true + onClicked: { + activeVehicle.requestOperatorControl(true) // Allow takeover + requestControlAllowTakeoverFact.rawValue = true + mainWindow.hideIndicatorPopup() + } + } + // Action label + QGCLabel { + font.pointSize: ScreenTools.defaultFontPointSize * 1.1 + text: qsTr("Ignoring automatically in ") + progresTimeLabel + qsTr(" seconds") + } + QGCButton { + id: ignoreButton + text: qsTr("Ignore") + onClicked: mainWindow.hideIndicatorPopup() + Layout.alignment: Qt.AlignHCenter + } + // Actual progress bar + Rectangle { + id: overlayRectangle + height: ScreenTools.defaultFontPixelWidth + width: parent.width * controlRequestRectangle.progress + color: qgcPal.buttonHighlight + Layout.columnSpan: 2 + } + } + } + } + + // Popup panel, appears when clicking top control indicator + Component { + id: controlPopup + + Rectangle { + id: popupBackground + width: mainLayout.width + mainLayout.anchors.margins * 2 + height: mainLayout.height + mainLayout.anchors.margins * 2 + color: qgcPal.window + radius: panelRadius + + Connections { + target: _root + onTriggerAnimations: doColorAnimation() + } + function doColorAnimation() { colorAnimation.restart() } + SequentialAnimation on color { + id: colorAnimation + running: false + loops: 1 + PropertyAnimation { to: qgcPal.windowShade; duration: 200 } + PropertyAnimation { to: qgcPal.window; duration: 200 } + } + + GridLayout { + id: mainLayout + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.top: parent.top + anchors.right: parent.right + columns: 2 + + QGCLabel { + text: qsTr("System in control: ") + font.bold: true + } + QGCLabel { + text: isThisGCSinControl ? (qsTr("This GCS") + " (" + sysidInControl + ")" ) : sysidInControl + font.bold: isThisGCSinControl + color: isThisGCSinControl ? qgcPal.colorGreen : qgcPal.text + Layout.alignment: Qt.AlignRight + Layout.fillWidth: true + horizontalAlignment: Text.AlignRight + } + QGCLabel { + text: gcsControlStatusFlags_TakeoverAllowed ? qsTr("Takeover allowed") : qsTr("Takeover NOT allowed") + Layout.columnSpan: 2 + Layout.alignment: Qt.AlignRight + Layout.fillWidth: true + horizontalAlignment: Text.AlignRight + } + // Separator + Rectangle { + Layout.columnSpan: 2 + Layout.preferredWidth: parent.width + Layout.alignment: Qt.AlignHCenter + color: qgcPal.windowShade + height: outdoorPalette ? 1 : 2 + } + QGCLabel { + text: qsTr("Send Control Request:") + Layout.columnSpan: 2 + visible: !isThisGCSinControl + } + QGCLabel { + text: qsTr("Change takeover condition:") + Layout.columnSpan: 2 + visible: isThisGCSinControl + } + FactCheckBox { + text: qsTr("Allow takeover") + fact: requestControlAllowTakeoverFact + enabled: gcsControlStatusFlags_TakeoverAllowed || isThisGCSinControl + } + QGCButton { + text: gcsControlStatusFlags_TakeoverAllowed ? qsTr("Adquire Control") : qsTr("Send Request") + onClicked: activeVehicle.requestOperatorControl(requestControlAllowTakeoverFact.rawValue) + Layout.alignment: Qt.AlignRight + visible: !isThisGCSinControl + } + QGCButton { + text: qsTr("Change") + onClicked: activeVehicle.requestOperatorControl(requestControlAllowTakeoverFact.rawValue) + visible: isThisGCSinControl + Layout.alignment: Qt.AlignRight + enabled: gcsControlStatusFlags_TakeoverAllowed != requestControlAllowTakeoverFact.rawValue + } + // Separator + Rectangle { + Layout.columnSpan: 2 + Layout.preferredWidth: parent.width + Layout.alignment: Qt.AlignHCenter + color: qgcPal.windowShade + height: outdoorPalette ? 1 : 2 + } + QGCLabel { + text: qsTr("This GCS Mavlink System ID: ") + } + QGCTextField { + text: QGroundControl.mavlinkSystemID.toString() + numericValuesOnly: true + Layout.alignment: Qt.AlignRight + Layout.preferredWidth: ScreenTools.defaultFontPixelWidth * 7 + horizontalAlignment: TextInput.AlignHCenter + onEditingFinished: { + if (parseInt(text) > 0 && parseInt(text) < 256) { + QGroundControl.mavlinkSystemID = parseInt(text) + } else { + mainWindow.showMessageDialog(qsTr("Invalid System ID"), qsTr("System ID must be in the range of 1 - 255")) + } + } + } + + } + } + } + + // Actual top toolbar indicator + Image { + id: controlIndicatorIcon + width: height + anchors.top: parent.top + anchors.bottom: parent.bottom + source: sysidInControl == QGroundControl.mavlinkSystemID ? "/controlIndicator/gcscontrol_3.svg" : "/controlIndicator/gcscontrol_1.svg" + fillMode: Image.PreserveAspectFit + sourceSize.height: height + + // Current GCS in control indicator + QGCLabel { + id: gcsInControlIndicator + text: sysidInControl + font.bold: true + font.pointSize: ScreenTools.smallFontPointSize * 1.1 + color: isThisGCSinControl ? qgcPal.colorGreen : qgcPal.text + anchors.bottom: parent.bottom + anchors.bottomMargin: -margins * 1.5 + anchors.right: parent.right + anchors.rightMargin: -margins + } + } + + MouseArea { + anchors.fill: parent + onClicked: { + mainWindow.showIndicatorPopup(_root, controlPopup, false) + } + } +} From 768dfcecec80705aa49858723ae5a2b88f81bcf3 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Thu, 14 Nov 2024 00:17:53 +0100 Subject: [PATCH 05/44] FirmwarePlugin: add multi-GCS control indicator in top toolbar --- src/FirmwarePlugin/FirmwarePlugin.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 0e2867723f88..59617af8af4f 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -212,6 +212,7 @@ const QVariantList &FirmwarePlugin::toolIndicators(const Vehicle*) QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Controls/BatteryIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/RemoteIDIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GimbalIndicator.qml")), + QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ControlIndicator.qml")), }); } From 3b515c52322c724a2818e7365d8300ee73394ae8 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 24 Nov 2024 02:29:15 +0100 Subject: [PATCH 06/44] resources: use new icons --- qgcresources.qrc | 5 ++-- resources/controlIndicator/gcscontrol_1.svg | 23 ---------------- resources/controlIndicator/gcscontrol_3.svg | 27 ------------------- .../controlIndicator/gcscontrol_device.svg | 20 ++++++++++++++ resources/controlIndicator/gcscontrol_gcs.svg | 20 ++++++++++++++ .../controlIndicator/gcscontrol_line.svg | 20 ++++++++++++++ 6 files changed, 63 insertions(+), 52 deletions(-) delete mode 100644 resources/controlIndicator/gcscontrol_1.svg delete mode 100644 resources/controlIndicator/gcscontrol_3.svg create mode 100644 resources/controlIndicator/gcscontrol_device.svg create mode 100644 resources/controlIndicator/gcscontrol_gcs.svg create mode 100644 resources/controlIndicator/gcscontrol_line.svg diff --git a/qgcresources.qrc b/qgcresources.qrc index e64eb0f3b014..213f81767964 100644 --- a/qgcresources.qrc +++ b/qgcresources.qrc @@ -111,7 +111,8 @@ resources/gimbal/payload.svg
- resources/controlIndicator/gcscontrol_1.svg - resources/controlIndicator/gcscontrol_3.svg + resources/controlIndicator/gcscontrol_device.svg + resources/controlIndicator/gcscontrol_gcs.svg + resources/controlIndicator/gcscontrol_line.svg diff --git a/resources/controlIndicator/gcscontrol_1.svg b/resources/controlIndicator/gcscontrol_1.svg deleted file mode 100644 index c14b221002d8..000000000000 --- a/resources/controlIndicator/gcscontrol_1.svg +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - \ No newline at end of file diff --git a/resources/controlIndicator/gcscontrol_3.svg b/resources/controlIndicator/gcscontrol_3.svg deleted file mode 100644 index 809970ad5891..000000000000 --- a/resources/controlIndicator/gcscontrol_3.svg +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - \ No newline at end of file diff --git a/resources/controlIndicator/gcscontrol_device.svg b/resources/controlIndicator/gcscontrol_device.svg new file mode 100644 index 000000000000..fb267ffe5074 --- /dev/null +++ b/resources/controlIndicator/gcscontrol_device.svg @@ -0,0 +1,20 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/resources/controlIndicator/gcscontrol_gcs.svg b/resources/controlIndicator/gcscontrol_gcs.svg new file mode 100644 index 000000000000..af965e771f2d --- /dev/null +++ b/resources/controlIndicator/gcscontrol_gcs.svg @@ -0,0 +1,20 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/resources/controlIndicator/gcscontrol_line.svg b/resources/controlIndicator/gcscontrol_line.svg new file mode 100644 index 000000000000..8e695693efd9 --- /dev/null +++ b/resources/controlIndicator/gcscontrol_line.svg @@ -0,0 +1,20 @@ + + + + + + + + + + + + \ No newline at end of file From 83342da59c4f1e529cef3643ee961e10dbbe1c65 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 24 Nov 2024 02:29:26 +0100 Subject: [PATCH 07/44] ControlIndicator.qml: use new icons --- src/UI/toolbar/ControlIndicator.qml | 33 +++++++++++++++++++++++------ 1 file changed, 27 insertions(+), 6 deletions(-) diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index 1fc3e895d03b..e28ec7d8f56d 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -11,7 +11,7 @@ import QGroundControl.FactControls Item { id: _root - width: controlIndicatorIcon.width * 1.1 + width: controlIndicatorIconGCS.width * 1.1 anchors.top: parent.top anchors.bottom: parent.bottom @@ -302,14 +302,35 @@ Item { } // Actual top toolbar indicator - Image { - id: controlIndicatorIcon + QGCColoredImage { + id: controlIndicatorIconLine width: height anchors.top: parent.top anchors.bottom: parent.bottom - source: sysidInControl == QGroundControl.mavlinkSystemID ? "/controlIndicator/gcscontrol_3.svg" : "/controlIndicator/gcscontrol_1.svg" + source: "/controlIndicator/gcscontrol_line.svg" fillMode: Image.PreserveAspectFit sourceSize.height: height + color: isThisGCSinControl ? qgcPal.colorGreen : qgcPal.text + } + QGCColoredImage { + id: controlIndicatorIconAircraft + width: height + anchors.top: parent.top + anchors.bottom: parent.bottom + source: "/controlIndicator/gcscontrol_device.svg" + fillMode: Image.PreserveAspectFit + sourceSize.height: height + color: isThisGCSinControl ? qgcPal.colorGreen : qgcPal.text + } + QGCColoredImage { + id: controlIndicatorIconGCS + width: height + anchors.top: parent.top + anchors.bottom: parent.bottom + source: "/controlIndicator/gcscontrol_gcs.svg" + fillMode: Image.PreserveAspectFit + sourceSize.height: height + color: qgcPal.text // Current GCS in control indicator QGCLabel { @@ -319,9 +340,9 @@ Item { font.pointSize: ScreenTools.smallFontPointSize * 1.1 color: isThisGCSinControl ? qgcPal.colorGreen : qgcPal.text anchors.bottom: parent.bottom - anchors.bottomMargin: -margins * 1.5 + anchors.bottomMargin: -margins * 0.7 anchors.right: parent.right - anchors.rightMargin: -margins + anchors.rightMargin: -margins * 0.1 } } From 726e45bdcd4056a1d28a57f85ef4e51e72efff87 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Thu, 5 Dec 2024 15:11:02 +0100 Subject: [PATCH 08/44] ControlIndicator.qml: use new color coding --- src/UI/toolbar/ControlIndicator.qml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index e28ec7d8f56d..d4c0525bec93 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -320,7 +320,7 @@ Item { source: "/controlIndicator/gcscontrol_device.svg" fillMode: Image.PreserveAspectFit sourceSize.height: height - color: isThisGCSinControl ? qgcPal.colorGreen : qgcPal.text + color: (isThisGCSinControl || gcsControlStatusFlags_TakeoverAllowed) ? qgcPal.colorGreen : qgcPal.text } QGCColoredImage { id: controlIndicatorIconGCS From 7cd001650490a6bb6a0a81e36f8c66737a59f0dc Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Thu, 5 Dec 2024 15:11:26 +0100 Subject: [PATCH 09/44] Vehicle.cc: use new cmd id for REQUEST_OPERATOR_CONTROL --- src/Vehicle/Vehicle.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 27e6862511e3..b7e139622720 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3979,7 +3979,7 @@ void Vehicle::_handleMessageInterval(const mavlink_message_t& message) void Vehicle::requestOperatorControl(bool allowOverride) { sendMavCommand(_defaultComponentId, - MAV_CMD(43005), // MAV_CMD_REQUEST_OPERATOR_CONTROL + MAV_CMD(32100), // MAV_CMD_REQUEST_OPERATOR_CONTROL true, // show errors 0, // System ID of GCS requesting control, 0 if it is this GCS 1, // Action - 0: Release control, 1: Request control. From 7c9132906a0a06623c907e41bd44efca91c9c7de Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 6 Dec 2024 10:32:22 +0100 Subject: [PATCH 10/44] FlyviewSettings: add new requestControlTimeout setting --- src/Settings/FlyView.SettingsGroup.json | 8 ++++++++ src/Settings/FlyViewSettings.cc | 1 + src/Settings/FlyViewSettings.h | 1 + 3 files changed, 10 insertions(+) diff --git a/src/Settings/FlyView.SettingsGroup.json b/src/Settings/FlyView.SettingsGroup.json index 3c50e0a0484d..48e54e0c3ee7 100644 --- a/src/Settings/FlyView.SettingsGroup.json +++ b/src/Settings/FlyView.SettingsGroup.json @@ -80,6 +80,14 @@ "shortDesc": "When requesting vehicle control, allow other GCS to override control automatically, or require this GCS to accept the request first.", "type": "bool", "default": false +}, +{ + "name": "requestControlTimeout", + "shortDesc": "Timeout in seconds before a request to a GCS to allow takeover is assumed to be rejected. This is used to display the timeout graphically on requestor and GCS in control.", + "type": "uint32", + "min": 3, + "max": 60, + "default": 10 } ] } diff --git a/src/Settings/FlyViewSettings.cc b/src/Settings/FlyViewSettings.cc index b2cce774cb3f..947ba39b5751 100644 --- a/src/Settings/FlyViewSettings.cc +++ b/src/Settings/FlyViewSettings.cc @@ -28,3 +28,4 @@ DECLARE_SETTINGSFACT(FlyViewSettings, showObstacleDistanceOverlay) DECLARE_SETTINGSFACT(FlyViewSettings, updateHomePosition) DECLARE_SETTINGSFACT(FlyViewSettings, instrumentQmlFile) DECLARE_SETTINGSFACT(FlyViewSettings, requestControlAllowTakeover) +DECLARE_SETTINGSFACT(FlyViewSettings, requestControlTimeout) diff --git a/src/Settings/FlyViewSettings.h b/src/Settings/FlyViewSettings.h index a80ed5cdd00c..20653281321d 100644 --- a/src/Settings/FlyViewSettings.h +++ b/src/Settings/FlyViewSettings.h @@ -31,4 +31,5 @@ class FlyViewSettings : public SettingsGroup DEFINE_SETTINGFACT(updateHomePosition) DEFINE_SETTINGFACT(instrumentQmlFile) DEFINE_SETTINGFACT(requestControlAllowTakeover) + DEFINE_SETTINGFACT(requestControlTimeout) }; From 3b3d8d693c60f2bcac52c1f935fb9ad48c3b79e6 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 6 Dec 2024 10:38:00 +0100 Subject: [PATCH 11/44] Vehicle: use new extra param for REQUEST_OPERATOR_CONTROL, and new cmd id --- src/Vehicle/Vehicle.cc | 18 ++++++++++++++---- src/Vehicle/Vehicle.h | 4 ++-- 2 files changed, 16 insertions(+), 6 deletions(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index b7e139622720..e25b57433fe8 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3976,14 +3976,24 @@ void Vehicle::_handleMessageInterval(const mavlink_message_t& message) } } -void Vehicle::requestOperatorControl(bool allowOverride) +void Vehicle::requestOperatorControl(bool allowOverride, int requestTimeoutSecs) { + int safeRequestTimeoutSecs; + int requestTimeoutSecsMin = _settingsManager->flyViewSettings()->requestControlTimeout()->cookedMin().toInt(); + int requestTimeoutSecsMax = _settingsManager->flyViewSettings()->requestControlTimeout()->cookedMax().toInt(); + if (requestTimeoutSecs > requestTimeoutSecsMin && requestTimeoutSecs < requestTimeoutSecsMax) { + safeRequestTimeoutSecs = requestTimeoutSecs; + } else { + // If out of limits use default value + safeRequestTimeoutSecs = _settingsManager->flyViewSettings()->requestControlTimeout()->cookedDefaultValue().toInt(); + } sendMavCommand(_defaultComponentId, MAV_CMD(32100), // MAV_CMD_REQUEST_OPERATOR_CONTROL - true, // show errors + false, // Don't show errors, as per Mavlink control protocol Autopilot will report result failed prior to forwarding the request to the GCS in control. 0, // System ID of GCS requesting control, 0 if it is this GCS 1, // Action - 0: Release control, 1: Request control. - allowOverride ? 1 : 0); // Allow takeover - Enable automatic granting of ownership on request. 0: Ask current owner and reject request, 1: Allow automatic takeover. + allowOverride ? 1 : 0, // Allow takeover - Enable automatic granting of ownership on request. 0: Ask current owner and reject request, 1: Allow automatic takeover. + safeRequestTimeoutSecs); // Timeout in seconds before a request to a GCS to allow takeover is assumed to be rejected. This is used to display the timeout graphically on requestor and GCS in control. } void Vehicle::_handleControlStatus(const mavlink_message_t& message) @@ -4016,7 +4026,7 @@ void Vehicle::_handleControlStatus(const mavlink_message_t& message) void Vehicle::_handleCommandRequestOperatorControl(const mavlink_command_long_t commandLong) { - emit requestOperatorControlReceived(commandLong.param1, commandLong.param3); + emit requestOperatorControlReceived(commandLong.param1, commandLong.param3, commandLong.param4); } void Vehicle::_handleCommandLong(const mavlink_message_t& message) diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 142516cb3837..4bf83f5d1fe1 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -1326,7 +1326,7 @@ private slots: /* CONTROL STATUS HANDLER */ /*===========================================================================*/ public: - Q_INVOKABLE void requestOperatorControl(bool allowOverride); + Q_INVOKABLE void requestOperatorControl(bool allowOverride, int requestTimeoutSecs = 0); private: void _handleControlStatus(const mavlink_message_t& message); @@ -1350,7 +1350,7 @@ private slots: signals: void gcsControlStatusChanged(); - void requestOperatorControlReceived(int sysIdRequestingControl, int allowTakeover); + void requestOperatorControlReceived(int sysIdRequestingControl, int allowTakeover, int requestTimeoutSecs); /*===========================================================================*/ /* STATUS TEXT HANDLER */ From 9ea3f98dc86d85ebfeae9bd697696540a2467820 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 6 Dec 2024 10:47:21 +0100 Subject: [PATCH 12/44] ControlIndicator.qml: add new param4 timeout functionality, for GCS in control --- src/UI/toolbar/ControlIndicator.qml | 23 ++++++++++++++++++++--- 1 file changed, 20 insertions(+), 3 deletions(-) diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index d4c0525bec93..ff80a467a63a 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -33,7 +33,7 @@ Item { property bool outdoorPalette: qgcPal.globalTheme === QGCPalette.Light // Used by control request popup, when other GCS ask us for control - property var receivedRequestTimeoutMs: 6000 + property var receivedRequestTimeoutMs: QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.defaultValue // Use this as default in case something goes wrong property var requestSysIdRequestingControl: 0 property var requestAllowTakeover: false @@ -42,13 +42,15 @@ Item { Connections { target: activeVehicle // Popup prompting user to accept control from other GCS - onRequestOperatorControlReceived: (sysIdRequestingControl, allowTakeover) => { + onRequestOperatorControlReceived: (sysIdRequestingControl, allowTakeover, requestTimeoutSecs) => { // If we don't have the indicator visible ( not receiving CONTROL_STATUS ) don't proceed if (!_root.showIndicator) { return } requestSysIdRequestingControl = sysIdRequestingControl requestAllowTakeover = allowTakeover + // If request came without request timeout, use our default one + receivedRequestTimeoutMs = requestTimeoutSecs !== 0 ? requestTimeoutSecs * 1000 : QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.defaultValue // First hide current popup, in case the normal control panel is visible mainWindow.hideIndicatorPopup() mainWindow.showIndicatorPopup(_root, controlRequestPopup, false) @@ -260,9 +262,24 @@ Item { } QGCButton { text: gcsControlStatusFlags_TakeoverAllowed ? qsTr("Adquire Control") : qsTr("Send Request") - onClicked: activeVehicle.requestOperatorControl(requestControlAllowTakeoverFact.rawValue) + onClicked: requestControl() Layout.alignment: Qt.AlignRight visible: !isThisGCSinControl + // If requesting control, we need to take care of sending the timeout, so the progress bar is on sync in requestor and GCS in control. Only needed if takeover isn't allowed + function requestControl() { + var timeout = gcsControlStatusFlags_TakeoverAllowed ? 0 : QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue + activeVehicle.requestOperatorControl(requestControlAllowTakeoverFact.rawValue, timeout) + } + } + QGCLabel { + text: qsTr("Request Timeout (sec):") + visible: !isThisGCSinControl && !gcsControlStatusFlags_TakeoverAllowed + } + FactTextField { + fact: QGroundControl.settingsManager.flyViewSettings.requestControlTimeout + visible: !isThisGCSinControl && !gcsControlStatusFlags_TakeoverAllowed + Layout.alignment: Qt.AlignRight + Layout.preferredWidth: ScreenTools.defaultFontPixelWidth * 7 } QGCButton { text: qsTr("Change") From 4bfa729c10ee5b2b6ed92f47cda53bc348552036 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 6 Dec 2024 11:59:11 +0100 Subject: [PATCH 13/44] ControlIndicator.qml: implement timeout indicator for requestor side --- src/UI/toolbar/ControlIndicator.qml | 60 +++++++++++++++++++++++++++-- 1 file changed, 57 insertions(+), 3 deletions(-) diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index ff80a467a63a..c3a8860406b1 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -33,7 +33,7 @@ Item { property bool outdoorPalette: qgcPal.globalTheme === QGCPalette.Light // Used by control request popup, when other GCS ask us for control - property var receivedRequestTimeoutMs: QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.defaultValue // Use this as default in case something goes wrong + property var receivedRequestTimeoutMs: QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.defaultValue // Use this as default in case something goes wrong. Usually it will be overriden on onRequestOperatorControlReceived property var requestSysIdRequestingControl: 0 property var requestAllowTakeover: false @@ -120,12 +120,12 @@ Item { } Component.onCompleted: { - requestTimer.restart() + requestReceivedTimer.restart() progressAnimation.restart() } Timer { - id: requestTimer + id: requestReceivedTimer interval: receivedRequestTimeoutMs repeat: false running: false @@ -211,6 +211,48 @@ Item { PropertyAnimation { to: qgcPal.window; duration: 200 } } + // Indicator for sending control request + property var progressTimeLabelSendRequest: "" + property double lastUpdateTimeSendRequest: 0 + onProgressSentRequestChanged: { + // Only update each 0.2 seconds + const currentTime = Date.now() * 0.001; + if (currentTime - lastUpdateTimeSendRequest < 0.1) { + return + } + var currentCount = (progressSentRequest * QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue) + progressTimeLabelSendRequest = (QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue - currentCount).toFixed(1) + lastUpdateTimeSendRequest = currentTime; + } + property var progressSentRequest: 0 + SequentialAnimation on progressSentRequest { + id: progressSentRequestAnimation + running: false + loops: 1 + NumberAnimation { target: popupBackground; property: "progressSentRequest"; to: 1; duration: QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue * 1000 } + } + Timer { + id: requestSentTimer + interval: QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue * 1000 + repeat: false + running: false + onTriggered: { + progressTimeLabelSendRequest = "" + progressSentRequest = 0 + } + } + + property var takeoverAllowedLocal: _root.gcsControlStatusFlags_TakeoverAllowed + onTakeoverAllowedLocalChanged: { + if (takeoverAllowedLocal && requestSentTimer.running) { + requestSentTimer.stop() + progressSentRequestAnimation.stop() + progressTimeLabelSendRequest = "" + progressSentRequest = 0 + } + } + // end Indicator for sending control request + GridLayout { id: mainLayout anchors.margins: ScreenTools.defaultFontPixelWidth @@ -236,6 +278,7 @@ Item { Layout.alignment: Qt.AlignRight Layout.fillWidth: true horizontalAlignment: Text.AlignRight + color: gcsControlStatusFlags_TakeoverAllowed ? qgcPal.colorGreen : qgcPal.text } // Separator Rectangle { @@ -255,6 +298,12 @@ Item { Layout.columnSpan: 2 visible: isThisGCSinControl } + QGCLabel { + id: requestSentTimeoutLabel + text: qsTr("Request sent: ") + progressTimeLabelSendRequest + Layout.columnSpan: 2 + visible: progressTimeLabelSendRequest != "" + } FactCheckBox { text: qsTr("Allow takeover") fact: requestControlAllowTakeoverFact @@ -265,10 +314,15 @@ Item { onClicked: requestControl() Layout.alignment: Qt.AlignRight visible: !isThisGCSinControl + enabled: !requestSentTimeoutLabel.visible // If requesting control, we need to take care of sending the timeout, so the progress bar is on sync in requestor and GCS in control. Only needed if takeover isn't allowed function requestControl() { var timeout = gcsControlStatusFlags_TakeoverAllowed ? 0 : QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue activeVehicle.requestOperatorControl(requestControlAllowTakeoverFact.rawValue, timeout) + if (timeout > 0) { + requestSentTimer.restart() + progressSentRequestAnimation.restart() + } } } QGCLabel { From 62b9c7ea4860c80dd8d839530193a76849cc4723 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 6 Dec 2024 11:59:54 +0100 Subject: [PATCH 14/44] ControlIndicator.qml: Don't permanently allow takeover when accepting a request --- src/UI/toolbar/ControlIndicator.qml | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index c3a8860406b1..154a9dddf2ff 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -160,7 +160,6 @@ Item { Layout.fillHeight: true onClicked: { activeVehicle.requestOperatorControl(true) // Allow takeover - requestControlAllowTakeoverFact.rawValue = true mainWindow.hideIndicatorPopup() } } @@ -211,7 +210,7 @@ Item { PropertyAnimation { to: qgcPal.window; duration: 200 } } - // Indicator for sending control request + // Indicator for visual feedback of sending control request timeout property var progressTimeLabelSendRequest: "" property double lastUpdateTimeSendRequest: 0 onProgressSentRequestChanged: { @@ -251,7 +250,7 @@ Item { progressSentRequest = 0 } } - // end Indicator for sending control request + // end Indicator for visual feedback of sending control request timeout GridLayout { id: mainLayout From 261ff7cf9b54d75b4fe471b91359a911cd175019 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 6 Dec 2024 14:57:41 +0100 Subject: [PATCH 15/44] qmlControls: add new ProgressTracker qml file --- qgroundcontrol.qrc | 1 + src/QmlControls/ProgressTracker.qml | 74 +++++++++++++++++++ .../QGroundControl/Controls/qmldir | 2 + 3 files changed, 77 insertions(+) create mode 100644 src/QmlControls/ProgressTracker.qml diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 3bf6185a4663..614d9f20b44b 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -209,6 +209,7 @@ src/QmlControls/VehicleRotationCal.qml src/QmlControls/VehicleSummaryRow.qml src/PlanView/VTOLLandingPatternMapVisual.qml + src/QmlControls/ProgressTracker.qml src/FactSystem/FactControls/AltitudeFactTextField.qml src/FactSystem/FactControls/FactBitmask.qml src/FactSystem/FactControls/FactCheckBox.qml diff --git a/src/QmlControls/ProgressTracker.qml b/src/QmlControls/ProgressTracker.qml new file mode 100644 index 000000000000..b98c7311b987 --- /dev/null +++ b/src/QmlControls/ProgressTracker.qml @@ -0,0 +1,74 @@ +import QtQuick + +Item { + id: root + // Setable propterties + property real timeoutSeconds: 0 + property string progressLabel: "" + property bool running: false + + // Do not set these properties + property real progress: 0 + + signal timeout() + + property double _lastUpdateTime: 0 + + Timer { + id: timeoutTimer + interval: timeoutSeconds * 1000 + repeat: false + running: running + + onTriggered: { + root.running = false + root.progress = 0 + root.progressLabel = "" + root.timeout() + } + } + + SequentialAnimation on progress { + id: progressAnimation + running: root.running + loops: 1 + + NumberAnimation { + target: root + property: "progress" + to: 1 + duration: timeoutSeconds * 1000 + } + } + + onProgressChanged: { + const currentTime = Date.now() * 0.001 + if (currentTime - _lastUpdateTime < 0.1) { + return + } + + if (running) { + var currentCount = (progress * timeoutSeconds) + progressLabel = (timeoutSeconds - currentCount).toFixed(1) + } else { + progressLabel = "" + } + + _lastUpdateTime = currentTime + } + + function start() { + running = true + progress = 0 + timeoutTimer.restart() + progressAnimation.restart() + } + + function stop() { + running = false + progress = 0 + timeoutTimer.stop() + progressAnimation.stop() + progressLabel = "" + } +} diff --git a/src/QmlControls/QGroundControl/Controls/qmldir b/src/QmlControls/QGroundControl/Controls/qmldir index 27243228ae61..6c29b7e70205 100644 --- a/src/QmlControls/QGroundControl/Controls/qmldir +++ b/src/QmlControls/QGroundControl/Controls/qmldir @@ -130,3 +130,5 @@ ValueSlider 1.0 ValueSlider.qml VehicleMessageList 1.0 VehicleMessageList.qml VehicleRotationCal 1.0 VehicleRotationCal.qml VehicleSummaryRow 1.0 VehicleSummaryRow.qml +MAVLinkChart 1.0 MAVLinkChart.qml +ProgressTracker 1.0 ProgressTracker.qml From 5954c64b80c682137f9750a1b9428d6ddee09a68 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 6 Dec 2024 14:58:06 +0100 Subject: [PATCH 16/44] ControlIndicator.qml: refactor using new ProgressTracker.qml --- src/UI/toolbar/ControlIndicator.qml | 105 ++++++---------------------- 1 file changed, 22 insertions(+), 83 deletions(-) diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index 154a9dddf2ff..e9bc21ff6977 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -53,6 +53,7 @@ Item { receivedRequestTimeoutMs = requestTimeoutSecs !== 0 ? requestTimeoutSecs * 1000 : QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.defaultValue // First hide current popup, in case the normal control panel is visible mainWindow.hideIndicatorPopup() + // When showing the popup, the component will automatically start the count down in controlRequestPopup mainWindow.showIndicatorPopup(_root, controlRequestPopup, false) } // Animation to blink indicator when any related info changes @@ -98,44 +99,14 @@ Item { opacity: 0.7 } - property var progress: 0 - SequentialAnimation on progress { - id: progressAnimation - running: false - loops: 1 - NumberAnimation { target: controlRequestRectangle; property: "progress"; to: 1; duration: receivedRequestTimeoutMs } - } - - property var progresTimeLabel - property double lastUpdateTime: 0 - onProgressChanged: { - // Only update each 0.2 seconds - const currentTime = Date.now() * 0.001; - if (currentTime - lastUpdateTime < 0.1) { - return - } - var currentCount = (progress * receivedRequestTimeoutMs * 0.001) - progresTimeLabel = (receivedRequestTimeoutMs * 0.001 - currentCount).toFixed(1) - lastUpdateTime = currentTime; + ProgressTracker { + id: requestProgressTracker + timeoutSeconds: receivedRequestTimeoutMs * 0.001 + onTimeout: mainWindow.hideIndicatorPopup() } Component.onCompleted: { - requestReceivedTimer.restart() - progressAnimation.restart() - } - - Timer { - id: requestReceivedTimer - interval: receivedRequestTimeoutMs - repeat: false - running: false - onTriggered: { - // Sanity check, only hide if this panel is visible - if (!controlRequestRectangle.visible) { - return - } - mainWindow.hideIndicatorPopup() - } + requestProgressTracker.start() } GridLayout { @@ -166,7 +137,7 @@ Item { // Action label QGCLabel { font.pointSize: ScreenTools.defaultFontPointSize * 1.1 - text: qsTr("Ignoring automatically in ") + progresTimeLabel + qsTr(" seconds") + text: qsTr("Ignoring automatically in ") + requestProgressTracker.progressLabel + qsTr(" seconds") } QGCButton { id: ignoreButton @@ -178,7 +149,7 @@ Item { Rectangle { id: overlayRectangle height: ScreenTools.defaultFontPixelWidth - width: parent.width * controlRequestRectangle.progress + width: parent.width * requestProgressTracker.progress color: qgcPal.buttonHighlight Layout.columnSpan: 2 } @@ -210,47 +181,17 @@ Item { PropertyAnimation { to: qgcPal.window; duration: 200 } } - // Indicator for visual feedback of sending control request timeout - property var progressTimeLabelSendRequest: "" - property double lastUpdateTimeSendRequest: 0 - onProgressSentRequestChanged: { - // Only update each 0.2 seconds - const currentTime = Date.now() * 0.001; - if (currentTime - lastUpdateTimeSendRequest < 0.1) { - return - } - var currentCount = (progressSentRequest * QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue) - progressTimeLabelSendRequest = (QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue - currentCount).toFixed(1) - lastUpdateTimeSendRequest = currentTime; + ProgressTracker { + id: sendRequestProgressTracker + timeoutSeconds: QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue } - property var progressSentRequest: 0 - SequentialAnimation on progressSentRequest { - id: progressSentRequestAnimation - running: false - loops: 1 - NumberAnimation { target: popupBackground; property: "progressSentRequest"; to: 1; duration: QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue * 1000 } - } - Timer { - id: requestSentTimer - interval: QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue * 1000 - repeat: false - running: false - onTriggered: { - progressTimeLabelSendRequest = "" - progressSentRequest = 0 - } - } - + // If a request was sent, and we get feedback that takeover has been allowed, stop the progress tracker as the request has been granted property var takeoverAllowedLocal: _root.gcsControlStatusFlags_TakeoverAllowed onTakeoverAllowedLocalChanged: { - if (takeoverAllowedLocal && requestSentTimer.running) { - requestSentTimer.stop() - progressSentRequestAnimation.stop() - progressTimeLabelSendRequest = "" - progressSentRequest = 0 + if (takeoverAllowedLocal && sendRequestProgressTracker.running) { + sendRequestProgressTracker.stop() } } - // end Indicator for visual feedback of sending control request timeout GridLayout { id: mainLayout @@ -299,9 +240,9 @@ Item { } QGCLabel { id: requestSentTimeoutLabel - text: qsTr("Request sent: ") + progressTimeLabelSendRequest + text: qsTr("Request sent: ") + sendRequestProgressTracker.progressLabel Layout.columnSpan: 2 - visible: progressTimeLabelSendRequest != "" + visible: sendRequestProgressTracker.running } FactCheckBox { text: qsTr("Allow takeover") @@ -310,19 +251,17 @@ Item { } QGCButton { text: gcsControlStatusFlags_TakeoverAllowed ? qsTr("Adquire Control") : qsTr("Send Request") - onClicked: requestControl() - Layout.alignment: Qt.AlignRight - visible: !isThisGCSinControl - enabled: !requestSentTimeoutLabel.visible - // If requesting control, we need to take care of sending the timeout, so the progress bar is on sync in requestor and GCS in control. Only needed if takeover isn't allowed - function requestControl() { + onClicked: { var timeout = gcsControlStatusFlags_TakeoverAllowed ? 0 : QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue activeVehicle.requestOperatorControl(requestControlAllowTakeoverFact.rawValue, timeout) if (timeout > 0) { - requestSentTimer.restart() - progressSentRequestAnimation.restart() + // Start UI timeout animation + sendRequestProgressTracker.start() } } + Layout.alignment: Qt.AlignRight + visible: !isThisGCSinControl + enabled: !sendRequestProgressTracker.running } QGCLabel { text: qsTr("Request Timeout (sec):") From dc5458c089b2d065c17bcd40b1acefe1f241d04c Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 7 Feb 2025 20:39:08 +0100 Subject: [PATCH 17/44] ControlIndicator.qml: add support to revert takeover not allowed after 10 seconds --- src/UI/toolbar/ControlIndicator.qml | 68 +++++++++++++++++++++++++++++ 1 file changed, 68 insertions(+) diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index e9bc21ff6977..aae0aecd248f 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -132,6 +132,9 @@ Item { onClicked: { activeVehicle.requestOperatorControl(true) // Allow takeover mainWindow.hideIndicatorPopup() + // After allowing takeover, if other GCS does not take control within 10 seconds + // takeover will be set to not allowed again. Notify user about this + mainWindow.showIndicatorPopup(_root, allowTakeoverExpirationPopup, false) } } // Action label @@ -157,6 +160,71 @@ Item { } } + // WE probably need to move this to backend, otherwise if panel dissapears countdown stops + + // Allow takeover expiration time popup. When a request is received and takeover was allowed, this popup alerts that after 10 seconds, this GCS will change back to takeover not allowed, as per mavlink specs + ProgressTracker { + id: revertTakeoverProgressTracker + timeoutSeconds: 10 + onTimeout: { + mainWindow.hideIndicatorPopup() + if (isThisGCSinControl) { + activeVehicle.requestOperatorControl(false) + } + } + } + Component { + id: allowTakeoverExpirationPopup + Item { + id: allowTakeoverExpirationRectangle + width: mainLayout.width + margins * 4 + height: mainLayout.height + margins * 4 + + Rectangle { + anchors.fill: parent + radius: ScreenTools.defaultFontPixelWidth / 2 + color: qgcPal.window + opacity: 0.7 + } + + // After accepting allow takeover after a request, we show the 10 seconds countdown after which takeover will be set again to not allowed. + // If during this time another GCS takes control, which is what we are expecting, remove this popup + property var isThisGCSinControlLocal: _root.isThisGCSinControl + onIsThisGCSinControlLocalChanged: { + if (visible && !isThisGCSinControlLocal) { + visible = false + } + } + + + Component.onCompleted: { + _root.revertTakeoverProgressTracker.start() + } + + GridLayout { + id: mainLayout + anchors.margins: margins * 2 + anchors.top: parent.top + anchors.right: parent.right + columns: 3 + + // Action label + QGCLabel { + font.pointSize: ScreenTools.defaultFontPointSize * 1.1 + text: qsTr("Reverting back to takeover not allowed if GCS ") + requestSysIdRequestingControl + + qsTr(" doesn't take control in ") + _root.revertTakeoverProgressTracker.progressLabel + + qsTr(" seconds ...") + } + QGCButton { + id: ignoreButton + text: qsTr("Ignore") + onClicked: mainWindow.hideIndicatorPopup() + Layout.alignment: Qt.AlignHCenter + } + } + } + } + // Popup panel, appears when clicking top control indicator Component { id: controlPopup From cd35a760fbc63eabc5c212d924ca7deb8e0bf8df Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Tue, 14 Jan 2025 14:55:37 +0100 Subject: [PATCH 18/44] vehicle.cc: fix after rebase --- src/Vehicle/Vehicle.cc | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index e25b57433fe8..f47351608d7f 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3979,13 +3979,13 @@ void Vehicle::_handleMessageInterval(const mavlink_message_t& message) void Vehicle::requestOperatorControl(bool allowOverride, int requestTimeoutSecs) { int safeRequestTimeoutSecs; - int requestTimeoutSecsMin = _settingsManager->flyViewSettings()->requestControlTimeout()->cookedMin().toInt(); - int requestTimeoutSecsMax = _settingsManager->flyViewSettings()->requestControlTimeout()->cookedMax().toInt(); + int requestTimeoutSecsMin = SettingsManager::instance()->flyViewSettings()->requestControlTimeout()->cookedMin().toInt(); + int requestTimeoutSecsMax = SettingsManager::instance()->flyViewSettings()->requestControlTimeout()->cookedMax().toInt(); if (requestTimeoutSecs > requestTimeoutSecsMin && requestTimeoutSecs < requestTimeoutSecsMax) { safeRequestTimeoutSecs = requestTimeoutSecs; } else { // If out of limits use default value - safeRequestTimeoutSecs = _settingsManager->flyViewSettings()->requestControlTimeout()->cookedDefaultValue().toInt(); + safeRequestTimeoutSecs = SettingsManager::instance()->flyViewSettings()->requestControlTimeout()->cookedDefaultValue().toInt(); } sendMavCommand(_defaultComponentId, MAV_CMD(32100), // MAV_CMD_REQUEST_OPERATOR_CONTROL From 66fe67b1bdf3fcd5626b84bec01bed9ce93d81a6 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Thu, 6 Feb 2025 20:29:23 +0100 Subject: [PATCH 19/44] MainRootWindow: allow to not dim background on showIndicatorDrawer --- src/UI/MainRootWindow.qml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/UI/MainRootWindow.qml b/src/UI/MainRootWindow.qml index a9f9e3639177..4a9d0dc951de 100644 --- a/src/UI/MainRootWindow.qml +++ b/src/UI/MainRootWindow.qml @@ -654,9 +654,10 @@ ApplicationWindow { //------------------------------------------------------------------------- //-- Indicator Drawer - function showIndicatorDrawer(drawerComponent, indicatorItem) { + function showIndicatorDrawer(drawerComponent, indicatorItem, dim = true) { indicatorDrawer.sourceComponent = drawerComponent indicatorDrawer.indicatorItem = indicatorItem + indicatorDrawer.dim = dim indicatorDrawer.open() } From e092b2461cc83d21a4a61e954d8752fdd2482f06 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 7 Feb 2025 20:12:55 +0100 Subject: [PATCH 20/44] Vehicle: requestOperatorControl(), adjust limits to use default value --- src/Vehicle/Vehicle.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index f47351608d7f..2748afeec7b2 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3981,7 +3981,7 @@ void Vehicle::requestOperatorControl(bool allowOverride, int requestTimeoutSecs) int safeRequestTimeoutSecs; int requestTimeoutSecsMin = SettingsManager::instance()->flyViewSettings()->requestControlTimeout()->cookedMin().toInt(); int requestTimeoutSecsMax = SettingsManager::instance()->flyViewSettings()->requestControlTimeout()->cookedMax().toInt(); - if (requestTimeoutSecs > requestTimeoutSecsMin && requestTimeoutSecs < requestTimeoutSecsMax) { + if (requestTimeoutSecs >= requestTimeoutSecsMin && requestTimeoutSecs <= requestTimeoutSecsMax) { safeRequestTimeoutSecs = requestTimeoutSecs; } else { // If out of limits use default value From a929d6209fbbbd3d5c57eb5f7ec6e78afbe7312e Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 7 Feb 2025 20:22:20 +0100 Subject: [PATCH 21/44] ControlIndicator.qml: fix after rebase to master --- src/UI/toolbar/ControlIndicator.qml | 138 +++++++++++----------------- 1 file changed, 54 insertions(+), 84 deletions(-) diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index aae0aecd248f..17b8d0ff408c 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -10,7 +10,7 @@ import QGroundControl.FactSystem import QGroundControl.FactControls Item { - id: _root + id: control width: controlIndicatorIconGCS.width * 1.1 anchors.top: parent.top anchors.bottom: parent.bottom @@ -44,7 +44,7 @@ Item { // Popup prompting user to accept control from other GCS onRequestOperatorControlReceived: (sysIdRequestingControl, allowTakeover, requestTimeoutSecs) => { // If we don't have the indicator visible ( not receiving CONTROL_STATUS ) don't proceed - if (!_root.showIndicator) { + if (!control.showIndicator) { return } requestSysIdRequestingControl = sysIdRequestingControl @@ -52,9 +52,9 @@ Item { // If request came without request timeout, use our default one receivedRequestTimeoutMs = requestTimeoutSecs !== 0 ? requestTimeoutSecs * 1000 : QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.defaultValue // First hide current popup, in case the normal control panel is visible - mainWindow.hideIndicatorPopup() + mainWindow.closeIndicatorDrawer() // When showing the popup, the component will automatically start the count down in controlRequestPopup - mainWindow.showIndicatorPopup(_root, controlRequestPopup, false) + mainWindow.showIndicatorDrawer(controlRequestPopup, control, false) } // Animation to blink indicator when any related info changes onGcsControlStatusChanged: { @@ -87,33 +87,20 @@ Item { // Control request popup. Appears when other GCS requests control, so operator on this one can accept or deny it Component { id: controlRequestPopup - Item { - id: controlRequestRectangle - width: mainLayout.width + margins * 4 - height: mainLayout.height + margins * 4 - - Rectangle { - anchors.fill: parent - radius: ScreenTools.defaultFontPixelWidth / 2 - color: qgcPal.window - opacity: 0.7 - } + ToolIndicatorPage { ProgressTracker { id: requestProgressTracker timeoutSeconds: receivedRequestTimeoutMs * 0.001 - onTimeout: mainWindow.hideIndicatorPopup() + onTimeout: mainWindow.closeIndicatorDrawer() } Component.onCompleted: { requestProgressTracker.start() } - GridLayout { + contentComponent: GridLayout { id: mainLayout - anchors.margins: margins * 2 - anchors.top: parent.top - anchors.right: parent.right columns: 3 // Action label @@ -130,11 +117,11 @@ Item { Layout.alignment: Qt.AlignBottom Layout.fillHeight: true onClicked: { - activeVehicle.requestOperatorControl(true) // Allow takeover - mainWindow.hideIndicatorPopup() + control.activeVehicle.requestOperatorControl(true) // Allow takeover + mainWindow.closeIndicatorDrawer() // After allowing takeover, if other GCS does not take control within 10 seconds // takeover will be set to not allowed again. Notify user about this - mainWindow.showIndicatorPopup(_root, allowTakeoverExpirationPopup, false) + mainWindow.showIndicatorDrawer(allowTakeoverExpirationPopup, control, false) } } // Action label @@ -145,7 +132,7 @@ Item { QGCButton { id: ignoreButton text: qsTr("Ignore") - onClicked: mainWindow.hideIndicatorPopup() + onClicked: mainWindow.closeIndicatorDrawer() Layout.alignment: Qt.AlignHCenter } // Actual progress bar @@ -160,65 +147,50 @@ Item { } } - // WE probably need to move this to backend, otherwise if panel dissapears countdown stops - - // Allow takeover expiration time popup. When a request is received and takeover was allowed, this popup alerts that after 10 seconds, this GCS will change back to takeover not allowed, as per mavlink specs - ProgressTracker { - id: revertTakeoverProgressTracker - timeoutSeconds: 10 - onTimeout: { - mainWindow.hideIndicatorPopup() - if (isThisGCSinControl) { - activeVehicle.requestOperatorControl(false) - } - } - } Component { id: allowTakeoverExpirationPopup - Item { - id: allowTakeoverExpirationRectangle - width: mainLayout.width + margins * 4 - height: mainLayout.height + margins * 4 - Rectangle { - anchors.fill: parent - radius: ScreenTools.defaultFontPixelWidth / 2 - color: qgcPal.window - opacity: 0.7 + ToolIndicatorPage { + // WE probably need to move this to backend, otherwise if panel dissapears countdown stops + // Allow takeover expiration time popup. When a request is received and takeover was allowed, this popup alerts that after 10 seconds, this GCS will change back to takeover not allowed, as per mavlink specs + ProgressTracker { + id: revertTakeoverProgressTracker + timeoutSeconds: 10 + onTimeout: { + mainWindow.closeIndicatorDrawer() + if (isThisGCSinControl) { + control.activeVehicle.requestOperatorControl(false) + } + } } - // After accepting allow takeover after a request, we show the 10 seconds countdown after which takeover will be set again to not allowed. // If during this time another GCS takes control, which is what we are expecting, remove this popup - property var isThisGCSinControlLocal: _root.isThisGCSinControl + property var isThisGCSinControlLocal: control.isThisGCSinControl onIsThisGCSinControlLocalChanged: { if (visible && !isThisGCSinControlLocal) { - visible = false + mainWindow.closeIndicatorDrawer() } } - Component.onCompleted: { - _root.revertTakeoverProgressTracker.start() + revertTakeoverProgressTracker.start() } - GridLayout { + contentComponent: GridLayout { id: mainLayout - anchors.margins: margins * 2 - anchors.top: parent.top - anchors.right: parent.right columns: 3 // Action label QGCLabel { font.pointSize: ScreenTools.defaultFontPointSize * 1.1 text: qsTr("Reverting back to takeover not allowed if GCS ") + requestSysIdRequestingControl + - qsTr(" doesn't take control in ") + _root.revertTakeoverProgressTracker.progressLabel + + qsTr(" doesn't take control in ") + revertTakeoverProgressTracker.progressLabel + qsTr(" seconds ...") } QGCButton { id: ignoreButton text: qsTr("Ignore") - onClicked: mainWindow.hideIndicatorPopup() + onClicked: mainWindow.closeIndicatorDrawer() Layout.alignment: Qt.AlignHCenter } } @@ -229,43 +201,41 @@ Item { Component { id: controlPopup - Rectangle { - id: popupBackground - width: mainLayout.width + mainLayout.anchors.margins * 2 - height: mainLayout.height + mainLayout.anchors.margins * 2 - color: qgcPal.window - radius: panelRadius - - Connections { - target: _root - onTriggerAnimations: doColorAnimation() - } - function doColorAnimation() { colorAnimation.restart() } - SequentialAnimation on color { - id: colorAnimation - running: false - loops: 1 - PropertyAnimation { to: qgcPal.windowShade; duration: 200 } - PropertyAnimation { to: qgcPal.window; duration: 200 } - } + ToolIndicatorPage { + // Rectangle { + // id: popupBackground + // anchors.fill: parent + // color: qgcPal.window + // radius: panelRadius + + // Connections { + // target: control + // onTriggerAnimations: doColorAnimation() + // } + // function doColorAnimation() { colorAnimation.restart() } + // SequentialAnimation on color { + // id: colorAnimation + // running: false + // loops: 1 + // PropertyAnimation { to: qgcPal.windowShade; duration: 200 } + // PropertyAnimation { to: qgcPal.window; duration: 200 } + // } + // } ProgressTracker { id: sendRequestProgressTracker timeoutSeconds: QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue } // If a request was sent, and we get feedback that takeover has been allowed, stop the progress tracker as the request has been granted - property var takeoverAllowedLocal: _root.gcsControlStatusFlags_TakeoverAllowed + property var takeoverAllowedLocal: control.gcsControlStatusFlags_TakeoverAllowed onTakeoverAllowedLocalChanged: { if (takeoverAllowedLocal && sendRequestProgressTracker.running) { sendRequestProgressTracker.stop() } } - GridLayout { + contentComponent: GridLayout { id: mainLayout - anchors.margins: ScreenTools.defaultFontPixelWidth - anchors.top: parent.top - anchors.right: parent.right columns: 2 QGCLabel { @@ -321,7 +291,7 @@ Item { text: gcsControlStatusFlags_TakeoverAllowed ? qsTr("Adquire Control") : qsTr("Send Request") onClicked: { var timeout = gcsControlStatusFlags_TakeoverAllowed ? 0 : QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue - activeVehicle.requestOperatorControl(requestControlAllowTakeoverFact.rawValue, timeout) + control.activeVehicle.requestOperatorControl(requestControlAllowTakeoverFact.rawValue, timeout) if (timeout > 0) { // Start UI timeout animation sendRequestProgressTracker.start() @@ -343,7 +313,7 @@ Item { } QGCButton { text: qsTr("Change") - onClicked: activeVehicle.requestOperatorControl(requestControlAllowTakeoverFact.rawValue) + onClicked: control.activeVehicle.requestOperatorControl(requestControlAllowTakeoverFact.rawValue) visible: isThisGCSinControl Layout.alignment: Qt.AlignRight enabled: gcsControlStatusFlags_TakeoverAllowed != requestControlAllowTakeoverFact.rawValue @@ -426,7 +396,7 @@ Item { MouseArea { anchors.fill: parent onClicked: { - mainWindow.showIndicatorPopup(_root, controlPopup, false) + mainWindow.showIndicatorDrawer(controlPopup, control, false) } } } From 6f403629e45bbe3ee50e4c89e7453631a2a27a2c Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sat, 8 Feb 2025 14:10:12 +0100 Subject: [PATCH 22/44] Vehicle: move revert takeover allowed to backend --- src/Vehicle/Vehicle.cc | 25 +++++++++++++++++++++++++ src/Vehicle/Vehicle.h | 4 ++++ 2 files changed, 29 insertions(+) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 2748afeec7b2..fa5ae92f231c 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -77,6 +77,10 @@ QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog") #define SET_HOME_TERRAIN_ALT_MAX 10000 #define SET_HOME_TERRAIN_ALT_MIN -500 +// After a second GCS has requested control and we have given it permission to takeover, we will remove takeover permission automatically after this timeout +// If the second GCS didn't get control +#define REQUEST_OPERATOR_CONTROL_ALLOW_TAKEOVER_TIMEOUT_MSECS 10000 + const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle."); // Standard connected vehicle @@ -3976,6 +3980,22 @@ void Vehicle::_handleMessageInterval(const mavlink_message_t& message) } } +void Vehicle::startTimerRevertAllowTakeover() +{ + _timerRevertAllowTakeover.stop(); + _timerRevertAllowTakeover.setSingleShot(true); + _timerRevertAllowTakeover.setInterval(operatorControlTakeoverTimeoutMsecs()); + // Disconnect any previous connections to avoid multiple handlers + disconnect(&_timerRevertAllowTakeover, &QTimer::timeout, nullptr, nullptr); + + connect(&_timerRevertAllowTakeover, &QTimer::timeout, [this](){ + if (MAVLinkProtocol::instance()->getSystemId() == _sysid_in_control) { + this->requestOperatorControl(false); + } + }); + _timerRevertAllowTakeover.start(); +} + void Vehicle::requestOperatorControl(bool allowOverride, int requestTimeoutSecs) { int safeRequestTimeoutSecs; @@ -4042,6 +4062,11 @@ void Vehicle::_handleCommandLong(const mavlink_message_t& message) } } +int Vehicle::operatorControlTakeoverTimeoutMsecs() const +{ + return REQUEST_OPERATOR_CONTROL_ALLOW_TAKEOVER_TIMEOUT_MSECS; +} + void Vehicle::_requestMessageMessageIntervalResultHandler(void* resultHandlerData, MAV_RESULT result, RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t& message) { if((result != MAV_RESULT_ACCEPTED) || (failureCode != RequestMessageNoFailure)) diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 4bf83f5d1fe1..6507fae01b9d 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -1326,6 +1326,7 @@ private slots: /* CONTROL STATUS HANDLER */ /*===========================================================================*/ public: + Q_INVOKABLE void startTimerRevertAllowTakeover(); Q_INVOKABLE void requestOperatorControl(bool allowOverride, int requestTimeoutSecs = 0); private: @@ -1336,17 +1337,20 @@ private slots: Q_PROPERTY(bool gcsControlStatusFlags_SystemManager READ gcsControlStatusFlags_SystemManager NOTIFY gcsControlStatusChanged) Q_PROPERTY(bool gcsControlStatusFlags_TakeoverAllowed READ gcsControlStatusFlags_TakeoverAllowed NOTIFY gcsControlStatusChanged) Q_PROPERTY(bool firstControlStatusReceived READ firstControlStatusReceived NOTIFY gcsControlStatusChanged) + Q_PROPERTY(int operatorControlTakeoverTimeoutMsecs READ operatorControlTakeoverTimeoutMsecs CONSTANT) uint8_t sysidInControl() const { return _sysid_in_control; } bool gcsControlStatusFlags_SystemManager() const { return _gcsControlStatusFlags_SystemManager; } bool gcsControlStatusFlags_TakeoverAllowed() const { return _gcsControlStatusFlags_TakeoverAllowed; } bool firstControlStatusReceived() const { return _firstControlStatusReceived; } + int operatorControlTakeoverTimeoutMsecs() const; uint8_t _sysid_in_control = 0; uint8_t _gcsControlStatusFlags = 0; bool _gcsControlStatusFlags_SystemManager = 0; bool _gcsControlStatusFlags_TakeoverAllowed = 0; bool _firstControlStatusReceived = false; + QTimer _timerRevertAllowTakeover; signals: void gcsControlStatusChanged(); From e9130b50c66f03fd947c27e77eacf1272d0bb381 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sat, 8 Feb 2025 14:10:28 +0100 Subject: [PATCH 23/44] ControlIndicator.qml: move revert takeover allowed to backend --- src/UI/toolbar/ControlIndicator.qml | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index 17b8d0ff408c..60348a76ba14 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -121,6 +121,7 @@ Item { mainWindow.closeIndicatorDrawer() // After allowing takeover, if other GCS does not take control within 10 seconds // takeover will be set to not allowed again. Notify user about this + control.activeVehicle.startTimerRevertAllowTakeover() mainWindow.showIndicatorDrawer(allowTakeoverExpirationPopup, control, false) } } @@ -151,16 +152,13 @@ Item { id: allowTakeoverExpirationPopup ToolIndicatorPage { - // WE probably need to move this to backend, otherwise if panel dissapears countdown stops - // Allow takeover expiration time popup. When a request is received and takeover was allowed, this popup alerts that after 10 seconds, this GCS will change back to takeover not allowed, as per mavlink specs + // Allow takeover expiration time popup. When a request is received and takeover was allowed, this popup alerts + // that after vehicle::REQUEST_OPERATOR_CONTROL_ALLOW_TAKEOVER_TIMEOUT_MSECS seconds, this GCS will change back to takeover not allowed, as per mavlink specs ProgressTracker { id: revertTakeoverProgressTracker - timeoutSeconds: 10 + timeoutSeconds: control.activeVehicle.operatorControlTakeoverTimeoutMsecs * 0.001 onTimeout: { mainWindow.closeIndicatorDrawer() - if (isThisGCSinControl) { - control.activeVehicle.requestOperatorControl(false) - } } } // After accepting allow takeover after a request, we show the 10 seconds countdown after which takeover will be set again to not allowed. From 600607adc6e3e1351824392b3bee2d40f37118b2 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sat, 8 Feb 2025 16:03:54 +0100 Subject: [PATCH 24/44] Vehicle: keep track on backend of timer for a request sent --- src/Vehicle/Vehicle.cc | 31 +++++++++++++++++++++++++++++++ src/Vehicle/Vehicle.h | 8 ++++++++ 2 files changed, 39 insertions(+) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index fa5ae92f231c..5b78635039cf 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -4014,6 +4014,29 @@ void Vehicle::requestOperatorControl(bool allowOverride, int requestTimeoutSecs) 1, // Action - 0: Release control, 1: Request control. allowOverride ? 1 : 0, // Allow takeover - Enable automatic granting of ownership on request. 0: Ask current owner and reject request, 1: Allow automatic takeover. safeRequestTimeoutSecs); // Timeout in seconds before a request to a GCS to allow takeover is assumed to be rejected. This is used to display the timeout graphically on requestor and GCS in control. + + // If this is a request we sent to other GCS, start timer so User can not keep sending requests until the current timeout expires + if (requestTimeoutSecs > 0) { + requestOperatorControlStartTimer(requestTimeoutSecs * 1000); + } +} + +void Vehicle::requestOperatorControlStartTimer(int requestTimeoutMsecs) +{ + // First flag requests not allowed + _sendControlRequestAllowed = false; + emit sendControlRequestAllowedChanged(false); + // Setup timer to re enable it again after timeout + _timerRequestOperatorControl.stop(); + _timerRequestOperatorControl.setSingleShot(true); + _timerRequestOperatorControl.setInterval(requestTimeoutMsecs); + // Disconnect any previous connections to avoid multiple handlers + disconnect(&_timerRequestOperatorControl, &QTimer::timeout, nullptr, nullptr); + connect(&_timerRequestOperatorControl, &QTimer::timeout, [this](){ + _sendControlRequestAllowed = true; + emit sendControlRequestAllowedChanged(true); + }); + _timerRequestOperatorControl.start(); } void Vehicle::_handleControlStatus(const mavlink_message_t& message) @@ -4042,6 +4065,14 @@ void Vehicle::_handleControlStatus(const mavlink_message_t& message) if (updateControlStatusSignals) { emit gcsControlStatusChanged(); } + + // If we were waiting for a request to be accepted and now it was accepted, adjust flags accordingly so + // UI unlocks the request/take control button + if (!sendControlRequestAllowed() && _gcsControlStatusFlags_TakeoverAllowed) { + disconnect(&_timerRequestOperatorControl, &QTimer::timeout, nullptr, nullptr); + _sendControlRequestAllowed = true; + emit sendControlRequestAllowedChanged(true); + } } void Vehicle::_handleCommandRequestOperatorControl(const mavlink_command_long_t commandLong) diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 6507fae01b9d..119342844e15 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -1338,12 +1338,17 @@ private slots: Q_PROPERTY(bool gcsControlStatusFlags_TakeoverAllowed READ gcsControlStatusFlags_TakeoverAllowed NOTIFY gcsControlStatusChanged) Q_PROPERTY(bool firstControlStatusReceived READ firstControlStatusReceived NOTIFY gcsControlStatusChanged) Q_PROPERTY(int operatorControlTakeoverTimeoutMsecs READ operatorControlTakeoverTimeoutMsecs CONSTANT) + Q_PROPERTY(int requestOperatorControlRemainingMsecs READ requestOperatorControlRemainingMsecs CONSTANT) + Q_PROPERTY(bool sendControlRequestAllowed READ sendControlRequestAllowed NOTIFY sendControlRequestAllowedChanged) uint8_t sysidInControl() const { return _sysid_in_control; } bool gcsControlStatusFlags_SystemManager() const { return _gcsControlStatusFlags_SystemManager; } bool gcsControlStatusFlags_TakeoverAllowed() const { return _gcsControlStatusFlags_TakeoverAllowed; } bool firstControlStatusReceived() const { return _firstControlStatusReceived; } int operatorControlTakeoverTimeoutMsecs() const; + int requestOperatorControlRemainingMsecs() const { return _timerRequestOperatorControl.remainingTime(); } + bool sendControlRequestAllowed() const { return _sendControlRequestAllowed; } + void requestOperatorControlStartTimer(int requestTimeoutMsecs); uint8_t _sysid_in_control = 0; uint8_t _gcsControlStatusFlags = 0; @@ -1351,10 +1356,13 @@ private slots: bool _gcsControlStatusFlags_TakeoverAllowed = 0; bool _firstControlStatusReceived = false; QTimer _timerRevertAllowTakeover; + QTimer _timerRequestOperatorControl; + bool _sendControlRequestAllowed = true; signals: void gcsControlStatusChanged(); void requestOperatorControlReceived(int sysIdRequestingControl, int allowTakeover, int requestTimeoutSecs); + void sendControlRequestAllowedChanged(bool sendControlRequestAllowed); /*===========================================================================*/ /* STATUS TEXT HANDLER */ From 0b9bb5ce5c86ad10e15522f08549f0c43986aac7 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sat, 8 Feb 2025 16:04:09 +0100 Subject: [PATCH 25/44] ControlIndicator.qml: keep track on backend of timer for a request sent --- src/UI/toolbar/ControlIndicator.qml | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index 60348a76ba14..22a36b501f2a 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -23,6 +23,7 @@ Item { property Fact requestControlAllowTakeoverFact: QGroundControl.settingsManager.flyViewSettings.requestControlAllowTakeover property bool requestControlAllowTakeover: requestControlAllowTakeoverFact.rawValue property bool isThisGCSinControl: sysidInControl == QGroundControl.mavlinkSystemID + property bool sendControlRequestAllowed: activeVehicle ? activeVehicle.sendControlRequestAllowed : false property var margins: ScreenTools.defaultFontPixelWidth property var panelRadius: ScreenTools.defaultFontPixelWidth * 0.5 @@ -232,6 +233,20 @@ Item { } } + Component.onCompleted: { + // If send control request is not allowed it means we recently sent a request, closed the popup, and opened again + // before the other request timeout expired. This way we can keep track of the time remaining and update UI accordingly + if (!sendControlRequestAllowed) { + // vehicle.requestOperatorControlRemainingMsecs holds the time remaining for the current request + startProgressTracker(control.activeVehicle.requestOperatorControlRemainingMsecs * 0.001) + } + } + + function startProgressTracker(timeoutSeconds) { + sendRequestProgressTracker.timeoutSeconds = timeoutSeconds + sendRequestProgressTracker.start() + } + contentComponent: GridLayout { id: mainLayout columns: 2 @@ -292,7 +307,7 @@ Item { control.activeVehicle.requestOperatorControl(requestControlAllowTakeoverFact.rawValue, timeout) if (timeout > 0) { // Start UI timeout animation - sendRequestProgressTracker.start() + startProgressTracker(timeout) } } Layout.alignment: Qt.AlignRight From 795a434c9bf7ebdd76651648a1345f67a80a9ba0 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Thu, 6 Feb 2025 20:29:48 +0100 Subject: [PATCH 26/44] GimbalIndicator.qml: do not dim background on showIndicatorDrawer --- src/UI/toolbar/GimbalIndicator.qml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/UI/toolbar/GimbalIndicator.qml b/src/UI/toolbar/GimbalIndicator.qml index 97e708929f8a..80386728761b 100644 --- a/src/UI/toolbar/GimbalIndicator.qml +++ b/src/UI/toolbar/GimbalIndicator.qml @@ -405,7 +405,7 @@ Item { MouseArea { anchors.fill: parent - onClicked: mainWindow.showIndicatorDrawer(gimbalControlsPage, control) + onClicked: mainWindow.showIndicatorDrawer(gimbalControlsPage, control, false) } Connections { From f71899c002a5aa19cef95accd9bd925a2403e3a8 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sat, 8 Feb 2025 13:18:17 +0100 Subject: [PATCH 27/44] main.cc: allow command line override of systemId (example --system-id:255) --- src/main.cc | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/src/main.cc b/src/main.cc index 0a8220b91718..99d2a6d87f9a 100644 --- a/src/main.cc +++ b/src/main.cc @@ -17,6 +17,7 @@ #include "QGCApplication.h" #include "QGCLogging.h" #include "CmdLineOptParser.h" +#include "MAVLinkProtocol.h" #if !defined(Q_OS_ANDROID) && !defined(Q_OS_IOS) #include @@ -134,6 +135,8 @@ int main(int argc, char *argv[]) bool runUnitTests = false; bool simpleBootTest = false; + QString systemIdStr = QString(); + bool hasSystemId = false; #ifdef QT_DEBUG // We parse a small set of command line options here prior to QGCApplication in order to handle the ones @@ -147,6 +150,7 @@ int main(int argc, char *argv[]) { "--unittest", &runUnitTests, &unitTestOptions }, { "--unittest-stress", &stressUnitTests, &unitTestOptions }, { "--no-windows-assert-ui", &quietWindowsAsserts, nullptr }, + { "--system-id", &hasSystemId, &systemIdStr }, // Add additional command line option flags here }; @@ -189,6 +193,18 @@ int main(int argc, char *argv[]) app.init(); + // Set system ID if specified via command line, for example --system-id:255 + if (hasSystemId) { + bool ok; + int systemId = systemIdStr.toInt(&ok); + if (ok && systemId >= 0 && systemId <= 255) { // MAVLink system IDs are 8-bit + qDebug() << "Setting MAVLink System ID to:" << systemId; + MAVLinkProtocol::instance()->setSystemId(systemId); + } else { + qDebug() << "Not setting MAVLink System ID. It must be between 0 and 255. Invalid system ID value:" << systemIdStr; + } + } + int exitCode = 0; #ifdef QGC_UNITTEST_BUILD From 4d3a10bc2b551f838b1b84dfdcb128c9e6a2f934 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 11 May 2025 13:19:00 +0200 Subject: [PATCH 28/44] main.cc: allow to not use runguard at startup by command line argument: Useful to test several instances of QGC on the same machine, to test multi GCS setups --- src/main.cc | 52 +++++++++++++++++++++++++--------------------------- 1 file changed, 25 insertions(+), 27 deletions(-) diff --git a/src/main.cc b/src/main.cc index 99d2a6d87f9a..71f1fb28ebb6 100644 --- a/src/main.cc +++ b/src/main.cc @@ -71,6 +71,30 @@ int WindowsCrtReportHook(int reportType, char* message, int* returnValue) int main(int argc, char *argv[]) { + bool runUnitTests = false; + bool simpleBootTest = false; + QString systemIdStr = QString(); + bool hasSystemId = false; + bool bypassRunGuard = false; + + bool stressUnitTests = false; // Stress test unit tests + bool quietWindowsAsserts = false; // Don't let asserts pop dialog boxes + QString unitTestOptions; + + CmdLineOpt_t rgCmdLineOptions[] = { +#ifdef QT_DEBUG + { "--unittest", &runUnitTests, &unitTestOptions }, + { "--unittest-stress", &stressUnitTests, &unitTestOptions }, + { "--no-windows-assert-ui", &quietWindowsAsserts, nullptr }, +#endif + { "--system-id", &hasSystemId, &systemIdStr }, + { "--allow-multiple", &bypassRunGuard, nullptr }, + { "--simple-boot-test", &simpleBootTest, nullptr }, + // Add additional command line option flags here + }; + + ParseCmdLineOptions(argc, argv, rgCmdLineOptions, std::size(rgCmdLineOptions), false); + #if !defined(Q_OS_ANDROID) && !defined(Q_OS_IOS) // We make the runguard key different for custom and non custom // builds, so they can be executed together in the same device. @@ -79,7 +103,7 @@ int main(int argc, char *argv[]) const QString runguardString = QStringLiteral("%1 RunGuardKey").arg(QGC_APP_NAME); RunGuard guard(runguardString); - if (!guard.tryToRun()) { + if (!bypassRunGuard && !guard.tryToRun()) { QApplication errorApp(argc, argv); QMessageBox::critical(nullptr, QObject::tr("Error"), QObject::tr("A second instance of %1 is already running. Please close the other instance and try again.").arg(QGC_APP_NAME) @@ -133,28 +157,7 @@ int main(int argc, char *argv[]) } #endif - bool runUnitTests = false; - bool simpleBootTest = false; - QString systemIdStr = QString(); - bool hasSystemId = false; - #ifdef QT_DEBUG - // We parse a small set of command line options here prior to QGCApplication in order to handle the ones - // which need to be handled before a QApplication object is started. - - bool stressUnitTests = false; // Stress test unit tests - bool quietWindowsAsserts = false; // Don't let asserts pop dialog boxes - - QString unitTestOptions; - CmdLineOpt_t rgCmdLineOptions[] = { - { "--unittest", &runUnitTests, &unitTestOptions }, - { "--unittest-stress", &stressUnitTests, &unitTestOptions }, - { "--no-windows-assert-ui", &quietWindowsAsserts, nullptr }, - { "--system-id", &hasSystemId, &systemIdStr }, - // Add additional command line option flags here - }; - - ParseCmdLineOptions(argc, argv, rgCmdLineOptions, std::size(rgCmdLineOptions), false); if (stressUnitTests) { runUnitTests = true; } @@ -175,11 +178,6 @@ int main(int argc, char *argv[]) SetErrorMode(dwMode | SEM_NOGPFAULTERRORBOX); } #endif // Q_OS_WIN -#else - CmdLineOpt_t rgCmdLineOptions[] = { - { "--simple-boot-test", &simpleBootTest, nullptr }, - }; - ParseCmdLineOptions(argc, argv, rgCmdLineOptions, std::size(rgCmdLineOptions), false); #endif // QT_DEBUG QGCApplication app(argc, argv, runUnitTests, simpleBootTest); From 83503ad6d9585dcbd7487834e110ec919d519976 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sat, 8 Feb 2025 17:29:46 +0100 Subject: [PATCH 29/44] ControlIndicator.qml: cleanup comments --- src/UI/toolbar/ControlIndicator.qml | 21 ++------------------- 1 file changed, 2 insertions(+), 19 deletions(-) diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index 22a36b501f2a..7d1548ce65c5 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -149,6 +149,8 @@ Item { } } + // Allow takeover expiration time popup. When a request is received and takeover was allowed, this popup alerts + // that after vehicle::REQUEST_OPERATOR_CONTROL_ALLOW_TAKEOVER_TIMEOUT_MSECS seconds, this GCS will change back to takeover not allowed, as per mavlink specs Component { id: allowTakeoverExpirationPopup @@ -201,25 +203,6 @@ Item { id: controlPopup ToolIndicatorPage { - // Rectangle { - // id: popupBackground - // anchors.fill: parent - // color: qgcPal.window - // radius: panelRadius - - // Connections { - // target: control - // onTriggerAnimations: doColorAnimation() - // } - // function doColorAnimation() { colorAnimation.restart() } - // SequentialAnimation on color { - // id: colorAnimation - // running: false - // loops: 1 - // PropertyAnimation { to: qgcPal.windowShade; duration: 200 } - // PropertyAnimation { to: qgcPal.window; duration: 200 } - // } - // } ProgressTracker { id: sendRequestProgressTracker From dbde31748a67430eb785369ae3b13d71b3e4b566 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 14 Feb 2025 19:49:41 +0100 Subject: [PATCH 30/44] main.cc: --allow-multiple argument only allowed if QT_DEBUG --- src/main.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main.cc b/src/main.cc index 71f1fb28ebb6..d8812e04b566 100644 --- a/src/main.cc +++ b/src/main.cc @@ -86,9 +86,9 @@ int main(int argc, char *argv[]) { "--unittest", &runUnitTests, &unitTestOptions }, { "--unittest-stress", &stressUnitTests, &unitTestOptions }, { "--no-windows-assert-ui", &quietWindowsAsserts, nullptr }, + { "--allow-multiple", &bypassRunGuard, nullptr }, #endif { "--system-id", &hasSystemId, &systemIdStr }, - { "--allow-multiple", &bypassRunGuard, nullptr }, { "--simple-boot-test", &simpleBootTest, nullptr }, // Add additional command line option flags here }; From 35755680faa3d6ccd7104c612270892c107cada0 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 14 Feb 2025 19:50:08 +0100 Subject: [PATCH 31/44] FirmwarePlugin: ControlIndicator.qml only available if QT_DEBUG --- src/FirmwarePlugin/FirmwarePlugin.cc | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 59617af8af4f..17cea3245a18 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -212,7 +212,10 @@ const QVariantList &FirmwarePlugin::toolIndicators(const Vehicle*) QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Controls/BatteryIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/RemoteIDIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GimbalIndicator.qml")), +// ControlIndicator is only available in debug builds for the moment +#ifdef QT_DEBUG QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ControlIndicator.qml")), +#endif }); } From 7545dd9f104bb0731f8fb3aa5db5298778566a16 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 16 Feb 2025 17:45:58 +0100 Subject: [PATCH 32/44] Revert "MainRootWindow: allow to not dim background on showIndicatorDrawer" This reverts commit e2d846ed71fdff64d5ed832e48bd59a8dc690dce. --- src/UI/MainRootWindow.qml | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/UI/MainRootWindow.qml b/src/UI/MainRootWindow.qml index 4a9d0dc951de..a2d1fa02a669 100644 --- a/src/UI/MainRootWindow.qml +++ b/src/UI/MainRootWindow.qml @@ -654,10 +654,9 @@ ApplicationWindow { //------------------------------------------------------------------------- //-- Indicator Drawer - function showIndicatorDrawer(drawerComponent, indicatorItem, dim = true) { + function showIndicatorDrawer(drawerComponent, indicatorItem) { indicatorDrawer.sourceComponent = drawerComponent indicatorDrawer.indicatorItem = indicatorItem - indicatorDrawer.dim = dim indicatorDrawer.open() } @@ -678,7 +677,6 @@ ApplicationWindow { modal: true focus: true closePolicy: Popup.CloseOnEscape | Popup.CloseOnPressOutside - dim: false property var sourceComponent property var indicatorItem From 4450e074105965d025f3ccec082195c3600b8926 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 16 Feb 2025 17:48:27 +0100 Subject: [PATCH 33/44] Revert "GimbalIndicator.qml: do not dim background on showIndicatorDrawer" This reverts commit c68c1c01d1178606d2e126e6c8310f9a8fdddcab. --- src/UI/toolbar/GimbalIndicator.qml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/UI/toolbar/GimbalIndicator.qml b/src/UI/toolbar/GimbalIndicator.qml index 80386728761b..97e708929f8a 100644 --- a/src/UI/toolbar/GimbalIndicator.qml +++ b/src/UI/toolbar/GimbalIndicator.qml @@ -405,7 +405,7 @@ Item { MouseArea { anchors.fill: parent - onClicked: mainWindow.showIndicatorDrawer(gimbalControlsPage, control, false) + onClicked: mainWindow.showIndicatorDrawer(gimbalControlsPage, control) } Connections { From dbacd7d7dad192268ef2f389958e85ed8c8b5062 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 16 Feb 2025 17:50:31 +0100 Subject: [PATCH 34/44] ControlIndicator.qml: adjust for new showIndicatorDrawer() function not dimming background --- src/UI/toolbar/ControlIndicator.qml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index 7d1548ce65c5..f331f01b2251 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -55,7 +55,7 @@ Item { // First hide current popup, in case the normal control panel is visible mainWindow.closeIndicatorDrawer() // When showing the popup, the component will automatically start the count down in controlRequestPopup - mainWindow.showIndicatorDrawer(controlRequestPopup, control, false) + mainWindow.showIndicatorDrawer(controlRequestPopup, control) } // Animation to blink indicator when any related info changes onGcsControlStatusChanged: { @@ -123,7 +123,7 @@ Item { // After allowing takeover, if other GCS does not take control within 10 seconds // takeover will be set to not allowed again. Notify user about this control.activeVehicle.startTimerRevertAllowTakeover() - mainWindow.showIndicatorDrawer(allowTakeoverExpirationPopup, control, false) + mainWindow.showIndicatorDrawer(allowTakeoverExpirationPopup, control) } } // Action label @@ -392,7 +392,7 @@ Item { MouseArea { anchors.fill: parent onClicked: { - mainWindow.showIndicatorDrawer(controlPopup, control, false) + mainWindow.showIndicatorDrawer(controlPopup, control) } } } From bae425812a0600f15a90a3ac1633604b58b43f57 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Wed, 26 Feb 2025 14:37:37 +0100 Subject: [PATCH 35/44] resources: change folder/prefix of controlIndicator to gcscontrolIndicator --- qgcresources.qrc | 8 ++++---- .../gcscontrol_device.svg | 0 .../gcscontrol_gcs.svg | 0 .../gcscontrol_line.svg | 0 src/UI/toolbar/ControlIndicator.qml | 6 +++--- 5 files changed, 7 insertions(+), 7 deletions(-) rename resources/{controlIndicator => gcscontrolIndicator}/gcscontrol_device.svg (100%) rename resources/{controlIndicator => gcscontrolIndicator}/gcscontrol_gcs.svg (100%) rename resources/{controlIndicator => gcscontrolIndicator}/gcscontrol_line.svg (100%) diff --git a/qgcresources.qrc b/qgcresources.qrc index 213f81767964..9b00de938759 100644 --- a/qgcresources.qrc +++ b/qgcresources.qrc @@ -110,9 +110,9 @@ resources/gimbal/payload.svg - - resources/controlIndicator/gcscontrol_device.svg - resources/controlIndicator/gcscontrol_gcs.svg - resources/controlIndicator/gcscontrol_line.svg + + resources/gcscontrolIndicator/gcscontrol_device.svg + resources/gcscontrolIndicator/gcscontrol_gcs.svg + resources/gcscontrolIndicator/gcscontrol_line.svg diff --git a/resources/controlIndicator/gcscontrol_device.svg b/resources/gcscontrolIndicator/gcscontrol_device.svg similarity index 100% rename from resources/controlIndicator/gcscontrol_device.svg rename to resources/gcscontrolIndicator/gcscontrol_device.svg diff --git a/resources/controlIndicator/gcscontrol_gcs.svg b/resources/gcscontrolIndicator/gcscontrol_gcs.svg similarity index 100% rename from resources/controlIndicator/gcscontrol_gcs.svg rename to resources/gcscontrolIndicator/gcscontrol_gcs.svg diff --git a/resources/controlIndicator/gcscontrol_line.svg b/resources/gcscontrolIndicator/gcscontrol_line.svg similarity index 100% rename from resources/controlIndicator/gcscontrol_line.svg rename to resources/gcscontrolIndicator/gcscontrol_line.svg diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/ControlIndicator.qml index f331f01b2251..45bb52de64bc 100644 --- a/src/UI/toolbar/ControlIndicator.qml +++ b/src/UI/toolbar/ControlIndicator.qml @@ -350,7 +350,7 @@ Item { width: height anchors.top: parent.top anchors.bottom: parent.bottom - source: "/controlIndicator/gcscontrol_line.svg" + source: "/gcscontrolIndicator/gcscontrol_line.svg" fillMode: Image.PreserveAspectFit sourceSize.height: height color: isThisGCSinControl ? qgcPal.colorGreen : qgcPal.text @@ -360,7 +360,7 @@ Item { width: height anchors.top: parent.top anchors.bottom: parent.bottom - source: "/controlIndicator/gcscontrol_device.svg" + source: "/gcscontrolIndicator/gcscontrol_device.svg" fillMode: Image.PreserveAspectFit sourceSize.height: height color: (isThisGCSinControl || gcsControlStatusFlags_TakeoverAllowed) ? qgcPal.colorGreen : qgcPal.text @@ -370,7 +370,7 @@ Item { width: height anchors.top: parent.top anchors.bottom: parent.bottom - source: "/controlIndicator/gcscontrol_gcs.svg" + source: "/gcscontrolIndicator/gcscontrol_gcs.svg" fillMode: Image.PreserveAspectFit sourceSize.height: height color: qgcPal.text From 6ded18c7e48b1b41e9acf35d689463423a9382cf Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Wed, 26 Feb 2025 14:39:06 +0100 Subject: [PATCH 36/44] rename ControlIndicator.qml to GCSControlIndicator.qml --- qgroundcontrol.qrc | 2 +- src/FirmwarePlugin/FirmwarePlugin.cc | 2 +- .../toolbar/{ControlIndicator.qml => GCSControlIndicator.qml} | 0 3 files changed, 2 insertions(+), 2 deletions(-) rename src/UI/toolbar/{ControlIndicator.qml => GCSControlIndicator.qml} (100%) diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 614d9f20b44b..1c5645882c4f 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -12,7 +12,7 @@ src/UI/toolbar/TelemetryRSSIIndicator.qml src/UI/toolbar/APMSupportForwardingIndicator.qml src/UI/toolbar/GimbalIndicator.qml - src/UI/toolbar/ControlIndicator.qml + src/UI/toolbar/GCSControlIndicator.qml src/FlightDisplay/DefaultChecklist.qml diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 17cea3245a18..d2eb469c5f42 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -214,7 +214,7 @@ const QVariantList &FirmwarePlugin::toolIndicators(const Vehicle*) QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GimbalIndicator.qml")), // ControlIndicator is only available in debug builds for the moment #ifdef QT_DEBUG - QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ControlIndicator.qml")), + QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GCSControlIndicator.qml")), #endif }); } diff --git a/src/UI/toolbar/ControlIndicator.qml b/src/UI/toolbar/GCSControlIndicator.qml similarity index 100% rename from src/UI/toolbar/ControlIndicator.qml rename to src/UI/toolbar/GCSControlIndicator.qml From f04014905176803db6e7dca34e5518e1fa90cce2 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Wed, 26 Feb 2025 14:45:20 +0100 Subject: [PATCH 37/44] Rename ProgressTracker.qml to TimedProgressTracker.qml --- qgroundcontrol.qrc | 2 +- src/QmlControls/QGroundControl/Controls/qmldir | 2 +- .../{ProgressTracker.qml => TimedProgressTracker.qml} | 0 src/UI/toolbar/GCSControlIndicator.qml | 6 +++--- 4 files changed, 5 insertions(+), 5 deletions(-) rename src/QmlControls/{ProgressTracker.qml => TimedProgressTracker.qml} (100%) diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 1c5645882c4f..e74bb3f8837c 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -209,7 +209,7 @@ src/QmlControls/VehicleRotationCal.qml src/QmlControls/VehicleSummaryRow.qml src/PlanView/VTOLLandingPatternMapVisual.qml - src/QmlControls/ProgressTracker.qml + src/QmlControls/TimedProgressTracker.qml src/FactSystem/FactControls/AltitudeFactTextField.qml src/FactSystem/FactControls/FactBitmask.qml src/FactSystem/FactControls/FactCheckBox.qml diff --git a/src/QmlControls/QGroundControl/Controls/qmldir b/src/QmlControls/QGroundControl/Controls/qmldir index 6c29b7e70205..452afe0285d8 100644 --- a/src/QmlControls/QGroundControl/Controls/qmldir +++ b/src/QmlControls/QGroundControl/Controls/qmldir @@ -131,4 +131,4 @@ VehicleMessageList 1.0 VehicleMessageList.qml VehicleRotationCal 1.0 VehicleRotationCal.qml VehicleSummaryRow 1.0 VehicleSummaryRow.qml MAVLinkChart 1.0 MAVLinkChart.qml -ProgressTracker 1.0 ProgressTracker.qml +TimedProgressTracker 1.0 TimedProgressTracker.qml diff --git a/src/QmlControls/ProgressTracker.qml b/src/QmlControls/TimedProgressTracker.qml similarity index 100% rename from src/QmlControls/ProgressTracker.qml rename to src/QmlControls/TimedProgressTracker.qml diff --git a/src/UI/toolbar/GCSControlIndicator.qml b/src/UI/toolbar/GCSControlIndicator.qml index 45bb52de64bc..caa22041239f 100644 --- a/src/UI/toolbar/GCSControlIndicator.qml +++ b/src/UI/toolbar/GCSControlIndicator.qml @@ -90,7 +90,7 @@ Item { id: controlRequestPopup ToolIndicatorPage { - ProgressTracker { + TimedProgressTracker { id: requestProgressTracker timeoutSeconds: receivedRequestTimeoutMs * 0.001 onTimeout: mainWindow.closeIndicatorDrawer() @@ -157,7 +157,7 @@ Item { ToolIndicatorPage { // Allow takeover expiration time popup. When a request is received and takeover was allowed, this popup alerts // that after vehicle::REQUEST_OPERATOR_CONTROL_ALLOW_TAKEOVER_TIMEOUT_MSECS seconds, this GCS will change back to takeover not allowed, as per mavlink specs - ProgressTracker { + TimedProgressTracker { id: revertTakeoverProgressTracker timeoutSeconds: control.activeVehicle.operatorControlTakeoverTimeoutMsecs * 0.001 onTimeout: { @@ -204,7 +204,7 @@ Item { ToolIndicatorPage { - ProgressTracker { + TimedProgressTracker { id: sendRequestProgressTracker timeoutSeconds: QGroundControl.settingsManager.flyViewSettings.requestControlTimeout.rawValue } From 5cd93b12b5fd77d6db9cdb2f80a6f2018f0dd1ce Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Wed, 12 Mar 2025 16:06:02 +0100 Subject: [PATCH 38/44] main.cc: fix mavlink sysid range 1-255 --- src/main.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main.cc b/src/main.cc index d8812e04b566..535a0c7d70c4 100644 --- a/src/main.cc +++ b/src/main.cc @@ -195,7 +195,7 @@ int main(int argc, char *argv[]) if (hasSystemId) { bool ok; int systemId = systemIdStr.toInt(&ok); - if (ok && systemId >= 0 && systemId <= 255) { // MAVLink system IDs are 8-bit + if (ok && systemId >= 1 && systemId <= 255) { // MAVLink system IDs are 8-bit qDebug() << "Setting MAVLink System ID to:" << systemId; MAVLinkProtocol::instance()->setSystemId(systemId); } else { From 122756c00278173ad00b99fcab037b6edeb1f376 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 11 May 2025 12:41:53 +0200 Subject: [PATCH 39/44] main.cc: adapt to new way of getting GCS systemID --- src/main.cc | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main.cc b/src/main.cc index 535a0c7d70c4..b599df106691 100644 --- a/src/main.cc +++ b/src/main.cc @@ -17,7 +17,8 @@ #include "QGCApplication.h" #include "QGCLogging.h" #include "CmdLineOptParser.h" -#include "MAVLinkProtocol.h" +#include "SettingsManager.h" +#include "MavlinkSettings.h" #if !defined(Q_OS_ANDROID) && !defined(Q_OS_IOS) #include @@ -197,7 +198,7 @@ int main(int argc, char *argv[]) int systemId = systemIdStr.toInt(&ok); if (ok && systemId >= 1 && systemId <= 255) { // MAVLink system IDs are 8-bit qDebug() << "Setting MAVLink System ID to:" << systemId; - MAVLinkProtocol::instance()->setSystemId(systemId); + SettingsManager::instance()->mavlinkSettings()->gcsMavlinkSystemID()->setRawValue(systemId); } else { qDebug() << "Not setting MAVLink System ID. It must be between 0 and 255. Invalid system ID value:" << systemIdStr; } From bb1a153f05bce21a8b565f4b228967649cd7ac38 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 11 May 2025 12:57:41 +0200 Subject: [PATCH 40/44] GCSControlIndicator.qml: adapt to new way of getting GCS systemID --- src/UI/toolbar/GCSControlIndicator.qml | 24 ++++++------------------ 1 file changed, 6 insertions(+), 18 deletions(-) diff --git a/src/UI/toolbar/GCSControlIndicator.qml b/src/UI/toolbar/GCSControlIndicator.qml index caa22041239f..7434ac65efbd 100644 --- a/src/UI/toolbar/GCSControlIndicator.qml +++ b/src/UI/toolbar/GCSControlIndicator.qml @@ -22,7 +22,7 @@ Item { property bool gcsControlStatusFlags_TakeoverAllowed: activeVehicle ? activeVehicle.gcsControlStatusFlags_TakeoverAllowed : false property Fact requestControlAllowTakeoverFact: QGroundControl.settingsManager.flyViewSettings.requestControlAllowTakeover property bool requestControlAllowTakeover: requestControlAllowTakeoverFact.rawValue - property bool isThisGCSinControl: sysidInControl == QGroundControl.mavlinkSystemID + property bool isThisGCSinControl: sysidInControl == QGroundControl.settingsManager.mavlinkSettings.gcsMavlinkSystemID.rawValue property bool sendControlRequestAllowed: activeVehicle ? activeVehicle.sendControlRequestAllowed : false property var margins: ScreenTools.defaultFontPixelWidth @@ -322,24 +322,12 @@ Item { color: qgcPal.windowShade height: outdoorPalette ? 1 : 2 } - QGCLabel { - text: qsTr("This GCS Mavlink System ID: ") - } - QGCTextField { - text: QGroundControl.mavlinkSystemID.toString() - numericValuesOnly: true - Layout.alignment: Qt.AlignRight - Layout.preferredWidth: ScreenTools.defaultFontPixelWidth * 7 - horizontalAlignment: TextInput.AlignHCenter - onEditingFinished: { - if (parseInt(text) > 0 && parseInt(text) < 256) { - QGroundControl.mavlinkSystemID = parseInt(text) - } else { - mainWindow.showMessageDialog(qsTr("Invalid System ID"), qsTr("System ID must be in the range of 1 - 255")) - } - } + LabelledFactTextField { + Layout.fillWidth: true + Layout.columnSpan: 2 + label: qsTr("This GCS Mavlink System ID: ") + fact: QGroundControl.settingsManager.mavlinkSettings.gcsMavlinkSystemID } - } } } From ce73792b82f75126c38dedb8f739f0f5169c923f Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 11 May 2025 13:03:45 +0200 Subject: [PATCH 41/44] Vehicle.cc: add this context in connect lambda functions --- src/Vehicle/Vehicle.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 5b78635039cf..dd3b6b0043cc 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3988,7 +3988,7 @@ void Vehicle::startTimerRevertAllowTakeover() // Disconnect any previous connections to avoid multiple handlers disconnect(&_timerRevertAllowTakeover, &QTimer::timeout, nullptr, nullptr); - connect(&_timerRevertAllowTakeover, &QTimer::timeout, [this](){ + connect(&_timerRevertAllowTakeover, &QTimer::timeout, this, [this](){ if (MAVLinkProtocol::instance()->getSystemId() == _sysid_in_control) { this->requestOperatorControl(false); } @@ -4032,7 +4032,7 @@ void Vehicle::requestOperatorControlStartTimer(int requestTimeoutMsecs) _timerRequestOperatorControl.setInterval(requestTimeoutMsecs); // Disconnect any previous connections to avoid multiple handlers disconnect(&_timerRequestOperatorControl, &QTimer::timeout, nullptr, nullptr); - connect(&_timerRequestOperatorControl, &QTimer::timeout, [this](){ + connect(&_timerRequestOperatorControl, &QTimer::timeout, this, [this](){ _sendControlRequestAllowed = true; emit sendControlRequestAllowedChanged(true); }); From 43ca6d39e8d3b957d0a535ce6864ae87e10ef2df Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 11 May 2025 13:41:27 +0200 Subject: [PATCH 42/44] cmake/CustomOptions.cmake: update mavlink c_library_v2 to latest version --- cmake/CustomOptions.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/CustomOptions.cmake b/cmake/CustomOptions.cmake index f8beca5cfa6b..d04a51f026cd 100644 --- a/cmake/CustomOptions.cmake +++ b/cmake/CustomOptions.cmake @@ -35,7 +35,7 @@ option(QGC_ENABLE_QT_VIDEOSTREAMING "Enable QtMultimedia Video Backend" OFF) # Q # MAVLink set(QGC_MAVLINK_GIT_REPO "https://github.com/mavlink/c_library_v2.git" CACHE STRING "URL to MAVLink Git Repo") -set(QGC_MAVLINK_GIT_TAG "7ea034366ee7f09f3991a5b82f51f0c259023b38" CACHE STRING "Tag of MAVLink Git Repo") +set(QGC_MAVLINK_GIT_TAG "19f9955598af9a9181064619bd2e3c04bd2d848a" CACHE STRING "Tag of MAVLink Git Repo") # APM option(QGC_DISABLE_APM_MAVLINK "Disable APM Dialect" OFF) From fc1520439b6b7037a1db32898c7b068db0678a47 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 11 May 2025 13:42:23 +0200 Subject: [PATCH 43/44] Vehicle.cc: After latest mavlink version we can use CMDs in development.xml --- src/Vehicle/Vehicle.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index dd3b6b0043cc..dc77c6ce6284 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -4008,7 +4008,7 @@ void Vehicle::requestOperatorControl(bool allowOverride, int requestTimeoutSecs) safeRequestTimeoutSecs = SettingsManager::instance()->flyViewSettings()->requestControlTimeout()->cookedDefaultValue().toInt(); } sendMavCommand(_defaultComponentId, - MAV_CMD(32100), // MAV_CMD_REQUEST_OPERATOR_CONTROL + MAV_CMD_REQUEST_OPERATOR_CONTROL, false, // Don't show errors, as per Mavlink control protocol Autopilot will report result failed prior to forwarding the request to the GCS in control. 0, // System ID of GCS requesting control, 0 if it is this GCS 1, // Action - 0: Release control, 1: Request control. @@ -4088,7 +4088,7 @@ void Vehicle::_handleCommandLong(const mavlink_message_t& message) if (commandLong.target_system != MAVLinkProtocol::instance()->getSystemId()) { return; } - if (commandLong.command == MAV_CMD(32100)) { // MAV_CMD_REQUEST_OPERATOR_CONTROL + if (commandLong.command == MAV_CMD_REQUEST_OPERATOR_CONTROL) { _handleCommandRequestOperatorControl(commandLong); } } From 862d647a204f330ce676933e301dd6b90fb8fd65 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sun, 11 May 2025 18:28:49 +0200 Subject: [PATCH 44/44] Vehicle: implement custom handler for request operator control command: fixes https://github.com/mavlink/qgroundcontrol/issues/12552 --- src/Vehicle/Vehicle.cc | 47 +++++++++++++++++++++++++++++++++++------- src/Vehicle/Vehicle.h | 1 + 2 files changed, 41 insertions(+), 7 deletions(-) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index dc77c6ce6284..0b22c5589bdd 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -4007,13 +4007,17 @@ void Vehicle::requestOperatorControl(bool allowOverride, int requestTimeoutSecs) // If out of limits use default value safeRequestTimeoutSecs = SettingsManager::instance()->flyViewSettings()->requestControlTimeout()->cookedDefaultValue().toInt(); } - sendMavCommand(_defaultComponentId, - MAV_CMD_REQUEST_OPERATOR_CONTROL, - false, // Don't show errors, as per Mavlink control protocol Autopilot will report result failed prior to forwarding the request to the GCS in control. - 0, // System ID of GCS requesting control, 0 if it is this GCS - 1, // Action - 0: Release control, 1: Request control. - allowOverride ? 1 : 0, // Allow takeover - Enable automatic granting of ownership on request. 0: Ask current owner and reject request, 1: Allow automatic takeover. - safeRequestTimeoutSecs); // Timeout in seconds before a request to a GCS to allow takeover is assumed to be rejected. This is used to display the timeout graphically on requestor and GCS in control. + + const MavCmdAckHandlerInfo_t handlerInfo = {&Vehicle::_requestOperatorControlAckHandler, this, nullptr, nullptr}; + sendMavCommandWithHandler( + &handlerInfo, + _defaultComponentId, + MAV_CMD_REQUEST_OPERATOR_CONTROL, + 0, // System ID of GCS requesting control, 0 if it is this GCS + 1, // Action - 0: Release control, 1: Request control. + allowOverride ? 1 : 0, // Allow takeover - Enable automatic granting of ownership on request. 0: Ask current owner and reject request, 1: Allow automatic takeover. + safeRequestTimeoutSecs // Timeout in seconds before a request to a GCS to allow takeover is assumed to be rejected. This is used to display the timeout graphically on requestor and GCS in control. + ); // If this is a request we sent to other GCS, start timer so User can not keep sending requests until the current timeout expires if (requestTimeoutSecs > 0) { @@ -4021,6 +4025,35 @@ void Vehicle::requestOperatorControl(bool allowOverride, int requestTimeoutSecs) } } +void Vehicle::_requestOperatorControlAckHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode) +{ + // For the moment, this will always come from an autopilot, compid 1 + Q_UNUSED(compId); + + // If duplicated or no response, show popup to user. Otherwise only log it. + switch (failureCode) { + case MavCmdResultFailureDuplicateCommand: + qgcApp()->showAppMessage(tr("Waiting for previous operator control request")); + return; + case MavCmdResultFailureNoResponseToCommand: + qgcApp()->showAppMessage(tr("No response to operator control request")); + return; + default: + break; + } + + Vehicle* vehicle = static_cast(resultHandlerData); + if (!vehicle) { + return; + } + + if (ack.result == MAV_RESULT_ACCEPTED) { + qCDebug(VehicleLog) << "Operator control request accepted"; + } else { + qCDebug(VehicleLog) << "Operator control request rejected"; + } +} + void Vehicle::requestOperatorControlStartTimer(int requestTimeoutMsecs) { // First flag requests not allowed diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 119342844e15..bc50a5ab6d0a 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -1332,6 +1332,7 @@ private slots: private: void _handleControlStatus(const mavlink_message_t& message); void _handleCommandRequestOperatorControl(const mavlink_command_long_t commandLong); + static void _requestOperatorControlAckHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode); Q_PROPERTY(uint8_t sysidInControl READ sysidInControl NOTIFY gcsControlStatusChanged) Q_PROPERTY(bool gcsControlStatusFlags_SystemManager READ gcsControlStatusFlags_SystemManager NOTIFY gcsControlStatusChanged)