6import QGroundControl.FactControls
7import QGroundControl.Controls
11 pageComponent: pageComponent
16 width: Math.max(availableWidth, outerColumn.width)
17 height: outerColumn.height
23 readonly property string hitlParam: "SYS_HITL"
25 property real _margins: ScreenTools.defaultFontPixelHeight
26 property real _labelWidth: ScreenTools.defaultFontPixelWidth * 30
27 property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 20
28 property real _imageHeight: ScreenTools.defaultFontPixelHeight * 3
29 property real _imageWidth: _imageHeight * 2
31 property Fact _enableLogging: controller.getParameterFact(-1, "SDLOG_MODE")
32 property Fact _fenceAction: controller.getParameterFact(-1, "GF_ACTION")
33 property Fact _fenceRadius: controller.getParameterFact(-1, "GF_MAX_HOR_DIST")
34 property Fact _fenceAlt: controller.getParameterFact(-1, "GF_MAX_VER_DIST")
35 property Fact _rtlLandDelay: controller.getParameterFact(-1, "RTL_LAND_DELAY")
36 property Fact _lowBattAction: controller.getParameterFact(-1, "COM_LOW_BAT_ACT")
37 property Fact _rcLossAction: controller.getParameterFact(-1, "NAV_RCL_ACT")
38 property Fact _dlLossAction: controller.getParameterFact(-1, "NAV_DLL_ACT")
39 property Fact _disarmLandDelay: controller.getParameterFact(-1, "COM_DISARM_LAND")
40 property Fact _collisionPrevention: controller.getParameterFact(-1, "CP_DIST")
41 property Fact _landSpeedMC: controller.getParameterFact(-1, "MPC_LAND_SPEED", false)
42 property bool _hitlAvailable: controller.parameterExists(-1, hitlParam)
43 property Fact _hitlEnabled: controller.getParameterFact(-1, hitlParam, false)
48 anchors.horizontalCenter: parent.horizontalCenter
51 text: qsTr("Low Battery Failsafe Trigger")
55 width: mainRow.width + (_margins * 2)
56 height: mainRow.height + (_margins * 2)
57 color: qgcPal.windowShade
61 anchors.centerIn: parent
65 anchors.verticalCenter: parent.verticalCenter
68 fillMode: Image.PreserveAspectFit
69 source: qgcPal.globalTheme === QGCPalette.Light ? "/qmlimages/LowBatteryLight.svg" : "/qmlimages/LowBattery.svg"
71 anchors.centerIn: parent
76 anchors.verticalCenter: parent.verticalCenter
79 text: qsTr("Failsafe Action:")
80 Layout.minimumWidth:_labelWidth
81 Layout.fillWidth: true
86 Layout.minimumWidth:_editFieldWidth
87 Layout.fillWidth: true
91 text: qsTr("Battery Warn Level:")
92 Layout.fillWidth: true
95 fact: controller.getParameterFact(-1, "BAT_LOW_THR")
96 Layout.fillWidth: true
100 text: qsTr("Battery Failsafe Level:")
101 Layout.fillWidth: true
104 fact: controller.getParameterFact(-1, "BAT_CRIT_THR")
105 Layout.fillWidth: true
109 text: qsTr("Battery Emergency Level:")
110 Layout.fillWidth: true
113 fact: controller.getParameterFact(-1, "BAT_EMERGEN_THR")
114 Layout.fillWidth: true
121 text: qsTr("Object Detection")
125 width: mainRow.width + (_margins * 2)
126 height: odRow.height + (_margins * 2)
127 color: qgcPal.windowShade
131 anchors.centerIn: parent
135 anchors.verticalCenter: parent.verticalCenter
138 source: "/qmlimages/ObjectAvoidance.svg"
140 width: _imageHeight * 2
141 anchors.centerIn: parent
146 anchors.verticalCenter: parent.verticalCenter
149 text: qsTr("Collision Prevention:")
150 Layout.minimumWidth:_labelWidth
151 Layout.fillWidth: true
154 model: [qsTr("Disabled"), qsTr("Enabled")]
155 enabled: _collisionPrevention
156 Layout.minimumWidth:_editFieldWidth
157 Layout.fillWidth: true
158 currentIndex: _collisionPrevention ? (_collisionPrevention.rawValue > 0 ? 1 : 0) : 0
159 onActivated: (index) => {
160 if(_collisionPrevention) {
161 _collisionPrevention.value = index > 0 ? 5 : -1
162 console.log('Collision prevention enabled: ' + _collisionPrevention.value)
163 showObstacleDistanceOverlayCheckBox.checked = _collisionPrevention.value > 0
169 text: qsTr("Minimum Distance: (") + QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsString + ")"
170 Layout.fillWidth: true
171 Layout.alignment: Qt.AlignVCenter
174 width: _editFieldWidth
175 enabled: _collisionPrevention && _collisionPrevention.rawValue > 0
176 Layout.minimumWidth:_editFieldWidth
177 Layout.minimumHeight: ScreenTools.defaultFontPixelHeight * 2
178 Layout.fillWidth: true
179 Layout.fillHeight: true
180 to: QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(15)
181 from: QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(1)
185 Layout.alignment: Qt.AlignVCenter
187 if (_collisionPrevention && _collisionPrevention.rawValue > 0) {
188 return QGroundControl.unitsConversion.metersToAppSettingsHorizontalDistanceUnits(_collisionPrevention.rawValue)
194 if(_collisionPrevention) {
195 //-- Negative means disabled
196 if(_collisionPrevention.rawValue >= 0) {
197 _collisionPrevention.rawValue = QGroundControl.unitsConversion.appSettingsHorizontalDistanceUnitsToMeters(value)
204 id: showObstacleDistanceOverlayCheckBox
205 text: qsTr("Show obstacle distance overlay")
206 visible: _showObstacleDistanceOverlay.visible
207 fact: _showObstacleDistanceOverlay
209 property Fact _showObstacleDistanceOverlay: QGroundControl.settingsManager.flyViewSettings.showObstacleDistanceOverlay
216 text: qsTr("RC Loss Failsafe Trigger")
220 width: mainRow.width + (_margins * 2)
221 height: rcLossGrid.height + (_margins * 2)
222 color: qgcPal.windowShade
226 anchors.centerIn: parent
230 anchors.verticalCenter: parent.verticalCenter
233 fillMode: Image.PreserveAspectFit
234 source: qgcPal.globalTheme === QGCPalette.Light ? "/qmlimages/RCLossLight.svg" : "/qmlimages/RCLoss.svg"
236 anchors.centerIn: parent
241 anchors.verticalCenter: parent.verticalCenter
244 text: qsTr("Failsafe Action:")
245 Layout.minimumWidth:_labelWidth
246 Layout.fillWidth: true
251 Layout.minimumWidth:_editFieldWidth
252 Layout.fillWidth: true
256 text: qsTr("RC Loss Timeout:")
257 Layout.fillWidth: true
260 fact: controller.getParameterFact(-1, "COM_RC_LOSS_T")
261 Layout.fillWidth: true
268 text: qsTr("Data Link Loss Failsafe Trigger")
272 width: mainRow.width + (_margins * 2)
273 height: dataLinkLossGrid.height + (_margins * 2)
274 color: qgcPal.windowShade
278 anchors.centerIn: parent
282 anchors.verticalCenter: parent.verticalCenter
285 fillMode: Image.PreserveAspectFit
286 source: qgcPal.globalTheme === QGCPalette.Light ? "/qmlimages/DatalinkLossLight.svg" : "/qmlimages/DatalinkLoss.svg"
288 anchors.centerIn: parent
293 anchors.verticalCenter: parent.verticalCenter
296 text: qsTr("Failsafe Action:")
297 Layout.minimumWidth:_labelWidth
298 Layout.fillWidth: true
303 Layout.minimumWidth:_editFieldWidth
304 Layout.fillWidth: true
308 text: qsTr("Data Link Loss Timeout:")
309 Layout.fillWidth: true
312 fact: controller.getParameterFact(-1, "COM_DL_LOSS_T")
313 Layout.fillWidth: true
320 text: qsTr("Geofence Failsafe Trigger")
324 width: mainRow.width + (_margins * 2)
325 height: geoFenceGrid.height + (_margins * 2)
326 color: qgcPal.windowShade
330 anchors.centerIn: parent
334 anchors.verticalCenter: parent.verticalCenter
337 fillMode: Image.PreserveAspectFit
338 source: qgcPal.globalTheme === QGCPalette.Light ? "/qmlimages/GeoFenceLight.svg" : "/qmlimages/GeoFence.svg"
340 anchors.centerIn: parent
346 anchors.verticalCenter: parent.verticalCenter
349 text: qsTr("Action on breach:")
350 Layout.minimumWidth:_labelWidth
351 Layout.fillWidth: true
356 Layout.minimumWidth:_editFieldWidth
357 Layout.fillWidth: true
361 id: fenceRadiusCheckBox
362 text: qsTr("Max Radius:")
363 checked: _fenceRadius.value > 0
364 onClicked: _fenceRadius.value = checked ? 100 : 0
365 Layout.fillWidth: true
369 enabled: fenceRadiusCheckBox.checked
370 Layout.fillWidth: true
374 id: fenceAltMaxCheckBox
375 text: qsTr("Max Altitude:")
376 checked: _fenceAlt ? _fenceAlt.value > 0 : false
377 onClicked: _fenceAlt.value = checked ? 100 : 0
378 Layout.fillWidth: true
382 enabled: fenceAltMaxCheckBox.checked
383 Layout.fillWidth: true
390 text: qsTr("Return To Launch Settings")
394 width: mainRow.width + (_margins * 2)
395 height: returnHomeGrid.height + (_margins * 2)
396 color: qgcPal.windowShade
400 anchors.centerIn: parent
404 anchors.verticalCenter: parent.verticalCenter
407 source: controller.vehicle.fixedWing ? "/qmlimages/ReturnToHomeAltitude.svg" : "/qmlimages/ReturnToHomeAltitudeCopter.svg"
409 width: _imageHeight * 2
410 anchors.centerIn: parent
415 anchors.verticalCenter: parent.verticalCenter
418 text: qsTr("Climb to altitude of:")
419 Layout.minimumWidth: _labelWidth
420 Layout.fillWidth: true
423 fact: controller.getParameterFact(-1, "RTL_RETURN_ALT")
424 Layout.minimumWidth: _editFieldWidth
425 Layout.fillWidth: true
429 text: qsTr("Return to launch, then:")
434 Item { width: ScreenTools.defaultFontPixelWidth; height: 1 }
437 checked: _rtlLandDelay ? _rtlLandDelay.value === 0 : false
438 text: qsTr("Land immediately")
439 onClicked: _rtlLandDelay.value = 0
444 Item { width: ScreenTools.defaultFontPixelWidth; height: 1 }
446 id: homeLoiterNoLandRadio
447 checked: _rtlLandDelay ? _rtlLandDelay.value < 0 : false
448 text: qsTr("Loiter and do not land")
449 onClicked: _rtlLandDelay.value = -1
454 Item { width: ScreenTools.defaultFontPixelWidth; height: 1 }
456 id: homeLoiterLandRadio
457 checked: _rtlLandDelay ? _rtlLandDelay.value > 0 : false
458 text: qsTr("Loiter and land after specified time")
459 onClicked: _rtlLandDelay.value = 60
464 text: qsTr("Loiter Time")
465 Layout.fillWidth: true
468 fact: controller.getParameterFact(-1, "RTL_LAND_DELAY")
469 enabled: homeLoiterLandRadio.checked === true
470 Layout.fillWidth: true
474 text: qsTr("Loiter Altitude")
475 Layout.fillWidth: true
478 fact: controller.getParameterFact(-1, "RTL_DESCEND_ALT")
479 enabled: homeLoiterLandRadio.checked === true || homeLoiterNoLandRadio.checked === true
480 Layout.fillWidth: true
487 text: qsTr("Land Mode Settings")
491 width: mainRow.width + (_margins * 2)
492 height: landModeGrid.height + (_margins * 2)
493 color: qgcPal.windowShade
497 anchors.centerIn: parent
501 anchors.verticalCenter: parent.verticalCenter
504 source: controller.vehicle.fixedWing ? "/qmlimages/LandMode.svg" : "/qmlimages/LandModeCopter.svg"
507 anchors.centerIn: parent
512 anchors.verticalCenter: parent.verticalCenter
515 id: landVelocityLabel
516 text: qsTr("Landing Descent Rate:")
517 visible: controller.vehicle && !controller.vehicle.fixedWing
518 Layout.minimumWidth:_labelWidth
519 Layout.fillWidth: true
523 visible: controller.vehicle && !controller.vehicle.fixedWing
524 Layout.minimumWidth:_editFieldWidth
525 Layout.fillWidth: true
529 id: disarmDelayCheckBox
530 text: qsTr("Disarm After:")
531 checked: _disarmLandDelay.value > 0
532 onClicked: _disarmLandDelay.value = checked ? 2 : 0
533 Layout.fillWidth: true
536 fact: _disarmLandDelay
537 enabled: disarmDelayCheckBox.checked
538 Layout.fillWidth: true
545 text: qsTr("Vehicle Telemetry Logging")
549 width: mainRow.width + (_margins * 2)
550 height: loggingGrid.height + (_margins * 2)
551 color: qgcPal.windowShade
555 anchors.centerIn: parent
559 anchors.verticalCenter: parent.verticalCenter
562 fillMode: Image.PreserveAspectFit
563 source: qgcPal.globalTheme === QGCPalette.Light ? "/qmlimages/no-logging-light.svg" : "/qmlimages/no-logging.svg"
565 anchors.centerIn: parent
570 anchors.verticalCenter: parent.verticalCenter
572 text: qsTr("Telemetry logging to vehicle storage:")
573 Layout.minimumWidth:_labelWidth
574 Layout.fillWidth: true
577 model: [qsTr("Disabled"), qsTr("Enabled")]
578 enabled: _enableLogging
579 Layout.minimumWidth:_editFieldWidth
580 Layout.fillWidth: true
581 Component.onCompleted: {
582 currentIndex = _enableLogging ? (_enableLogging.value >= 0 ? 1 : 0) : 0
584 onActivated: (index) => {
586 _enableLogging.value = index > 0 ? 0 : -1
595 text: qsTr("Hardware in the Loop Simulation")
596 visible: _hitlAvailable
600 width: mainRow.width + (_margins * 2)
601 height: hitlGrid.height + (_margins * 2)
602 color: qgcPal.windowShade
603 visible: _hitlAvailable
607 anchors.centerIn: parent
611 anchors.verticalCenter: parent.verticalCenter
614 source: "/qmlimages/HITL.svg"
617 anchors.centerIn: parent
622 anchors.verticalCenter: parent.verticalCenter
624 text: qsTr("HITL Enabled:")
625 Layout.minimumWidth:_labelWidth
626 Layout.fillWidth: true
631 Layout.minimumWidth:_editFieldWidth
632 Layout.fillWidth: true