diff --git a/files/ardupilotmega/arduplane.pdef.xml b/files/ardupilotmega/arduplane.pdef.xml
new file mode 100644
index 0000000000000000000000000000000000000000..382892d2dcfa4bae83c056c6e654c75d8f590619
--- /dev/null
+++ b/files/ardupilotmega/arduplane.pdef.xml
@@ -0,0 +1,2858 @@
+
+
+
+
+
+
+
+1200
+2400
+4800
+9600
+19200
+38400
+57600
+111100
+115200
+
+
+
+
+1200
+2400
+4800
+9600
+19200
+38400
+57600
+111100
+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
+
+
+
+
+Disabled
+Enabled
+
+
+
+centi-Degrees
+
+
+0.1
+meters
+
+
+0.1
+seconds
+
+
+0 2000
+1
+
+
+0 9000
+1
+centi-Degrees
+
+
+
+Disabled
+Enabled
+
+
+
+0 32767
+1
+Meters
+
+
+0 1
+0.1
+Percent
+
+
+
+Default Method
+non-airspeed
+
+
+
+-32767 32767
+1
+Meters
+
+
+1 127
+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
+
+
+
+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
+STABILIZE
+TRAINING
+FBWA
+FBWB
+Auto
+RTL
+Loiter
+Guided
+
+
+
+
+Manual
+CIRCLE
+STABILIZE
+TRAINING
+FBWA
+FBWB
+Auto
+RTL
+Loiter
+Guided
+
+
+
+
+Manual
+CIRCLE
+STABILIZE
+TRAINING
+FBWA
+FBWB
+Auto
+RTL
+Loiter
+Guided
+
+
+
+
+Manual
+CIRCLE
+STABILIZE
+TRAINING
+FBWA
+FBWB
+Auto
+RTL
+Loiter
+Guided
+
+
+
+
+Manual
+CIRCLE
+STABILIZE
+TRAINING
+FBWA
+FBWB
+Auto
+RTL
+Loiter
+Guided
+
+
+
+
+Manual
+CIRCLE
+STABILIZE
+TRAINING
+FBWA
+FBWB
+Auto
+RTL
+Loiter
+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
+
+
+
+
+
+
+
+
+
+
+
+cm/s
+
+
+m/s
+
+
+cm/s
+
+
+centi-Degrees
+
+
+centimeters
+
+
+
+Disabled
+Enabled
+
+
+
+A/V
+
+
+Volts
+
+
+mAh
+
+
+
+Disabled
+A0
+A1
+A13
+
+
+
+
+Disabled
+A1
+A2
+A12
+
+
+
+
+Disabled
+A0
+A1
+A13
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+1200
+2400
+4800
+9600
+19200
+38400
+57600
+111100
+115200
+
+
+
+0 10
+1
+seconds
+
+
+0 4000
+1
+Centimeters
+
+
+
+Disabled
+Enabled
+
+
+
+
+XL-EZ0
+LV-EZ0
+XLL-EZ0
+HRLV
+
+
+
+
+Disabled
+Voltage Only
+Voltage and Current
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+
+
+
+
+
+mAh
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 20
+.1
+
+
+
+Disabled
+Enabled
+
+
+
+-1 1000
+1
+Centimeters
+
+
+0 100
+1
+
+
+
+Disabled
+A0
+A1
+A13
+
+
+
+
+Disabled
+A1
+A2
+A12
+
+
+
+
+Disabled
+A0
+A1
+A2
+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
+CH6_STABILIZE_KI
+CH6_YAW_KP
+CH6_RATE_KP
+CH6_RATE_KI
+CH6_YAW_RATE_KP
+CH6_THROTTLE_KP
+CH6_TOP_BOTTOM_RATIO
+CH6_RELAY
+CH6_TRAVERSE_SPEED
+CH6_NAV_KP
+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
+CH6_YAW_KI
+CH6_ACRO_KP
+CH6_YAW_RATE_KD
+CH6_LOITER_KI
+CH6_LOITER_RATE_KI
+CH6_STABILIZE_KD
+CH6_AHRS_YAW_KP
+CH6_AHRS_KP
+CH6_INAV_TC
+CH6_THROTTLE_KI
+CH6_THR_ACCEL_KP
+CH6_THR_ACCEL_KI
+CH6_THR_ACCEL_KD
+
+
+
+0 32767
+
+
+0 32767
+
+
+0 32767
+
+Plus
+X
+V
+
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+Sonar
+
+
+
+1 45
+1
+Degrees/Second
+
+
+125,400,490
+Hertz (Hz)
+
+
+1 10
+
+
+
+Disabled
+Enabled
+
+
+
+0 300
+1
+
+
+0 300
+1
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enable
+GPS On
+Aux
+Buzzer
+Oscillate
+Nav Blink
+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
+A1
+A13
+
+
+
+
+Disabled
+A0
+A1
+A13
+
+
+
+
+Disabled
+A1
+A2
+A12
+
+
+
+
+
+
+
+
+1200
+2400
+4800
+9600
+19200
+38400
+57600
+111100
+115200
+
+
+
+
+1200
+2400
+4800
+9600
+19200
+38400
+57600
+111100
+115200
+
+
+
+0 10
+1
+seconds
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Voltage Only
+Voltage and Current
+
+
+
+
+
+
+
+
+
+mAh
+
+
+0 2000
+1
+
+
+0 9000
+1
+centi-Degrees
+
+
+0 100
+0.1
+m/s
+
+
+
+Nothing
+LearnWaypoint
+
+
+
+0 100
+1
+Percent
+
+
+0 100
+1
+Percent
+
+
+0 100
+1
+Percent
+
+
+0 100
+1
+Percent
+
+
+
+Nothing
+RTL
+STOP
+
+
+
+seconds
+
+
+
+Disabled
+Enabled
+
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+
+
+Manual
+LEARNING
+Auto
+RTL
+Guided
+
+
+
+
+Manual
+LEARNING
+Auto
+RTL
+Guided
+
+
+
+
+Manual
+LEARNING
+Auto
+RTL
+Guided
+
+
+
+
+Manual
+LEARNING
+Auto
+RTL
+Guided
+
+
+
+
+Manual
+LEARNING
+Auto
+RTL
+Guided
+
+
+
+
+Manual
+LEARNING
+Auto
+RTL
+Guided
+
+
+
+0 1000
+0.1
+meters
+
+
+
+
+
+Servo
+Relay
+Servo and turn off throttle
+Servo when 3m from waypoint
+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
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+
+Reversed
+Normal
+
+
+
+
+
+
+
+
+Disabled
+Manual
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+
+Reversed
+Normal
+
+
+
+
+
+
+
+
+Disabled
+Manual
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+
+Reversed
+Normal
+
+
+
+
+
+
+
+
+Disabled
+Manual
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+
+Reversed
+Normal
+
+
+
+
+
+
+
+
+Disabled
+Manual
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+
+Reversed
+Normal
+
+
+
+
+
+
+
+
+Disabled
+Manual
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+
+Reversed
+Normal
+
+
+
+
+
+
+
+
+Disabled
+Manual
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+
+Reversed
+Normal
+
+
+
+
+
+
+
+-400 400
+1
+
+
+-3.142 3.142
+0.01
+Radians
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+
+
+
+-300 300
+m/s/s
+
+
+rad/s
+
+
+
+Default
+5Hz
+10Hz
+20Hz
+42Hz
+98Hz
+
+Hz
+
+
+
+
+0.0 1.0
+.01
+
+
+
+
+0.1 0.4
+.01
+
+
+0.1 0.4
+.01
+
+
+0 127
+1
+m/s
+
+
+
+Disabled
+Enabled
+
+
+
+Radians
+
+
+
+None
+Yaw45
+Yaw90
+Yaw135
+Yaw180
+Yaw225
+Yaw270
+Yaw315
+Roll180
+Roll180Yaw45
+Roll180Yaw90
+Roll180Yaw135
+Pitch180
+Roll180Yaw225
+Roll180Yaw270
+Roll180Yaw315
+Roll90
+Roll90Yaw45
+Roll90Yaw135
+Roll270
+Roll270Yaw45
+Roll270Yaw90
+Roll270Yaw136
+Pitch90
+Pitch270
+
+
+
+
+
+
+Disable
+Enable
+
+
+
+
+Use
+Don't Use
+
+
+
+0.1
+
+
+0.1
+
+
+
+
+
+retract
+neutral
+MavLink_targeting
+RC_targeting
+GPS_point
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+0 10
+1
+
+
+
+
+
+retract
+neutral
+MavLink_targeting
+RC_targeting
+GPS_point
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+0 10
+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
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+
+Reversed
+Normal
+
+
+
+
+
+
+Disabled
+Manual
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+
+Reversed
+Normal
+
+
+
+
+
+
+Disabled
+Manual
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+
+Reversed
+Normal
+
+
+
+
+
+
+Disabled
+Manual
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+
+Reversed
+Normal
+
+
+
+
+
+
+Disabled
+Manual
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+800 2200
+1
+ms
+
+
+
+Reversed
+Normal
+
+
+
+
+
+
+Disabled
+Manual
+Flap
+Flap_auto
+Aileron
+flaperon
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoiler1
+DifferentialSpoiler2
+AileronWithInput
+Elevator
+ElevatorWithInput
+
+
+
+
+
+
+Servo
+Relay
+Servo and turn off throttle
+Servo when 3m from waypoint
+transistor
+
+
+
+0 50
+
+
+1000 2000
+
+
+1000 2000
+
+
+
+
+-400 400
+1
+
+
+-3.142 3.142
+0.01
+Radians
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+
+0 10
+0.1
+
+
+0 10
+0.1
+
+
+
+
+0 10
+0.1
+
+
+0 10
+0.1
+
+
+
+
+0 10
+0.1
+
+
+0 10
+0.1
+
+
+
+
+0.0 1.0
+.01
+
+
+
+
+0.1 0.4
+.01
+
+
+0.1 0.4
+.01
+
+
+0 127
+1
+m/s
+
+
+
+Disabled
+Enabled
+
+
+
+Radians
+
+
+
+None
+Yaw45
+Yaw90
+Yaw135
+Yaw180
+Yaw225
+Yaw270
+Yaw315
+Roll180
+Roll180Yaw45
+Roll180Yaw90
+Roll180Yaw135
+Pitch180
+Roll180Yaw225
+Roll180Yaw270
+Roll180Yaw315
+Roll90
+Roll90Yaw45
+Roll90Yaw135
+Roll270
+Roll270Yaw45
+Roll270Yaw90
+Roll270Yaw136
+Pitch90
+Pitch270
+
+
+
+
+
+
+retract
+neutral
+MavLink_targeting
+RC_targeting
+GPS_point
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+0 10
+1
+
+
+
+
+
+retract
+neutral
+MavLink_targeting
+RC_targeting
+GPS_point
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+-18000 17999
+1
+Centi-Degrees
+
+
+0 10
+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
+
+
+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
+
+
+0 5
+
+
+1000 2000
+10
+PWM
+
+
+1 3
+
+
+0 6000
+Seconds
+
+
+0 1
+
+
+0 50
+1
+1%
+
+
+50 100
+1
+1%
+
+
+
+
+
+
+
+Disabled
+Enable
+
+
+
+20 80
+
+
+20 80
+
+
+
+
+
+
+-300 300
+m/s/s
+
+
+rad/s
+
+
+
+Default
+5Hz
+10Hz
+20Hz
+42Hz
+98Hz
+
+Hz
+
+
+
+
+0.0 1.0
+.01
+
+
+
+
+0.1 0.4
+.01
+
+
+0.1 0.4
+.01
+
+
+0 127
+1
+m/s
+
+
+
+Disabled
+Enabled
+
+
+
+Radians
+
+
+
+None
+Yaw45
+Yaw90
+Yaw135
+Yaw180
+Yaw225
+Yaw270
+Yaw315
+Roll180
+Roll180Yaw45
+Roll180Yaw90
+Roll180Yaw135
+Pitch180
+Roll180Yaw225
+Roll180Yaw270
+Roll180Yaw315
+Roll90
+Roll90Yaw45
+Roll90Yaw135
+Roll270
+Roll270Yaw45
+Roll270Yaw90
+Roll270Yaw136
+Pitch90
+Pitch270
+
+
+
+
\ No newline at end of file
diff --git a/src/uas/QGCUASParamManager.h b/src/uas/QGCUASParamManager.h
index 069edc8a8c77a68520d654dcca892b4ebc82616d..69dee9eb444e6253cee3f3cc80b718b6ea1c938c 100644
--- a/src/uas/QGCUASParamManager.h
+++ b/src/uas/QGCUASParamManager.h
@@ -43,6 +43,7 @@ public:
virtual double getParamMax(const QString& param) = 0;
virtual double getParamDefault(const QString& param) = 0;
virtual QString getParamInfo(const QString& param) = 0;
+ virtual void setParamInfo(const QMap& param) = 0;
/** @brief Request an update for the parameter list */
void requestParameterListUpdate(int component = 0);
diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h
index c66cad8da26b6550b5995b9e27cf14f6dd90cc9b..4cc84a87bd2b6d98175666cb7309fde41bba09d8 100644
--- a/src/ui/MainWindow.h
+++ b/src/ui/MainWindow.h
@@ -127,7 +127,6 @@ public:
QList listLinkMenuActions(void);
public slots:
-
/** @brief Shows a status message on the bottom status bar */
void showStatusMessage(const QString& status, int timeout);
/** @brief Shows a status message on the bottom status bar */
diff --git a/src/ui/QGCParamWidget.h b/src/ui/QGCParamWidget.h
index 8dc801e5778d77ed768abed00736714ae098fb7f..f62227d015ddc7079443ea4e3c5fe31182c52a2e 100644
--- a/src/ui/QGCParamWidget.h
+++ b/src/ui/QGCParamWidget.h
@@ -58,6 +58,7 @@ public:
double getParamMax(const QString& param) { return paramMax.value(param, 0.0f); }
double getParamDefault(const QString& param) { return paramDefault.value(param, 0.0f); }
QString getParamInfo(const QString& param) { return paramToolTips.value(param, ""); }
+ void setParamInfo(const QMap& param) { paramToolTips = param; }
signals:
/** @brief A parameter was changed in the widget, NOT onboard */
diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc
index b4ee5ca9380922ca0bc3feeb34690732bb1757c4..98b03b46fb054df5409f385a183084a682beb483 100644
--- a/src/ui/QGCVehicleConfig.cc
+++ b/src/ui/QGCVehicleConfig.cc
@@ -9,6 +9,7 @@
#include
#include
+#include
#include "QGCVehicleConfig.h"
#include "UASManager.h"
@@ -149,46 +150,8 @@ void QGCVehicleConfig::stopCalibrationRC()
ui->rcTypeComboBox->setEnabled(true);
ui->rcCalibrationButton->setText(tr("Start RC Calibration"));
}
-
-void QGCVehicleConfig::setActiveUAS(UASInterface* active)
+void QGCVehicleConfig::loadQgcConfig()
{
- // Do nothing if system is the same or NULL
- if ((active == NULL) || mav == active) return;
-
- if (mav)
- {
- // Disconnect old system
- disconnect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
- SLOT(remoteControlChannelRawChanged(int,float)));
- disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
- SLOT(parameterChanged(int,int,QString,QVariant)));
-
- foreach (QGCToolWidget* tool, toolWidgets)
- {
- delete tool;
- }
- toolWidgets.clear();
- }
-
- // Reset current state
- resetCalibrationRC();
-
- chanCount = 0;
-
- // Connect new system
- mav = active;
- connect(active, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
- SLOT(remoteControlChannelRawChanged(int,float)));
- connect(active, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
- SLOT(parameterChanged(int,int,QString,QVariant)));
-
- mav->requestParameters();
-
- QString defaultsDir = qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower() + "/widgets/";
- qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName();
-
- QGCToolWidget* tool;
-
QDir autopilotdir(qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower());
QDir generaldir = QDir(autopilotdir.absolutePath() + "/general/widgets");
QDir vehicledir = QDir(autopilotdir.absolutePath() + "/" + mav->getSystemTypeName().toLower() + "/widgets");
@@ -202,10 +165,8 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active)
//TODO: Throw an error here too, no autopilot specific configuration
qDebug() << "invalid vehicle dir";
}
- qDebug() << autopilotdir.absolutePath();
- qDebug() << generaldir.absolutePath();
- qDebug() << vehicledir.absolutePath();
- int left = true;
+ QGCToolWidget *tool;
+ bool left = true;
foreach (QString file,generaldir.entryList(QDir::Files | QDir::NoDotAndDotDot))
{
if (file.toLower().endsWith(".qgw")) {
@@ -281,12 +242,12 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active)
if (tool->loadSettings(defaultsDir + "px4_mc_attitude_pid_params.qgw", false))
{
toolWidgets.append(tool);
- QGroupBox *box = new QGroupBox(this);
- box->setTitle(tool->objectName());
- box->setLayout(new QVBoxLayout());
- box->layout()->addWidget(tool);
- ui->multiRotorAttitudeLayout->addWidget(box);
- //ui->multiRotorAttitudeLayout->addWidget(tool);
+ QGroupBox *box = new QGroupBox(this);
+ box->setTitle(tool->objectName());
+ box->setLayout(new QVBoxLayout());
+ box->layout()->addWidget(tool);
+ ui->multiRotorAttitudeLayout->addWidget(box);
+ //ui->multiRotorAttitudeLayout->addWidget(tool);
} else {
delete tool;
}
@@ -296,12 +257,12 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active)
if (tool->loadSettings(defaultsDir + "px4_mc_position_pid_params.qgw", false))
{
toolWidgets.append(tool);
- QGroupBox *box = new QGroupBox(this);
- box->setTitle(tool->objectName());
- box->setLayout(new QVBoxLayout());
- box->layout()->addWidget(tool);
- ui->multiRotorAttitudeLayout->addWidget(box);
- //ui->multiRotorPositionLayout->addWidget(tool);
+ QGroupBox *box = new QGroupBox(this);
+ box->setTitle(tool->objectName());
+ box->setLayout(new QVBoxLayout());
+ box->layout()->addWidget(tool);
+ ui->multiRotorAttitudeLayout->addWidget(box);
+ //ui->multiRotorPositionLayout->addWidget(tool);
} else {
delete tool;
}
@@ -311,12 +272,12 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active)
if (tool->loadSettings(defaultsDir + "px4_fw_attitude_pid_params.qgw", false))
{
toolWidgets.append(tool);
- QGroupBox *box = new QGroupBox(this);
- box->setTitle(tool->objectName());
- box->setLayout(new QVBoxLayout());
- box->layout()->addWidget(tool);
- ui->multiRotorAttitudeLayout->addWidget(box);
- //ui->fixedWingAttitudeLayout->addWidget(tool);
+ QGroupBox *box = new QGroupBox(this);
+ box->setTitle(tool->objectName());
+ box->setLayout(new QVBoxLayout());
+ box->layout()->addWidget(tool);
+ ui->multiRotorAttitudeLayout->addWidget(box);
+ //ui->fixedWingAttitudeLayout->addWidget(tool);
} else {
delete tool;
}
@@ -326,19 +287,261 @@ void QGCVehicleConfig::setActiveUAS(UASInterface* active)
if (tool->loadSettings(defaultsDir + "px4_fw_position_pid_params.qgw", false))
{
toolWidgets.append(tool);
- QGroupBox *box = new QGroupBox(this);
- box->setTitle(tool->objectName());
- box->setLayout(new QVBoxLayout());
- box->layout()->addWidget(tool);
- ui->multiRotorAttitudeLayout->addWidget(box);
- //ui->fixedWingPositionLayout->addWidget(tool);
+ QGroupBox *box = new QGroupBox(this);
+ box->setTitle(tool->objectName());
+ box->setLayout(new QVBoxLayout());
+ box->layout()->addWidget(tool);
+ ui->multiRotorAttitudeLayout->addWidget(box);
+ //ui->fixedWingPositionLayout->addWidget(tool);
} else {
delete tool;
}*/
+}
- updateStatus(QString("Reading from system %1").arg(mav->getUASName()));
+void QGCVehicleConfig::loadConfig()
+{
+ QGCToolWidget* tool;
+
+ QDir autopilotdir(qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower());
+ QDir generaldir = QDir(autopilotdir.absolutePath() + "/general/widgets");
+ QDir vehicledir = QDir(autopilotdir.absolutePath() + "/" + mav->getSystemTypeName().toLower() + "/widgets");
+ if (!autopilotdir.exists("general"))
+ {
+ //TODO: Throw some kind of error here. There is no general configuration directory
+ qDebug() << "invalid general dir";
+ }
+ if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower()))
+ {
+ //TODO: Throw an error here too, no autopilot specific configuration
+ qDebug() << "invalid vehicle dir";
+ }
+ qDebug() << autopilotdir.absolutePath();
+ qDebug() << generaldir.absolutePath();
+ qDebug() << vehicledir.absolutePath();
+ QFile xmlfile(autopilotdir.absolutePath() + "/arduplane.pdef.xml");
+ if (!xmlfile.open(QIODevice::ReadOnly))
+ {
+ loadQgcConfig();
+ return;
+ }
+
+ QXmlStreamReader xml(xmlfile.readAll());
+ xmlfile.close();
+ while (!xml.atEnd())
+ {
+ if (xml.isStartElement() && xml.name() == "paramfile")
+ {
+ //Beginning of the file
+ xml.readNext();
+ while ((xml.name() != "paramfile") && !xml.atEnd())
+ {
+ QString valuetype = "";
+ if (xml.isStartElement() && (xml.name() == "vehicles" || xml.name() == "libraries")) //Enter into the vehicles loop
+ {
+ valuetype = xml.name().toString();
+ xml.readNext();
+ while ((xml.name() != valuetype) && !xml.atEnd())
+ {
+ if (xml.isStartElement() && xml.name() == "parameters") //This is a parameter block
+ {
+ QString parametersname = "";
+ if (xml.attributes().hasAttribute("name"))
+ {
+ parametersname = xml.attributes().value("name").toString();
+ }
+ QVariantMap set;
+ set["title"] = parametersname;
+ QString setname = parametersname;
+ xml.readNext();
+ int arraycount = 0;
+ while ((xml.name() != "parameters") && !xml.atEnd())
+ {
+ if (xml.isStartElement() && xml.name() == "param")
+ {
+ //set.setArrayIndex(arraycount++);
+ QString humanname = xml.attributes().value("humanName").toString();
+ QString name = xml.attributes().value("name").toString();
+ if (name.contains(":"))
+ {
+ name = name.split(":")[1];
+ }
+ QString docs = xml.attributes().value("documentation").toString();
+ paramTooltips[name] = name + " - " + docs;
+ // qDebug() << "Found param:" << name << humanname;
+
+ int type = -1; //Type of item
+ QMap fieldmap;
+ xml.readNext();
+ while ((xml.name() != "param") && !xml.atEnd())
+ {
+ 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;
+ int paramcount = 0;
+ xml.readNext();
+ while ((xml.name() != "values") && !xml.atEnd())
+ {
+ if (xml.isStartElement() && xml.name() == "value")
+ {
+
+ 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();
+ paramcount++;
+ //qDebug() << "Code:" << code << "Arg:" << arg;
+ }
+ xml.readNext();
+ }
+ set[setname + "\\" + QString::number(arraycount) + "\\" + "QGC_PARAM_COMBOBOX_COUNT"] = paramcount;
+ }
+ if (xml.isStartElement() && xml.name() == "field")
+ {
+ type = 2; //2 is a slider
+ QString fieldtype = xml.attributes().value("name").toString();
+ QString text = xml.readElementText();
+ fieldmap[fieldtype] = text;
+ // qDebug() << "Field:" << fieldtype << "Text:" << text;
+ }
+ xml.readNext();
+ }
+ if (type == -1)
+ {
+ //Nothing inside! Assume it's a value
+ type = 2;
+ QString fieldtype = "Range";
+ QString text = "0 100";
+ fieldmap[fieldtype] = text;
+ }
+ 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 (fieldmap.contains("Range"))
+ {
+ float min = 0;
+ float max = 0;
+ if (fieldmap["Range"].split(" ").size() > 1)
+ {
+ min = fieldmap["Range"].split(" ")[0].trimmed().toFloat();
+ max = fieldmap["Range"].split(" ")[1].trimmed().toFloat();
+ }
+ else if (fieldmap["Range"].split("-").size() > 1)
+ {
+ 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;
+ }
+ }
+ arraycount++;
+ }
+ xml.readNext();
+ }
+ set["count"] = arraycount;
+
+ tool = new QGCToolWidget("", this);
+ tool->setTitle(parametersname);
+ tool->setObjectName(parametersname);
+ tool->setSettings(set);
+ QList paramlist = tool->getParamList();
+ for (int i=0;isetTitle(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);
+ }
+ box->hide();
+ toolToBoxMap[tool] = box;
+
+
+ }
+ xml.readNext();
+ }
+
+ }
+
+ xml.readNext();
+ }
+ }
+ xml.readNext();
+ }
+ if (mav)
+ {
+ mav->getParamManager()->setParamInfo(paramTooltips);
+ }
+ emit configReady();
}
+void QGCVehicleConfig::setActiveUAS(UASInterface* active)
+{
+ // Do nothing if system is the same or NULL
+ if ((active == NULL) || mav == active) return;
+
+ if (mav)
+ {
+ // Disconnect old system
+ disconnect(mav, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
+ SLOT(remoteControlChannelRawChanged(int,float)));
+ disconnect(mav, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
+ SLOT(parameterChanged(int,int,QString,QVariant)));
+
+ foreach (QGCToolWidget* tool, toolWidgets)
+ {
+ delete tool;
+ }
+ toolWidgets.clear();
+ }
+
+ // Reset current state
+ resetCalibrationRC();
+
+ chanCount = 0;
+
+ // Connect new system
+ mav = active;
+ connect(active, SIGNAL(remoteControlChannelRawChanged(int,float)), this,
+ SLOT(remoteControlChannelRawChanged(int,float)));
+ connect(active, SIGNAL(parameterChanged(int,int,QString,QVariant)), this,
+ SLOT(parameterChanged(int,int,QString,QVariant)));
+
+ if (!paramTooltips.isEmpty())
+ {
+ mav->getParamManager()->setParamInfo(paramTooltips);
+ }
+
+ mav->requestParameters();
+
+ QString defaultsDir = qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower() + "/widgets/";
+ qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName();
+
+
+ //Load configuration after 1ms. This allows it to go into the event loop, and prevents application hangups due to the
+ //amount of time it actually takes to load the configuration windows.
+ QTimer::singleShot(1,this,SLOT(loadConfig()));
+
+ updateStatus(QString("Reading from system %1").arg(mav->getUASName()));
+}
void QGCVehicleConfig::resetCalibrationRC()
{
for (unsigned int i = 0; i < chanMax; ++i)
@@ -559,6 +762,24 @@ void QGCVehicleConfig::parameterChanged(int uas, int component, QString paramete
Q_UNUSED(uas);
Q_UNUSED(component);
+ if (paramToWidgetMap.contains(parameterName))
+ {
+ paramToWidgetMap[parameterName]->setParameterValue(uas,component,parameterName,value);
+ if (toolToBoxMap.contains(paramToWidgetMap[parameterName]))
+ {
+ qDebug() << "Parameter update:" << parameterName;
+ toolToBoxMap[paramToWidgetMap[parameterName]]->show();
+ }
+ else
+ {
+ qDebug() << "ERROR!!!!!!!!!! widget with no box:" << parameterName;
+ }
+ }
+ else
+ {
+ qDebug() << "Param with no widget:" << parameterName;
+ }
+
// Channel calibration values
QRegExp minTpl("RC?_MIN");
minTpl.setPatternSyntax(QRegExp::Wildcard);
diff --git a/src/ui/QGCVehicleConfig.h b/src/ui/QGCVehicleConfig.h
index 9069776ffdc1e9258571f0e9c77f8b8863010e96..6674b153db8404d213f0fb9c8ad594943258cd1c 100644
--- a/src/ui/QGCVehicleConfig.h
+++ b/src/ui/QGCVehicleConfig.h
@@ -4,6 +4,7 @@
#include
#include
#include
+#include
#include "QGCToolWidget.h"
#include "UASInterface.h"
@@ -30,7 +31,8 @@ public:
public slots:
/** Set the MAV currently being calibrated */
void setActiveUAS(UASInterface* active);
-
+ void loadQgcConfig();
+ void loadConfig();
/** Start the RC calibration routine */
void startCalibrationRC();
/** Stop the RC calibration routine */
@@ -169,12 +171,16 @@ protected:
enum RC_MODE rc_mode; ///< Mode of the remote control, according to usual convention
QList toolWidgets; ///< Configurable widgets
bool calibrationEnabled; ///< calibration mode on / off
+ QMap paramToWidgetMap;
+ QMap toolToBoxMap;
+ QMap paramTooltips;
private:
Ui::QGCVehicleConfig *ui;
signals:
void visibilityChanged(bool visible);
+ void configReady();
};
#endif // QGCVEHICLECONFIG_H
diff --git a/src/ui/designer/QGCComboBox.cc b/src/ui/designer/QGCComboBox.cc
index 5f3340497396d90267a03ae2437d8305b4460650..b0a80baab16a195e2d7a3b48cf27b05c3f0c60f8 100644
--- a/src/ui/designer/QGCComboBox.cc
+++ b/src/ui/designer/QGCComboBox.cc
@@ -11,7 +11,7 @@
QGCComboBox::QGCComboBox(QWidget *parent) :
- QGCToolWidgetItem("Slider", parent),
+ QGCToolWidgetItem("Combo", parent),
parameterName(""),
parameterValue(0.0f),
parameterScalingFactor(0.0),
@@ -41,10 +41,8 @@ QGCComboBox::QGCComboBox(QWidget *parent) :
ui->itemNameLabel->hide();
ui->editOptionComboBox->setEnabled(false);
isDisabled = true;
-
- ui->editLine1->setStyleSheet("QWidget { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
- ui->editLine2->setStyleSheet("QWidget { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
-
+ //ui->editLine1->setStyleSheet("QWidget { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
+ // ui->editLine2->setStyleSheet("QWidget { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
connect(ui->editDoneButton, SIGNAL(clicked()), this, SLOT(endEditMode()));
connect(ui->editOptionComboBox,SIGNAL(currentIndexChanged(QString)),this,SLOT(comboBoxIndexChanged(QString)));
connect(ui->editAddItemButton,SIGNAL(clicked()),this,SLOT(addButtonClicked()));
@@ -64,7 +62,9 @@ QGCComboBox::QGCComboBox(QWidget *parent) :
// connect to self
connect(ui->infoLabel, SIGNAL(released()), this, SLOT(showTooltip()));
// Set the current UAS if present
+
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
+
}
QGCComboBox::~QGCComboBox()
@@ -107,7 +107,7 @@ void QGCComboBox::setActiveUAS(UASInterface* activeUas)
connect(activeUas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), this, SLOT(setParameterValue(int,int,int,int,QString,QVariant)), Qt::UniqueConnection);
uas = activeUas;
// Update current param value
- requestParameter();
+ //requestParameter();
// Set param info
QString text = uas->getParamManager()->getParamInfo(parameterName);
ui->infoLabel->setToolTip(text);
@@ -351,7 +351,34 @@ void QGCComboBox::writeSettings(QSettings& settings)
}
settings.sync();
}
+void QGCComboBox::readSettings(const QString& pre,const QVariantMap& settings)
+{
+ parameterName = settings.value(pre + "QGC_PARAM_COMBOBOX_PARAMID").toString();
+ component = settings.value(pre + "QGC_PARAM_COMBOBOX_COMPONENTID").toInt();
+ ui->nameLabel->setText(settings.value(pre + "QGC_PARAM_COMBOBOX_DESCRIPTION").toString());
+ ui->editNameLabel->setText(settings.value(pre + "QGC_PARAM_COMBOBOX_DESCRIPTION").toString());
+ //settings.setValue("QGC_PARAM_SLIDER_BUTTONTEXT", ui->actionButton->text());
+ ui->editSelectParamComboBox->addItem(settings.value(pre + "QGC_PARAM_COMBOBOX_PARAMID").toString());
+ ui->editSelectParamComboBox->setCurrentIndex(ui->editSelectParamComboBox->count()-1);
+ ui->editSelectComponentComboBox->addItem(tr("Component #%1").arg(settings.value(pre + "QGC_PARAM_COMBOBOX_COMPONENTID").toInt()), settings.value(pre + "QGC_PARAM_COMBOBOX_COMPONENTID").toInt());
+ showInfo(settings.value(pre + "QGC_PARAM_COMBOBOX_DISPLAY_INFO", true).toBool());
+ ui->editSelectParamComboBox->setEnabled(true);
+ ui->editSelectComponentComboBox->setEnabled(true);
+
+ int num = settings.value(pre + "QGC_PARAM_COMBOBOX_COUNT").toInt();
+ for (int i=0;ieditOptionComboBox->addItem(settings.value(pre + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(i) + "_TEXT").toString());
+ //qDebug() << "Adding val:" << settings.value(pre + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(i) + "_TEXT").toString() << settings.value(pre + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(i) + "_VAL").toInt();
+ comboBoxTextToValMap[settings.value(pre + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(i) + "_TEXT").toString()] = settings.value(pre + "QGC_PARAM_COMBOBOX_ITEM_" + QString::number(i) + "_VAL").toInt();
+ }
+
+ setActiveUAS(UASManager::instance()->getActiveUAS());
+
+ // Get param value after settings have been loaded
+ // requestParameter();
+}
void QGCComboBox::readSettings(const QSettings& settings)
{
parameterName = settings.value("QGC_PARAM_COMBOBOX_PARAMID").toString();
@@ -394,7 +421,6 @@ void QGCComboBox::delButtonClicked()
}
void QGCComboBox::comboBoxIndexChanged(QString val)
{
- qDebug() << "comboboxchanged:" << comboBoxTextToValMap[val] << val;
switch (parameterValue.type())
{
case QVariant::Char:
diff --git a/src/ui/designer/QGCComboBox.h b/src/ui/designer/QGCComboBox.h
index ff39a32565cc3d5f267534c78cbba1e94d57a56d..96270c7161ba0cf8466395e254069c1231dd3998 100644
--- a/src/ui/designer/QGCComboBox.h
+++ b/src/ui/designer/QGCComboBox.h
@@ -28,6 +28,7 @@ public slots:
/** @brief Update the UI with the new parameter value */
void setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, const QVariant value);
void writeSettings(QSettings& settings);
+ void readSettings(const QString& pre,const QVariantMap& settings);
void readSettings(const QSettings& settings);
void refreshParamList();
void setActiveUAS(UASInterface *uas);
diff --git a/src/ui/designer/QGCComboBox.ui b/src/ui/designer/QGCComboBox.ui
index 40ba771b504dda4d2302c008eae00f9b80449c5e..dc21384bde97aaf965e9a5ba507a59cf20b27ec0 100644
--- a/src/ui/designer/QGCComboBox.ui
+++ b/src/ui/designer/QGCComboBox.ui
@@ -247,11 +247,7 @@
Qt::LeftToRight
-
-
-
-
- :/files/images/status/dialog-information.svg:/files/images/status/dialog-information.svg
+ ?
QToolButton::DelayedPopup
@@ -285,8 +281,6 @@
-
-
-
+
diff --git a/src/ui/designer/QGCCommandButton.cc b/src/ui/designer/QGCCommandButton.cc
index 86ae0fd84f40be683b7a0eecd918d273a97e0a54..fd5ffeea2134177b9b93754b1bafe1146da5db79 100644
--- a/src/ui/designer/QGCCommandButton.cc
+++ b/src/ui/designer/QGCCommandButton.cc
@@ -241,7 +241,58 @@ void QGCCommandButton::writeSettings(QSettings& settings)
settings.setValue("QGC_COMMAND_BUTTON_PARAM7", ui->editParam7SpinBox->value());
settings.sync();
}
+void QGCCommandButton::readSettings(const QString& pre,const QVariantMap& settings)
+{
+ ui->editButtonName->setText(settings.value(pre + "QGC_COMMAND_BUTTON_BUTTONTEXT", "UNKNOWN").toString());
+ ui->editCommandComboBox->setCurrentIndex(settings.value(pre + "QGC_COMMAND_BUTTON_COMMANDID", 0).toInt());
+ ui->commandButton->setText(settings.value(pre + "QGC_COMMAND_BUTTON_BUTTONTEXT", "UNKNOWN").toString());
+
+ int commandId = settings.value(pre + "QGC_COMMAND_BUTTON_COMMANDID", 0).toInt();
+
+ ui->editParam1SpinBox->setValue(settings.value(pre + "QGC_COMMAND_BUTTON_PARAM1", 0.0).toDouble());
+ ui->editParam2SpinBox->setValue(settings.value(pre + "QGC_COMMAND_BUTTON_PARAM2", 0.0).toDouble());
+ ui->editParam3SpinBox->setValue(settings.value(pre + "QGC_COMMAND_BUTTON_PARAM3", 0.0).toDouble());
+ ui->editParam4SpinBox->setValue(settings.value(pre + "QGC_COMMAND_BUTTON_PARAM4", 0.0).toDouble());
+ ui->editParam5SpinBox->setValue(settings.value(pre + "QGC_COMMAND_BUTTON_PARAM5", 0.0).toDouble());
+ ui->editParam6SpinBox->setValue(settings.value(pre + "QGC_COMMAND_BUTTON_PARAM6", 0.0).toDouble());
+ ui->editParam7SpinBox->setValue(settings.value(pre + "QGC_COMMAND_BUTTON_PARAM7", 0.0).toDouble());
+
+ ui->editCommandComboBox->setCurrentIndex(0);
+
+ // Find combobox entry for this data
+ for (int i = 0; i < ui->editCommandComboBox->count(); ++i)
+ {
+ if (commandId == ui->editCommandComboBox->itemData(i).toInt())
+ {
+ ui->editCommandComboBox->setCurrentIndex(i);
+ }
+ }
+
+ ui->editParamsVisibleCheckBox->setChecked(settings.value(pre + "QGC_COMMAND_BUTTON_PARAMS_VISIBLE").toBool());
+ if (ui->editParamsVisibleCheckBox->isChecked())
+ {
+ ui->editParam1SpinBox->show();
+ ui->editParam2SpinBox->show();
+ ui->editParam3SpinBox->show();
+ ui->editParam4SpinBox->show();
+ ui->editParam5SpinBox->show();
+ ui->editParam6SpinBox->show();
+ ui->editParam7SpinBox->show();
+ }
+ else
+ {
+ ui->editParam1SpinBox->hide();
+ ui->editParam2SpinBox->hide();
+ ui->editParam3SpinBox->hide();
+ ui->editParam4SpinBox->hide();
+ ui->editParam5SpinBox->hide();
+ ui->editParam6SpinBox->hide();
+ ui->editParam7SpinBox->hide();
+ }
+ ui->editNameLabel->setText(settings.value(pre + "QGC_COMMAND_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString());
+ ui->nameLabel->setText(settings.value(pre + "QGC_COMMAND_BUTTON_DESCRIPTION", "ERROR LOADING BUTTON").toString());
+}
void QGCCommandButton::readSettings(const QSettings& settings)
{
ui->editButtonName->setText(settings.value("QGC_COMMAND_BUTTON_BUTTONTEXT", "UNKNOWN").toString());
diff --git a/src/ui/designer/QGCCommandButton.h b/src/ui/designer/QGCCommandButton.h
index f7d759ec6c2b445b258fcad4c82f7c640a56babb..7832bef890e0b74ce110bd29445660952e696ca3 100644
--- a/src/ui/designer/QGCCommandButton.h
+++ b/src/ui/designer/QGCCommandButton.h
@@ -25,6 +25,7 @@ public slots:
void endEditMode();
void writeSettings(QSettings& settings);
void readSettings(const QSettings& settings);
+ void readSettings(const QString& pre,const QVariantMap& settings);
private:
Ui::QGCCommandButton *ui;
diff --git a/src/ui/designer/QGCParamSlider.cc b/src/ui/designer/QGCParamSlider.cc
index 6fe1f48dd4375332119270779dedcf2eb2f94ee8..a02834d60679f8e7e2893c2b422572404b87ce8d 100644
--- a/src/ui/designer/QGCParamSlider.cc
+++ b/src/ui/designer/QGCParamSlider.cc
@@ -40,8 +40,8 @@ QGCParamSlider::QGCParamSlider(QWidget *parent) :
ui->editLine1->hide();
ui->editLine2->hide();
- ui->editLine1->setStyleSheet("QWidget { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
- ui->editLine2->setStyleSheet("QWidget { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
+ //ui->editLine1->setStyleSheet("QWidget { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
+ //ui->editLine2->setStyleSheet("QWidget { border: 1px solid #66666B; border-radius: 3px; padding: 10px 0px 0px 0px; background: #111122; }");
connect(ui->editDoneButton, SIGNAL(clicked()), this, SLOT(endEditMode()));
@@ -102,7 +102,7 @@ void QGCParamSlider::setActiveUAS(UASInterface* activeUas)
connect(activeUas, SIGNAL(parameterChanged(int,int,int,int,QString,QVariant)), this, SLOT(setParameterValue(int,int,int,int,QString,QVariant)), Qt::UniqueConnection);
uas = activeUas;
// Update current param value
- requestParameter();
+ //requestParameter();
// Set param info
QString text = uas->getParamManager()->getParamInfo(parameterName);
ui->infoLabel->setToolTip(text);
@@ -428,6 +428,27 @@ void QGCParamSlider::writeSettings(QSettings& settings)
settings.setValue("QGC_PARAM_SLIDER_DISPLAY_INFO", ui->editInfoCheckBox->isChecked());
settings.sync();
}
+void QGCParamSlider::readSettings(const QString& pre,const QVariantMap& settings)
+{
+ parameterName = settings.value(pre + "QGC_PARAM_SLIDER_PARAMID").toString();
+ component = settings.value(pre + "QGC_PARAM_SLIDER_COMPONENTID").toInt();
+ ui->nameLabel->setText(settings.value(pre + "QGC_PARAM_SLIDER_DESCRIPTION").toString());
+ ui->editNameLabel->setText(settings.value(pre + "QGC_PARAM_SLIDER_DESCRIPTION").toString());
+ //settings.setValue("QGC_PARAM_SLIDER_BUTTONTEXT", ui->actionButton->text());
+ ui->editSelectParamComboBox->addItem(settings.value(pre + "QGC_PARAM_SLIDER_PARAMID").toString());
+ ui->editSelectParamComboBox->setCurrentIndex(ui->editSelectParamComboBox->count()-1);
+ ui->editSelectComponentComboBox->addItem(tr("Component #%1").arg(settings.value(pre + "QGC_PARAM_SLIDER_COMPONENTID").toInt()), settings.value(pre + "QGC_PARAM_SLIDER_COMPONENTID").toInt());
+ ui->editMinSpinBox->setValue(settings.value(pre + "QGC_PARAM_SLIDER_MIN").toFloat());
+ ui->editMaxSpinBox->setValue(settings.value(pre + "QGC_PARAM_SLIDER_MAX").toFloat());
+ showInfo(settings.value(pre + "QGC_PARAM_SLIDER_DISPLAY_INFO", true).toBool());
+ ui->editSelectParamComboBox->setEnabled(true);
+ ui->editSelectComponentComboBox->setEnabled(true);
+
+ setActiveUAS(UASManager::instance()->getActiveUAS());
+
+ // Get param value after settings have been loaded
+ //requestParameter();
+}
void QGCParamSlider::readSettings(const QSettings& settings)
{
@@ -448,5 +469,5 @@ void QGCParamSlider::readSettings(const QSettings& settings)
setActiveUAS(UASManager::instance()->getActiveUAS());
// Get param value after settings have been loaded
- requestParameter();
+ //requestParameter();
}
diff --git a/src/ui/designer/QGCParamSlider.h b/src/ui/designer/QGCParamSlider.h
index 38f21e6e16c350da7f29393655c196ba10183013..fe6fae4d2663a151cf7b54e7e38612ffa172f98c 100644
--- a/src/ui/designer/QGCParamSlider.h
+++ b/src/ui/designer/QGCParamSlider.h
@@ -31,6 +31,7 @@ public slots:
void setParameterValue(int uas, int component, int paramCount, int paramIndex, QString parameterName, const QVariant value);
void writeSettings(QSettings& settings);
void readSettings(const QSettings& settings);
+ void readSettings(const QString& pre,const QVariantMap& settings);
void refreshParamList();
void setActiveUAS(UASInterface *uas);
void selectComponent(int componentIndex);
diff --git a/src/ui/designer/QGCParamSlider.ui b/src/ui/designer/QGCParamSlider.ui
index ed911775491303530e740c2204991c7ae55fe636..4066b41552a880112c12a8218582e4f49976d82a 100644
--- a/src/ui/designer/QGCParamSlider.ui
+++ b/src/ui/designer/QGCParamSlider.ui
@@ -282,18 +282,12 @@
-
-
-
-
-
- :/files/images/status/dialog-information.svg:/files/images/status/dialog-information.svg
+ ?
-
-
-
+
diff --git a/src/ui/designer/QGCToolWidget.cc b/src/ui/designer/QGCToolWidget.cc
index 58ee8e8d4cd0d05bd9f009751051420edd324c01..b9f005fd3e3819cf4796d70c94cbdfda3f4ac019 100644
--- a/src/ui/designer/QGCToolWidget.cc
+++ b/src/ui/designer/QGCToolWidget.cc
@@ -65,7 +65,7 @@ QGCToolWidget::QGCToolWidget(const QString& title, QWidget *parent, QSettings* s
// Enforce storage if this not loaded from settings
// is MUST NOT BE SAVED if it was loaded from settings!
- if (!settings) storeWidgetsToSettings();
+ //if (!settings) storeWidgetsToSettings();
}
QGCToolWidget::~QGCToolWidget()
@@ -169,6 +169,130 @@ bool QGCToolWidget::loadSettings(const QString& settings, bool singleinstance)
return false;
}
}
+void QGCToolWidget::setSettings(QVariantMap& settings)
+{
+ settingsMap = settings;
+ QString widgetName = getTitle();
+ int size = settingsMap["count"].toInt();
+ for (int j = 0; j < size; j++)
+ {
+ QString type = settings.value(widgetName + "\\" + QString::number(j) + "\\" + "TYPE", "UNKNOWN").toString();
+ if (type == "SLIDER")
+ {
+ QString checkparam = settingsMap.value(widgetName + "\\" + QString::number(j) + "\\" + "QGC_PARAM_SLIDER_PARAMID").toString();
+ paramList.append(checkparam);
+ }
+ else if (type == "COMBO")
+ {
+ QString checkparam = settingsMap.value(widgetName + "\\" + QString::number(j) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID").toString();
+ paramList.append(checkparam);
+ }
+ }
+}
+QList QGCToolWidget::getParamList()
+{
+ return paramList;
+}
+void QGCToolWidget::setParameterValue(int uas, int component, QString parameterName, const QVariant value)
+{
+//settings.setValue("QGC_PARAM_SLIDER_PARAMID", parameterName);
+//settings.setValue("QGC_PARAM_COMBOBOX_PARAMID", parameterName);
+ QString widgetName = getTitle();
+ //settings.beginGroup(widgetName);
+ //qDebug() << "LOADING FOR" << widgetName;
+ //int size = settings.beginReadArray("QGC_TOOL_WIDGET_ITEMS");
+ int size = settingsMap["count"].toInt();
+ //qDebug() << "CHILDREN SIZE:" << size;
+
+ for (int j = 0; j < size; j++)
+ {
+ QString type = settingsMap.value(widgetName + "\\" + QString::number(j) + "\\" + "TYPE", "UNKNOWN").toString();
+ QGCToolWidgetItem* item = NULL;
+ if (type == "COMMANDBUTTON")
+ {
+ return;
+ //item = new QGCCommandButton(this);
+ //qDebug() << "CREATED COMMANDBUTTON";
+ }
+ else if (type == "SLIDER")
+ {
+ QString checkparam = settingsMap.value(widgetName + "\\" + QString::number(j) + "\\" + "QGC_PARAM_SLIDER_PARAMID").toString();
+ if (checkparam == parameterName)
+ {
+ item = new QGCParamSlider(this);
+ addToolWidget(item);
+ item->readSettings(widgetName + "\\" + QString::number(j) + "\\",settingsMap);
+
+ return;
+ }
+
+ //qDebug() << "CREATED PARAM SLIDER";
+ }
+ else if (type == "COMBO")
+ {
+ QString checkparam = settingsMap.value(widgetName + "\\" + QString::number(j) + "\\" + "QGC_PARAM_COMBOBOX_PARAMID").toString();
+ if (checkparam == parameterName)
+ {
+ item = new QGCComboBox(this);
+ addToolWidget(item);
+ item->readSettings(widgetName + "\\" + QString::number(j) + "\\",settingsMap);
+ return;
+ }
+
+ //qDebug() << "CREATED PARAM COMBOBOX";
+ }
+ }
+}
+
+void QGCToolWidget::loadSettings(QVariantMap& settings)
+{
+
+ QString widgetName = getTitle();
+ //settings.beginGroup(widgetName);
+ qDebug() << "LOADING FOR" << widgetName;
+ //int size = settings.beginReadArray("QGC_TOOL_WIDGET_ITEMS");
+ int size = settings["count"].toInt();
+ qDebug() << "CHILDREN SIZE:" << size;
+ for (int j = 0; j < size; j++)
+ {
+ QApplication::processEvents();
+ //settings.setArrayIndex(j);
+ QString type = settings.value(widgetName + "\\" + QString::number(j) + "\\" + "TYPE", "UNKNOWN").toString();
+ if (type != "UNKNOWN")
+ {
+ QGCToolWidgetItem* item = NULL;
+ if (type == "COMMANDBUTTON")
+ {
+ item = new QGCCommandButton(this);
+ //qDebug() << "CREATED COMMANDBUTTON";
+ }
+ else if (type == "SLIDER")
+ {
+ item = new QGCParamSlider(this);
+ //qDebug() << "CREATED PARAM SLIDER";
+ }
+ else if (type == "COMBO")
+ {
+ item = new QGCComboBox(this);
+ //qDebug() << "CREATED PARAM COMBOBOX";
+ }
+ if (item)
+ {
+ // Configure and add to layout
+ addToolWidget(item);
+ item->readSettings(widgetName + "\\" + QString::number(j) + "\\",settings);
+
+ //qDebug() << "Created tool widget";
+ }
+ }
+ else
+ {
+ qDebug() << "UNKNOWN TOOL WIDGET TYPE" << type;
+ }
+ }
+ //settings.endArray();
+ //settings.endGroup();
+}
void QGCToolWidget::loadSettings(QSettings& settings)
{
@@ -480,7 +604,7 @@ void QGCToolWidget::setTitle(QString title)
QDockWidget* parent = dynamic_cast(this->parentWidget());
if (parent) parent->setWindowTitle(title);
// Store all widgets
- storeWidgetsToSettings();
+ //storeWidgetsToSettings();
emit titleChanged(title);
if (mainMenuAction) mainMenuAction->setText(title);
diff --git a/src/ui/designer/QGCToolWidget.h b/src/ui/designer/QGCToolWidget.h
index 1a897ac1f4578c4e4234e81a785a9049ef8d22c2..ef8fb922ffa10b892e4721f6c63cc274fe7bab80 100644
--- a/src/ui/designer/QGCToolWidget.h
+++ b/src/ui/designer/QGCToolWidget.h
@@ -45,6 +45,7 @@ public slots:
void importWidget();
/** @brief Store all widgets of this type to QSettings */
static void storeWidgetsToSettings(QString settingsFile=QString());
+ void loadSettings(QVariantMap& settings);
/** @brief Load this widget from a QSettings object */
void loadSettings(QSettings& settings);
/** @brief Load this widget from a settings file */
@@ -57,11 +58,15 @@ public slots:
void storeSettings();
/** @brief Store the view id and dock widget area */
void setViewVisibilityAndDockWidgetArea(int view, bool visible, Qt::DockWidgetArea area);
-
+ void setSettings(QVariantMap& settings);
+ QList getParamList();
+ void setParameterValue(int uas, int component, QString parameterName, const QVariant value);
signals:
void titleChanged(QString);
protected:
+ QList paramList;
+ QVariantMap settingsMap;
QAction* addParamAction;
QAction* addCommandAction;
QAction* setTitleAction;
@@ -83,12 +88,13 @@ protected:
void addToolWidget(QGCToolWidgetItem* widget);
void hideEvent(QHideEvent* event);
-
+public slots:
+ void setTitle(QString title);
protected slots:
void addParam();
void addCommand();
void setTitle();
- void setTitle(QString title);
+
void setWindowTitle(const QString& title);
diff --git a/src/ui/designer/QGCToolWidgetItem.h b/src/ui/designer/QGCToolWidgetItem.h
index 4fdbbe254cb551a048f7ab9d8ff91413dede3611..e0a0cb0a3337e6e934ada388e3889c1f2880c436 100644
--- a/src/ui/designer/QGCToolWidgetItem.h
+++ b/src/ui/designer/QGCToolWidgetItem.h
@@ -26,6 +26,7 @@ public slots:
}
virtual void writeSettings(QSettings& settings) = 0;
virtual void readSettings(const QSettings& settings) = 0;
+ virtual void readSettings(const QString& pre,const QVariantMap& settings) = 0;
virtual void setActiveUAS(UASInterface *uas);
signals: