diff --git a/files/ardupilotmega/arduplane.pdef.xml b/files/ardupilotmega/arduplane.pdef.xml
index 382892d..f157f70 100644
--- a/files/ardupilotmega/arduplane.pdef.xml
+++ b/files/ardupilotmega/arduplane.pdef.xml
@@ -3,7 +3,7 @@
-
+
1200
2400
@@ -16,7 +16,7 @@
115200
-
+
1200
2400
@@ -29,206 +29,206 @@
115200
-
+
0 10
1
seconds
-
+
0 1
0.01
-
+
0 1
0.01
-
+
0 5
0.01
-
+
0 5
0.01
-
+
Disabled
Enabled
-
+
Disabled
-Enabled
+FBWMixing
+DirectMixing
-
-
-Disabled
-Enabled
-
+
+0 30
+0.1
+m/s
-
+
+0 30
+0.1
+m/s/s
+
+
+0 45
+1
+degrees
+
+
centi-Degrees
-
+
0.1
meters
-
+
0.1
seconds
-
-0 2000
-1
-
-
-0 9000
-1
-centi-Degrees
-
-
+
-Disabled
-Enabled
+Legacy
+L1Controller
-
-0 32767
-1
-Meters
-
-
+
0 1
0.1
Percent
-
+
Default Method
non-airspeed
-
+
-32767 32767
1
Meters
-
-1 127
+
+1 32767
1
Meters
-
+
1 32767
1
Meters
-
+
None
GuidedMode
ReportOnly
-
+
-
+
-
+
0 32767
1
meters
-
+
0 32767
1
meters
-
+
5 50
1
m/s
-
+
5 50
1
m/s
-
+
Disabled
Enabled
-
+
+1-10
+0.1
+
+
0 100
1
Percent
-
+
0 100
1
Percent
-
+
0 100
1
Percent
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
-
+
0 100
1
Percent
-
+
Disabled
Enabled
-
+
None
ReturnToLaunch
-
+
None
ReturnToLaunch
-
+
Disabled
Enabled
-
+
-
+
Manual
CIRCLE
@@ -242,7 +242,7 @@
Guided
-
+
Manual
CIRCLE
@@ -256,7 +256,7 @@
Guided
-
+
Manual
CIRCLE
@@ -270,7 +270,7 @@
Guided
-
+
Manual
CIRCLE
@@ -284,7 +284,7 @@
Guided
-
+
Manual
CIRCLE
@@ -298,7 +298,7 @@
Guided
-
+
Manual
CIRCLE
@@ -312,90 +312,102 @@
Guided
-
+
0 9000
1
centi-Degrees
-
+
0 9000
1
centi-Degrees
-
+
-9000 0
1
centi-Degrees
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
+
+Disabled
+UpUp
+UpDown
+DownUp
+DownDown
+
-
+
-
+
-
+
-
+
+
+
cm/s
-
+
m/s
-
+
cm/s
-
+
centi-Degrees
-
+
+centimeters
+
+
centimeters
-
+
Disabled
Enabled
-
+
A/V
-
+
Volts
-
+
mAh
-
+
Disabled
A0
@@ -403,7 +415,7 @@
A13
-
+
Disabled
A1
@@ -411,7 +423,7 @@
A12
-
+
Disabled
A0
@@ -419,17 +431,36 @@
A13
+
+
+Disabled
+Channel1
+Channel2
+Channel3
+Channel4
+Channel5
+Channel6
+Channel7
+Channel8
+
+
+
+
+Disabled
+Enabled
+
+
-
+
-
+
-
+
-
+
-
+
1200
2400
@@ -442,23 +473,23 @@
115200
-
+
0 10
1
seconds
-
+
0 4000
1
Centimeters
-
+
Disabled
Enabled
-
+
XL-EZ0
LV-EZ0
@@ -466,60 +497,60 @@
HRLV
-
+
Disabled
Voltage Only
Voltage and Current
-
+
Disabled
Enabled
-
+
+
+Disabled
+Enabled
+
-
+
-
+
mAh
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
0 20
.1
-
+
Disabled
Enabled
-
+
-1 1000
1
Centimeters
-
-0 100
-1
-
-
+
Disabled
A0
@@ -527,7 +558,7 @@
A13
-
+
Disabled
A1
@@ -535,7 +566,7 @@
A12
-
+
Disabled
A0
@@ -544,122 +575,105 @@
A13
-
+
Disabled
Enabled
-
+
At Next WP
On Mission Restart
-
+
-
+
-
+
1 127
1
Meters
-
-1 127
-1
-Meters
-
-
-100
-Centimeters/Second
-
-
-Dimensionless
-
-
-0 32767
-1
-Meters
-
-
+
0 60000
1000
ms
-
+
10 200
10
Centimeters/Second
-
+
-500 -50
10
Centimeters/Second
-
+
50 500
10
Centimeters/Second
-
+
10 500
10
Centimeters/Second
-
+
0 1000
1
ms
-
+
0 1000
1
ms
-
+
Disabled
Enabled always RTL
Enabled Continue with Mission in Auto Mode
-
+
-
+
0 1000
PWM
-
+
300 700
1
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
-
+
1 10
-
+
Normal Start-up
Start-up in ESC Calibration mode
-
+
CH6_NONE
CH6_STABILIZE_KP
@@ -671,15 +685,13 @@
CH6_THROTTLE_KP
CH6_TOP_BOTTOM_RATIO
CH6_RELAY
-CH6_TRAVERSE_SPEED
-CH6_NAV_KP
+CH6_WP_SPEED
CH6_LOITER_KP
CH6_HELI_EXTERNAL_GYRO
CH6_THR_HOLD_KP
CH6_OPTFLOW_KP
CH6_OPTFLOW_KI
CH6_OPTFLOW_KD
-CH6_NAV_KI
CH6_RATE_KD
CH6_LOITER_RATE_KP
CH6_LOITER_RATE_KD
@@ -696,15 +708,16 @@
CH6_THR_ACCEL_KP
CH6_THR_ACCEL_KI
CH6_THR_ACCEL_KD
+CH6_DECLINATION
-
+
0 32767
-
+
0 32767
-
+
0 32767
Plus
@@ -712,7 +725,7 @@
V
-
+
Do Nothing
Flip
@@ -724,39 +737,39 @@
Sonar
-
-1 45
+
+1 90
1
Degrees/Second
-
+
125,400,490
Hertz (Hz)
-
+
1 10
-
+
Disabled
Enabled
-
+
0 300
1
-
+
0 300
1
-
+
Disabled
Enabled
-
+
Disabled
Enable
@@ -768,60 +781,54 @@
GPS Nav Blink
-
+
0.001 0.008
-
+
0.001 0.008
-
+
0.000 0.001
-
+
0.200 0.600
-
+
0.200 0.600
-
-0.000 0.100
-
-
-0.000 0.100
-
-
+
0.000 0.400
-
+
0.000 0.400
-
+
0.100 0.140
-
+
0.100 0.140
-
+
0 4500
-
+
0 4500
-
+
0 4500
-
+
0 500
-
+
0 3000
-
+
0 3000
-
+
Disabled
A0
@@ -829,7 +836,7 @@
A13
-
+
Disabled
A0
@@ -837,7 +844,7 @@
A13
-
+
Disabled
A1
@@ -845,11 +852,11 @@
A12
-
+
-
+
-
+
1200
2400
@@ -862,7 +869,7 @@
115200
-
+
1200
2400
@@ -875,167 +882,223 @@
115200
-
+
0 10
1
seconds
-
+
Disabled
Enabled
-
+
Disabled
Voltage Only
Voltage and Current
-
-
-
+
-
+
mAh
-
+
0 2000
1
-
+
0 9000
1
centi-Degrees
-
+
+
+Disabled
+TiggerPin
+
+
+
+0 20
+0.1
+m/s/s
+
+
0 100
0.1
m/s
-
+
+0 100
+1
+percent
+
+
+0 100
+0.1
+meters
+
+
Nothing
LearnWaypoint
-
+
0 100
1
Percent
-
+
0 100
1
Percent
-
+
0 100
1
Percent
-
+
0 100
1
Percent
-
+
+
+Disabled
+SkidSteeringOutput
+
+
+
+
+Disabled
+SkidSteeringInput
+
+
+
Nothing
RTL
-STOP
+HOLD
-
+
seconds
-
+
Disabled
Enabled
-
+
-
+
Disabled
Enabled
-
-
-Disabled
-Enabled
-
+
+0 1000
+1
+centimeters
+
+
+-45 45
+1
+centimeters
-
+
+0 100
+0.1
+seconds
-
+
+1 100
+1
+
+
+
+
Manual
LEARNING
+STEERING
+HOLD
Auto
RTL
Guided
-
+
Manual
LEARNING
+STEERING
+HOLD
Auto
RTL
Guided
-
+
Manual
LEARNING
+STEERING
+HOLD
Auto
RTL
Guided
-
+
Manual
LEARNING
+STEERING
+HOLD
Auto
RTL
Guided
-
+
Manual
LEARNING
+STEERING
+HOLD
Auto
RTL
Guided
-
+
Manual
LEARNING
+STEERING
+HOLD
Auto
RTL
Guided
-
+
0 1000
0.1
meters
-
+
Servo
Relay
@@ -1044,118 +1107,118 @@
transistor
-
+
0 50
-
+
1000 2000
-
+
1000 2000
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -1180,32 +1243,32 @@
ElevatorWithInput
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -1230,32 +1293,32 @@
ElevatorWithInput
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -1280,32 +1343,32 @@
ElevatorWithInput
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -1330,32 +1393,32 @@
ElevatorWithInput
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -1380,32 +1443,32 @@
ElevatorWithInput
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -1430,32 +1493,32 @@
ElevatorWithInput
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -1480,28 +1543,28 @@
ElevatorWithInput
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
@@ -1509,41 +1572,53 @@
-400 400
1
-
+
-3.142 3.142
0.01
Radians
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
Enabled
+
+
+Disabled
+Use Throttle
+Use Current
+
+1
+
+
+-1000 1000
+1
+
-
+
-
+
-300 300
m/s/s
-
+
rad/s
-
+
Default
5Hz
@@ -1560,7 +1635,7 @@
0.0 1.0
.01
-
+
0.1 0.4
@@ -1575,16 +1650,10 @@
1
m/s
-
-
-Disabled
-Enabled
-
-
-
+
Radians
-
+
None
Yaw45
@@ -1613,6 +1682,10 @@
Pitch270
+
+0.001 0.5
+.01
+
@@ -1634,8 +1707,19 @@
0.1
+
+
+1-60
+1
+seconds
+
+
+0.6-1.0
+0.05
+
+
-
+
retract
neutral
@@ -1644,12 +1728,12 @@
GPS_point
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
@@ -1659,19 +1743,19 @@
1
Centi-Degrees
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
RC5
@@ -1680,17 +1764,17 @@
RC8
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
-
+
Disabled
RC5
@@ -1699,17 +1783,17 @@
RC8
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
-
+
Disabled
RC5
@@ -1718,23 +1802,23 @@
RC8
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
-
-0 10
+
+0 100
1
-
+
retract
neutral
@@ -1743,12 +1827,12 @@
GPS_point
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
@@ -1758,19 +1842,19 @@
1
Centi-Degrees
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
RC5
@@ -1779,17 +1863,17 @@
RC8
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
-
+
Disabled
RC5
@@ -1798,17 +1882,17 @@
RC8
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
-
+
Disabled
RC5
@@ -1817,146 +1901,146 @@
RC8
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
-
-0 10
+
+0 100
1
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -1983,30 +2067,30 @@
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -2033,30 +2117,30 @@
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -2083,30 +2167,30 @@
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -2133,30 +2217,30 @@
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -2183,30 +2267,30 @@
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
800 2200
1
ms
-
+
Reversed
Normal
-
+
-
+
Disabled
Manual
@@ -2233,7 +2317,7 @@
-
+
Servo
Relay
@@ -2242,13 +2326,13 @@
transistor
-
+
0 50
-
+
1000 2000
-
+
1000 2000
@@ -2257,29 +2341,41 @@
-400 400
1
-
+
-3.142 3.142
0.01
Radians
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
Enabled
+
+
+Disabled
+Use Throttle
+Use Current
+
+1
+
+
+-1000 1000
+1
+
@@ -2291,24 +2387,40 @@
0.1
+
+
+0 1000
+100
+Centimeters/Second
+
+
+100 1000
+1
+Centimeters
+
+
-
-0 10
-0.1
+
+0 1000
+100
+Centimeters/Second
-
-0 10
-0.1
+
+100 1000
+1
+Centimeters
-
-0 10
-0.1
+
+0 1000
+100
+Centimeters/Second
-
-0 10
-0.1
+
+100 1000
+1
+Centimeters
@@ -2316,7 +2428,7 @@
0.0 1.0
.01
-
+
0.1 0.4
@@ -2331,16 +2443,10 @@
1
m/s
-
-
-Disabled
-Enabled
-
-
-
+
Radians
-
+
None
Yaw45
@@ -2369,9 +2475,13 @@
Pitch270
+
+0.001 0.5
+.01
+
-
+
retract
neutral
@@ -2380,12 +2490,12 @@
GPS_point
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
@@ -2395,19 +2505,19 @@
1
Centi-Degrees
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
RC5
@@ -2416,17 +2526,17 @@
RC8
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
-
+
Disabled
RC5
@@ -2435,17 +2545,17 @@
RC8
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
-
+
Disabled
RC5
@@ -2454,23 +2564,23 @@
RC8
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
-
-0 10
+
+0 100
1
-
+
retract
neutral
@@ -2479,12 +2589,12 @@
GPS_point
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
@@ -2494,19 +2604,19 @@
1
Centi-Degrees
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
RC5
@@ -2515,17 +2625,17 @@
RC8
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
-
+
Disabled
RC5
@@ -2534,17 +2644,17 @@
RC8
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
-
+
Disabled
RC5
@@ -2553,86 +2663,86 @@
RC8
-
+
-18000 17999
1
Centi-Degrees
-
+
-18000 17999
1
Centi-Degrees
-
-0 10
+
+0 100
1
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
Seconds before returning control
-
+
1-8
-
+
RTL mode
Bounce mode
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
0 32767
1
Meters
@@ -2641,90 +2751,90 @@
0 6
1
-
+
Disabled
Enabled
-
+
Disabled
Enabled
-
+
0 250000
1
Meters
-
+
0 250000
1
Meters
-
+
-180 180
1
Degrees
-
+
-180 180
1
Degrees
-
+
-180 180
1
Degrees
-
+
0 18000
1
Degrees
-
+
0 18000
1
Degrees
-
+
1000 2000
1
PWM
-
+
1000 2000
1
PWM
-
+
1000 2000
1
PWM
-
+
Disabled
Enabled
-
+
-
+
1000 2000
1
PWM
-
+
Disabled
Enabled
-
+
-90 90
1
Degrees
@@ -2732,27 +2842,27 @@
0 5
-
+
1000 2000
10
PWM
-
+
1 3
-
+
0 6000
Seconds
-
+
0 1
-
+
0 50
1
1%
-
+
50 100
1
1%
@@ -2774,17 +2884,50 @@
20 80
+
+
+
+
+meters/Volt
+0.001
+
+
+Volts
+0.001
+
+
+
+Linear
+Inverted
+Hyperbolic
+
+
+
+centimeters
+1
+
+
+centimeters
+1
+
+
+
+Disabled
+Enabled
+
+
+
-
+
-
+
-300 300
m/s/s
-
+
rad/s
-
+
Default
5Hz
@@ -2801,7 +2944,7 @@
0.0 1.0
.01
-
+
0.1 0.4
@@ -2816,16 +2959,10 @@
1
m/s
-
-
-Disabled
-Enabled
-
-
-
+
Radians
-
+
None
Yaw45
@@ -2854,5 +2991,9 @@
Pitch270
+
+0.001 0.5
+.01
+
-
\ No newline at end of file
+
diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc
index 1bcbf5d..99f0c4c 100644
--- a/src/ui/QGCVehicleConfig.cc
+++ b/src/ui/QGCVehicleConfig.cc
@@ -399,17 +399,28 @@ void QGCVehicleConfig::loadConfig()
{
parametersname = xml.attributes().value("name").toString();
}
- QVariantMap set;
- set["title"] = parametersname;
+ QVariantMap genset;
+ QVariantMap advset;
+
QString setname = parametersname;
xml.readNext();
- int arraycount = 0;
+ int genarraycount = 0;
+ int advarraycount = 0;
while ((xml.name() != "parameters") && !xml.atEnd())
{
if (xml.isStartElement() && xml.name() == "param")
{
QString humanname = xml.attributes().value("humanName").toString();
QString name = xml.attributes().value("name").toString();
+ QString tab= xml.attributes().value("user").toString();
+ if (tab == "Advanced")
+ {
+ advset["title"] = parametersname;
+ }
+ else
+ {
+ genset["title"] = parametersname;
+ }
if (name.contains(":"))
{
name = name.split(":")[1];
@@ -425,10 +436,20 @@ void QGCVehicleConfig::loadConfig()
if (xml.isStartElement() && xml.name() == "values")
{
type = 1; //1 is a combobox
- set[setname + "\\" + QString::number(arraycount) + "\\" + "TYPE"] = "COMBO";
- set[setname + "\\" + QString::number(arraycount) + "\\" + "QGC_PARAM_COMBOBOX_DESCRIPTION"] = humanname;
- set[setname + "\\" + QString::number(arraycount) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID"] = name;
- set[setname + "\\" + QString::number(arraycount) + "\\" + "QGC_PARAM_COMBOBOX_COMPONENTID"] = 1;
+ if (tab == "Advanced")
+ {
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "TYPE"] = "COMBO";
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_DESCRIPTION"] = humanname;
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID"] = name;
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COMPONENTID"] = 1;
+ }
+ else
+ {
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "TYPE"] = "COMBO";
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_DESCRIPTION"] = humanname;
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID"] = name;
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COMPONENTID"] = 1;
+ }
int paramcount = 0;
xml.readNext();
while ((xml.name() != "values") && !xml.atEnd())
@@ -438,13 +459,28 @@ void QGCVehicleConfig::loadConfig()
QString code = xml.attributes().value("code").toString();
QString arg = xml.readElementText();
- set[setname + "\\" + QString::number(arraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_TEXT"] = arg;
- set[setname + "\\" + QString::number(arraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_VAL"] = code.toInt();
+ if (tab == "Advanced")
+ {
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_TEXT"] = arg;
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_VAL"] = code.toInt();
+ }
+ else
+ {
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_TEXT"] = arg;
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(paramcount) + "_VAL"] = code.toInt();
+ }
paramcount++;
}
xml.readNext();
}
- set[setname + "\\" + QString::number(arraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
+ if (tab == "Advanced")
+ {
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
+ }
+ else
+ {
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
+ }
}
if (xml.isStartElement() && xml.name() == "field")
{
@@ -465,10 +501,20 @@ void QGCVehicleConfig::loadConfig()
}
if (type == 2)
{
- set[setname + "\\" + QString::number(arraycount) + "\\" + "TYPE"] = "SLIDER";
- set[setname + "\\" + QString::number(arraycount) + "\\" + "QGC_PARAM_SLIDER_DESCRIPTION"] = humanname;
- set[setname + "\\" + QString::number(arraycount) + "\\" + "QGC_PARAM_SLIDER_PARAMID"] = name;
- set[setname + "\\" + QString::number(arraycount) + "\\" + "QGC_PARAM_SLIDER_COMPONENTID"] = 1;
+ if (tab == "Advanced")
+ {
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "TYPE"] = "SLIDER";
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_DESCRIPTION"] = humanname;
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_PARAMID"] = name;
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_COMPONENTID"] = 1;
+ }
+ else
+ {
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "TYPE"] = "SLIDER";
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_DESCRIPTION"] = humanname;
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_PARAMID"] = name;
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_COMPONENTID"] = 1;
+ }
if (fieldmap.contains("Range"))
{
float min = 0;
@@ -484,59 +530,123 @@ void QGCVehicleConfig::loadConfig()
min = fieldmap["Range"].split("-")[0].trimmed().toFloat();
max = fieldmap["Range"].split("-")[1].trimmed().toFloat();
}
-
- set[setname + "\\" + QString::number(arraycount) + "\\" + "QGC_PARAM_SLIDER_MIN"] = min;
- set[setname + "\\" + QString::number(arraycount) + "\\" + "QGC_PARAM_SLIDER_MAX"] = max;
+ if (tab == "Advanced")
+ {
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_MIN"] = min;
+ advset[setname + "\\" + QString::number(advarraycount) + "\\" + "QGC_PARAM_SLIDER_MAX"] = max;
+ }
+ else
+ {
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_MIN"] = min;
+ genset[setname + "\\" + QString::number(genarraycount) + "\\" + "QGC_PARAM_SLIDER_MAX"] = max;
+ }
}
}
- arraycount++;
+ if (tab == "Advanced")
+ {
+ advarraycount++;
+ advset["count"] = advarraycount;
+ }
+ else
+ {
+ genarraycount++;
+ genset["count"] = genarraycount;
+ }
}
xml.readNext();
}
- set["count"] = arraycount;
-
- tool = new QGCToolWidget("", this);
- tool->addUAS(mav);
- tool->setTitle(parametersname);
- tool->setObjectName(parametersname);
- tool->setSettings(set);
- QList paramlist = tool->getParamList();
- for (int i=0;i 0)
{
- //Based on the airframe, we add the parameter to different categories.
- if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
+ tool = new QGCToolWidget("", this);
+ tool->addUAS(mav);
+ tool->setTitle(parametersname);
+ tool->setObjectName(parametersname);
+ tool->setSettings(genset);
+ QList paramlist = tool->getParamList();
+ for (int i=0;iinsert(paramlist[i],tool);
+ //Based on the airframe, we add the parameter to different categories.
+ if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
+ {
+ systemTypeToParamMap["FIXED_WING"]->insert(paramlist[i],tool);
+ }
+ else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
+ {
+ systemTypeToParamMap["QUADROTOR"]->insert(paramlist[i],tool);
+ }
+ else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
+ {
+ systemTypeToParamMap["GROUND_ROVER"]->insert(paramlist[i],tool);
+ }
+ else
+ {
+ libParamToWidgetMap->insert(paramlist[i],tool);
+ }
}
- else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
+
+ toolWidgets.append(tool);
+ QGroupBox *box = new QGroupBox(this);
+ box->setTitle(tool->objectName());
+ box->setLayout(new QVBoxLayout());
+ box->layout()->addWidget(tool);
+ if (valuetype == "vehicles")
{
- systemTypeToParamMap["QUADROTOR"]->insert(paramlist[i],tool);
+ ui->leftGeneralLayout->addWidget(box);
}
- else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
+ else if (valuetype == "libraries")
{
- systemTypeToParamMap["GROUND_ROVER"]->insert(paramlist[i],tool);
+ ui->rightGeneralLayout->addWidget(box);
}
- else
+ box->hide();
+ toolToBoxMap[tool] = box;
+ }
+ if (advarraycount > 0)
+ {
+ tool = new QGCToolWidget("", this);
+ tool->addUAS(mav);
+ tool->setTitle(parametersname);
+ tool->setObjectName(parametersname);
+ tool->setSettings(advset);
+ QList paramlist = tool->getParamList();
+ for (int i=0;iinsert(paramlist[i],tool);
+ //Based on the airframe, we add the parameter to different categories.
+ if (parametersname == "ArduPlane") //MAV_TYPE_FIXED_WING FIXED_WING
+ {
+ systemTypeToParamMap["FIXED_WING"]->insert(paramlist[i],tool);
+ }
+ else if (parametersname == "ArduCopter") //MAV_TYPE_QUADROTOR "QUADROTOR
+ {
+ systemTypeToParamMap["QUADROTOR"]->insert(paramlist[i],tool);
+ }
+ else if (parametersname == "APMrover2") //MAV_TYPE_GROUND_ROVER GROUND_ROVER
+ {
+ systemTypeToParamMap["GROUND_ROVER"]->insert(paramlist[i],tool);
+ }
+ else
+ {
+ libParamToWidgetMap->insert(paramlist[i],tool);
+ }
}
- }
- toolWidgets.append(tool);
- QGroupBox *box = new QGroupBox(this);
- box->setTitle(tool->objectName());
- box->setLayout(new QVBoxLayout());
- box->layout()->addWidget(tool);
- if (valuetype == "vehicles")
- {
- ui->leftGeneralLayout->addWidget(box);
- }
- else if (valuetype == "libraries")
- {
- ui->rightGeneralLayout->addWidget(box);
+ toolWidgets.append(tool);
+ QGroupBox *box = new QGroupBox(this);
+ box->setTitle(tool->objectName());
+ box->setLayout(new QVBoxLayout());
+ box->layout()->addWidget(tool);
+ if (valuetype == "vehicles")
+ {
+ ui->leftAdvancedLayout->addWidget(box);
+ }
+ else if (valuetype == "libraries")
+ {
+ ui->rightAdvancedLayout->addWidget(box);
+ }
+ box->hide();
+ toolToBoxMap[tool] = box;
}
- box->hide();
- toolToBoxMap[tool] = box;
+
+
}
diff --git a/src/ui/QGCVehicleConfig.ui b/src/ui/QGCVehicleConfig.ui
index 158b6bc..ac75d46 100644
--- a/src/ui/QGCVehicleConfig.ui
+++ b/src/ui/QGCVehicleConfig.ui
@@ -40,7 +40,7 @@
-
- 2
+ 0
@@ -735,7 +735,7 @@
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
p, li { white-space: pre-wrap; }
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
-<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p></body></html>
+<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"><br /></p></body></html>