QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
APMGimbalParams.qml
Go to the documentation of this file.
1import QtQuick
2
3import QGroundControl
4
5/// Manages access to ArduPilot mount parameters
6Item {
7 /// The MNT#_ parameters this object manages
8 property int instance: 1
9
10 property var controller: FactPanelController {}
11
12 /// Number of MNT#_ instances available, 0 indicates no gimbal support
13 readonly property int instanceCount: _instanceCount
14
15 /// True if gimbal parameters are available, False indicates MNT#_TYPE disabled, or reboot required to get params
16 property bool paramsAvailable: false
17
18 property Fact typeFact: controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "TYPE", false)
19 property Fact defaultModeFact: controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "DEFLT_MODE", false)
20
21 property Fact optionsFact: null
22 property Fact neutralXFact: null
23 property Fact neutralYFact: null
24 property Fact neutralZFact: null
25 property Fact retractXFact: null
26 property Fact retractYFact: null
27 property Fact retractZFact: null
28 property Fact pitchMinFact: null
29 property Fact pitchMaxFact: null
30 property Fact rollMinFact: null
31 property Fact rollMaxFact: null
32 property Fact yawMinFact: null
33 property Fact yawMaxFact: null
34 property Fact rcRateFact: null
35 property Fact pitchLeadFact: null
36 property Fact rollLeadFact: null
37
38 property int _instanceCount: _instancedParamCount("MNT#_TYPE")
39 property string _prefixTemplate: "MNT#_"
40
41 function _instancedParamCount(paramNameTemplate) {
42 let instanceIndex = 1
43 while (controller.parameterExists(-1, paramNameTemplate.replace("#", instanceIndex))) {
44 instanceIndex++
45 }
46 return instanceIndex - 1
47 }
48
49 Component.onCompleted: {
50 if (defaultModeFact === null) {
51 paramsAvailable = false
52 } else {
53 optionsFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "OPTIONS")
54 neutralXFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "NEUTRAL_X")
55 neutralYFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "NEUTRAL_Y")
56 neutralZFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "NEUTRAL_Z")
57 retractXFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "RETRACT_X")
58 retractYFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "RETRACT_Y")
59 retractZFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "RETRACT_Z")
60 pitchMinFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "PITCH_MIN")
61 pitchMaxFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "PITCH_MAX")
62 rollMinFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "ROLL_MIN")
63 rollMaxFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "ROLL_MAX")
64 yawMinFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "YAW_MIN")
65 yawMaxFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "YAW_MAX")
66 rcRateFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "RC_RATE")
67 pitchLeadFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "LEAD_PTCH")
68 rollLeadFact = controller.getParameterFact(-1, _prefixTemplate.replace("#", instance) + "LEAD_RLL")
69 paramsAvailable = true
70 }
71 }
72}