diff --git a/src/AutoPilotPlugins/APM/APMSafetyComponent.qml b/src/AutoPilotPlugins/APM/APMSafetyComponent.qml index a63824a9aba3bc473bac21a8f9fbfa8600ab7d44..d46f26fbf9971818a9cc32274688800a8e77ddb8 100644 --- a/src/AutoPilotPlugins/APM/APMSafetyComponent.qml +++ b/src/AutoPilotPlugins/APM/APMSafetyComponent.qml @@ -58,6 +58,7 @@ SetupPage { property Fact _armingCheck: controller.getParameterFact(-1, "ARMING_CHECK") property real _margins: ScreenTools.defaultFontPixelHeight + property real _innerMargin: _margins / 2 property bool _showIcon: !ScreenTools.isTinyScreen property bool _roverFirmware: controller.parameterExists(-1, "MODE1") // This catches all usage of ArduRover firmware vehicle types: Rover, Boat... @@ -551,8 +552,8 @@ SetupPage { Rectangle { id: rtlSettings - width: rltAltFinalField.x + rltAltFinalField.width + _margins - height: rltAltFinalField.y + rltAltFinalField.height + _margins + width: landSpeedField.x + landSpeedField.width + _margins + height: landSpeedField.y + landSpeedField.height + _margins color: ggcPal.windowShade Image { @@ -578,7 +579,7 @@ SetupPage { QGCRadioButton { id: returnAtCurrentRadio - anchors.margins: _margins + anchors.margins: _innerMargin anchors.left: _showIcon ? icon.right : parent.left anchors.top: parent.top text: qsTr("Return at current altitude") @@ -589,9 +590,9 @@ SetupPage { QGCRadioButton { id: returnAltRadio - anchors.topMargin: _margins - anchors.left: returnAtCurrentRadio.left + anchors.topMargin: _innerMargin anchors.top: returnAtCurrentRadio.bottom + anchors.left: returnAtCurrentRadio.left text: qsTr("Return at specified altitude:") checked: _rtlAltFact.value != 0 @@ -620,7 +621,7 @@ SetupPage { FactTextField { id: landDelayField - anchors.topMargin: _margins * 1.5 + anchors.topMargin: _innerMargin anchors.left: rltAltField.left anchors.top: rltAltField.bottom fact: _rtlLoitTimeFact @@ -628,42 +629,33 @@ SetupPage { enabled: homeLoiterCheckbox.checked === true } - QGCRadioButton { - id: landRadio + QGCLabel { anchors.left: returnAtCurrentRadio.left - anchors.baseline: landSpeedField.baseline - text: qsTr("Land with descent speed:") - checked: _rtlAltFinalFact.value == 0 - - onClicked: _rtlAltFinalFact.value = 0 + anchors.baseline: rltAltFinalField.baseline + text: qsTr("Final land stage altitude:") } FactTextField { - id: landSpeedField - anchors.topMargin: _margins * 1.5 - anchors.top: landDelayField.bottom + id: rltAltFinalField + anchors.topMargin: _innerMargin anchors.left: rltAltField.left - fact: _landSpeedFact + anchors.top: landDelayField.bottom + fact: _rtlAltFinalFact showUnits: true - enabled: landRadio.checked } - QGCRadioButton { - id: finalLoiterRadio + QGCLabel { anchors.left: returnAtCurrentRadio.left - anchors.baseline: rltAltFinalField.baseline - text: qsTr("Final loiter altitude:") - - onClicked: _rtlAltFinalFact.value = _rtlAltFact.value + anchors.baseline: landSpeedField.baseline + text: qsTr("Final land stage descent speed:") } FactTextField { - id: rltAltFinalField - anchors.topMargin: _margins / 2 + id: landSpeedField + anchors.topMargin: _innerMargin anchors.left: rltAltField.left - anchors.top: landSpeedField.bottom - fact: _rtlAltFinalFact - enabled: finalLoiterRadio.checked + anchors.top: rltAltFinalField.bottom + fact: _landSpeedFact showUnits: true } } // Rectangle - RTL Settings diff --git a/src/AutoPilotPlugins/Common/RadioComponent.qml b/src/AutoPilotPlugins/Common/RadioComponent.qml index 5a1f4bf5a81d55ce2fe1784a2ca41085a468b009..f49e46c92daa0ba513d8416467c5356a69f280f2 100644 --- a/src/AutoPilotPlugins/Common/RadioComponent.qml +++ b/src/AutoPilotPlugins/Common/RadioComponent.qml @@ -8,7 +8,7 @@ ****************************************************************************/ import QtQuick 2.3 -import QtQuick.Controls 1.2 +import QtQuick.Controls 2.4 import QtQuick.Dialogs 1.2 import QtQuick.Layouts 1.11 @@ -90,7 +90,7 @@ SetupPage { QGCViewDialog { function accept() { - controller.spektrumBindMode(radioGroup.current.bindMode) + controller.spektrumBindMode(radioGroup.checkedButton.bindMode) hideDialog() } @@ -98,6 +98,8 @@ SetupPage { hideDialog() } + ButtonGroup { id: radioGroup } + Column { anchors.fill: parent spacing: 5 @@ -109,18 +111,21 @@ SetupPage { } QGCRadioButton { - text: qsTr("DSM2 Mode") + text: qsTr("DSM2 Mode") + ButtonGroup.group: radioGroup property int bindMode: RadioComponentController.DSM2 } QGCRadioButton { - text: qsTr("DSMX (7 channels or less)") + text: qsTr("DSMX (7 channels or less)") + ButtonGroup.group: radioGroup property int bindMode: RadioComponentController.DSMX7 } QGCRadioButton { - checked: true - text: qsTr("DSMX (8 channels or more)") + checked: true + text: qsTr("DSMX (8 channels or more)") + ButtonGroup.group: radioGroup property int bindMode: RadioComponentController.DSMX8 } }