Commit 06339ea1 authored by DonLakeFlyer's avatar DonLakeFlyer

Fixup Power/Safety for new/missing params

parent cf765dfc
...@@ -30,20 +30,20 @@ QString APMSafetyComponent::name(void) const ...@@ -30,20 +30,20 @@ QString APMSafetyComponent::name(void) const
QString APMSafetyComponent::description(void) const QString APMSafetyComponent::description(void) const
{ {
switch (_vehicle->vehicleType()) { switch (_vehicle->vehicleType()) {
case MAV_TYPE_SUBMARINE: case MAV_TYPE_SUBMARINE:
return tr("Safety Setup is used to setup failsafe actions, leak detection, and arming checks."); return tr("Safety Setup is used to setup failsafe actions, leak detection, and arming checks.");
break; break;
case MAV_TYPE_GROUND_ROVER: case MAV_TYPE_GROUND_ROVER:
case MAV_TYPE_FIXED_WING: case MAV_TYPE_FIXED_WING:
case MAV_TYPE_QUADROTOR: case MAV_TYPE_QUADROTOR:
case MAV_TYPE_COAXIAL: case MAV_TYPE_COAXIAL:
case MAV_TYPE_HELICOPTER: case MAV_TYPE_HELICOPTER:
case MAV_TYPE_HEXAROTOR: case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR: case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER: case MAV_TYPE_TRICOPTER:
default: default:
return tr("Safety Setup is used to setup triggers for Return to Land as well as the settings for Return to Land itself."); return tr("Safety Setup is used to setup triggers for Return to Land as well as the settings for Return to Land itself.");
break; break;
} }
} }
...@@ -73,26 +73,22 @@ QUrl APMSafetyComponent::setupSource(void) const ...@@ -73,26 +73,22 @@ QUrl APMSafetyComponent::setupSource(void) const
QString qmlFile; QString qmlFile;
switch (_vehicle->vehicleType()) { switch (_vehicle->vehicleType()) {
case MAV_TYPE_FIXED_WING: case MAV_TYPE_FIXED_WING:
qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentPlane.qml"); case MAV_TYPE_QUADROTOR:
break; case MAV_TYPE_COAXIAL:
case MAV_TYPE_QUADROTOR: case MAV_TYPE_HELICOPTER:
case MAV_TYPE_COAXIAL: case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_HELICOPTER: case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_HEXAROTOR: case MAV_TYPE_TRICOPTER:
case MAV_TYPE_OCTOROTOR: case MAV_TYPE_GROUND_ROVER:
case MAV_TYPE_TRICOPTER: qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponent.qml");
qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentCopter.qml"); break;
break; case MAV_TYPE_SUBMARINE:
case MAV_TYPE_SUBMARINE: qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSub.qml");
qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSub.qml"); break;
break; default:
case MAV_TYPE_GROUND_ROVER: qmlFile = QStringLiteral("qrc:/qml/APMNotSupported.qml");
qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentRover.qml"); break;
break;
default:
qmlFile = QStringLiteral("qrc:/qml/APMNotSupported.qml");
break;
} }
return QUrl::fromUserInput(qmlFile); return QUrl::fromUserInput(qmlFile);
...@@ -103,26 +99,22 @@ QUrl APMSafetyComponent::summaryQmlSource(void) const ...@@ -103,26 +99,22 @@ QUrl APMSafetyComponent::summaryQmlSource(void) const
QString qmlFile; QString qmlFile;
switch (_vehicle->vehicleType()) { switch (_vehicle->vehicleType()) {
case MAV_TYPE_FIXED_WING: case MAV_TYPE_FIXED_WING:
qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummaryPlane.qml"); case MAV_TYPE_QUADROTOR:
break; case MAV_TYPE_COAXIAL:
case MAV_TYPE_QUADROTOR: case MAV_TYPE_HELICOPTER:
case MAV_TYPE_COAXIAL: case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_HELICOPTER: case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_HEXAROTOR: case MAV_TYPE_TRICOPTER:
case MAV_TYPE_OCTOROTOR: case MAV_TYPE_GROUND_ROVER:
case MAV_TYPE_TRICOPTER: qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummary.qml");
qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummaryCopter.qml"); break;
break; case MAV_TYPE_SUBMARINE:
case MAV_TYPE_SUBMARINE: qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummarySub.qml");
qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummarySub.qml"); break;
break; default:
case MAV_TYPE_GROUND_ROVER: qmlFile = QStringLiteral("qrc:/qml/APMNotSupported.qml");
qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummaryRover.qml"); break;
break;
default:
qmlFile = QStringLiteral("qrc:/qml/APMNotSupported.qml");
break;
} }
return QUrl::fromUserInput(qmlFile); return QUrl::fromUserInput(qmlFile);
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtGraphicalEffects 1.0
import QtQuick.Layouts 1.2
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
SetupPage {
id: safetyPage
pageComponent: safetyPageComponent
Component {
id: safetyPageComponent
Flow {
id: flowLayout
width: availableWidth
spacing: _margins
FactPanelController { id: controller; factPanel: safetyPage.viewPanel }
QGCPalette { id: ggcPal; colorGroupEnabled: true }
property Fact _batt1Monitor: controller.getParameterFact(-1, "BATT_MONITOR")
property Fact _batt2Monitor: controller.getParameterFact(-1, "BATT2_MONITOR", false /* reportMissing */)
property bool _batt2MonitorAvailable: controller.parameterExists(-1, "BATT2_MONITOR")
property bool _batt1MonitorEnabled: _batt1Monitor.rawValue !== 0
property bool _batt2MonitorEnabled: _batt2MonitorAvailable ? _batt2Monitor.rawValue !== 0 : false
property bool _batt1ParamsAvailable: controller.parameterExists(-1, "BATT_CAPACITY")
property bool _batt2ParamsAvailable: controller.parameterExists(-1, "BATT2_CAPACITY")
property Fact _failsafeBatt1LowAct: controller.getParameterFact(-1, "BATT_FS_LOW_ACT", false /* reportMissing */)
property Fact _failsafeBatt2LowAct: controller.getParameterFact(-1, "BATT2_FS_LOW_ACT", false /* reportMissing */)
property Fact _failsafeBatt1CritAct: controller.getParameterFact(-1, "BATT_FS_CRT_ACT", false /* reportMissing */)
property Fact _failsafeBatt2CritAct: controller.getParameterFact(-1, "BATT2_FS_CRT_ACT", false /* reportMissing */)
property Fact _failsafeBatt1Mah: controller.getParameterFact(-1, "BATT_LOW_MAH", false /* reportMissing */)
property Fact _failsafeBatt2Mah: controller.getParameterFact(-1, "BATT2_LOW_MAH", false /* reportMissing */)
property Fact _failsafeBatt1Voltage: controller.getParameterFact(-1, "BATT_LOW_VOLT", false /* reportMissing */)
property Fact _failsafeBatt2Voltage: controller.getParameterFact(-1, "BATT2_LOW_VOLT", false /* reportMissing */)
property Fact _armingCheck: controller.getParameterFact(-1, "ARMING_CHECK")
property real _margins: ScreenTools.defaultFontPixelHeight
property bool _showIcon: !ScreenTools.isTinyScreen
ExclusiveGroup { id: fenceActionRadioGroup }
ExclusiveGroup { id: landLoiterRadioGroup }
ExclusiveGroup { id: returnAltRadioGroup }
Column {
spacing: _margins / 2
visible: _batt1MonitorEnabled && _batt1ParamsAvailable
QGCLabel {
text: qsTr("Battery1 Failsafe Triggers")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
width: batteryFailsafeColumn.x + batteryFailsafeColumn.width + _margins
height: batteryFailsafeColumn.y + batteryFailsafeColumn.height + _margins
color: ggcPal.windowShade
Column {
id: batteryFailsafeColumn
anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
spacing: _margins
GridLayout {
id: gridLayout
columnSpacing: _margins
rowSpacing: _margins
columns: 2
QGCLabel { text: qsTr("Battery low action:") }
FactComboBox {
fact: _failsafeBatt1LowAct
indexModel: false
Layout.fillWidth: true
}
QGCLabel {
text: qsTr("Battery critical action:")
}
FactComboBox {
fact: _failsafeBatt1CritAct
indexModel: false
Layout.fillWidth: true
}
QGCCheckBox {
text: qsTr("Voltage threshold:")
checked: _failsafeBatt1Voltage.value != 0
onClicked: _failsafeBatt1Voltage.value = checked ? 10.5 : 0
}
FactTextField {
fact: _failsafeBatt1Voltage
showUnits: true
Layout.fillWidth: true
}
QGCCheckBox {
text: qsTr("MAH threshold:")
checked: _failsafeBatt1Mah.value != 0
onClicked: _failsafeBatt1Mah.value = checked ? 600 : 0
}
FactTextField {
fact: _failsafeBatt1Mah
showUnits: true
Layout.fillWidth: true
}
} // GridLayout
} // Column
} // Rectangle
} // Column - Battery Failsafe Settings
Column {
spacing: _margins / 2
visible: _batt2MonitorEnabled && _batt2ParamsAvailable
QGCLabel {
text: qsTr("Battery2 Failsafe Triggers")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
id: failsafeSettings
width: battery2FailsafeColumn.x + battery2FailsafeColumn.width + _margins
height: battery2FailsafeColumn.y + battery2FailsafeColumn.height + _margins
color: ggcPal.windowShade
Column {
id: battery2FailsafeColumn
anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
spacing: _margins
GridLayout {
columnSpacing: _margins
rowSpacing: _margins
columns: 2
visible: _batt2MonitorEnabled && _failsafeBatt2LowActAvailable
QGCLabel { text: qsTr("Battery low action:") }
FactComboBox {
fact: _failsafeBatt2LowAct
indexModel: false
Layout.fillWidth: true
}
QGCLabel {
text: qsTr("Battery critical action:")
}
FactComboBox {
fact: _failsafeBatt2CritAct
indexModel: false
Layout.fillWidth: true
}
QGCCheckBox {
text: qsTr("Voltage threshold:")
checked: _failsafeBatt2Voltage.value != 0
onClicked: _failsafeBatt2Voltage.value = checked ? 10.5 : 0
}
FactTextField {
fact: _failsafeBatt2Voltage
showUnits: true
Layout.fillWidth: true
}
QGCCheckBox {
text: qsTr("MAH threshold:")
checked: _failsafeBatt2Mah.value != 0
onClicked: _failsafeBatt2Mah.value = checked ? 600 : 0
}
FactTextField {
fact: _failsafeBatt2Mah
showUnits: true
Layout.fillWidth: true
}
} // GridLayout
} // Column
} // Rectangle
} // Column - Battery2 Failsafe Settings
Component {
id: planeGeneralFS
Column {
spacing: _margins / 2
property Fact _failsafeThrEnable: controller.getParameterFact(-1, "THR_FAILSAFE")
property Fact _failsafeThrValue: controller.getParameterFact(-1, "THR_FS_VALUE")
property Fact _failsafeGCSEnable: controller.getParameterFact(-1, "FS_GCS_ENABL")
QGCLabel {
text: qsTr("Failsafe Triggers")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
width: fsColumn.x + fsColumn.width + _margins
height: fsColumn.y + fsColumn.height + _margins
color: qgcPal.windowShade
ColumnLayout {
id: fsColumn
anchors.margins: _margins
anchors.left: parent.left
anchors.top: parent.top
RowLayout {
QGCCheckBox {
id: throttleEnableCheckBox
text: qsTr("Throttle PWM threshold:")
checked: _failsafeThrEnable.value === 1
onClicked: _failsafeThrEnable.value = (checked ? 1 : 0)
}
FactTextField {
fact: _failsafeThrValue
showUnits: true
enabled: throttleEnableCheckBox.checked
}
}
QGCCheckBox {
text: qsTr("GCS failsafe")
checked: _failsafeGCSEnable.value != 0
onClicked: _failsafeGCSEnable.value = checked ? 1 : 0
}
}
} // Rectangle - Failsafe trigger settings
} // Column - Failsafe trigger settings
}
Loader {
sourceComponent: controller.vehicle.fixedWing ? planeGeneralFS : undefined
}
Component {
id: roverGeneralFS
Column {
spacing: _margins / 2
property Fact _failsafeGCSEnable: controller.getParameterFact(-1, "FS_GCS_ENABLE")
property Fact _failsafeThrEnable: controller.getParameterFact(-1, "FS_THR_ENABLE")
property Fact _failsafeThrValue: controller.getParameterFact(-1, "FS_THR_VALUE")
property Fact _failsafeAction: controller.getParameterFact(-1, "FS_ACTION")
property Fact _failsafeCrashCheck: controller.getParameterFact(-1, "FS_CRASH_CHECK")
QGCLabel {
id: failsafeLabel
text: qsTr("Failsafe Triggers")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
id: failsafeSettings
width: fsGrid.x + fsGrid.width + _margins
height: fsGrid.y + fsGrid.height + _margins
color: ggcPal.windowShade
GridLayout {
id: fsGrid
anchors.margins: _margins
anchors.left: parent.left
anchors.top: parent.top
columns: 2
QGCLabel { text: qsTr("Ground Station failsafe:") }
FactComboBox {
Layout.fillWidth: true
fact: _failsafeGCSEnable
indexModel: false
}
QGCLabel { text: qsTr("Throttle failsafe:") }
FactComboBox {
Layout.fillWidth: true
fact: _failsafeThrEnable
indexModel: false
}
QGCLabel { text: qsTr("PWM threshold:") }
FactTextField {
Layout.fillWidth: true
fact: _failsafeThrValue
}
QGCLabel { text: qsTr("Failsafe Crash Check:") }
FactComboBox {
Layout.fillWidth: true
fact: _failsafeCrashCheck
indexModel: false
}
}
} // Rectangle - Failsafe Settings
} // Column - Failsafe Settings
}
Loader {
sourceComponent: controller.vehicle.rover ? roverGeneralFS : undefined
}
Component {
id: copterGeneralFS
Column {
spacing: _margins / 2
property Fact _failsafeGCSEnable: controller.getParameterFact(-1, "FS_GCS_ENABLE")
property Fact _failsafeBattLowAct: controller.getParameterFact(-1, "r.BATT_FS_LOW_ACT", false /* reportMissing */)
property Fact _failsafeBattMah: controller.getParameterFact(-1, "r.BATT_LOW_MAH", false /* reportMissing */)
property Fact _failsafeBattVoltage: controller.getParameterFact(-1, "r.BATT_LOW_VOLT", false /* reportMissing */)
property Fact _failsafeThrEnable: controller.getParameterFact(-1, "FS_THR_ENABLE")
property Fact _failsafeThrValue: controller.getParameterFact(-1, "FS_THR_VALUE")
QGCLabel {
text: qsTr("General Failsafe Triggers")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
width: generalFailsafeColumn.x + generalFailsafeColumn.width + _margins
height: generalFailsafeColumn.y + generalFailsafeColumn.height + _margins
color: ggcPal.windowShade
Column {
id: generalFailsafeColumn
anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
spacing: _margins
GridLayout {
columnSpacing: _margins
rowSpacing: _margins
columns: 2
QGCLabel { text: qsTr("Ground Station failsafe:") }
FactComboBox {
fact: _failsafeGCSEnable
indexModel: false
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Throttle failsafe:") }
QGCComboBox {
model: [qsTr("Disabled"), qsTr("Always RTL"),
qsTr("Continue with Mission in Auto Mode"), qsTr("Always Land")]
currentIndex: _failsafeThrEnable.value
Layout.fillWidth: true
onActivated: _failsafeThrEnable.value = index
}
QGCLabel { text: qsTr("PWM threshold:") }
FactTextField {
fact: _failsafeThrValue
showUnits: true
Layout.fillWidth: true
}
} // GridLayout
} // Column
} // Rectangle - Failsafe Settings
} // Column - General Failsafe Settings
}
Loader {
sourceComponent: controller.vehicle.multiRotor ? copterGeneralFS : undefined
}
Component {
id: copterGeoFence
Column {
spacing: _margins / 2
property Fact _fenceAction: controller.getParameterFact(-1, "FENCE_ACTION")
property Fact _fenceAltMax: controller.getParameterFact(-1, "FENCE_ALT_MAX")
property Fact _fenceEnable: controller.getParameterFact(-1, "FENCE_ENABLE")
property Fact _fenceMargin: controller.getParameterFact(-1, "FENCE_MARGIN")
property Fact _fenceRadius: controller.getParameterFact(-1, "FENCE_RADIUS")
property Fact _fenceType: controller.getParameterFact(-1, "FENCE_TYPE")
QGCLabel {
id: geoFenceLabel
text: qsTr("GeoFence")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
id: geoFenceSettings
width: fenceAltMaxField.x + fenceAltMaxField.width + _margins
height: fenceAltMaxField.y + fenceAltMaxField.height + _margins
color: ggcPal.windowShade
QGCCheckBox {
id: circleGeo
anchors.margins: _margins
anchors.left: parent.left
anchors.top: parent.top
text: qsTr("Circle GeoFence enabled")
checked: _fenceEnable.value != 0 && _fenceType.value & 2
onClicked: {
if (checked) {
if (_fenceEnable.value == 1) {
_fenceType.value |= 2
} else {
_fenceEnable.value = 1
_fenceType.value = 2
}
} else if (altitudeGeo.checked) {
_fenceType.value &= ~2
} else {
_fenceEnable.value = 0
_fenceType.value = 0
}
}
}
QGCCheckBox {
id: altitudeGeo
anchors.topMargin: _margins / 2
anchors.left: circleGeo.left
anchors.top: circleGeo.bottom
text: qsTr("Altitude GeoFence enabled")
checked: _fenceEnable.value != 0 && _fenceType.value & 1
onClicked: {
if (checked) {
if (_fenceEnable.value == 1) {
_fenceType.value |= 1
} else {
_fenceEnable.value = 1
_fenceType.value = 1
}
} else if (circleGeo.checked) {
_fenceType.value &= ~1
} else {
_fenceEnable.value = 0
_fenceType.value = 0
}
}
}
QGCRadioButton {
id: geoReportRadio
anchors.margins: _margins
anchors.left: parent.left
anchors.top: altitudeGeo.bottom
text: qsTr("Report only")
exclusiveGroup: fenceActionRadioGroup
checked: _fenceAction.value == 0
onClicked: _fenceAction.value = 0
}
QGCRadioButton {
id: geoRTLRadio
anchors.topMargin: _margins / 2
anchors.left: circleGeo.left
anchors.top: geoReportRadio.bottom
text: qsTr("RTL or Land")
exclusiveGroup: fenceActionRadioGroup
checked: _fenceAction.value == 1
onClicked: _fenceAction.value = 1
}
QGCLabel {
id: fenceRadiusLabel
anchors.left: circleGeo.left
anchors.baseline: fenceRadiusField.baseline
text: qsTr("Max radius:")
}
FactTextField {
id: fenceRadiusField
anchors.topMargin: _margins
anchors.left: fenceAltMaxField.left
anchors.top: geoRTLRadio.bottom
fact: _fenceRadius
showUnits: true
}
QGCLabel {
id: fenceAltMaxLabel
anchors.left: circleGeo.left
anchors.baseline: fenceAltMaxField.baseline
text: qsTr("Max altitude:")
}
FactTextField {
id: fenceAltMaxField
anchors.topMargin: _margins / 2
anchors.leftMargin: _margins
anchors.left: fenceAltMaxLabel.right
anchors.top: fenceRadiusField.bottom
fact: _fenceAltMax
showUnits: true
}
} // Rectangle - GeoFence Settings
} // Column - GeoFence Settings
}
Loader {
sourceComponent: controller.vehicle.multiRotor ? copterGeoFence : undefined
}
Component {
id: copterRTL
Column {
spacing: _margins / 2
property Fact _landSpeedFact: controller.getParameterFact(-1, "LAND_SPEED")
property Fact _rtlAltFact: controller.getParameterFact(-1, "RTL_ALT")
property Fact _rtlLoitTimeFact: controller.getParameterFact(-1, "RTL_LOIT_TIME")
property Fact _rtlAltFinalFact: controller.getParameterFact(-1, "RTL_ALT_FINAL")
QGCLabel {
id: rtlLabel
text: qsTr("Return to Launch")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
id: rtlSettings
width: rltAltFinalField.x + rltAltFinalField.width + _margins
height: rltAltFinalField.y + rltAltFinalField.height + _margins
color: ggcPal.windowShade
Image {
id: icon
anchors.margins: _margins
anchors.left: parent.left
anchors.top: parent.top
height: ScreenTools.defaultFontPixelWidth * 20
width: ScreenTools.defaultFontPixelWidth * 20
sourceSize.width: width
mipmap: true
fillMode: Image.PreserveAspectFit
visible: false
source: "/qmlimages/ReturnToHomeAltitude.svg"
}
ColorOverlay {
anchors.fill: icon
source: icon
color: ggcPal.text
visible: _showIcon
}
QGCRadioButton {
id: returnAtCurrentRadio
anchors.margins: _margins
anchors.left: _showIcon ? icon.right : parent.left
anchors.top: parent.top
text: qsTr("Return at current altitude")
checked: _rtlAltFact.value == 0
exclusiveGroup: returnAltRadioGroup
onClicked: _rtlAltFact.value = 0
}
QGCRadioButton {
id: returnAltRadio
anchors.topMargin: _margins
anchors.left: returnAtCurrentRadio.left
anchors.top: returnAtCurrentRadio.bottom
text: qsTr("Return at specified altitude:")
exclusiveGroup: returnAltRadioGroup
checked: _rtlAltFact.value != 0
onClicked: _rtlAltFact.value = 1500
}
FactTextField {
id: rltAltField
anchors.leftMargin: _margins
anchors.left: returnAltRadio.right
anchors.baseline: returnAltRadio.baseline
fact: _rtlAltFact
showUnits: true
enabled: returnAltRadio.checked
}
QGCCheckBox {
id: homeLoiterCheckbox
anchors.left: returnAtCurrentRadio.left
anchors.baseline: landDelayField.baseline
checked: _rtlLoitTimeFact.value > 0
text: qsTr("Loiter above Home for:")
onClicked: _rtlLoitTimeFact.value = (checked ? 60 : 0)
}
FactTextField {
id: landDelayField
anchors.topMargin: _margins * 1.5
anchors.left: rltAltField.left
anchors.top: rltAltField.bottom
fact: _rtlLoitTimeFact
showUnits: true
enabled: homeLoiterCheckbox.checked === true
}
QGCRadioButton {
id: landRadio
anchors.left: returnAtCurrentRadio.left
anchors.baseline: landSpeedField.baseline
text: qsTr("Land with descent speed:")
checked: _rtlAltFinalFact.value == 0
exclusiveGroup: landLoiterRadioGroup
onClicked: _rtlAltFinalFact.value = 0
}
FactTextField {
id: landSpeedField
anchors.topMargin: _margins * 1.5
anchors.top: landDelayField.bottom
anchors.left: rltAltField.left
fact: _landSpeedFact
showUnits: true
enabled: landRadio.checked
}
QGCRadioButton {
id: finalLoiterRadio
anchors.left: returnAtCurrentRadio.left
anchors.baseline: rltAltFinalField.baseline
text: qsTr("Final loiter altitude:")
exclusiveGroup: landLoiterRadioGroup
onClicked: _rtlAltFinalFact.value = _rtlAltFact.value
}
FactTextField {
id: rltAltFinalField
anchors.topMargin: _margins / 2
anchors.left: rltAltField.left
anchors.top: landSpeedField.bottom
fact: _rtlAltFinalFact
enabled: finalLoiterRadio.checked
showUnits: true
}
} // Rectangle - RTL Settings
} // Column - RTL Settings
}
Loader {
sourceComponent: controller.vehicle.multiRotor ? copterRTL : undefined
}
Component {
id: planeRTL
Column {
spacing: _margins / 2
property Fact _rtlAltFact: controller.getParameterFact(-1, "ALT_HOLD_RTL")
QGCLabel {
text: qsTr("Return to Launch")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
width: rltAltField.x + rltAltField.width + _margins
height: rltAltField.y + rltAltField.height + _margins
color: qgcPal.windowShade
QGCRadioButton {
id: returnAtCurrentRadio
anchors.margins: _margins
anchors.left: parent.left
anchors.top: parent.top
text: qsTr("Return at current altitude")
checked: _rtlAltFact.value < 0
exclusiveGroup: returnAltRadioGroup
onClicked: _rtlAltFact.value = -1
}
QGCRadioButton {
id: returnAltRadio
anchors.topMargin: _margins / 2
anchors.left: returnAtCurrentRadio.left
anchors.top: returnAtCurrentRadio.bottom
text: qsTr("Return at specified altitude:")
exclusiveGroup: returnAltRadioGroup
checked: _rtlAltFact.value >= 0
onClicked: _rtlAltFact.value = 10000
}
FactTextField {
id: rltAltField
anchors.leftMargin: _margins
anchors.left: returnAltRadio.right
anchors.baseline: returnAltRadio.baseline
fact: _rtlAltFact
showUnits: true
enabled: returnAltRadio.checked
}
} // Rectangle - RTL Settings
} // Column - RTL Settings
}
Loader {
sourceComponent: controller.vehicle.fixedWing ? planeRTL : undefined
}
Column {
spacing: _margins / 2
QGCLabel {
text: qsTr("Arming Checks")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
width: flowLayout.width
height: armingCheckInnerColumn.height + (_margins * 2)
color: ggcPal.windowShade
Column {
id: armingCheckInnerColumn
anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
spacing: _margins
FactBitmask {
id: armingCheckBitmask
anchors.left: parent.left
anchors.right: parent.right
firstEntryIsAll: true
fact: _armingCheck
}
QGCLabel {
id: armingCheckWarning
anchors.left: parent.left
anchors.right: parent.right
wrapMode: Text.WordWrap
color: qgcPal.warningText
text: qsTr("Warning: Turning off arming checks can lead to loss of Vehicle control.")
visible: _armingCheck.value != 1
}
}
} // Rectangle - Arming checks
} // Column - Arming Checks
} // Flow
} // Component - safetyPageComponent
} // SetupView
import QtQuick 2.3
import QtQuick.Controls 1.2
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
FactPanel {
id: panel
anchors.fill: parent
color: qgcPal.windowShadeDark
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
FactPanelController { id: controller; factPanel: panel }
property Fact _copterFenceAction: controller.getParameterFact(-1, "FENCE_ACTION", false /* reportMissing */)
property Fact _copterFenceEnable: controller.getParameterFact(-1, "FENCE_ENABLE", false /* reportMissing */)
property Fact _copterFenceType: controller.getParameterFact(-1, "FENCE_TYPE", false /* reportMissing */)
property Fact _batt1Monitor: controller.getParameterFact(-1, "BATT_MONITOR")
property Fact _batt2Monitor: controller.getParameterFact(-1, "BATT2_MONITOR", false /* reportMissing */)
property bool _batt2MonitorAvailable: controller.parameterExists(-1, "BATT2_MONITOR")
property bool _batt1MonitorEnabled: _batt1Monitor.rawValue !== 0
property bool _batt2MonitorEnabled: _batt2MonitorAvailable && _batt2Monitor.rawValue !== 0
property Fact _batt1FSLowAct: controller.getParameterFact(-1, "r.BATT_FS_LOW_ACT", false /* reportMissing */)
property Fact _batt1FSCritAct: controller.getParameterFact(-1, "BATT_FS_CRT_ACT", false /* reportMissing */)
property Fact _batt2FSLowAct: controller.getParameterFact(-1, "BATT2_FS_LOW_ACT", false /* reportMissing */)
property Fact _batt2FSCritAct: controller.getParameterFact(-1, "BATT2_FS_CRT_ACT", false /* reportMissing */)
property bool _batt1FSCritActAvailable: controller.parameterExists(-1, "BATT_FS_CRT_ACT")
Column {
anchors.fill: parent
VehicleSummaryRow {
labelText: qsTr("Arming Checks:")
valueText: fact.value & 1 ? qsTr("Enabled") : qsTr("Some disabled")
property Fact fact: controller.getParameterFact(-1, "ARMING_CHECK")
}
VehicleSummaryRow {
labelText: qsTr("Throttle failsafe:")
valueText: Fact.enumStringValue
visible: controller.vehicle.multiRotor
property Fact fact: controller.getParameterFact(-1, "FS_THR_ENABLE", false /* reportMissing */)
}
VehicleSummaryRow {
labelText: qsTr("Throttle failsafe:")
valueText: fact.enumStringValue
visible: controller.vehicle.fixedWing
property Fact fact: controller.getParameterFact(-1, "THR_FAILSAFE", false /* reportMissing */)
}
VehicleSummaryRow {
labelText: qsTr("Throttle failsafe:")
valueText: fact.enumStringValue
visible: controller.vehicle.rover
property Fact fact: controller.getParameterFact(-1, "FS_THR_ENABLE", false /* reportMissing */)
}
VehicleSummaryRow {
labelText: qsTr("Failsafe Action:")
valueText: fact.enumStringValue
visible: controller.vehicle.rover
property Fact fact: controller.getParameterFact(-1, "FS_ACTION", false /* reportMissing */)
}
VehicleSummaryRow {
labelText: qsTr("Failsafe Crash Check:")
valueText: fact.enumStringValue
visible: controller.vehicle.rover
property Fact fact: controller.getParameterFact(-1, "FS_CRASH_CHECK", false /* reportMissing */)
}
VehicleSummaryRow {
labelText: qsTr("Batt1 low failsafe:")
valueText: _batt1MonitorEnabled ? _batt1FSLowAct.enumStringValue : ""
visible: _batt1MonitorEnabled
}
VehicleSummaryRow {
labelText: qsTr("Batt1 critical failsafe:")
valueText: _batt1FSCritActAvailable ? _batt1FSCritAct.enumStringValue : ""
visible: _batt1FSCritActAvailable
}
VehicleSummaryRow {
labelText: qsTr("Batt2 low failsafe:")
valueText: _batt2MonitorEnabled ? _batt2FSLowAct.enumStringValue : ""
visible: _batt2MonitorEnabled
}
VehicleSummaryRow {
labelText: qsTr("Batt2 critical failsafe:")
valueText: _batt2MonitorEnabled ? _batt2FSCritAct.enumStringValue : ""
visible: _batt2MonitorEnabled
}
VehicleSummaryRow {
labelText: qsTr("GeoFence:")
valueText: _copterFenceEnable.value == 0 || _copterFenceType == 0 ?
qsTr("Disabled") :
(_copterFenceType.value == 1 ?
qsTr("Altitude") :
(_copterFenceType.value == 2 ? qsTr("Circle") : qsTr("Altitude,Circle")))
visible: controller.vehicle.multiRotor
}
VehicleSummaryRow {
labelText: qsTr("GeoFence:")
valueText: _copterFenceAction.value == 0 ?
qsTr("Report only") :
(_copterFenceAction.value == 1 ? qsTr("RTL or Land") : qsTr("Unknown"))
visible: controller.vehicle.multiRotor && _copterFenceEnable.value !== 0
}
VehicleSummaryRow {
labelText: qsTr("RTL min alt:")
valueText: fact.value == 0 ? qsTr("current") : fact.valueString + " " + fact.units
visible: controller.vehicle.multiRotor
property Fact fact: controller.getParameterFact(-1, "RTL_ALT", false /* reportMissing */)
}
VehicleSummaryRow {
labelText: qsTr("RTL min alt:")
valueText: fact.value < 0 ? qsTr("current") : fact.valueString + " " + fact.units
visible: controller.vehicle.fixedWing
property Fact fact: controller.getParameterFact(-1, "ALT_HOLD_RTL", false /* reportMissing */)
}
}
}
...@@ -785,6 +785,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) ...@@ -785,6 +785,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml");
} else if (majorVersion == 3) { } else if (majorVersion == 3) {
switch (minorVersion) { switch (minorVersion) {
case 0:
case 1:
case 2:
case 3: case 3:
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml");
case 4: case 4:
...@@ -792,11 +795,8 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) ...@@ -792,11 +795,8 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case 5: case 5:
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml");
case 6: case 6:
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml");
default: default:
if (minorVersion < 3) { return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml");
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml");
}
} }
} }
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml");
...@@ -812,6 +812,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) ...@@ -812,6 +812,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml");
} else if (majorVersion == 3) { } else if (majorVersion == 3) {
switch (minorVersion) { switch (minorVersion) {
case 0:
case 1:
case 2:
case 3: case 3:
case 4: case 4:
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml");
...@@ -820,10 +823,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) ...@@ -820,10 +823,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml");
case 7: case 7:
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.7.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.7.xml");
case 8:
default: default:
if (minorVersion < 3) { return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml");
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml");
}
} }
} }
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml");
...@@ -836,8 +838,12 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) ...@@ -836,8 +838,12 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case 0: case 0:
case 1: case 1:
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml");
default: case 2:
case 3:
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml");
case 4:
default:
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.4.xml");
} }
} }
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"); return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml");
......
This source diff could not be displayed because it is too large. You can view the blob instead.
This source diff could not be displayed because it is too large. You can view the blob instead.
...@@ -15,13 +15,9 @@ ...@@ -15,13 +15,9 @@
<file alias="APMPowerComponent.qml">../../AutoPilotPlugins/APM/APMPowerComponent.qml</file> <file alias="APMPowerComponent.qml">../../AutoPilotPlugins/APM/APMPowerComponent.qml</file>
<file alias="APMPowerComponentSummary.qml">../../AutoPilotPlugins/APM/APMPowerComponentSummary.qml</file> <file alias="APMPowerComponentSummary.qml">../../AutoPilotPlugins/APM/APMPowerComponentSummary.qml</file>
<file alias="APMRadioComponentSummary.qml">../../AutoPilotPlugins/APM/APMRadioComponentSummary.qml</file> <file alias="APMRadioComponentSummary.qml">../../AutoPilotPlugins/APM/APMRadioComponentSummary.qml</file>
<file alias="APMSafetyComponentCopter.qml">../../AutoPilotPlugins/APM/APMSafetyComponentCopter.qml</file> <file alias="APMSafetyComponent.qml">../../AutoPilotPlugins/APM/APMSafetyComponent.qml</file>
<file alias="APMSafetyComponentPlane.qml">../../AutoPilotPlugins/APM/APMSafetyComponentPlane.qml</file>
<file alias="APMSafetyComponentRover.qml">../../AutoPilotPlugins/APM/APMSafetyComponentRover.qml</file>
<file alias="APMSafetyComponentSub.qml">../../AutoPilotPlugins/APM/APMSafetyComponentSub.qml</file> <file alias="APMSafetyComponentSub.qml">../../AutoPilotPlugins/APM/APMSafetyComponentSub.qml</file>
<file alias="APMSafetyComponentSummaryCopter.qml">../../AutoPilotPlugins/APM/APMSafetyComponentSummaryCopter.qml</file> <file alias="APMSafetyComponentSummary.qml">../../AutoPilotPlugins/APM/APMSafetyComponentSummary.qml</file>
<file alias="APMSafetyComponentSummaryPlane.qml">../../AutoPilotPlugins/APM/APMSafetyComponentSummaryPlane.qml</file>
<file alias="APMSafetyComponentSummaryRover.qml">../../AutoPilotPlugins/APM/APMSafetyComponentSummaryRover.qml</file>
<file alias="APMSafetyComponentSummarySub.qml">../../AutoPilotPlugins/APM/APMSafetyComponentSummarySub.qml</file> <file alias="APMSafetyComponentSummarySub.qml">../../AutoPilotPlugins/APM/APMSafetyComponentSummarySub.qml</file>
<file alias="APMSensorsComponent.qml">../../AutoPilotPlugins/APM/APMSensorsComponent.qml</file> <file alias="APMSensorsComponent.qml">../../AutoPilotPlugins/APM/APMSensorsComponent.qml</file>
<file alias="APMSensorsComponentSummary.qml">../../AutoPilotPlugins/APM/APMSensorsComponentSummary.qml</file> <file alias="APMSensorsComponentSummary.qml">../../AutoPilotPlugins/APM/APMSensorsComponentSummary.qml</file>
...@@ -51,6 +47,7 @@ ...@@ -51,6 +47,7 @@
<file alias="APMParameterFactMetaData.Copter.3.6.xml">APMParameterFactMetaData.Copter.3.6.xml</file> <file alias="APMParameterFactMetaData.Copter.3.6.xml">APMParameterFactMetaData.Copter.3.6.xml</file>
<file alias="APMParameterFactMetaData.Rover.3.0.xml">APMParameterFactMetaData.Rover.3.0.xml</file> <file alias="APMParameterFactMetaData.Rover.3.0.xml">APMParameterFactMetaData.Rover.3.0.xml</file>
<file alias="APMParameterFactMetaData.Rover.3.2.xml">APMParameterFactMetaData.Rover.3.2.xml</file> <file alias="APMParameterFactMetaData.Rover.3.2.xml">APMParameterFactMetaData.Rover.3.2.xml</file>
<file alias="APMParameterFactMetaData.Rover.3.4.xml">APMParameterFactMetaData.Rover.3.4.xml</file>
<file alias="APMParameterFactMetaData.Sub.3.4.xml">APMParameterFactMetaData.Sub.3.4.xml</file> <file alias="APMParameterFactMetaData.Sub.3.4.xml">APMParameterFactMetaData.Sub.3.4.xml</file>
<file alias="APMParameterFactMetaData.Sub.3.5.xml">APMParameterFactMetaData.Sub.3.5.xml</file> <file alias="APMParameterFactMetaData.Sub.3.5.xml">APMParameterFactMetaData.Sub.3.5.xml</file>
<file alias="Copter.OfflineEditing.params">Copter3.5.OfflineEditing.params</file> <file alias="Copter.OfflineEditing.params">Copter3.5.OfflineEditing.params</file>
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment