5import QGroundControl.FactControls
6import QGroundControl.Controls
11 FactPanelController { id: controller; }
13 property Fact _copterFenceAction: controller.getParameterFact(-1, "FENCE_ACTION", false /* reportMissing */)
14 property Fact _copterFenceEnable: controller.getParameterFact(-1, "FENCE_ENABLE", false /* reportMissing */)
15 property Fact _copterFenceType: controller.getParameterFact(-1, "FENCE_TYPE", false /* reportMissing */)
17 property Fact _batt1Monitor: controller.getParameterFact(-1, "BATT_MONITOR")
18 property Fact _batt2Monitor: controller.getParameterFact(-1, "BATT2_MONITOR", false /* reportMissing */)
19 property bool _batt2MonitorAvailable: controller.parameterExists(-1, "BATT2_MONITOR")
20 property bool _batt1MonitorEnabled: _batt1Monitor.rawValue !== 0
21 property bool _batt2MonitorEnabled: _batt2MonitorAvailable && _batt2Monitor.rawValue !== 0
23 property Fact _batt1FSLowAct: controller.getParameterFact(-1, "r.BATT_FS_LOW_ACT", false /* reportMissing */)
24 property Fact _batt1FSCritAct: controller.getParameterFact(-1, "BATT_FS_CRT_ACT", false /* reportMissing */)
25 property Fact _batt2FSLowAct: controller.getParameterFact(-1, "BATT2_FS_LOW_ACT", false /* reportMissing */)
26 property Fact _batt2FSCritAct: controller.getParameterFact(-1, "BATT2_FS_CRT_ACT", false /* reportMissing */)
27 property bool _batt1FSCritActAvailable: controller.parameterExists(-1, "BATT_FS_CRT_ACT")
29 property bool _roverFirmware: controller.parameterExists(-1, "MODE1") // This catches all usage of ArduRover firmware vehicle types: Rover, Boat...
36 labelText: qsTr("Arming Checks:")
38 if (_armingCheckFact) {
39 return _armingCheckFact.value & 1 ? qsTr("Enabled") : qsTr("Some disabled")
40 } else if (_armingSkipCheckFact) {
41 return _armingSkipCheckFact.value === 0 ? qsTr("Enabled") : qsTr("Some disabled")
46 // Older firmwares use ARMING_CHECK. Newer firmwares use ARMING_SKIPCHK.
47 property Fact _armingCheckFact: controller.getParameterFact(-1, "ARMING_CHECK", false /* reportMissing */)
48 property Fact _armingSkipCheckFact: controller.getParameterFact(-1, "ARMING_SKIPCHK", false /* reportMissing */)
52 labelText: qsTr("Throttle failsafe:")
53 valueText: fact ? fact.enumStringValue : ""
54 visible: controller.vehicle.multiRotor
56 property Fact fact: controller.getParameterFact(-1, "FS_THR_ENABLE", false /* reportMissing */)
60 labelText: qsTr("Throttle failsafe:")
61 valueText: fact ? fact.enumStringValue : ""
62 visible: controller.vehicle.fixedWing
64 property Fact fact: controller.getParameterFact(-1, "THR_FAILSAFE", false /* reportMissing */)
68 labelText: qsTr("Throttle failsafe:")
69 valueText: fact ? fact.enumStringValue : ""
70 visible: _roverFirmware
72 property Fact fact: controller.getParameterFact(-1, "FS_THR_ENABLE", false /* reportMissing */)
76 labelText: qsTr("Failsafe Action:")
77 valueText: fact ? fact.enumStringValue : ""
78 visible: _roverFirmware
80 property Fact fact: controller.getParameterFact(-1, "FS_ACTION", false /* reportMissing */)
84 labelText: qsTr("Failsafe Crash Check:")
85 valueText: fact ? fact.enumStringValue : ""
86 visible: _roverFirmware
88 property Fact fact: controller.getParameterFact(-1, "FS_CRASH_CHECK", false /* reportMissing */)
92 labelText: qsTr("Batt1 low failsafe:")
93 valueText: _batt1MonitorEnabled ? _batt1FSLowAct.enumStringValue : ""
94 visible: _batt1MonitorEnabled
98 labelText: qsTr("Batt1 critical failsafe:")
99 valueText: _batt1FSCritActAvailable ? _batt1FSCritAct.enumStringValue : ""
100 visible: _batt1FSCritActAvailable
104 labelText: qsTr("Batt2 low failsafe:")
105 valueText: _batt2MonitorEnabled ? _batt2FSLowAct.enumStringValue : ""
106 visible: _batt2MonitorEnabled
110 labelText: qsTr("Batt2 critical failsafe:")
111 valueText: _batt2MonitorEnabled ? _batt2FSCritAct.enumStringValue : ""
112 visible: _batt2MonitorEnabled
116 labelText: qsTr("GeoFence:")
118 if(_copterFenceEnable && _copterFenceType) {
119 if(_copterFenceEnable.value == 0 || _copterFenceType == 0) {
120 return qsTr("Disabled")
122 if(_copterFenceType.value == 1) {
123 return qsTr("Altitude")
125 if(_copterFenceType.value == 2) {
126 return qsTr("Circle")
128 return qsTr("Altitude,Circle")
133 visible: controller.vehicle.multiRotor
137 labelText: qsTr("GeoFence:")
138 valueText: _copterFenceAction.value == 0 ?
139 qsTr("Report only") :
140 (_copterFenceAction.value == 1 ? qsTr("RTL or Land") : qsTr("Unknown"))
141 visible: controller.vehicle.multiRotor && _copterFenceEnable.value !== 0
145 labelText: qsTr("RTL min alt:")
146 valueText: fact ? (fact.value == 0 ? qsTr("current") : fact.valueString + " " + fact.units) : ""
147 visible: controller.vehicle.multiRotor
149 property Fact fact: controller.getParameterFact(-1, "RTL_ALT", false /* reportMissing */)
153 labelText: qsTr("RTL min alt:")
154 valueText: fact ? (fact.value < 0 ? qsTr("current") : fact.valueString + " " + fact.units) : ""
155 visible: controller.vehicle.fixedWing
157 property Fact fact: controller.getParameterFact(-1, "r.RTL_ALTITUDE", false /* reportMissing */)