diff --git a/CREDITS.txt b/CREDITS.txt
index b6b4ab91b..dbfb057e2 100644
--- a/CREDITS.txt
+++ b/CREDITS.txt
@@ -81,14 +81,22 @@ E: joe (dot) hlebasko(plus) openpilot (at) gmail (dot) com
D: Production Main Board & Production OP GPS
M: Hardware Architecture Team
+N: Mark James
+E: mjames (plus) openpilot (at) gmail (dot) com
+D: Some of Silk Icon set used in GCS - http://www.famfamfam.com/lab/icons/silk
+
N: Sami Korhonen
E: samik (dot) korhonen (plus) openpilot (at) gmail (dot) com
-D: GPS Module, Spektrum RC Module
+D: GPS Module, Spektrum RC Module, OSD work
N: Thorsten Klose
-E: thorsten.klose (at) dmx (dot) de
+E: thorsten (dot) klose (at) dmx (dot) de
D: Embedded STM32 infrastructure
+N: Hallvard Kristiansen
+E: hal (at) fleshmx (dot) com
+D: GCS Artwork, Quad layout diagrams
+
N: Edouard Lafargue
E: edouard (at) lafargue (dot) name
D: GCS Dial Plugins, GCS PFD Plugin, GCS GPS plugin, GCS Config plugin
@@ -138,7 +146,7 @@ D: The GLC_lib as used in the ModelView Plugin
D: See: http://www.glc-lib.net/
N: Julien Rouviere
-E: julien.rouviere (plus) openpilot (at) gmail (dot) com
+E: julien (dot) rouviere (plus) openpilot (at) gmail (dot) com
D: GCS Core Developer
D: GCS Framework and Plugins for the GCS
@@ -191,6 +199,6 @@ D: Module architecture and UAVTalk/UAVObjects implementation.
M: Architecture co-lead
N: Alex Vrubel
-E: alex.vrubel (plus) openpilot (at) gmail (dot) com
+E: alex (dot) vrubel (plus) openpilot (at) gmail (dot) com
D: Russian translation of the GCS
diff --git a/Makefile b/Makefile
index 5d712252a..0cc2eeb72 100644
--- a/Makefile
+++ b/Makefile
@@ -232,6 +232,18 @@ openpilotgcs: uavobjects_gcs
$(MAKE) -w ; \
)
+.PHONY: gcs_installer
+gcs_installer: openpilotgcs
+ifeq ($(QT_SPEC), win32-g++)
+ifeq ($(GCS_BUILD_CONF), release)
+ $(V1) cd $(BUILD_DIR)/ground/openpilotgcs/packaging/winx86 && $(MAKE) -r --no-print-directory $@
+else
+ $(error $@ can be generated for release build only (GCS_BUILD_CONF=release))
+endif
+else
+ $(error $@ is currently only available on Windows)
+endif
+
.PHONY: uavobjgenerator
uavobjgenerator:
$(V1) mkdir -p $(BUILD_DIR)/ground/$@
@@ -286,7 +298,7 @@ openpilot: openpilot_bin
openpilot_%: uavobjects_flight
$(V1) mkdir -p $(BUILD_DIR)/openpilot/dep
- $(V1) $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/openpilot" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" -C $(ROOT_DIR)/flight/OpenPilot $*
+ $(V1) cd $(ROOT_DIR)/flight/OpenPilot && $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/openpilot" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" $*
.PHONY: openpilot_clean
openpilot_clean:
@@ -298,7 +310,7 @@ bl_openpilot: bl_openpilot_elf
bl_openpilot_%:
$(V1) mkdir -p $(BUILD_DIR)/bl_openpilot/dep
- $(V1) $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/bl_openpilot" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" -C $(ROOT_DIR)/flight/Bootloaders/OpenPilot $*
+ $(V1) cd $(ROOT_DIR)/flight/Bootloaders/OpenPilot && $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/bl_openpilot" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" $*
.PHONY: bl_openpilot_clean
bl_openpilot_clean:
@@ -310,7 +322,7 @@ ahrs: ahrs_bin
ahrs_%: uavobjects_flight
$(V1) mkdir -p $(BUILD_DIR)/ahrs/dep
- $(V1) $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/ahrs" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" -C $(ROOT_DIR)/flight/AHRS $*
+ $(V1) cd $(ROOT_DIR)/flight/AHRS && $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/ahrs" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" $*
.PHONY: ahrs_clean
ahrs_clean:
@@ -322,7 +334,7 @@ bl_ahrs: bl_ahrs_elf
bl_ahrs_%:
$(V1) mkdir -p $(BUILD_DIR)/bl_ahrs/dep
- $(V1) $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/bl_ahrs" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" -C $(ROOT_DIR)/flight/Bootloaders/AHRS $*
+ $(V1) cd $(ROOT_DIR)/flight/Bootloaders/AHRS && $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/bl_ahrs" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" $*
.PHONY: bl_ahrs_clean
bl_ahrs_clean:
@@ -334,7 +346,7 @@ coptercontrol: coptercontrol_bin
coptercontrol_%: uavobjects_flight
$(V1) mkdir -p $(BUILD_DIR)/coptercontrol/dep
- $(V1) $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/coptercontrol" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" -C $(ROOT_DIR)/flight/CopterControl $*
+ $(V1) cd $(ROOT_DIR)/flight/CopterControl && $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/coptercontrol" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" $*
.PHONY: coptercontrol_clean
coptercontrol_clean:
@@ -346,7 +358,7 @@ bl_coptercontrol: bl_coptercontrol_elf
bl_coptercontrol_%:
$(V1) mkdir -p $(BUILD_DIR)/bl_coptercontrol/dep
- $(V1) $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/bl_coptercontrol" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" -C $(ROOT_DIR)/flight/Bootloaders/CopterControl $*
+ $(V1) cd $(ROOT_DIR)/flight/Bootloaders/CopterControl && $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/bl_coptercontrol" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" $*
.PHONY: bl_coptercontrol_clean
bl_coptercontrol_clean:
@@ -358,7 +370,7 @@ pipxtreme: pipxtreme_bin
pipxtreme_%: uavobjects_flight
$(V1) mkdir -p $(BUILD_DIR)/pipxtreme/dep
- $(V1) $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/pipxtreme" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" -C $(ROOT_DIR)/flight/PipXtreme $*
+ $(V1) cd $(ROOT_DIR)/flight/PipXtreme && $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/pipxtreme" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" $*
.PHONY: pipxtreme_clean
pipxtreme_clean:
@@ -370,7 +382,7 @@ bl_pipxtreme: bl_pipxtreme_elf
bl_pipxtreme_%:
$(V1) mkdir -p $(BUILD_DIR)/bl_pipxtreme/dep
- $(V1) $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/bl_pipxtreme" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" -C $(ROOT_DIR)/flight/Bootloaders/PipXtreme $*
+ $(V1) cd $(ROOT_DIR)/flight/Bootloaders/PipXtreme && $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/bl_pipxtreme" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" $*
.PHONY: bl_pipxtreme_clean
bl_pipxtreme_clean:
@@ -382,7 +394,7 @@ ins: ins_bin
ins_%: uavobjects_flight
$(V1) mkdir -p $(BUILD_DIR)/ins/dep
- $(V1) $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/ins" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" -C $(ROOT_DIR)/flight/INS $*
+ $(V1) cd $(ROOT_DIR)/flight/INS && $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/ins" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" $*
.PHONY: ins_clean
ins_clean:
@@ -394,7 +406,7 @@ bl_ins: bl_ins_elf
bl_ins_%:
$(V1) mkdir -p $(BUILD_DIR)/bl_ins/dep
- $(V1) $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/bl_ins" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" -C $(ROOT_DIR)/flight/Bootloaders/INS $*
+ $(V1) cd $(ROOT_DIR)/flight/Bootloaders/INS && $(MAKE) -r --no-print-directory OUTDIR="$(BUILD_DIR)/bl_ins" TCHAIN_PREFIX="$(ARM_SDK_PREFIX)" REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" $*
.PHONY: bl_ins_clean
bl_ins_clean:
diff --git a/Makefile.cmd b/Makefile.cmd
deleted file mode 100644
index e24fca324..000000000
--- a/Makefile.cmd
+++ /dev/null
@@ -1,135 +0,0 @@
-@echo off
-rem
-rem Windows-friendly batch file for all flight targets
-rem
-
-rem -------------------------------------------------------------------
-rem Help
-rem -------------------------------------------------------------------
-if '%1' == 'build' goto Proceed
-if '%1' == 'clean' goto Proceed
-for %%F in (%0) do echo SYNTAX: %%~nF%%~xF [build / clean / help]
-echo - build: builds all flight targets including uavobjects, bootloaders and firmware
-echo - clean: cleans all flight targets including bootloaders and firmware
-echo - help: this help
-echo:
-echo Environment variables:
-echo - TARGETS_BL - list of target (default is all flight bootloader targets)
-echo - TARGETS_FW - list of target (default is all flight targets)
-echo - UAVOBJGENERATOR - path and filename override for UAVObjGenerator.exe
-echo:
-echo Example usage (from a batch file with .cmd extension):
-echo set PATH=D:\Work\OpenPilot\Apps\CodeSourcery\bin\;%%PATH%%
-echo set TARGETS_FW=ahrs openpilot
-echo set TARGETS_BL=%%TARGETS_FW%%
-echo call svn\trunk\Makefile.cmd build
-echo:
-goto Abort
-
-
-:Proceed
-rem -------------------------------------------------------------------
-rem Settings and definitions
-rem -------------------------------------------------------------------
-
-rem Set desired targets and paths
-if "%TARGETS_BL%" == "" set TARGETS_BL=ahrs openpilot pipxtreme coptercontrol
-if "%TARGETS_FW%" == "" set TARGETS_FW=%TARGETS_BL%
-if "%TARGET_BL_SUBDIR%" == "" set TARGET_BL_SUBDIR=bootloaders
-if "%TARGET_FW_SUBDIR%" == "" set TARGET_FW_SUBDIR=.
-
-rem Set toolset paths (if you don't have them added permanently)
-rem set PATH=D:\Work\OpenPilot\Apps\CodeSourcery\bin\;%PATH%
-
-set MAKE=cs-make
-
-rem Set some project path variables
-for %%D in (%0) do set CURDIR=%%~dpD
-
-set ROOT_DIR=%CURDIR%
-set BUILD_DIR=%ROOT_DIR%\build
-set UAVOBJ_XML_DIR=%ROOT_DIR%\shared\uavobjectdefinition
-set UAVOBJ_OUT_DIR=%BUILD_DIR%\uavobject-synthetics
-
-rem -------------------------------------------------------------------
-rem Proceed with target
-rem -------------------------------------------------------------------
-
-set TARGET=%1
-if '%TARGET%' == 'clean' goto UAVObjectsDone
-
-rem -------------------------------------------------------------------
-rem Searching for UAVObjGenerator executable
-rem -------------------------------------------------------------------
-
-set UAVOBJGENERATOR_FILENAME=uavobjgenerator.exe
-
-rem If environment variable is set then expand it to full path and use
-for %%G in (%UAVOBJGENERATOR%) do set UAVOBJGENERATOR=%%~fG
-if exist "%UAVOBJGENERATOR%" goto UAVObjGeneratorFound
-
-rem Searching in builds
-for %%G in (debug release) do (
- if exist %BUILD_DIR%\ground\uavobjgenerator\%%G\%UAVOBJGENERATOR_FILENAME% (
- set UAVOBJGENERATOR="%BUILD_DIR%\ground\uavobjgenerator\%%G\%UAVOBJGENERATOR_FILENAME%"
- goto UAVObjGeneratorFound
- )
-)
-
-rem Searching in PATH
-for %%G in (%UAVOBJGENERATOR_FILENAME%) do set UAVOBJGENERATOR=%%~$PATH:G
-if exist %UAVOBJGENERATOR% goto UAVObjGeneratorFound
-
-rem Report error
-for %%G in (%ROOT_DIR%/ground/ground.pro) do set GROUND_PRO=%%~fG
-echo UAVObjGenerator was not found, please build it first using %GROUND_PRO%
-goto Abort
-
-:UAVObjGeneratorFound
-echo UAVObjGenerator found: %UAVOBJGENERATOR%
-
-rem -------------------------------------------------------------------
-rem UAVObjects for flight build
-rem -------------------------------------------------------------------
-
-mkdir %UAVOBJ_OUT_DIR% >NUL 2>&1
-pushd %UAVOBJ_OUT_DIR%
-%UAVOBJGENERATOR% -flight %UAVOBJ_XML_DIR% %ROOT_DIR%
-if errorlevel 1 goto Abort2
-popd
-
-:UAVObjectsDone
-rem -------------------------------------------------------------------
-rem Bootloaders build
-rem -------------------------------------------------------------------
-
-for %%G in (%TARGETS_BL%) do (
- %MAKE% CODE_SOURCERY=YES USE_BOOTLOADER=NO OUTDIR="%BUILD_DIR%\%TARGET_BL_SUBDIR%\%%G" -C "%ROOT_DIR%\flight\Bootloaders\%%G" %TARGET%
- if errorlevel 1 goto Abort1
-)
-
-rem -------------------------------------------------------------------
-rem Firmware build
-rem -------------------------------------------------------------------
-
-for %%G in (%TARGETS_FW%) do (
- %MAKE% CODE_SOURCERY=YES USE_BOOTLOADER=YES OUTDIR="%BUILD_DIR%\%TARGET_FW_SUBDIR%\%%G" -C "%ROOT_DIR%\flight\%%G" %TARGET%
- if errorlevel 1 goto Abort1
-)
-goto Done
-
-
-rem -------------------------------------------------------------------
-rem Error handling
-rem -------------------------------------------------------------------
-
-:Abort2
-popd
-
-:Abort1
-echo Error returned, build aborted
-
-:Abort
-pause
-
-:Done
diff --git a/artwork/3D Model/backgrounds/default_background.png b/artwork/3D Model/backgrounds/default_background.png
index 67094ecce..13a8a38bd 100644
Binary files a/artwork/3D Model/backgrounds/default_background.png and b/artwork/3D Model/backgrounds/default_background.png differ
diff --git a/artwork/3D Model/backgrounds/default_background.psd b/artwork/3D Model/backgrounds/default_background.psd
new file mode 100644
index 000000000..4f4dc4adf
Binary files /dev/null and b/artwork/3D Model/backgrounds/default_background.psd differ
diff --git a/artwork/Misc/multirotor-shapes-simple.svg b/artwork/Misc/multirotor-shapes-simple.svg
new file mode 100644
index 000000000..2cf5d5eda
--- /dev/null
+++ b/artwork/Misc/multirotor-shapes-simple.svg
@@ -0,0 +1,3140 @@
+
+
+
+
diff --git a/artwork/Misc/multirotor-shapes.svg b/artwork/Misc/multirotor-shapes.svg
new file mode 100644
index 000000000..2ff48cfdc
--- /dev/null
+++ b/artwork/Misc/multirotor-shapes.svg
@@ -0,0 +1,6746 @@
+
+
+
+
\ No newline at end of file
diff --git a/flight/Bootloaders/AHRS/Makefile b/flight/Bootloaders/AHRS/Makefile
index f7d101443..258c00693 100644
--- a/flight/Bootloaders/AHRS/Makefile
+++ b/flight/Bootloaders/AHRS/Makefile
@@ -29,7 +29,7 @@ include $(TOP)/make/firmware-defs.mk
# Set developer code and compile options
# Set to YES for debugging
DEBUG ?= NO
-OVERRIDE USE_BOOTLOADER = NO
+override USE_BOOTLOADER = NO
# Set to YES when using Code Sourcery toolchain
CODE_SOURCERY ?= YES
diff --git a/flight/Bootloaders/CopterControl/Makefile b/flight/Bootloaders/CopterControl/Makefile
index 3c71770de..52a894a5b 100644
--- a/flight/Bootloaders/CopterControl/Makefile
+++ b/flight/Bootloaders/CopterControl/Makefile
@@ -37,7 +37,7 @@ ENABLE_DEBUG_PINS ?= NO
ENABLE_AUX_UART ?= NO
#
-OVERRIDE USE_BOOTLOADER = NO
+override USE_BOOTLOADER = NO
# Set to YES when using Code Sourcery toolchain
diff --git a/flight/Bootloaders/OpenPilot/Makefile b/flight/Bootloaders/OpenPilot/Makefile
index 7633c6f96..0aa43662c 100644
--- a/flight/Bootloaders/OpenPilot/Makefile
+++ b/flight/Bootloaders/OpenPilot/Makefile
@@ -37,7 +37,7 @@ ENABLE_DEBUG_PINS ?= NO
ENABLE_AUX_UART ?= NO
#
-OVERRIDE USE_BOOTLOADER = NO
+override USE_BOOTLOADER = NO
# Set to YES when using Code Sourcery toolchain
diff --git a/flight/Bootloaders/PipXtreme/Makefile b/flight/Bootloaders/PipXtreme/Makefile
index e31930426..eb8742608 100644
--- a/flight/Bootloaders/PipXtreme/Makefile
+++ b/flight/Bootloaders/PipXtreme/Makefile
@@ -37,7 +37,7 @@ ENABLE_DEBUG_PINS ?= NO
ENABLE_AUX_UART ?= NO
#
-OVERRIDE USE_BOOTLOADER = NO
+override USE_BOOTLOADER = NO
# Set to YES when using Code Sourcery toolchain
diff --git a/flight/Modules/Actuator/actuator.c b/flight/Modules/Actuator/actuator.c
index 97d0ccdb3..69a29062f 100644
--- a/flight/Modules/Actuator/actuator.c
+++ b/flight/Modules/Actuator/actuator.c
@@ -191,34 +191,40 @@ static void actuatorTask(void* parameters)
AlarmsClear(SYSTEMALARMS_ALARM_ACTUATOR);
bool armed = manualControl.Armed == MANUALCONTROLCOMMAND_ARMED_TRUE;
- armed &= desired.Throttle > 0.00; //zero throttle stops the motors
-
+ bool positiveThrottle = desired.Throttle >= 0.00;
+ bool spinWhileArmed = settings.MotorsSpinWhileArmed == ACTUATORSETTINGS_MOTORSSPINWHILEARMED_TRUE &&
+ manualControl.Armed == MANUALCONTROLCOMMAND_ARMED_TRUE;
+
float curve1 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve1);
float curve2 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve2);
for(int ct=0; ct < MAX_MIX_ACTUATORS; ct++)
{
- if(mixers[ct].type != MIXERSETTINGS_MIXER1TYPE_DISABLED)
- {
- status[ct] = ProcessMixer(ct, curve1, curve2, &mixerSettings, &desired, dT);
+ if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_DISABLED)
+ continue;
+
+ status[ct] = ProcessMixer(ct, curve1, curve2, &mixerSettings, &desired, dT);
+
+ // Motors have additional protection for when to be on
+ if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) {
- if(!armed &&
- mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_MOTOR)
+ // If not armed or motors aren't meant to spin all the time
+ if( !armed ||
+ (!spinWhileArmed && !positiveThrottle))
{
- command.Channel[ct] = settings.ChannelMin[ct]; //force zero throttle
filterAccumulator[ct] = 0;
- lastResult[ct] = 0;
- }else
- {
- // For motors when armed keep above neutral
- if((mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) && (status[ct] < 0))
- status[ct] = 0;
-
- command.Channel[ct] = scaleChannel(status[ct],
- settings.ChannelMax[ct],
- settings.ChannelMin[ct],
- settings.ChannelNeutral[ct]);
- }
+ lastResult[ct] = 0;
+ status[ct] = -1; //force min throttle
+ }
+ // If armed meant to keep spinning,
+ else if ((spinWhileArmed && !positiveThrottle) ||
+ (status[ct] < 0) )
+ status[ct] = 0;
}
+
+ command.Channel[ct] = scaleChannel(status[ct],
+ settings.ChannelMax[ct],
+ settings.ChannelMin[ct],
+ settings.ChannelNeutral[ct]);
}
MixerStatusSet(&mixerStatus);
@@ -442,7 +448,7 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) {
ActuatorSettingsData settings;
ActuatorSettingsGet(&settings);
-
+
switch(settings.ChannelType[mixer_channel]) {
case ACTUATORSETTINGS_CHANNELTYPE_PWMALARMBUZZER: {
// This is for buzzers that take a PWM input
@@ -495,19 +501,7 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) {
return true;
#if defined(PIOS_INCLUDE_I2C_ESC)
case ACTUATORSETTINGS_CHANNELTYPE_MK:
- {
- ManualControlCommandData manual;
- ManualControlCommandGet(&manual);
- /* Unfortunately MK controller take forever to start so keep */
- /* them spinning when armed */
- if(manual.Armed)
- value = (value < 0) ? 1 : value;
- else
- value = 0;
-
return PIOS_SetMKSpeed(settings.ChannelAddr[mixer_channel],value);
- break;
- }
case ACTUATORSETTINGS_CHANNELTYPE_ASTEC4:
return PIOS_SetAstec4Speed(settings.ChannelAddr[mixer_channel],value);
break;
diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c
index fd343e1d4..75d096de8 100644
--- a/flight/Modules/ManualControl/manualcontrol.c
+++ b/flight/Modules/ManualControl/manualcontrol.c
@@ -366,9 +366,9 @@ static void manualControlTask(void *parameters)
if (connection_state == CONNECTED) {
// Should use RC input only if RX is connected
- if (armingInputLevel <= -0.90)
+ if (armingInputLevel <= -0.50)
manualArm = true;
- else if (armingInputLevel >= +0.90)
+ else if (armingInputLevel >= +0.50)
manualDisarm = true;
}
diff --git a/ground/openpilotgcs/share/openpilotgcs/models/backgrounds/default_background.png b/ground/openpilotgcs/share/openpilotgcs/models/backgrounds/default_background.png
index 67094ecce..13a8a38bd 100644
Binary files a/ground/openpilotgcs/share/openpilotgcs/models/backgrounds/default_background.png and b/ground/openpilotgcs/share/openpilotgcs/models/backgrounds/default_background.png differ
diff --git a/ground/openpilotgcs/src/experimental/PowerLog6S/main.cpp b/ground/openpilotgcs/src/experimental/PowerLog6S/main.cpp
index 8a28f137a..a95611270 100644
--- a/ground/openpilotgcs/src/experimental/PowerLog6S/main.cpp
+++ b/ground/openpilotgcs/src/experimental/PowerLog6S/main.cpp
@@ -1,3 +1,27 @@
+/**
+ ******************************************************************************
+ *
+ * @file main.cpp
+ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
+ * @see The GNU Public License (GPL) Version 3
+ * @brief Junsi Powerlog utility CLI
+ *
+ *****************************************************************************/
+/*
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
+ * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
+ * for more details.
+ *
+ * You should have received a copy of the GNU General Public License along
+ * with this program; if not, write to the Free Software Foundation, Inc.,
+ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
+ */
#include
#include
#include
diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui
index e6a970165..09ed33ce7 100644
--- a/ground/openpilotgcs/src/plugins/config/airframe.ui
+++ b/ground/openpilotgcs/src/plugins/config/airframe.ui
@@ -73,7 +73,7 @@
-
- 1
+ 0
@@ -620,7 +620,7 @@ Typical values are 100% for + configuration and 50% for X configuration on quads
Typical value is 50% for + or X configuration on quads.
- 0
+ -100
100
@@ -666,6 +666,15 @@ Typical value is 50% for + or X configuration on quads.
110
+
+ background:transparent
+
+
+ QFrame::NoFrame
+
+
+ QFrame::Plain
+
@@ -679,6 +688,19 @@ Typical value is 50% for + or X configuration on quads.
-
+
-
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
-
@@ -733,7 +755,9 @@ Typical value is 50% for + or X configuration on quads.
120
-
+
+ background:transparent
+
-
@@ -2289,12 +2313,12 @@ p, li { white-space: pre-wrap; }
setNum(int)
- 236
- 253
+ 124
+ 126
- 226
- 310
+ 124
+ 126
@@ -2305,12 +2329,12 @@ p, li { white-space: pre-wrap; }
setNum(int)
- 306
- 273
+ 124
+ 126
- 301
- 315
+ 124
+ 126
@@ -2321,12 +2345,12 @@ p, li { white-space: pre-wrap; }
setNum(int)
- 651
- 112
+ 115
+ 117
- 600
- 112
+ 115
+ 117
@@ -2337,12 +2361,12 @@ p, li { white-space: pre-wrap; }
setNum(int)
- 659
- 211
+ 115
+ 117
- 581
- 218
+ 115
+ 117
diff --git a/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp b/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp
index 70b4f6f14..24d74ddcd 100644
--- a/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp
+++ b/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp
@@ -1003,7 +1003,7 @@ void ConfigAirframeWidget::setupAirframeUI(QString frameType)
} else if (frameType == "HexaX" || frameType == "Hexacopter X" ) {
m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Multirotor"));
m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Hexacopter X"));
- quad->setElementId("quad-hexa-X");
+ quad->setElementId("quad-hexa-H");
m_aircraft->multiMotor4->setEnabled(true);
m_aircraft->multiMotor5->setEnabled(true);
m_aircraft->multiMotor6->setEnabled(true);
diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp
index 34b29338b..a762ce742 100644
--- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp
+++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp
@@ -144,20 +144,22 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren
firstUpdate = true;
- enableControls(false);
+ connect(m_config->spinningArmed, SIGNAL(toggled(bool)), this, SLOT(setSpinningArmed(bool)));
- // Listen to telemetry connection events
- if (pm)
- {
- TelemetryManager *tm = pm->getObject();
- if (tm)
- {
- connect(tm, SIGNAL(myStart()), this, SLOT(onTelemetryStart()));
- connect(tm, SIGNAL(myStop()), this, SLOT(onTelemetryStop()));
- connect(tm, SIGNAL(connected()), this, SLOT(onTelemetryConnect()));
- connect(tm, SIGNAL(disconnected()), this, SLOT(onTelemetryDisconnect()));
- }
- }
+ enableControls(false);
+
+ // Listen to telemetry connection events
+ if (pm)
+ {
+ TelemetryManager *tm = pm->getObject();
+ if (tm)
+ {
+ connect(tm, SIGNAL(myStart()), this, SLOT(onTelemetryStart()));
+ connect(tm, SIGNAL(myStop()), this, SLOT(onTelemetryStop()));
+ connect(tm, SIGNAL(connected()), this, SLOT(onTelemetryConnect()));
+ connect(tm, SIGNAL(disconnected()), this, SLOT(onTelemetryDisconnect()));
+ }
+ }
}
ConfigOutputWidget::~ConfigOutputWidget()
@@ -307,7 +309,20 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str)
}
}
-
+/**
+ * Set the "Spin motors at neutral when armed" flag in ActuatorSettings
+ */
+void ConfigOutputWidget::setSpinningArmed(bool val)
+{
+ UAVDataObject *obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings")));
+ if (!obj) return;
+ UAVObjectField *field = obj->getField("MotorsSpinWhileArmed");
+ if (!field) return;
+ if(val)
+ field->setValue("TRUE");
+ else
+ field->setValue("FALSE");
+}
/**
Sends the channel value to the UAV to move the servo.
@@ -372,13 +387,6 @@ void ConfigOutputWidget::requestRCOutputUpdate()
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject();
- // Get the Airframe type from the system settings:
- UAVDataObject* obj = dynamic_cast(objManager->getObject(QString("SystemSettings")));
- Q_ASSERT(obj);
- obj->requestUpdate();
- UAVObjectField *field = obj->getField(QString("AirframeType"));
- m_config->aircraftType->setText(QString("Aircraft type: ") + field->getValue().toString());
-
// Reset all channel assignements:
m_config->ch0Output->setCurrentIndex(0);
m_config->ch1Output->setCurrentIndex(0);
@@ -390,7 +398,7 @@ void ConfigOutputWidget::requestRCOutputUpdate()
m_config->ch7Output->setCurrentIndex(0);
// Get the channel assignements:
- obj = dynamic_cast(objManager->getObject(QString("ActuatorSettings")));
+ UAVDataObject * obj = dynamic_cast(objManager->getObject(QString("ActuatorSettings")));
Q_ASSERT(obj);
obj->requestUpdate();
QList fieldList = obj->getFields();
@@ -400,10 +408,44 @@ void ConfigOutputWidget::requestRCOutputUpdate()
}
}
+ // Get the SpinWhileArmed setting
+ UAVObjectField *field = obj->getField(QString("MotorsSpinWhileArmed"));
+ m_config->spinningArmed->setChecked(field->getValue().toString().contains("TRUE"));
+
// Get Output rates for both banks
field = obj->getField(QString("ChannelUpdateFreq"));
+ UAVObjectUtilManager* utilMngr = pm->getObject();
m_config->outputRate1->setValue(field->getValue(0).toInt());
m_config->outputRate2->setValue(field->getValue(1).toInt());
+ if (utilMngr) {
+ int board = utilMngr->getBoardModel();
+ if ((board & 0xff00) == 1024) {
+ // CopterControl family
+ m_config->chBank1->setText("1-3");
+ m_config->chBank2->setText("4");
+ m_config->chBank3->setText("5");
+ m_config->chBank4->setText("6");
+ m_config->outputRate1->setEnabled(true);
+ m_config->outputRate2->setEnabled(true);
+ m_config->outputRate3->setEnabled(true);
+ m_config->outputRate4->setEnabled(true);
+ m_config->outputRate3->setValue(field->getValue(2).toInt());
+ m_config->outputRate4->setValue(field->getValue(3).toInt());
+ } else if ((board & 0xff00) == 256 ) {
+ // Mainboard family
+ m_config->outputRate1->setEnabled(true);
+ m_config->outputRate2->setEnabled(true);
+ m_config->outputRate3->setEnabled(false);
+ m_config->outputRate4->setEnabled(false);
+ m_config->chBank1->setText("1-4");
+ m_config->chBank2->setText("5-8");
+ m_config->chBank3->setText("-");
+ m_config->chBank4->setText("-");
+ m_config->outputRate3->setValue(0);
+ m_config->outputRate4->setValue(0);
+ }
+ }
+
// Get Channel ranges:
for (int i=0;i<8;i++) {
@@ -463,6 +505,8 @@ void ConfigOutputWidget::sendRCOutputUpdate()
field = obj->getField(QString("ChannelUpdateFreq"));
field->setValue(m_config->outputRate1->value(),0);
field->setValue(m_config->outputRate2->value(),1);
+ field->setValue(m_config->outputRate3->value(),2);
+ field->setValue(m_config->outputRate4->value(),3);
// Set Actuator assignement for each channel:
// Rule: if two channels have the same setting (which is wrong!) the higher channel
diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h
index 5255a92c1..f3083e725 100644
--- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h
+++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h
@@ -32,6 +32,7 @@
#include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h"
#include "uavobject.h"
+#include "uavobjectutilmanager.h"
#include
#include
@@ -85,6 +86,7 @@ private slots:
void setChOutRange();
void reverseChannel(bool state);
void linkToggled(bool state);
+ void setSpinningArmed(bool val);
};
#endif
diff --git a/ground/openpilotgcs/src/plugins/config/images/quad-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/quad-shapes.svg
index bee517fc5..8452bfd11 100644
--- a/ground/openpilotgcs/src/plugins/config/images/quad-shapes.svg
+++ b/ground/openpilotgcs/src/plugins/config/images/quad-shapes.svg
@@ -7,3134 +7,6741 @@
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns="http://www.w3.org/2000/svg"
+ xmlns:xlink="http://www.w3.org/1999/xlink"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
- width="649.92664"
- height="953.03302"
- id="svg2917"
+ id="svg4183"
version="1.1"
- inkscape:version="0.48.0 r9654"
- sodipodi:docname="quad-shapes.svg">
-
-
-
-
-
- image/svg+xml
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- image/svg+xml
-
-
-
-
-
-
-
-
-
-
-
-
-
- 1
- 2
- 3
- 4
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- 1
-
-
-
-
-
-
-
- 3
-
-
-
-
-
-
-
- 4
-
-
-
-
-
-
-
- 2
-
-
-
-
-
-
-
-
-
-
- 1
-
-
-
-
-
-
-
-
- 5
-
-
-
-
-
-
-
-
-
- 7
-
-
-
-
-
-
- 3
-
-
-
-
-
- 8
-
-
-
-
-
-
-
- 4
-
-
-
-
-
-
-
- 6
-
-
-
-
-
- 2
-
-
-
-
-
-
-
-
-
- 1
-
-
-
-
-
-
-
-
- 4
-
-
-
-
-
-
-
-
- 6
-
-
-
-
-
-
-
- 3
-
-
-
-
-
-
-
- 5
-
-
-
-
-
- 2
-
-
-
-
-
-
-
-
-
-
-
- 1
-
-
-
-
-
-
-
- 5
-
-
-
-
-
-
-
-
-
- 7
-
-
-
-
-
-
- 3
-
-
-
-
-
- 8
-
-
-
-
-
-
-
- 4
-
-
-
-
-
-
-
- 6
-
-
-
-
-
-
-
- 2
-
-
-
-
-
-
-
-
-
- 1
-
-
-
-
-
-
-
-
-
- 4
-
-
-
-
-
-
-
- 6
-
-
-
-
-
-
-
- 3
-
-
-
-
-
-
-
- 5
-
-
-
-
-
- 2
-
-
-
-
-
-
-
-
-
-
-
-
-
- 1
- 2
- 3
- 4
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- 1
- 3
- 5
- 7
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- 2
- 4
- 6
- 8
-
-
-
-
-
-
-
-
-
- 1
- 3
- 4
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- 1
- 3
- 5
- 7
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- 2
- 4
- 6
- 8
-
-
-
-
-
-
- 2
- 3
-
-
-
-
-
-
- 1
-
-
-
-
-
-
- 1
- 2
-
-
-
- 3
-
-
- 4
-
-
-
- 5
-
-
-
-
- 6
-
-
-
-
-
-
-
- 2
-
-
- 3
-
-
-
-
-
-
-
-
- 1
-
-
-
-
-
-
-
+ inkscape:connector-curvature="0" />
\ No newline at end of file
diff --git a/ground/openpilotgcs/src/plugins/config/mixercurvewidget.cpp b/ground/openpilotgcs/src/plugins/config/mixercurvewidget.cpp
index 7e99f8a35..2acf5babd 100644
--- a/ground/openpilotgcs/src/plugins/config/mixercurvewidget.cpp
+++ b/ground/openpilotgcs/src/plugins/config/mixercurvewidget.cpp
@@ -60,6 +60,8 @@ MixerCurveWidget::MixerCurveWidget(QWidget *parent) : QGraphicsView(parent)
curveMax=1.0;
+ setFrameStyle(QFrame::NoFrame);
+ setStyleSheet("background:transparent");
QGraphicsScene *scene = new QGraphicsScene(this);
QSvgRenderer *renderer = new QSvgRenderer();
diff --git a/ground/openpilotgcs/src/plugins/config/output.ui b/ground/openpilotgcs/src/plugins/config/output.ui
index 7023cca09..db63ba4c7 100644
--- a/ground/openpilotgcs/src/plugins/config/output.ui
+++ b/ground/openpilotgcs/src/plugins/config/output.ui
@@ -7,7 +7,7 @@
0
0
663
- 395
+ 500
@@ -15,136 +15,162 @@
-
-
-
- 0
+
+
+ QFrame::StyledPanel
-
-
- Servo Output
-
-
-
-
- 10
- 10
- 221
- 17
-
-
-
- Aircraft type: undefined
-
-
+
+ QFrame::Raised
+
+
+
+ 1
+
+
+ 1
+
+
+ 1
+
+
+ 3
+
+
+ 2
+
+
-
+
+
+ false
+
+
+ Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
+Leave at 50Hz for fixed wing.
+
+
+ 400
+
+
+
+ -
+
+
+ -
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ -
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ -
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ false
+
+
+ Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
+Leave at 50Hz for fixed wing.
+
+
+ 400
+
+
+
+ -
+
+
+ false
+
+
+ Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
+Leave at 50Hz for fixed wing.
+
+
+ 400
+
+
+
+ -
+
+
+ false
+
+
+ Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
+Leave at 50Hz for fixed wing.
+
+
+ 400
+
+
+
+ -
+
+
+ Update rate:
+
+
+ Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter
+
+
+
+ -
+
+
+ -
+
+
+ Qt::AlignCenter
+
+
+
+ -
+
+
+ Channel:
+
+
+ Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter
+
+
+
+
+
+
+ -
+
+
-
-
-
- 10
- 70
- 71
- 17
-
-
Channel 1
-
-
-
- 10
- 100
- 71
- 17
-
-
-
- Channel 2
-
-
-
-
-
- 10
- 130
- 71
- 17
-
-
-
- Channel 3
-
-
-
-
-
- 10
- 160
- 71
- 17
-
-
-
- Channel 4
-
-
-
-
-
- 10
- 190
- 71
- 17
-
-
-
- Channel 5
-
-
-
-
-
- 10
- 220
- 71
- 17
-
-
-
- Channel 6
-
-
-
-
- true
-
-
-
- 300
- 70
- 160
- 18
-
-
-
- 9999
-
-
- Qt::Horizontal
-
-
+
+ -
false
-
-
- 100
- 70
- 121
- 21
-
-
8
@@ -159,18 +185,12 @@ p, li { white-space: pre-wrap; }
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
+
+ -
true
-
-
- 240
- 70
- 55
- 21
-
-
8
@@ -187,17 +207,24 @@ p, li { white-space: pre-wrap; }
9999
-
+
+ -
+
true
-
-
- 460
- 70
- 55
- 21
-
+
+ 9999
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ true
@@ -215,17 +242,802 @@ p, li { white-space: pre-wrap; }
9999
-
+
+ -
+
+
+ Current value of slider.
+
+
+ 0000
+
+
+
+ -
+
+
+
+ FreeSans
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
+
+
+
+
+
+
+ -
+
+
+ Only used with Test Output mode
+
+
+
+
+
+
+ -
+
+
+ Link
+
+
+
+ -
+
+
+ Rev.
+
+
+
+ -
+
+
+ Channel 2
+
+
+
+ -
+
+
+ false
+
+
+
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
+
+
+
+ -
+
true
-
-
- 10
- 40
- 151
- 22
-
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ true
+
+
+ 9999
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ true
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ 0000
+
+
+
+ -
+
+
+
+ FreeSans
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
+
+
+
+
+
+
+ -
+
+
+ Only used with Test Output mode
+
+
+
+
+
+
+ -
+
+
+ Channel 3
+
+
+
+ -
+
+
+ false
+
+
+
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
+
+
+
+ -
+
+
+ true
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ true
+
+
+ 9999
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ true
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ 0000
+
+
+
+ -
+
+
+
+ FreeSans
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
+
+
+
+
+
+
+ -
+
+
+ Only used with Test Output mode
+
+
+
+
+
+
+ -
+
+
+ Channel 4
+
+
+
+ -
+
+
+ false
+
+
+
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
+
+
+
+ -
+
+
+ true
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ true
+
+
+ 9999
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+ true
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ 0000
+
+
+
+ -
+
+
+
+ FreeSans
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
+
+
+
+
+
+
+ -
+
+
+ Only used with Test Output mode
+
+
+
+
+
+
+ -
+
+
+ Channel 5
+
+
+
+ -
+
+
+ false
+
+
+
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
+
+
+
+ -
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ 9999
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ 0000
+
+
+
+ -
+
+
+
+ FreeSans
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
+
+
+
+
+
+
+ -
+
+
+ Only used with Test Output mode
+
+
+
+
+
+
+ -
+
+
+ Channel 6
+
+
+
+ -
+
+
+ false
+
+
+
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
+
+
+
+ -
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ 9999
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ 0000
+
+
+
+ -
+
+
+
+ FreeSans
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
+
+
+
+
+
+
+ -
+
+
+ Only used with Test Output mode
+
+
+
+
+
+
+ -
+
+
+ Channel 7
+
+
+
+ -
+
+
+ false
+
+
+
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
+
+
+
+ -
+
+
+ Channel 8
+
+
+
+ -
+
+
+ false
+
+
+
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
+
+
+
+ -
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ 9999
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ 0000
+
+
+
+ -
+
+
+
+ FreeSans
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
+
+
+
+
+
+
+ -
+
+
+ Only used with Test Output mode
+
+
+
+
+
+
+ -
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ 9999
+
+
+ Qt::Horizontal
+
+
+
+ -
+
+
+
+ 8
+
+
+
+ 9999
+
+
+
+ -
+
+
+ 0000
+
+
+
+ -
+
+
+
+ FreeSans
+ 8
+
+
+
+ <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
+<html><head><meta name="qrichtext" content="1" /><style type="text/css">
+p, li { white-space: pre-wrap; }
+</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
+<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
+
+
+
+
+
+
+ -
+
+
+ Only used with Test Output mode
+
+
+
+
+
+
+
+
+ -
+
+
+ Motors spin at neutral output when armed and throttle below zero (be careful)
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+ -
+
+
-
+
+
+ true
Move the servos using the sliders. Two important things:
@@ -236,631 +1048,22 @@ p, li { white-space: pre-wrap; }
Test outputs
-
-
-
- 10
- 250
- 71
- 17
-
-
-
- Channel 7
-
-
-
-
-
- 10
- 280
- 71
- 17
-
-
-
- Channel 8
-
-
-
-
- false
-
-
-
- 100
- 100
- 121
- 21
-
-
-
-
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
-
-
-
-
- true
-
-
-
- 460
- 100
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
- true
-
-
-
- 240
- 100
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
- true
-
-
-
- 300
- 100
- 160
- 18
-
-
-
- 9999
-
+
+ -
+
Qt::Horizontal
-
-
-
- false
-
-
-
- 100
- 130
- 121
- 21
-
-
-
-
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
-
-
-
-
- true
-
-
-
- 460
- 130
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
- true
-
-
-
- 240
- 130
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
- true
-
-
-
- 300
- 130
- 160
- 18
-
-
-
- 9999
-
-
- Qt::Horizontal
-
-
-
-
- false
-
-
-
- 100
- 160
- 121
- 21
-
-
-
-
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
-
-
-
-
- true
-
-
-
- 460
- 160
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
- true
-
-
-
- 240
- 160
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
- true
-
-
-
- 300
- 160
- 160
- 18
-
-
-
- 9999
-
-
- Qt::Horizontal
-
-
-
-
- false
-
-
-
- 100
- 190
- 121
- 21
-
-
-
-
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
-
-
-
-
-
- 460
- 190
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
-
- 240
- 190
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
-
- 300
- 190
- 160
- 18
-
-
-
- 9999
-
-
- Qt::Horizontal
-
-
-
-
- false
-
-
-
- 100
- 220
- 121
- 21
-
-
-
-
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
-
-
-
-
-
- 460
- 220
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
-
- 240
- 220
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
-
- 300
- 220
- 160
- 18
-
-
-
- 9999
-
-
- Qt::Horizontal
-
-
-
-
- false
-
-
-
- 100
- 250
- 121
- 21
-
-
-
-
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
-
-
-
-
-
- 460
- 250
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
-
- 240
- 250
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
-
- 300
- 250
- 160
- 18
-
-
-
- 9999
-
-
- Qt::Horizontal
-
-
-
-
- false
-
-
-
- 100
- 280
- 121
- 21
-
-
-
-
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'Ubuntu'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">This is the actuator connected to this channel.</span></p>
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans';">You can change this through the "Airframe" dialog (on the left).</span></p></body></html>
-
-
-
-
-
- 460
- 280
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
-
- 240
- 280
- 55
- 21
-
-
-
-
- 8
-
-
-
- 9999
-
-
-
-
-
- 300
- 280
- 160
- 18
-
-
-
- 9999
-
-
- Qt::Horizontal
-
-
-
-
-
- 490
- 310
- 93
- 27
-
-
-
- Be sure to set the Neutral position on all sliders before sending!
-Applies and Saves all settings to SD
-
-
- Save
-
-
+
+
+ 40
+ 20
+
+
+
+
+ -
-
-
- 270
- 310
- 93
- 27
-
-
Retrieve settings from OpenPilot
@@ -868,15 +1071,9 @@ Applies and Saves all settings to SD
Get Current
+
+ -
-
-
- 380
- 310
- 93
- 27
-
-
Send to OpenPilot but don't write in SD.
Be sure to set the Neutral position on all sliders before sending!
@@ -885,613 +1082,77 @@ Be sure to set the Neutral position on all sliders before sending!
Apply
-
-
-
- 240
- 10
- 291
- 51
-
-
-
- QFrame::StyledPanel
-
-
- QFrame::Raised
-
-
-
-
- 220
- 20
- 55
- 27
-
-
-
- Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
-Leave at 50Hz for fixed wing.
-
-
- 9999
-
-
-
-
-
- 20
- 20
- 81
- 17
-
-
-
- Update rate:
-
-
-
-
-
- 120
- 20
- 55
- 27
-
-
-
- Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
-Leave at 50Hz for fixed wing.
-
-
- 9999
-
-
-
-
-
- 110
- 0
- 81
- 17
-
-
-
- Channel 0-3
-
-
-
-
-
- 210
- 0
- 81
- 17
-
-
-
- Channel 4-7
-
-
-
-
-
-
- 520
- 70
- 41
- 17
-
-
+
+ -
+
- Current value of slider.
+ Be sure to set the Neutral position on all sliders before sending!
+Applies and Saves all settings to SD
- 0000
+ Save
-
-
-
- 520
- 100
- 41
- 17
-
-
-
- 0000
-
-
-
-
-
- 520
- 130
- 41
- 17
-
-
-
- 0000
-
-
-
-
-
- 520
- 160
- 41
- 17
-
-
-
- 0000
-
-
-
-
-
- 520
- 190
- 41
- 17
-
-
-
- 0000
-
-
-
-
-
- 520
- 220
- 41
- 17
-
-
-
- 0000
-
-
-
-
-
- 520
- 250
- 41
- 17
-
-
-
- 0000
-
-
-
-
-
- 520
- 280
- 41
- 17
-
-
-
- 0000
-
-
-
-
-
- 560
- 220
- 21
- 22
-
-
-
-
- FreeSans
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
-
-
-
-
-
-
-
-
- 560
- 70
- 21
- 22
-
-
-
-
- FreeSans
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
-
-
-
-
-
-
-
-
- 560
- 130
- 21
- 22
-
-
-
-
- FreeSans
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
-
-
-
-
-
-
-
-
- 560
- 250
- 21
- 22
-
-
-
-
- FreeSans
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
-
-
-
-
-
-
-
-
- 560
- 280
- 21
- 22
-
-
-
-
- FreeSans
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
-
-
-
-
-
-
-
-
- 560
- 100
- 21
- 22
-
-
-
-
- FreeSans
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
-
-
-
-
-
-
-
-
- 560
- 160
- 21
- 22
-
-
-
-
- FreeSans
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
-
-
-
-
-
-
-
-
- 560
- 190
- 21
- 22
-
-
-
-
- FreeSans
- 8
-
-
-
- <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
-<html><head><meta name="qrichtext" content="1" /><style type="text/css">
-p, li { white-space: pre-wrap; }
-</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;">
-<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html>
-
-
-
-
-
-
-
-
- 560
- 50
- 31
- 17
-
-
-
- Rev.
-
-
-
-
-
- 600
- 50
- 31
- 17
-
-
-
- Link
-
-
-
-
-
- 610
- 70
- 21
- 22
-
-
-
- Only used with Test Output mode
-
-
-
-
-
-
-
-
- 610
- 100
- 21
- 22
-
-
-
- Only used with Test Output mode
-
-
-
-
-
-
-
-
- 610
- 130
- 21
- 22
-
-
-
- Only used with Test Output mode
-
-
-
-
-
-
-
-
- 610
- 160
- 21
- 22
-
-
-
- Only used with Test Output mode
-
-
-
-
-
-
-
-
- 610
- 190
- 21
- 22
-
-
-
- Only used with Test Output mode
-
-
-
-
-
-
-
-
- 610
- 220
- 21
- 22
-
-
-
- Only used with Test Output mode
-
-
-
-
-
-
-
-
- 610
- 250
- 21
- 22
-
-
-
- Only used with Test Output mode
-
-
-
-
-
-
-
-
- 610
- 280
- 21
- 22
-
-
-
- Only used with Test Output mode
-
-
-
-
-
-
-
+
+
- channelOutTest
outputRate1
outputRate2
- ch0Output
+ outputRate3
+ outputRate4
ch0OutMin
- ch0OutSlider
ch0OutMax
- ch0Rev
- ch1Output
ch1OutMin
- ch1OutSlider
ch1OutMax
- ch1Rev
- ch2Output
ch2OutMin
- ch2OutSlider
ch2OutMax
- ch2Rev
- ch3Output
ch3OutMin
- ch3OutSlider
ch3OutMax
- ch3Rev
- ch4Output
ch4OutMin
- ch4OutSlider
ch4OutMax
- ch4Rev
- ch5Output
ch5OutMin
- ch5OutSlider
ch5OutMax
- ch5Rev
- ch6Output
ch6OutMin
- ch6OutSlider
ch6OutMax
- ch6Rev
- ch7Output
ch7OutMin
- ch7OutSlider
ch7OutMax
+ ch0Output
+ ch0OutSlider
+ ch0Rev
+ ch0Link
+ ch1Output
+ ch1OutSlider
+ ch1Rev
+ ch1Link
+ ch2Output
+ ch2OutSlider
+ ch2Rev
+ ch2Link
+ ch3Output
+ ch3OutSlider
+ ch3Rev
+ ch3Link
+ ch4Output
+ ch4OutSlider
+ ch4Rev
+ ch4Link
+ ch5Output
+ ch5OutSlider
+ ch5Rev
+ ch5Link
+ ch6Output
+ ch6OutSlider
+ ch6Rev
+ ch6Link
+ ch7Output
+ ch7OutSlider
ch7Rev
+ ch7Link
+ spinningArmed
+ channelOutTest
getRCOutputCurrent
saveRCOutputToRAM
saveRCOutputToSD
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini
index c8ca09ac3..0b1ef6aca 100644
--- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini
+++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini
@@ -1,1896 +1,1908 @@
-[Workspace]
-NumberOfWorkspaces=6
-Workspace1=Flight data
-Icon1=:/core/images/openpilot_logo_64.png
-Workspace2=Configuration
-Icon2=:/core/images/openpilot_logo_64.png
-Workspace3=Dials Showcase
-Icon3=:/core/images/openpilot_logo_64.png
-Workspace4=Large Map
-Icon4=:/core/images/openpilot_logo_64.png
-Workspace5=Scopes
-Icon5=:/core/images/openpilot_logo_64.png
-Workspace6=HITL
-Icon6=:/core/images/openpilot_logo_64.png
-Workspace7=Workspace7
-Icon7=:/core/images/openpilot_logo_64.png
-Workspace8=Workspace8
-Icon8=:/core/images/openpilot_logo_64.png
-Workspace9=Workspace9
-Icon9=:/core/images/openpilot_logo_64.png
-Workspace10=Workspace10
-Icon10=:/core/images/openpilot_logo_64.png
-
-[MainWindow]
-Color=@Variant(\0\0\0\x43\x1\xff\xff\x66\x66\x66\x66\x66\x66\0\0)
-Maximized=true
-FullScreen=false
-
-[UAVGadgetManager]
-Mode1\version=UAVGadgetManagerV1
-Mode1\showToolbars=false
-Mode1\splitter\type=splitter
-Mode1\splitter\splitterOrientation=1
-Mode1\splitter\splitterSizes=590, 595
-Mode1\splitter\side0\type=splitter
-Mode1\splitter\side0\splitterOrientation=2
-Mode1\splitter\side0\splitterSizes=422, 209
-Mode1\splitter\side0\side0\type=splitter
-Mode1\splitter\side0\side0\splitterOrientation=1
-Mode1\splitter\side0\side0\splitterSizes=615, 64
-Mode1\splitter\side0\side0\side0\type=uavGadget
-Mode1\splitter\side0\side0\side0\classId=PFDGadget
-Mode1\splitter\side0\side0\side0\gadget\activeConfiguration=smooth
-Mode1\splitter\side0\side0\side1\type=uavGadget
-Mode1\splitter\side0\side0\side1\classId=LineardialGadget
-Mode1\splitter\side0\side0\side1\gadget\activeConfiguration=Throttle
-Mode1\splitter\side0\side1\type=splitter
-Mode1\splitter\side0\side1\splitterOrientation=1
-Mode1\splitter\side0\side1\splitterSizes=301, 378
-Mode1\splitter\side0\side1\side0\type=splitter
-Mode1\splitter\side0\side1\side0\splitterOrientation=2
-Mode1\splitter\side0\side1\side0\splitterSizes=64, 64
-Mode1\splitter\side0\side1\side0\side0\type=splitter
-Mode1\splitter\side0\side1\side0\side0\splitterOrientation=1
-Mode1\splitter\side0\side1\side0\side0\splitterSizes=200, 199
-Mode1\splitter\side0\side1\side0\side0\side0\type=uavGadget
-Mode1\splitter\side0\side1\side0\side0\side0\classId=LineardialGadget
-Mode1\splitter\side0\side1\side0\side0\side0\gadget\activeConfiguration=Flight Time
-Mode1\splitter\side0\side1\side0\side0\side1\type=uavGadget
-Mode1\splitter\side0\side1\side0\side0\side1\classId=LineardialGadget
-Mode1\splitter\side0\side1\side0\side0\side1\gadget\activeConfiguration=Flight mode
-Mode1\splitter\side0\side1\side0\side1\type=splitter
-Mode1\splitter\side0\side1\side0\side1\splitterOrientation=1
-Mode1\splitter\side0\side1\side0\side1\splitterSizes=200, 199
-Mode1\splitter\side0\side1\side0\side1\side0\type=uavGadget
-Mode1\splitter\side0\side1\side0\side1\side0\classId=LineardialGadget
-Mode1\splitter\side0\side1\side0\side1\side0\gadget\activeConfiguration=GPS Sats
-Mode1\splitter\side0\side1\side0\side1\side1\type=uavGadget
-Mode1\splitter\side0\side1\side0\side1\side1\classId=LineardialGadget
-Mode1\splitter\side0\side1\side0\side1\side1\gadget\activeConfiguration=Arm Status
-Mode1\splitter\side0\side1\side1\type=splitter
-Mode1\splitter\side0\side1\side1\splitterOrientation=1
-Mode1\splitter\side0\side1\side1\splitterSizes=279, 129
-Mode1\splitter\side0\side1\side1\side0\type=uavGadget
-Mode1\splitter\side0\side1\side1\side0\classId=SystemHealthGadget
-Mode1\splitter\side0\side1\side1\side0\gadget\activeConfiguration=default
-Mode1\splitter\side0\side1\side1\side1\type=splitter
-Mode1\splitter\side0\side1\side1\side1\splitterOrientation=1
-Mode1\splitter\side0\side1\side1\side1\splitterSizes=104, 64
-Mode1\splitter\side0\side1\side1\side1\side0\type=uavGadget
-Mode1\splitter\side0\side1\side1\side1\side0\classId=LineardialGadget
-Mode1\splitter\side0\side1\side1\side1\side0\gadget\activeConfiguration=AHRS CPU
-Mode1\splitter\side0\side1\side1\side1\side1\type=uavGadget
-Mode1\splitter\side0\side1\side1\side1\side1\classId=LineardialGadget
-Mode1\splitter\side0\side1\side1\side1\side1\gadget\activeConfiguration=Mainboard CPU
-Mode1\splitter\side1\type=splitter
-Mode1\splitter\side1\splitterOrientation=2
-Mode1\splitter\side1\splitterSizes=353, 278
-Mode1\splitter\side1\side0\type=splitter
-Mode1\splitter\side1\side0\splitterOrientation=1
-Mode1\splitter\side1\side0\splitterSizes=373, 311
-Mode1\splitter\side1\side0\side0\type=uavGadget
-Mode1\splitter\side1\side0\side0\classId=ScopeGadget
-Mode1\splitter\side1\side0\side0\gadget\activeConfiguration=Attitude
-Mode1\splitter\side1\side0\side1\type=uavGadget
-Mode1\splitter\side1\side0\side1\classId=ModelViewGadget
-Mode1\splitter\side1\side0\side1\gadget\activeConfiguration=Test Quad X
-Mode1\splitter\side1\side1\type=uavGadget
-Mode1\splitter\side1\side1\classId=GpsDisplayGadget
-Mode1\splitter\side1\side1\gadget\activeConfiguration=Flight GPS
-Mode2\version=UAVGadgetManagerV1
-Mode2\showToolbars=false
-Mode2\splitter\type=splitter
-Mode2\splitter\splitterOrientation=1
-Mode2\splitter\splitterSizes=661, 704
-Mode2\splitter\side0\type=splitter
-Mode2\splitter\side0\splitterOrientation=2
-Mode2\splitter\side0\splitterSizes=565, 66
-Mode2\splitter\side0\side0\type=uavGadget
-Mode2\splitter\side0\side0\classId=ConfigGadget
-Mode2\splitter\side0\side0\gadget\activeConfiguration=default
-Mode2\splitter\side0\side1\type=splitter
-Mode2\splitter\side0\side1\splitterOrientation=1
-Mode2\splitter\side0\side1\splitterSizes=@Invalid()
-Mode2\splitter\side0\side1\side0\type=uavGadget
-Mode2\splitter\side0\side1\side0\classId=LineardialGadget
-Mode2\splitter\side0\side1\side0\gadget\activeConfiguration=Telemetry RX Rate Horizontal
-Mode2\splitter\side0\side1\side1\type=uavGadget
-Mode2\splitter\side0\side1\side1\classId=LineardialGadget
-Mode2\splitter\side0\side1\side1\gadget\activeConfiguration=Telemetry TX Rate Horizontal
-Mode2\splitter\side1\type=splitter
-Mode2\splitter\side1\splitterOrientation=2
-Mode2\splitter\side1\splitterSizes=259, 372
-Mode2\splitter\side1\side0\type=uavGadget
-Mode2\splitter\side1\side0\classId=UAVObjectBrowser
-Mode2\splitter\side1\side0\gadget\activeConfiguration=default
-Mode2\splitter\side1\side1\type=uavGadget
-Mode2\splitter\side1\side1\classId=Uploader
-Mode2\splitter\side1\side1\gadget\activeConfiguration=default
-Mode3\version=UAVGadgetManagerV1
-Mode3\showToolbars=false
-Mode3\splitter\type=splitter
-Mode3\splitter\splitterOrientation=1
-Mode3\splitter\splitterSizes=377, 189
-Mode3\splitter\side0\type=splitter
-Mode3\splitter\side0\splitterOrientation=1
-Mode3\splitter\side0\splitterSizes=49, 49
-Mode3\splitter\side0\side0\type=splitter
-Mode3\splitter\side0\side0\splitterOrientation=1
-Mode3\splitter\side0\side0\splitterSizes=49, 49
-Mode3\splitter\side0\side0\side0\type=uavGadget
-Mode3\splitter\side0\side0\side0\classId=DialGadget
-Mode3\splitter\side0\side0\side0\gadget\activeConfiguration=Attitude
-Mode3\splitter\side0\side0\side1\type=uavGadget
-Mode3\splitter\side0\side0\side1\classId=DialGadget
-Mode3\splitter\side0\side0\side1\gadget\activeConfiguration=Baro Altimeter
-Mode3\splitter\side0\side1\type=splitter
-Mode3\splitter\side0\side1\splitterOrientation=1
-Mode3\splitter\side0\side1\splitterSizes=49, 49
-Mode3\splitter\side0\side1\side0\type=uavGadget
-Mode3\splitter\side0\side1\side0\classId=DialGadget
-Mode3\splitter\side0\side1\side0\gadget\activeConfiguration=Compass
-Mode3\splitter\side0\side1\side1\type=uavGadget
-Mode3\splitter\side0\side1\side1\classId=DialGadget
-Mode3\splitter\side0\side1\side1\gadget\activeConfiguration=Groundspeed kph
-Mode3\splitter\side1\type=splitter
-Mode3\splitter\side1\splitterOrientation=1
-Mode3\splitter\side1\splitterSizes=394, 210
-Mode3\splitter\side1\side0\type=splitter
-Mode3\splitter\side1\side0\splitterOrientation=1
-Mode3\splitter\side1\side0\splitterSizes=49, 49
-Mode3\splitter\side1\side0\side0\type=uavGadget
-Mode3\splitter\side1\side0\side0\classId=DialGadget
-Mode3\splitter\side1\side0\side0\gadget\activeConfiguration=Temperature
-Mode3\splitter\side1\side0\side1\type=uavGadget
-Mode3\splitter\side1\side0\side1\classId=DialGadget
-Mode3\splitter\side1\side0\side1\gadget\activeConfiguration=Climbrate
-Mode3\splitter\side1\side1\type=uavGadget
-Mode3\splitter\side1\side1\classId=DialGadget
-Mode3\splitter\side1\side1\gadget\activeConfiguration=Barometer
-Mode4\version=UAVGadgetManagerV1
-Mode4\showToolbars=false
-Mode4\splitter\type=splitter
-Mode4\splitter\splitterOrientation=1
-Mode4\splitter\splitterSizes=980, 385
-Mode4\splitter\side0\type=uavGadget
-Mode4\splitter\side0\classId=OPMapGadget
-Mode4\splitter\side0\gadget\activeConfiguration=default
-Mode4\splitter\side1\type=splitter
-Mode4\splitter\side1\splitterOrientation=2
-Mode4\splitter\side1\splitterSizes=395, 236
-Mode4\splitter\side1\side0\type=uavGadget
-Mode4\splitter\side1\side0\classId=ModelViewGadget
-Mode4\splitter\side1\side0\gadget\activeConfiguration=Test Quad X
-Mode4\splitter\side1\side1\type=splitter
-Mode4\splitter\side1\side1\splitterOrientation=1
-Mode4\splitter\side1\side1\splitterSizes=@Invalid()
-Mode4\splitter\side1\side1\side0\type=uavGadget
-Mode4\splitter\side1\side1\side0\classId=DialGadget
-Mode4\splitter\side1\side1\side0\gadget\activeConfiguration=Attitude
-Mode4\splitter\side1\side1\side1\type=uavGadget
-Mode4\splitter\side1\side1\side1\classId=DialGadget
-Mode4\splitter\side1\side1\side1\gadget\activeConfiguration=Compass
-Mode5\version=UAVGadgetManagerV1
-Mode5\showToolbars=false
-Mode5\splitter\type=splitter
-Mode5\splitter\splitterOrientation=1
-Mode5\splitter\splitterSizes=653, 660
-Mode5\splitter\side0\type=uavGadget
-Mode5\splitter\side0\classId=ScopeGadget
-Mode5\splitter\side0\gadget\activeConfiguration=Accel
-Mode5\splitter\side1\type=splitter
-Mode5\splitter\side1\splitterOrientation=2
-Mode5\splitter\side1\splitterSizes=437, 194
-Mode5\splitter\side1\side0\type=uavGadget
-Mode5\splitter\side1\side0\classId=ScopeGadget
-Mode5\splitter\side1\side0\gadget\activeConfiguration=Uptimes
-Mode5\splitter\side1\side1\type=splitter
-Mode5\splitter\side1\side1\splitterOrientation=1
-Mode5\splitter\side1\side1\splitterSizes=194, 464
-Mode5\splitter\side1\side1\side0\type=uavGadget
-Mode5\splitter\side1\side1\side0\classId=DialGadget
-Mode5\splitter\side1\side1\side0\gadget\activeConfiguration=Attitude
-Mode5\splitter\side1\side1\side1\type=splitter
-Mode5\splitter\side1\side1\side1\splitterOrientation=1
-Mode5\splitter\side1\side1\side1\splitterSizes=208, 274
-Mode5\splitter\side1\side1\side1\side0\type=uavGadget
-Mode5\splitter\side1\side1\side1\side0\classId=EmptyGadget
-Mode5\splitter\side1\side1\side1\side1\type=splitter
-Mode5\splitter\side1\side1\side1\side1\splitterOrientation=2
-Mode5\splitter\side1\side1\side1\side1\splitterSizes=90, 103
-Mode5\splitter\side1\side1\side1\side1\side0\type=uavGadget
-Mode5\splitter\side1\side1\side1\side1\side0\classId=LoggingGadget
-Mode5\splitter\side1\side1\side1\side1\side1\type=uavGadget
-Mode5\splitter\side1\side1\side1\side1\side1\classId=EmptyGadget
-Mode6\version=UAVGadgetManagerV1
-Mode6\showToolbars=false
-Mode6\splitter\type=splitter
-Mode6\splitter\splitterOrientation=1
-Mode6\splitter\splitterSizes=780, 585
-Mode6\splitter\side0\type=splitter
-Mode6\splitter\side0\splitterOrientation=2
-Mode6\splitter\side0\splitterSizes=361, 270
-Mode6\splitter\side0\side0\type=uavGadget
-Mode6\splitter\side0\side0\classId=HITL
-Mode6\splitter\side0\side0\gadget\activeConfiguration=XPlane HITL
-Mode6\splitter\side0\side1\type=splitter
-Mode6\splitter\side0\side1\splitterOrientation=1
-Mode6\splitter\side0\side1\splitterSizes=488, 194
-Mode6\splitter\side0\side1\side0\type=uavGadget
-Mode6\splitter\side0\side1\side0\classId=GCSControlGadget
-Mode6\splitter\side0\side1\side0\gadget\activeConfiguration=MS Sidewinder
-Mode6\splitter\side0\side1\side1\type=splitter
-Mode6\splitter\side0\side1\side1\splitterOrientation=1
-Mode6\splitter\side0\side1\side1\splitterSizes=276, 64
-Mode6\splitter\side0\side1\side1\side0\type=splitter
-Mode6\splitter\side0\side1\side1\side0\splitterOrientation=1
-Mode6\splitter\side0\side1\side1\side0\splitterSizes=@Invalid()
-Mode6\splitter\side0\side1\side1\side0\side0\type=uavGadget
-Mode6\splitter\side0\side1\side1\side0\side0\classId=LineardialGadget
-Mode6\splitter\side0\side1\side1\side0\side0\gadget\activeConfiguration=PitchDesired
-Mode6\splitter\side0\side1\side1\side0\side1\type=uavGadget
-Mode6\splitter\side0\side1\side1\side0\side1\classId=LineardialGadget
-Mode6\splitter\side0\side1\side1\side0\side1\gadget\activeConfiguration=PitchActual
-Mode6\splitter\side0\side1\side1\side1\type=uavGadget
-Mode6\splitter\side0\side1\side1\side1\classId=LineardialGadget
-Mode6\splitter\side0\side1\side1\side1\gadget\activeConfiguration=PitchCommand
-Mode6\splitter\side1\type=uavGadget
-Mode6\splitter\side1\classId=UAVObjectBrowser
-Mode6\splitter\side1\gadget\activeConfiguration=default
-
-[General]
-ViewGroup_Default=@ByteArray(\0\0\0\xff\0\0\0\0\xfd\0\0\0\0\0\0\x4\0\0\0\x2\n\0\0\0\x4\0\0\0\x4\0\0\0\x1\0\0\0\b\xfc\0\0\0\0)
-
-[KeyBindings]
-size=0
-
-[%General]
-SaveSettingsOnExit=true
-
-[UAVGadgetConfigurations]
-configInfo\version=1.2.0
-configInfo\locked=false
-ConfigGadget\default\configInfo\version=0.0.0
-ConfigGadget\default\configInfo\locked=false
-DialGadget\Attitude\data\dialFile=%%DATAPATH%%dials/default/attitude.svg
-DialGadget\Attitude\data\dialBackgroundID=background
-DialGadget\Attitude\data\dialForegroundID=foreground
-DialGadget\Attitude\data\dialNeedleID1=needle
-DialGadget\Attitude\data\dialNeedleID2=needle
-DialGadget\Attitude\data\dialNeedleID3=needle3
-DialGadget\Attitude\data\needle1MinValue=0
-DialGadget\Attitude\data\needle1MaxValue=360
-DialGadget\Attitude\data\needle2MinValue=0
-DialGadget\Attitude\data\needle2MaxValue=20
-DialGadget\Attitude\data\needle3MinValue=0
-DialGadget\Attitude\data\needle3MaxValue=360
-DialGadget\Attitude\data\needle1DataObject=AttitudeActual
-DialGadget\Attitude\data\needle1ObjectField=Roll
-DialGadget\Attitude\data\needle2DataObject=AttitudeActual
-DialGadget\Attitude\data\needle2ObjectField=Pitch
-DialGadget\Attitude\data\needle3DataObject=AttitudeActual
-DialGadget\Attitude\data\needle3ObjectField=Roll
-DialGadget\Attitude\data\needle1Factor=-1
-DialGadget\Attitude\data\needle2Factor=75
-DialGadget\Attitude\data\needle3Factor=-1
-DialGadget\Attitude\data\needle1Move=Rotate
-DialGadget\Attitude\data\needle2Move=Vertical
-DialGadget\Attitude\data\needle3Move=Rotate
-DialGadget\Attitude\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Attitude\data\useOpenGLFlag=false
-DialGadget\Attitude\data\beSmooth=false
-DialGadget\Attitude\configInfo\version=0.0.0
-DialGadget\Attitude\configInfo\locked=false
-DialGadget\Baro%20Altimeter\data\dialFile=%%DATAPATH%%dials/default/altimeter.svg
-DialGadget\Baro%20Altimeter\data\dialBackgroundID=background
-DialGadget\Baro%20Altimeter\data\dialForegroundID=foreground
-DialGadget\Baro%20Altimeter\data\dialNeedleID1=needle
-DialGadget\Baro%20Altimeter\data\dialNeedleID2=needle2
-DialGadget\Baro%20Altimeter\data\dialNeedleID3=needle3
-DialGadget\Baro%20Altimeter\data\needle1MinValue=0
-DialGadget\Baro%20Altimeter\data\needle1MaxValue=10
-DialGadget\Baro%20Altimeter\data\needle2MinValue=0
-DialGadget\Baro%20Altimeter\data\needle2MaxValue=100
-DialGadget\Baro%20Altimeter\data\needle3MinValue=0
-DialGadget\Baro%20Altimeter\data\needle3MaxValue=1000
-DialGadget\Baro%20Altimeter\data\needle1DataObject=BaroAltitude
-DialGadget\Baro%20Altimeter\data\needle1ObjectField=Altitude
-DialGadget\Baro%20Altimeter\data\needle2DataObject=BaroAltitude
-DialGadget\Baro%20Altimeter\data\needle2ObjectField=Altitude
-DialGadget\Baro%20Altimeter\data\needle3DataObject=BaroAltitude
-DialGadget\Baro%20Altimeter\data\needle3ObjectField=Altitude
-DialGadget\Baro%20Altimeter\data\needle1Factor=1
-DialGadget\Baro%20Altimeter\data\needle2Factor=1
-DialGadget\Baro%20Altimeter\data\needle3Factor=1
-DialGadget\Baro%20Altimeter\data\needle1Move=Rotate
-DialGadget\Baro%20Altimeter\data\needle2Move=Rotate
-DialGadget\Baro%20Altimeter\data\needle3Move=Rotate
-DialGadget\Baro%20Altimeter\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Baro%20Altimeter\data\useOpenGLFlag=false
-DialGadget\Baro%20Altimeter\data\beSmooth=false
-DialGadget\Baro%20Altimeter\configInfo\version=0.0.0
-DialGadget\Baro%20Altimeter\configInfo\locked=false
-DialGadget\Barometer\data\dialFile=%%DATAPATH%%dials/default/barometer.svg
-DialGadget\Barometer\data\dialBackgroundID=background
-DialGadget\Barometer\data\dialForegroundID=
-DialGadget\Barometer\data\dialNeedleID1=needle
-DialGadget\Barometer\data\dialNeedleID2=
-DialGadget\Barometer\data\dialNeedleID3=
-DialGadget\Barometer\data\needle1MinValue=1000
-DialGadget\Barometer\data\needle1MaxValue=1120
-DialGadget\Barometer\data\needle2MinValue=0
-DialGadget\Barometer\data\needle2MaxValue=100
-DialGadget\Barometer\data\needle3MinValue=0
-DialGadget\Barometer\data\needle3MaxValue=1000
-DialGadget\Barometer\data\needle1DataObject=BaroAltitude
-DialGadget\Barometer\data\needle1ObjectField=Pressure
-DialGadget\Barometer\data\needle2DataObject=BaroAltitude
-DialGadget\Barometer\data\needle2ObjectField=Altitude
-DialGadget\Barometer\data\needle3DataObject=BaroAltitude
-DialGadget\Barometer\data\needle3ObjectField=Altitude
-DialGadget\Barometer\data\needle1Factor=10
-DialGadget\Barometer\data\needle2Factor=1
-DialGadget\Barometer\data\needle3Factor=1
-DialGadget\Barometer\data\needle1Move=Rotate
-DialGadget\Barometer\data\needle2Move=Rotate
-DialGadget\Barometer\data\needle3Move=Rotate
-DialGadget\Barometer\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Barometer\data\useOpenGLFlag=false
-DialGadget\Barometer\data\beSmooth=false
-DialGadget\Barometer\configInfo\version=0.0.0
-DialGadget\Barometer\configInfo\locked=false
-DialGadget\Climbrate\data\dialFile=%%DATAPATH%%dials/default/vsi.svg
-DialGadget\Climbrate\data\dialBackgroundID=background
-DialGadget\Climbrate\data\dialForegroundID=
-DialGadget\Climbrate\data\dialNeedleID1=needle
-DialGadget\Climbrate\data\dialNeedleID2=
-DialGadget\Climbrate\data\dialNeedleID3=
-DialGadget\Climbrate\data\needle1MinValue=-12
-DialGadget\Climbrate\data\needle1MaxValue=12
-DialGadget\Climbrate\data\needle2MinValue=0
-DialGadget\Climbrate\data\needle2MaxValue=100
-DialGadget\Climbrate\data\needle3MinValue=0
-DialGadget\Climbrate\data\needle3MaxValue=1000
-DialGadget\Climbrate\data\needle1DataObject=VelocityActual
-DialGadget\Climbrate\data\needle1ObjectField=Down
-DialGadget\Climbrate\data\needle2DataObject=BaroAltitude
-DialGadget\Climbrate\data\needle2ObjectField=Altitude
-DialGadget\Climbrate\data\needle3DataObject=BaroAltitude
-DialGadget\Climbrate\data\needle3ObjectField=Altitude
-DialGadget\Climbrate\data\needle1Factor=0.01
-DialGadget\Climbrate\data\needle2Factor=1
-DialGadget\Climbrate\data\needle3Factor=1
-DialGadget\Climbrate\data\needle1Move=Rotate
-DialGadget\Climbrate\data\needle2Move=Rotate
-DialGadget\Climbrate\data\needle3Move=Rotate
-DialGadget\Climbrate\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Climbrate\data\useOpenGLFlag=false
-DialGadget\Climbrate\data\beSmooth=false
-DialGadget\Climbrate\configInfo\version=0.0.0
-DialGadget\Climbrate\configInfo\locked=false
-DialGadget\Compass\data\dialFile=%%DATAPATH%%dials/default/compass.svg
-DialGadget\Compass\data\dialBackgroundID=background
-DialGadget\Compass\data\dialForegroundID=foreground
-DialGadget\Compass\data\dialNeedleID1=needle
-DialGadget\Compass\data\dialNeedleID2=
-DialGadget\Compass\data\dialNeedleID3=
-DialGadget\Compass\data\needle1MinValue=0
-DialGadget\Compass\data\needle1MaxValue=360
-DialGadget\Compass\data\needle2MinValue=0
-DialGadget\Compass\data\needle2MaxValue=100
-DialGadget\Compass\data\needle3MinValue=0
-DialGadget\Compass\data\needle3MaxValue=1000
-DialGadget\Compass\data\needle1DataObject=AttitudeActual
-DialGadget\Compass\data\needle1ObjectField=Yaw
-DialGadget\Compass\data\needle2DataObject=BaroAltitude
-DialGadget\Compass\data\needle2ObjectField=Altitude
-DialGadget\Compass\data\needle3DataObject=BaroAltitude
-DialGadget\Compass\data\needle3ObjectField=Altitude
-DialGadget\Compass\data\needle1Factor=-1
-DialGadget\Compass\data\needle2Factor=1
-DialGadget\Compass\data\needle3Factor=1
-DialGadget\Compass\data\needle1Move=Rotate
-DialGadget\Compass\data\needle2Move=Rotate
-DialGadget\Compass\data\needle3Move=Rotate
-DialGadget\Compass\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Compass\data\useOpenGLFlag=false
-DialGadget\Compass\data\beSmooth=false
-DialGadget\Compass\configInfo\version=0.0.0
-DialGadget\Compass\configInfo\locked=false
-DialGadget\Deluxe%20Attitude\data\dialFile=%%DATAPATH%%dials/deluxe/attitude.svg
-DialGadget\Deluxe%20Attitude\data\dialBackgroundID=background
-DialGadget\Deluxe%20Attitude\data\dialForegroundID=foreground
-DialGadget\Deluxe%20Attitude\data\dialNeedleID1=needle
-DialGadget\Deluxe%20Attitude\data\dialNeedleID2=needle
-DialGadget\Deluxe%20Attitude\data\dialNeedleID3=needle3
-DialGadget\Deluxe%20Attitude\data\needle1MinValue=0
-DialGadget\Deluxe%20Attitude\data\needle1MaxValue=360
-DialGadget\Deluxe%20Attitude\data\needle2MinValue=0
-DialGadget\Deluxe%20Attitude\data\needle2MaxValue=20
-DialGadget\Deluxe%20Attitude\data\needle3MinValue=0
-DialGadget\Deluxe%20Attitude\data\needle3MaxValue=360
-DialGadget\Deluxe%20Attitude\data\needle1DataObject=AttitudeActual
-DialGadget\Deluxe%20Attitude\data\needle1ObjectField=Roll
-DialGadget\Deluxe%20Attitude\data\needle2DataObject=AttitudeActual
-DialGadget\Deluxe%20Attitude\data\needle2ObjectField=Pitch
-DialGadget\Deluxe%20Attitude\data\needle3DataObject=AttitudeActual
-DialGadget\Deluxe%20Attitude\data\needle3ObjectField=Roll
-DialGadget\Deluxe%20Attitude\data\needle1Factor=-1
-DialGadget\Deluxe%20Attitude\data\needle2Factor=75
-DialGadget\Deluxe%20Attitude\data\needle3Factor=-1
-DialGadget\Deluxe%20Attitude\data\needle1Move=Rotate
-DialGadget\Deluxe%20Attitude\data\needle2Move=Vertical
-DialGadget\Deluxe%20Attitude\data\needle3Move=Rotate
-DialGadget\Deluxe%20Attitude\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Deluxe%20Attitude\data\useOpenGLFlag=false
-DialGadget\Deluxe%20Attitude\data\beSmooth=false
-DialGadget\Deluxe%20Attitude\configInfo\version=0.0.0
-DialGadget\Deluxe%20Attitude\configInfo\locked=false
-DialGadget\Deluxe%20Baro%20Altimeter\data\dialFile=%%DATAPATH%%dials/deluxe/altimeter.svg
-DialGadget\Deluxe%20Baro%20Altimeter\data\dialBackgroundID=background
-DialGadget\Deluxe%20Baro%20Altimeter\data\dialForegroundID=foreground
-DialGadget\Deluxe%20Baro%20Altimeter\data\dialNeedleID1=needle
-DialGadget\Deluxe%20Baro%20Altimeter\data\dialNeedleID2=needle2
-DialGadget\Deluxe%20Baro%20Altimeter\data\dialNeedleID3=needle3
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle1MinValue=0
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle1MaxValue=10
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle2MinValue=0
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle2MaxValue=100
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle3MinValue=0
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle3MaxValue=1000
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle1DataObject=BaroAltitude
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle1ObjectField=Altitude
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle2DataObject=BaroAltitude
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle2ObjectField=Altitude
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle3DataObject=BaroAltitude
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle3ObjectField=Altitude
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle1Factor=1
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle2Factor=1
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle3Factor=1
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle1Move=Rotate
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle2Move=Rotate
-DialGadget\Deluxe%20Baro%20Altimeter\data\needle3Move=Rotate
-DialGadget\Deluxe%20Baro%20Altimeter\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Deluxe%20Baro%20Altimeter\data\useOpenGLFlag=false
-DialGadget\Deluxe%20Baro%20Altimeter\data\beSmooth=false
-DialGadget\Deluxe%20Baro%20Altimeter\configInfo\version=0.0.0
-DialGadget\Deluxe%20Baro%20Altimeter\configInfo\locked=false
-DialGadget\Deluxe%20Barometer\data\dialFile=%%DATAPATH%%dials/deluxe/barometer.svg
-DialGadget\Deluxe%20Barometer\data\dialBackgroundID=background
-DialGadget\Deluxe%20Barometer\data\dialForegroundID=foreground
-DialGadget\Deluxe%20Barometer\data\dialNeedleID1=needle
-DialGadget\Deluxe%20Barometer\data\dialNeedleID2=
-DialGadget\Deluxe%20Barometer\data\dialNeedleID3=
-DialGadget\Deluxe%20Barometer\data\needle1MinValue=1000
-DialGadget\Deluxe%20Barometer\data\needle1MaxValue=1120
-DialGadget\Deluxe%20Barometer\data\needle2MinValue=0
-DialGadget\Deluxe%20Barometer\data\needle2MaxValue=100
-DialGadget\Deluxe%20Barometer\data\needle3MinValue=0
-DialGadget\Deluxe%20Barometer\data\needle3MaxValue=1000
-DialGadget\Deluxe%20Barometer\data\needle1DataObject=BaroAltitude
-DialGadget\Deluxe%20Barometer\data\needle1ObjectField=Pressure
-DialGadget\Deluxe%20Barometer\data\needle2DataObject=BaroAltitude
-DialGadget\Deluxe%20Barometer\data\needle2ObjectField=Altitude
-DialGadget\Deluxe%20Barometer\data\needle3DataObject=BaroAltitude
-DialGadget\Deluxe%20Barometer\data\needle3ObjectField=Altitude
-DialGadget\Deluxe%20Barometer\data\needle1Factor=10
-DialGadget\Deluxe%20Barometer\data\needle2Factor=1
-DialGadget\Deluxe%20Barometer\data\needle3Factor=1
-DialGadget\Deluxe%20Barometer\data\needle1Move=Rotate
-DialGadget\Deluxe%20Barometer\data\needle2Move=Rotate
-DialGadget\Deluxe%20Barometer\data\needle3Move=Rotate
-DialGadget\Deluxe%20Barometer\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Deluxe%20Barometer\data\useOpenGLFlag=false
-DialGadget\Deluxe%20Barometer\data\beSmooth=false
-DialGadget\Deluxe%20Barometer\configInfo\version=0.0.0
-DialGadget\Deluxe%20Barometer\configInfo\locked=false
-DialGadget\Deluxe%20Climbrate\data\dialFile=%%DATAPATH%%dials/deluxe/vsi.svg
-DialGadget\Deluxe%20Climbrate\data\dialBackgroundID=background
-DialGadget\Deluxe%20Climbrate\data\dialForegroundID=foreground
-DialGadget\Deluxe%20Climbrate\data\dialNeedleID1=needle
-DialGadget\Deluxe%20Climbrate\data\dialNeedleID2=
-DialGadget\Deluxe%20Climbrate\data\dialNeedleID3=
-DialGadget\Deluxe%20Climbrate\data\needle1MinValue=-11.2
-DialGadget\Deluxe%20Climbrate\data\needle1MaxValue=11.2
-DialGadget\Deluxe%20Climbrate\data\needle2MinValue=0
-DialGadget\Deluxe%20Climbrate\data\needle2MaxValue=100
-DialGadget\Deluxe%20Climbrate\data\needle3MinValue=0
-DialGadget\Deluxe%20Climbrate\data\needle3MaxValue=1000
-DialGadget\Deluxe%20Climbrate\data\needle1DataObject=VelocityActual
-DialGadget\Deluxe%20Climbrate\data\needle1ObjectField=Down
-DialGadget\Deluxe%20Climbrate\data\needle2DataObject=BaroAltitude
-DialGadget\Deluxe%20Climbrate\data\needle2ObjectField=Altitude
-DialGadget\Deluxe%20Climbrate\data\needle3DataObject=BaroAltitude
-DialGadget\Deluxe%20Climbrate\data\needle3ObjectField=Altitude
-DialGadget\Deluxe%20Climbrate\data\needle1Factor=0.01
-DialGadget\Deluxe%20Climbrate\data\needle2Factor=1
-DialGadget\Deluxe%20Climbrate\data\needle3Factor=1
-DialGadget\Deluxe%20Climbrate\data\needle1Move=Rotate
-DialGadget\Deluxe%20Climbrate\data\needle2Move=Rotate
-DialGadget\Deluxe%20Climbrate\data\needle3Move=Rotate
-DialGadget\Deluxe%20Climbrate\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Deluxe%20Climbrate\data\useOpenGLFlag=false
-DialGadget\Deluxe%20Climbrate\data\beSmooth=false
-DialGadget\Deluxe%20Climbrate\configInfo\version=0.0.0
-DialGadget\Deluxe%20Climbrate\configInfo\locked=false
-DialGadget\Deluxe%20Compass\data\dialFile=%%DATAPATH%%dials/deluxe/compass.svg
-DialGadget\Deluxe%20Compass\data\dialBackgroundID=background
-DialGadget\Deluxe%20Compass\data\dialForegroundID=foreground
-DialGadget\Deluxe%20Compass\data\dialNeedleID1=needle
-DialGadget\Deluxe%20Compass\data\dialNeedleID2=
-DialGadget\Deluxe%20Compass\data\dialNeedleID3=
-DialGadget\Deluxe%20Compass\data\needle1MinValue=0
-DialGadget\Deluxe%20Compass\data\needle1MaxValue=360
-DialGadget\Deluxe%20Compass\data\needle2MinValue=0
-DialGadget\Deluxe%20Compass\data\needle2MaxValue=100
-DialGadget\Deluxe%20Compass\data\needle3MinValue=0
-DialGadget\Deluxe%20Compass\data\needle3MaxValue=1000
-DialGadget\Deluxe%20Compass\data\needle1DataObject=AttitudeActual
-DialGadget\Deluxe%20Compass\data\needle1ObjectField=Yaw
-DialGadget\Deluxe%20Compass\data\needle2DataObject=BaroAltitude
-DialGadget\Deluxe%20Compass\data\needle2ObjectField=Altitude
-DialGadget\Deluxe%20Compass\data\needle3DataObject=BaroAltitude
-DialGadget\Deluxe%20Compass\data\needle3ObjectField=Altitude
-DialGadget\Deluxe%20Compass\data\needle1Factor=-1
-DialGadget\Deluxe%20Compass\data\needle2Factor=1
-DialGadget\Deluxe%20Compass\data\needle3Factor=1
-DialGadget\Deluxe%20Compass\data\needle1Move=Rotate
-DialGadget\Deluxe%20Compass\data\needle2Move=Rotate
-DialGadget\Deluxe%20Compass\data\needle3Move=Rotate
-DialGadget\Deluxe%20Compass\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Deluxe%20Compass\data\useOpenGLFlag=false
-DialGadget\Deluxe%20Compass\data\beSmooth=false
-DialGadget\Deluxe%20Compass\configInfo\version=0.0.0
-DialGadget\Deluxe%20Compass\configInfo\locked=false
-DialGadget\Deluxe%20Groundspeed%20kph\data\dialFile=%%DATAPATH%%dials/deluxe/speed.svg
-DialGadget\Deluxe%20Groundspeed%20kph\data\dialBackgroundID=background
-DialGadget\Deluxe%20Groundspeed%20kph\data\dialForegroundID=foreground
-DialGadget\Deluxe%20Groundspeed%20kph\data\dialNeedleID1=needle
-DialGadget\Deluxe%20Groundspeed%20kph\data\dialNeedleID2=
-DialGadget\Deluxe%20Groundspeed%20kph\data\dialNeedleID3=
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle1MinValue=0
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle1MaxValue=120
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle2MinValue=0
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle2MaxValue=100
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle3MinValue=0
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle3MaxValue=1000
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle1DataObject=GPSPosition
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle1ObjectField=Groundspeed
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle2DataObject=BaroAltitude
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle2ObjectField=Altitude
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle3DataObject=BaroAltitude
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle3ObjectField=Altitude
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle1Factor=3.6
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle2Factor=1
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle3Factor=1
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle1Move=Rotate
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle2Move=Rotate
-DialGadget\Deluxe%20Groundspeed%20kph\data\needle3Move=Rotate
-DialGadget\Deluxe%20Groundspeed%20kph\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Deluxe%20Groundspeed%20kph\data\useOpenGLFlag=false
-DialGadget\Deluxe%20Groundspeed%20kph\data\beSmooth=false
-DialGadget\Deluxe%20Groundspeed%20kph\configInfo\version=0.0.0
-DialGadget\Deluxe%20Groundspeed%20kph\configInfo\locked=false
-DialGadget\Deluxe%20Temperature\data\dialFile=%%DATAPATH%%dials/deluxe/thermometer.svg
-DialGadget\Deluxe%20Temperature\data\dialBackgroundID=background
-DialGadget\Deluxe%20Temperature\data\dialForegroundID=foreground
-DialGadget\Deluxe%20Temperature\data\dialNeedleID1=needle
-DialGadget\Deluxe%20Temperature\data\dialNeedleID2=needle2
-DialGadget\Deluxe%20Temperature\data\dialNeedleID3=needle3
-DialGadget\Deluxe%20Temperature\data\needle1MinValue=0
-DialGadget\Deluxe%20Temperature\data\needle1MaxValue=120
-DialGadget\Deluxe%20Temperature\data\needle2MinValue=0
-DialGadget\Deluxe%20Temperature\data\needle2MaxValue=100
-DialGadget\Deluxe%20Temperature\data\needle3MinValue=0
-DialGadget\Deluxe%20Temperature\data\needle3MaxValue=1000
-DialGadget\Deluxe%20Temperature\data\needle1DataObject=BaroAltitude
-DialGadget\Deluxe%20Temperature\data\needle1ObjectField=Temperature
-DialGadget\Deluxe%20Temperature\data\needle2DataObject=BaroAltitude
-DialGadget\Deluxe%20Temperature\data\needle2ObjectField=Altitude
-DialGadget\Deluxe%20Temperature\data\needle3DataObject=BaroAltitude
-DialGadget\Deluxe%20Temperature\data\needle3ObjectField=Altitude
-DialGadget\Deluxe%20Temperature\data\needle1Factor=1
-DialGadget\Deluxe%20Temperature\data\needle2Factor=1
-DialGadget\Deluxe%20Temperature\data\needle3Factor=1
-DialGadget\Deluxe%20Temperature\data\needle1Move=Rotate
-DialGadget\Deluxe%20Temperature\data\needle2Move=Rotate
-DialGadget\Deluxe%20Temperature\data\needle3Move=Rotate
-DialGadget\Deluxe%20Temperature\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Deluxe%20Temperature\data\useOpenGLFlag=false
-DialGadget\Deluxe%20Temperature\data\beSmooth=false
-DialGadget\Deluxe%20Temperature\configInfo\version=0.0.0
-DialGadget\Deluxe%20Temperature\configInfo\locked=false
-DialGadget\Deluxe%20Turn%20Coordinator\data\dialFile=/home/lafargue/OP/OpenPilot/trunk/artwork/Dials/deluxe/turncoordinator.svg
-DialGadget\Deluxe%20Turn%20Coordinator\data\dialBackgroundID=background
-DialGadget\Deluxe%20Turn%20Coordinator\data\dialForegroundID=foreground
-DialGadget\Deluxe%20Turn%20Coordinator\data\dialNeedleID1=needle
-DialGadget\Deluxe%20Turn%20Coordinator\data\dialNeedleID2=needle2
-DialGadget\Deluxe%20Turn%20Coordinator\data\dialNeedleID3=needle2
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle1MinValue=0
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle1MaxValue=360
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle2MinValue=-20
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle2MaxValue=20
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle3MinValue=0
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle3MaxValue=360
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle1DataObject=AttitudeActual
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle1ObjectField=Roll
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle2DataObject=AttitudeRaw
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle2ObjectField=accels-X
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle3DataObject=AttitudeRaw
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle3ObjectField=accels-X
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle1Factor=-1
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle2Factor=1
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle3Factor=-1
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle1Move=Rotate
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle2Move=Horizontal
-DialGadget\Deluxe%20Turn%20Coordinator\data\needle3Move=Rotate
-DialGadget\Deluxe%20Turn%20Coordinator\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Deluxe%20Turn%20Coordinator\data\useOpenGLFlag=false
-DialGadget\Deluxe%20Turn%20Coordinator\data\beSmooth=false
-DialGadget\Deluxe%20Turn%20Coordinator\configInfo\version=0.0.0
-DialGadget\Deluxe%20Turn%20Coordinator\configInfo\locked=false
-DialGadget\Groundspeed%20kph\data\dialFile=%%DATAPATH%%dials/default/speed.svg
-DialGadget\Groundspeed%20kph\data\dialBackgroundID=background
-DialGadget\Groundspeed%20kph\data\dialForegroundID=
-DialGadget\Groundspeed%20kph\data\dialNeedleID1=needle
-DialGadget\Groundspeed%20kph\data\dialNeedleID2=
-DialGadget\Groundspeed%20kph\data\dialNeedleID3=
-DialGadget\Groundspeed%20kph\data\needle1MinValue=0
-DialGadget\Groundspeed%20kph\data\needle1MaxValue=120
-DialGadget\Groundspeed%20kph\data\needle2MinValue=0
-DialGadget\Groundspeed%20kph\data\needle2MaxValue=100
-DialGadget\Groundspeed%20kph\data\needle3MinValue=0
-DialGadget\Groundspeed%20kph\data\needle3MaxValue=1000
-DialGadget\Groundspeed%20kph\data\needle1DataObject=GPSPosition
-DialGadget\Groundspeed%20kph\data\needle1ObjectField=Groundspeed
-DialGadget\Groundspeed%20kph\data\needle2DataObject=BaroAltitude
-DialGadget\Groundspeed%20kph\data\needle2ObjectField=Altitude
-DialGadget\Groundspeed%20kph\data\needle3DataObject=BaroAltitude
-DialGadget\Groundspeed%20kph\data\needle3ObjectField=Altitude
-DialGadget\Groundspeed%20kph\data\needle1Factor=3.6
-DialGadget\Groundspeed%20kph\data\needle2Factor=1
-DialGadget\Groundspeed%20kph\data\needle3Factor=1
-DialGadget\Groundspeed%20kph\data\needle1Move=Rotate
-DialGadget\Groundspeed%20kph\data\needle2Move=Rotate
-DialGadget\Groundspeed%20kph\data\needle3Move=Rotate
-DialGadget\Groundspeed%20kph\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Groundspeed%20kph\data\useOpenGLFlag=false
-DialGadget\Groundspeed%20kph\data\beSmooth=false
-DialGadget\Groundspeed%20kph\configInfo\version=0.0.0
-DialGadget\Groundspeed%20kph\configInfo\locked=false
-DialGadget\HiContrast%20Attitude\data\dialFile=%%DATAPATH%%dials/hi-contrast/attitude.svg
-DialGadget\HiContrast%20Attitude\data\dialBackgroundID=background
-DialGadget\HiContrast%20Attitude\data\dialForegroundID=foreground
-DialGadget\HiContrast%20Attitude\data\dialNeedleID1=needle
-DialGadget\HiContrast%20Attitude\data\dialNeedleID2=needle
-DialGadget\HiContrast%20Attitude\data\dialNeedleID3=needle3
-DialGadget\HiContrast%20Attitude\data\needle1MinValue=0
-DialGadget\HiContrast%20Attitude\data\needle1MaxValue=360
-DialGadget\HiContrast%20Attitude\data\needle2MinValue=0
-DialGadget\HiContrast%20Attitude\data\needle2MaxValue=20
-DialGadget\HiContrast%20Attitude\data\needle3MinValue=0
-DialGadget\HiContrast%20Attitude\data\needle3MaxValue=360
-DialGadget\HiContrast%20Attitude\data\needle1DataObject=AttitudeActual
-DialGadget\HiContrast%20Attitude\data\needle1ObjectField=Roll
-DialGadget\HiContrast%20Attitude\data\needle2DataObject=AttitudeActual
-DialGadget\HiContrast%20Attitude\data\needle2ObjectField=Pitch
-DialGadget\HiContrast%20Attitude\data\needle3DataObject=AttitudeActual
-DialGadget\HiContrast%20Attitude\data\needle3ObjectField=Roll
-DialGadget\HiContrast%20Attitude\data\needle1Factor=-1
-DialGadget\HiContrast%20Attitude\data\needle2Factor=75
-DialGadget\HiContrast%20Attitude\data\needle3Factor=-1
-DialGadget\HiContrast%20Attitude\data\needle1Move=Rotate
-DialGadget\HiContrast%20Attitude\data\needle2Move=Vertical
-DialGadget\HiContrast%20Attitude\data\needle3Move=Rotate
-DialGadget\HiContrast%20Attitude\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\HiContrast%20Attitude\data\useOpenGLFlag=false
-DialGadget\HiContrast%20Attitude\data\beSmooth=false
-DialGadget\HiContrast%20Attitude\configInfo\version=0.0.0
-DialGadget\HiContrast%20Attitude\configInfo\locked=false
-DialGadget\HiContrast%20Baro%20Altimeter\data\dialFile=%%DATAPATH%%dials/hi-contrast/altimeter.svg
-DialGadget\HiContrast%20Baro%20Altimeter\data\dialBackgroundID=background
-DialGadget\HiContrast%20Baro%20Altimeter\data\dialForegroundID=foreground
-DialGadget\HiContrast%20Baro%20Altimeter\data\dialNeedleID1=needle
-DialGadget\HiContrast%20Baro%20Altimeter\data\dialNeedleID2=needle2
-DialGadget\HiContrast%20Baro%20Altimeter\data\dialNeedleID3=needle3
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle1MinValue=0
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle1MaxValue=10
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle2MinValue=0
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle2MaxValue=100
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle3MinValue=0
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle3MaxValue=1000
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle1DataObject=BaroAltitude
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle1ObjectField=Altitude
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle2DataObject=BaroAltitude
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle2ObjectField=Altitude
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle3DataObject=BaroAltitude
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle3ObjectField=Altitude
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle1Factor=1
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle2Factor=1
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle3Factor=1
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle1Move=Rotate
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle2Move=Rotate
-DialGadget\HiContrast%20Baro%20Altimeter\data\needle3Move=Rotate
-DialGadget\HiContrast%20Baro%20Altimeter\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\HiContrast%20Baro%20Altimeter\data\useOpenGLFlag=false
-DialGadget\HiContrast%20Baro%20Altimeter\data\beSmooth=false
-DialGadget\HiContrast%20Baro%20Altimeter\configInfo\version=0.0.0
-DialGadget\HiContrast%20Baro%20Altimeter\configInfo\locked=false
-DialGadget\HiContrast%20Barometer\data\dialFile=%%DATAPATH%%dials/hi-contrast/barometer.svg
-DialGadget\HiContrast%20Barometer\data\dialBackgroundID=background
-DialGadget\HiContrast%20Barometer\data\dialForegroundID=
-DialGadget\HiContrast%20Barometer\data\dialNeedleID1=needle
-DialGadget\HiContrast%20Barometer\data\dialNeedleID2=
-DialGadget\HiContrast%20Barometer\data\dialNeedleID3=
-DialGadget\HiContrast%20Barometer\data\needle1MinValue=1000
-DialGadget\HiContrast%20Barometer\data\needle1MaxValue=1120
-DialGadget\HiContrast%20Barometer\data\needle2MinValue=0
-DialGadget\HiContrast%20Barometer\data\needle2MaxValue=100
-DialGadget\HiContrast%20Barometer\data\needle3MinValue=0
-DialGadget\HiContrast%20Barometer\data\needle3MaxValue=1000
-DialGadget\HiContrast%20Barometer\data\needle1DataObject=BaroAltitude
-DialGadget\HiContrast%20Barometer\data\needle1ObjectField=Pressure
-DialGadget\HiContrast%20Barometer\data\needle2DataObject=BaroAltitude
-DialGadget\HiContrast%20Barometer\data\needle2ObjectField=Altitude
-DialGadget\HiContrast%20Barometer\data\needle3DataObject=BaroAltitude
-DialGadget\HiContrast%20Barometer\data\needle3ObjectField=Altitude
-DialGadget\HiContrast%20Barometer\data\needle1Factor=10
-DialGadget\HiContrast%20Barometer\data\needle2Factor=1
-DialGadget\HiContrast%20Barometer\data\needle3Factor=1
-DialGadget\HiContrast%20Barometer\data\needle1Move=Rotate
-DialGadget\HiContrast%20Barometer\data\needle2Move=Rotate
-DialGadget\HiContrast%20Barometer\data\needle3Move=Rotate
-DialGadget\HiContrast%20Barometer\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\HiContrast%20Barometer\data\useOpenGLFlag=false
-DialGadget\HiContrast%20Barometer\data\beSmooth=false
-DialGadget\HiContrast%20Barometer\configInfo\version=0.0.0
-DialGadget\HiContrast%20Barometer\configInfo\locked=false
-DialGadget\HiContrast%20Climbrate\data\dialFile=%%DATAPATH%%dials/hi-contrast/vsi.svg
-DialGadget\HiContrast%20Climbrate\data\dialBackgroundID=background
-DialGadget\HiContrast%20Climbrate\data\dialForegroundID=
-DialGadget\HiContrast%20Climbrate\data\dialNeedleID1=needle
-DialGadget\HiContrast%20Climbrate\data\dialNeedleID2=
-DialGadget\HiContrast%20Climbrate\data\dialNeedleID3=
-DialGadget\HiContrast%20Climbrate\data\needle1MinValue=-12
-DialGadget\HiContrast%20Climbrate\data\needle1MaxValue=12
-DialGadget\HiContrast%20Climbrate\data\needle2MinValue=0
-DialGadget\HiContrast%20Climbrate\data\needle2MaxValue=100
-DialGadget\HiContrast%20Climbrate\data\needle3MinValue=0
-DialGadget\HiContrast%20Climbrate\data\needle3MaxValue=1000
-DialGadget\HiContrast%20Climbrate\data\needle1DataObject=VelocityActual
-DialGadget\HiContrast%20Climbrate\data\needle1ObjectField=Down
-DialGadget\HiContrast%20Climbrate\data\needle2DataObject=BaroAltitude
-DialGadget\HiContrast%20Climbrate\data\needle2ObjectField=Altitude
-DialGadget\HiContrast%20Climbrate\data\needle3DataObject=BaroAltitude
-DialGadget\HiContrast%20Climbrate\data\needle3ObjectField=Altitude
-DialGadget\HiContrast%20Climbrate\data\needle1Factor=0.01
-DialGadget\HiContrast%20Climbrate\data\needle2Factor=1
-DialGadget\HiContrast%20Climbrate\data\needle3Factor=1
-DialGadget\HiContrast%20Climbrate\data\needle1Move=Rotate
-DialGadget\HiContrast%20Climbrate\data\needle2Move=Rotate
-DialGadget\HiContrast%20Climbrate\data\needle3Move=Rotate
-DialGadget\HiContrast%20Climbrate\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\HiContrast%20Climbrate\data\useOpenGLFlag=false
-DialGadget\HiContrast%20Climbrate\data\beSmooth=false
-DialGadget\HiContrast%20Climbrate\configInfo\version=0.0.0
-DialGadget\HiContrast%20Climbrate\configInfo\locked=false
-DialGadget\HiContrast%20Compass\data\dialFile=%%DATAPATH%%dials/hi-contrast/compass.svg
-DialGadget\HiContrast%20Compass\data\dialBackgroundID=background
-DialGadget\HiContrast%20Compass\data\dialForegroundID=foreground
-DialGadget\HiContrast%20Compass\data\dialNeedleID1=needle
-DialGadget\HiContrast%20Compass\data\dialNeedleID2=
-DialGadget\HiContrast%20Compass\data\dialNeedleID3=
-DialGadget\HiContrast%20Compass\data\needle1MinValue=0
-DialGadget\HiContrast%20Compass\data\needle1MaxValue=360
-DialGadget\HiContrast%20Compass\data\needle2MinValue=0
-DialGadget\HiContrast%20Compass\data\needle2MaxValue=100
-DialGadget\HiContrast%20Compass\data\needle3MinValue=0
-DialGadget\HiContrast%20Compass\data\needle3MaxValue=1000
-DialGadget\HiContrast%20Compass\data\needle1DataObject=AttitudeActual
-DialGadget\HiContrast%20Compass\data\needle1ObjectField=Yaw
-DialGadget\HiContrast%20Compass\data\needle2DataObject=BaroAltitude
-DialGadget\HiContrast%20Compass\data\needle2ObjectField=Altitude
-DialGadget\HiContrast%20Compass\data\needle3DataObject=BaroAltitude
-DialGadget\HiContrast%20Compass\data\needle3ObjectField=Altitude
-DialGadget\HiContrast%20Compass\data\needle1Factor=-1
-DialGadget\HiContrast%20Compass\data\needle2Factor=1
-DialGadget\HiContrast%20Compass\data\needle3Factor=1
-DialGadget\HiContrast%20Compass\data\needle1Move=Rotate
-DialGadget\HiContrast%20Compass\data\needle2Move=Rotate
-DialGadget\HiContrast%20Compass\data\needle3Move=Rotate
-DialGadget\HiContrast%20Compass\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\HiContrast%20Compass\data\useOpenGLFlag=false
-DialGadget\HiContrast%20Compass\data\beSmooth=false
-DialGadget\HiContrast%20Compass\configInfo\version=0.0.0
-DialGadget\HiContrast%20Compass\configInfo\locked=false
-DialGadget\HiContrast%20Groundspeed%20kph\data\dialFile=%%DATAPATH%%dials/hi-contrast/speed.svg
-DialGadget\HiContrast%20Groundspeed%20kph\data\dialBackgroundID=background
-DialGadget\HiContrast%20Groundspeed%20kph\data\dialForegroundID=
-DialGadget\HiContrast%20Groundspeed%20kph\data\dialNeedleID1=needle
-DialGadget\HiContrast%20Groundspeed%20kph\data\dialNeedleID2=
-DialGadget\HiContrast%20Groundspeed%20kph\data\dialNeedleID3=
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle1MinValue=0
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle1MaxValue=120
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle2MinValue=0
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle2MaxValue=100
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle3MinValue=0
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle3MaxValue=1000
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle1DataObject=GPSPosition
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle1ObjectField=Groundspeed
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle2DataObject=BaroAltitude
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle2ObjectField=Altitude
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle3DataObject=BaroAltitude
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle3ObjectField=Altitude
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle1Factor=3.6
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle2Factor=1
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle3Factor=1
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle1Move=Rotate
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle2Move=Rotate
-DialGadget\HiContrast%20Groundspeed%20kph\data\needle3Move=Rotate
-DialGadget\HiContrast%20Groundspeed%20kph\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\HiContrast%20Groundspeed%20kph\data\useOpenGLFlag=false
-DialGadget\HiContrast%20Groundspeed%20kph\data\beSmooth=false
-DialGadget\HiContrast%20Groundspeed%20kph\configInfo\version=0.0.0
-DialGadget\HiContrast%20Groundspeed%20kph\configInfo\locked=false
-DialGadget\HiContrast%20Temperature\data\dialFile=%%DATAPATH%%dials/hi-contrast/thermometer.svg
-DialGadget\HiContrast%20Temperature\data\dialBackgroundID=background
-DialGadget\HiContrast%20Temperature\data\dialForegroundID=
-DialGadget\HiContrast%20Temperature\data\dialNeedleID1=needle
-DialGadget\HiContrast%20Temperature\data\dialNeedleID2=needle2
-DialGadget\HiContrast%20Temperature\data\dialNeedleID3=needle3
-DialGadget\HiContrast%20Temperature\data\needle1MinValue=0
-DialGadget\HiContrast%20Temperature\data\needle1MaxValue=120
-DialGadget\HiContrast%20Temperature\data\needle2MinValue=0
-DialGadget\HiContrast%20Temperature\data\needle2MaxValue=100
-DialGadget\HiContrast%20Temperature\data\needle3MinValue=0
-DialGadget\HiContrast%20Temperature\data\needle3MaxValue=1000
-DialGadget\HiContrast%20Temperature\data\needle1DataObject=BaroAltitude
-DialGadget\HiContrast%20Temperature\data\needle1ObjectField=Temperature
-DialGadget\HiContrast%20Temperature\data\needle2DataObject=BaroAltitude
-DialGadget\HiContrast%20Temperature\data\needle2ObjectField=Altitude
-DialGadget\HiContrast%20Temperature\data\needle3DataObject=BaroAltitude
-DialGadget\HiContrast%20Temperature\data\needle3ObjectField=Altitude
-DialGadget\HiContrast%20Temperature\data\needle1Factor=1
-DialGadget\HiContrast%20Temperature\data\needle2Factor=1
-DialGadget\HiContrast%20Temperature\data\needle3Factor=1
-DialGadget\HiContrast%20Temperature\data\needle1Move=Rotate
-DialGadget\HiContrast%20Temperature\data\needle2Move=Rotate
-DialGadget\HiContrast%20Temperature\data\needle3Move=Rotate
-DialGadget\HiContrast%20Temperature\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\HiContrast%20Temperature\data\useOpenGLFlag=false
-DialGadget\HiContrast%20Temperature\data\beSmooth=false
-DialGadget\HiContrast%20Temperature\configInfo\version=0.0.0
-DialGadget\HiContrast%20Temperature\configInfo\locked=false
-DialGadget\Servo%20Channel%201\data\dialFile=%%DATAPATH%%dials/default/thermometer.svg
-DialGadget\Servo%20Channel%201\data\dialBackgroundID=background
-DialGadget\Servo%20Channel%201\data\dialForegroundID=
-DialGadget\Servo%20Channel%201\data\dialNeedleID1=needle
-DialGadget\Servo%20Channel%201\data\dialNeedleID2=needle2
-DialGadget\Servo%20Channel%201\data\dialNeedleID3=needle3
-DialGadget\Servo%20Channel%201\data\needle1MinValue=1000
-DialGadget\Servo%20Channel%201\data\needle1MaxValue=2000
-DialGadget\Servo%20Channel%201\data\needle2MinValue=0
-DialGadget\Servo%20Channel%201\data\needle2MaxValue=100
-DialGadget\Servo%20Channel%201\data\needle3MinValue=0
-DialGadget\Servo%20Channel%201\data\needle3MaxValue=1000
-DialGadget\Servo%20Channel%201\data\needle1DataObject=ManualControlCommand
-DialGadget\Servo%20Channel%201\data\needle1ObjectField=Channel-3
-DialGadget\Servo%20Channel%201\data\needle2DataObject=BaroAltitude
-DialGadget\Servo%20Channel%201\data\needle2ObjectField=Altitude
-DialGadget\Servo%20Channel%201\data\needle3DataObject=BaroAltitude
-DialGadget\Servo%20Channel%201\data\needle3ObjectField=Altitude
-DialGadget\Servo%20Channel%201\data\needle1Factor=1
-DialGadget\Servo%20Channel%201\data\needle2Factor=1
-DialGadget\Servo%20Channel%201\data\needle3Factor=1
-DialGadget\Servo%20Channel%201\data\needle1Move=Rotate
-DialGadget\Servo%20Channel%201\data\needle2Move=Rotate
-DialGadget\Servo%20Channel%201\data\needle3Move=Rotate
-DialGadget\Servo%20Channel%201\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Servo%20Channel%201\data\useOpenGLFlag=false
-DialGadget\Servo%20Channel%201\data\beSmooth=false
-DialGadget\Servo%20Channel%201\configInfo\version=0.0.0
-DialGadget\Servo%20Channel%201\configInfo\locked=false
-DialGadget\Temperature\data\dialFile=%%DATAPATH%%dials/default/thermometer.svg
-DialGadget\Temperature\data\dialBackgroundID=background
-DialGadget\Temperature\data\dialForegroundID=
-DialGadget\Temperature\data\dialNeedleID1=needle
-DialGadget\Temperature\data\dialNeedleID2=needle2
-DialGadget\Temperature\data\dialNeedleID3=needle3
-DialGadget\Temperature\data\needle1MinValue=0
-DialGadget\Temperature\data\needle1MaxValue=120
-DialGadget\Temperature\data\needle2MinValue=0
-DialGadget\Temperature\data\needle2MaxValue=100
-DialGadget\Temperature\data\needle3MinValue=0
-DialGadget\Temperature\data\needle3MaxValue=1000
-DialGadget\Temperature\data\needle1DataObject=BaroAltitude
-DialGadget\Temperature\data\needle1ObjectField=Temperature
-DialGadget\Temperature\data\needle2DataObject=BaroAltitude
-DialGadget\Temperature\data\needle2ObjectField=Altitude
-DialGadget\Temperature\data\needle3DataObject=BaroAltitude
-DialGadget\Temperature\data\needle3ObjectField=Altitude
-DialGadget\Temperature\data\needle1Factor=1
-DialGadget\Temperature\data\needle2Factor=1
-DialGadget\Temperature\data\needle3Factor=1
-DialGadget\Temperature\data\needle1Move=Rotate
-DialGadget\Temperature\data\needle2Move=Rotate
-DialGadget\Temperature\data\needle3Move=Rotate
-DialGadget\Temperature\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0"
-DialGadget\Temperature\data\useOpenGLFlag=false
-DialGadget\Temperature\data\beSmooth=false
-DialGadget\Temperature\configInfo\version=0.0.0
-DialGadget\Temperature\configInfo\locked=false
-GCSControlGadget\MS%20Sidewinder\data\controlsMode=2
-GCSControlGadget\MS%20Sidewinder\data\rollChannel=0
-GCSControlGadget\MS%20Sidewinder\data\pitchChannel=1
-GCSControlGadget\MS%20Sidewinder\data\yawChannel=3
-GCSControlGadget\MS%20Sidewinder\data\throttleChannel=2
-GCSControlGadget\MS%20Sidewinder\data\button0Action=0
-GCSControlGadget\MS%20Sidewinder\data\button0Function=0
-GCSControlGadget\MS%20Sidewinder\data\button0Amount=0
-GCSControlGadget\MS%20Sidewinder\data\channel0Reverse=false
-GCSControlGadget\MS%20Sidewinder\data\button1Action=0
-GCSControlGadget\MS%20Sidewinder\data\button1Function=0
-GCSControlGadget\MS%20Sidewinder\data\button1Amount=0
-GCSControlGadget\MS%20Sidewinder\data\channel1Reverse=false
-GCSControlGadget\MS%20Sidewinder\data\button2Action=0
-GCSControlGadget\MS%20Sidewinder\data\button2Function=3
-GCSControlGadget\MS%20Sidewinder\data\button2Amount=0.1
-GCSControlGadget\MS%20Sidewinder\data\channel2Reverse=true
-GCSControlGadget\MS%20Sidewinder\data\button3Action=0
-GCSControlGadget\MS%20Sidewinder\data\button3Function=3
-GCSControlGadget\MS%20Sidewinder\data\button3Amount=0.1
-GCSControlGadget\MS%20Sidewinder\data\channel3Reverse=false
-GCSControlGadget\MS%20Sidewinder\data\button4Action=0
-GCSControlGadget\MS%20Sidewinder\data\button4Function=0
-GCSControlGadget\MS%20Sidewinder\data\button4Amount=0
-GCSControlGadget\MS%20Sidewinder\data\channel4Reverse=false
-GCSControlGadget\MS%20Sidewinder\data\button5Action=0
-GCSControlGadget\MS%20Sidewinder\data\button5Function=0
-GCSControlGadget\MS%20Sidewinder\data\button5Amount=0
-GCSControlGadget\MS%20Sidewinder\data\channel5Reverse=false
-GCSControlGadget\MS%20Sidewinder\data\button6Action=0
-GCSControlGadget\MS%20Sidewinder\data\button6Function=0
-GCSControlGadget\MS%20Sidewinder\data\button6Amount=0
-GCSControlGadget\MS%20Sidewinder\data\channel6Reverse=false
-GCSControlGadget\MS%20Sidewinder\data\button7Action=0
-GCSControlGadget\MS%20Sidewinder\data\button7Function=0
-GCSControlGadget\MS%20Sidewinder\data\button7Amount=0
-GCSControlGadget\MS%20Sidewinder\data\channel7Reverse=false
-GCSControlGadget\MS%20Sidewinder\configInfo\version=0.0.0
-GCSControlGadget\MS%20Sidewinder\configInfo\locked=false
-GpsDisplayGadget\Flight%20GPS\data\defaultSpeed=11
-GpsDisplayGadget\Flight%20GPS\data\defaultDataBits=3
-GpsDisplayGadget\Flight%20GPS\data\defaultFlow=0
-GpsDisplayGadget\Flight%20GPS\data\defaultParity=0
-GpsDisplayGadget\Flight%20GPS\data\defaultStopBits=0
-GpsDisplayGadget\Flight%20GPS\data\defaultPort=Serial port 0
-GpsDisplayGadget\Flight%20GPS\data\connectionMode=Telemetry
-GpsDisplayGadget\Flight%20GPS\configInfo\version=0.0.0
-GpsDisplayGadget\Flight%20GPS\configInfo\locked=false
-GpsDisplayGadget\GPS%20Mouse\data\defaultSpeed=17
-GpsDisplayGadget\GPS%20Mouse\data\defaultDataBits=3
-GpsDisplayGadget\GPS%20Mouse\data\defaultFlow=0
-GpsDisplayGadget\GPS%20Mouse\data\defaultParity=0
-GpsDisplayGadget\GPS%20Mouse\data\defaultStopBits=0
-GpsDisplayGadget\GPS%20Mouse\data\defaultPort=Serial port 0
-GpsDisplayGadget\GPS%20Mouse\data\connectionMode=Serial
-GpsDisplayGadget\GPS%20Mouse\configInfo\version=0.0.0
-GpsDisplayGadget\GPS%20Mouse\configInfo\locked=false
-HITL\Flightgear%20HITL\data\simulatorId=FG
-HITL\Flightgear%20HITL\data\binPath=/usr/games/fgfs
-HITL\Flightgear%20HITL\data\dataPath=/usr/share/games/FlightGear
-HITL\Flightgear%20HITL\data\manual=false
-HITL\Flightgear%20HITL\data\startSim=true
-HITL\Flightgear%20HITL\data\hostAddress=127.0.0.1
-HITL\Flightgear%20HITL\data\remoteHostAddress=127.0.0.1
-HITL\Flightgear%20HITL\data\outPort=9010
-HITL\Flightgear%20HITL\data\inPort=9009
-HITL\Flightgear%20HITL\data\latitude=
-HITL\Flightgear%20HITL\data\longitude=
-HITL\Flightgear%20HITL\configInfo\version=0.0.0
-HITL\Flightgear%20HITL\configInfo\locked=false
-HITL\XPlane%20HITL\data\simulatorId=X-Plane
-HITL\XPlane%20HITL\data\binPath=/home/lafargue/X-Plane 9/X-Plane-i686
-HITL\XPlane%20HITL\data\dataPath=/usr/share/games/FlightGear
-HITL\XPlane%20HITL\data\manual=false
-HITL\XPlane%20HITL\data\startSim=false
-HITL\XPlane%20HITL\data\hostAddress=127.0.0.3
-HITL\XPlane%20HITL\data\remoteHostAddress=127.0.0.1
-HITL\XPlane%20HITL\data\outPort=49000
-HITL\XPlane%20HITL\data\inPort=6756
-HITL\XPlane%20HITL\data\latitude=
-HITL\XPlane%20HITL\data\longitude=
-HITL\XPlane%20HITL\configInfo\version=0.0.0
-HITL\XPlane%20HITL\configInfo\locked=false
-ImportExportGadget\default\data\iniFile=gcs.ini
-ImportExportGadget\default\configInfo\version=1.0.1
-ImportExportGadget\default\configInfo\locked=false
-LineardialGadget\AHRS%20CPU\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
-LineardialGadget\AHRS%20CPU\data\sourceDataObject=AhrsStatus
-LineardialGadget\AHRS%20CPU\data\sourceObjectField=CPULoad
-LineardialGadget\AHRS%20CPU\data\minValue=0
-LineardialGadget\AHRS%20CPU\data\maxValue=100
-LineardialGadget\AHRS%20CPU\data\redMin=80
-LineardialGadget\AHRS%20CPU\data\redMax=100
-LineardialGadget\AHRS%20CPU\data\yellowMin=50
-LineardialGadget\AHRS%20CPU\data\yellowMax=80
-LineardialGadget\AHRS%20CPU\data\greenMin=0
-LineardialGadget\AHRS%20CPU\data\greenMax=50
-LineardialGadget\AHRS%20CPU\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
-LineardialGadget\AHRS%20CPU\data\decimalPlaces=0
-LineardialGadget\AHRS%20CPU\data\factor=1
-LineardialGadget\AHRS%20CPU\data\useOpenGLFlag=false
-LineardialGadget\AHRS%20CPU\configInfo\version=0.0.0
-LineardialGadget\AHRS%20CPU\configInfo\locked=false
-LineardialGadget\Accel%20Horizontal%20X\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg
-LineardialGadget\Accel%20Horizontal%20X\data\sourceDataObject=AttitudeRaw
-LineardialGadget\Accel%20Horizontal%20X\data\sourceObjectField=accels-X
-LineardialGadget\Accel%20Horizontal%20X\data\minValue=-11
-LineardialGadget\Accel%20Horizontal%20X\data\maxValue=11
-LineardialGadget\Accel%20Horizontal%20X\data\redMin=-11
-LineardialGadget\Accel%20Horizontal%20X\data\redMax=11
-LineardialGadget\Accel%20Horizontal%20X\data\yellowMin=-11
-LineardialGadget\Accel%20Horizontal%20X\data\yellowMax=-5
-LineardialGadget\Accel%20Horizontal%20X\data\greenMin=-10
-LineardialGadget\Accel%20Horizontal%20X\data\greenMax=-9
-LineardialGadget\Accel%20Horizontal%20X\data\font="Andale Mono,8,-1,5,50,0,0,0,0,0"
-LineardialGadget\Accel%20Horizontal%20X\data\decimalPlaces=2
-LineardialGadget\Accel%20Horizontal%20X\data\factor=1
-LineardialGadget\Accel%20Horizontal%20X\data\useOpenGLFlag=false
-LineardialGadget\Accel%20Horizontal%20X\configInfo\version=0.0.0
-LineardialGadget\Accel%20Horizontal%20X\configInfo\locked=false
-LineardialGadget\Accel%20Horizontal%20Y\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg
-LineardialGadget\Accel%20Horizontal%20Y\data\sourceDataObject=AttitudeRaw
-LineardialGadget\Accel%20Horizontal%20Y\data\sourceObjectField=accels-Y
-LineardialGadget\Accel%20Horizontal%20Y\data\minValue=-11
-LineardialGadget\Accel%20Horizontal%20Y\data\maxValue=11
-LineardialGadget\Accel%20Horizontal%20Y\data\redMin=-11
-LineardialGadget\Accel%20Horizontal%20Y\data\redMax=11
-LineardialGadget\Accel%20Horizontal%20Y\data\yellowMin=-11
-LineardialGadget\Accel%20Horizontal%20Y\data\yellowMax=-5
-LineardialGadget\Accel%20Horizontal%20Y\data\greenMin=-10
-LineardialGadget\Accel%20Horizontal%20Y\data\greenMax=-9
-LineardialGadget\Accel%20Horizontal%20Y\data\font="Andale Mono,6,-1,5,50,0,0,0,0,0"
-LineardialGadget\Accel%20Horizontal%20Y\data\decimalPlaces=2
-LineardialGadget\Accel%20Horizontal%20Y\data\factor=1
-LineardialGadget\Accel%20Horizontal%20Y\data\useOpenGLFlag=false
-LineardialGadget\Accel%20Horizontal%20Y\configInfo\version=0.0.0
-LineardialGadget\Accel%20Horizontal%20Y\configInfo\locked=false
-LineardialGadget\Accel%20Horizontal%20Z\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg
-LineardialGadget\Accel%20Horizontal%20Z\data\sourceDataObject=AttitudeRaw
-LineardialGadget\Accel%20Horizontal%20Z\data\sourceObjectField=accels-Z
-LineardialGadget\Accel%20Horizontal%20Z\data\minValue=-11
-LineardialGadget\Accel%20Horizontal%20Z\data\maxValue=11
-LineardialGadget\Accel%20Horizontal%20Z\data\redMin=-11
-LineardialGadget\Accel%20Horizontal%20Z\data\redMax=11
-LineardialGadget\Accel%20Horizontal%20Z\data\yellowMin=-11
-LineardialGadget\Accel%20Horizontal%20Z\data\yellowMax=-5
-LineardialGadget\Accel%20Horizontal%20Z\data\greenMin=-10
-LineardialGadget\Accel%20Horizontal%20Z\data\greenMax=-9
-LineardialGadget\Accel%20Horizontal%20Z\data\font="Andale Mono,8,-1,5,50,0,0,0,0,0"
-LineardialGadget\Accel%20Horizontal%20Z\data\decimalPlaces=2
-LineardialGadget\Accel%20Horizontal%20Z\data\factor=1
-LineardialGadget\Accel%20Horizontal%20Z\data\useOpenGLFlag=false
-LineardialGadget\Accel%20Horizontal%20Z\configInfo\version=0.0.0
-LineardialGadget\Accel%20Horizontal%20Z\configInfo\locked=false
-LineardialGadget\Arm%20Status\data\dFile=%%DATAPATH%%dials/default/arm-status.svg
-LineardialGadget\Arm%20Status\data\sourceDataObject=ManualControlCommand
-LineardialGadget\Arm%20Status\data\sourceObjectField=Armed
-LineardialGadget\Arm%20Status\data\minValue=0
-LineardialGadget\Arm%20Status\data\maxValue=100
-LineardialGadget\Arm%20Status\data\redMin=0
-LineardialGadget\Arm%20Status\data\redMax=33
-LineardialGadget\Arm%20Status\data\yellowMin=33
-LineardialGadget\Arm%20Status\data\yellowMax=66
-LineardialGadget\Arm%20Status\data\greenMin=66
-LineardialGadget\Arm%20Status\data\greenMax=100
-LineardialGadget\Arm%20Status\data\font=",12,-1,5,50,0,0,0,0,0"
-LineardialGadget\Arm%20Status\data\decimalPlaces=0
-LineardialGadget\Arm%20Status\data\factor=1
-LineardialGadget\Arm%20Status\data\useOpenGLFlag=false
-LineardialGadget\Arm%20Status\configInfo\version=0.0.0
-LineardialGadget\Arm%20Status\configInfo\locked=false
-LineardialGadget\Flight%20Time\data\dFile=%%DATAPATH%%dials/default/textonly.svg
-LineardialGadget\Flight%20Time\data\sourceDataObject=SystemStats
-LineardialGadget\Flight%20Time\data\sourceObjectField=FlightTime
-LineardialGadget\Flight%20Time\data\minValue=0
-LineardialGadget\Flight%20Time\data\maxValue=100
-LineardialGadget\Flight%20Time\data\redMin=0
-LineardialGadget\Flight%20Time\data\redMax=33
-LineardialGadget\Flight%20Time\data\yellowMin=33
-LineardialGadget\Flight%20Time\data\yellowMax=66
-LineardialGadget\Flight%20Time\data\greenMin=66
-LineardialGadget\Flight%20Time\data\greenMax=100
-LineardialGadget\Flight%20Time\data\font=",12,-1,5,50,0,0,0,0,0"
-LineardialGadget\Flight%20Time\data\decimalPlaces=0
-LineardialGadget\Flight%20Time\data\factor=0.001
-LineardialGadget\Flight%20Time\data\useOpenGLFlag=false
-LineardialGadget\Flight%20Time\configInfo\version=0.0.0
-LineardialGadget\Flight%20Time\configInfo\locked=false
-LineardialGadget\Flight%20mode\data\dFile=%%DATAPATH%%dials/default/flightmode-status.svg
-LineardialGadget\Flight%20mode\data\sourceDataObject=ManualControlCommand
-LineardialGadget\Flight%20mode\data\sourceObjectField=FlightMode
-LineardialGadget\Flight%20mode\data\minValue=0
-LineardialGadget\Flight%20mode\data\maxValue=100
-LineardialGadget\Flight%20mode\data\redMin=0
-LineardialGadget\Flight%20mode\data\redMax=33
-LineardialGadget\Flight%20mode\data\yellowMin=33
-LineardialGadget\Flight%20mode\data\yellowMax=66
-LineardialGadget\Flight%20mode\data\greenMin=66
-LineardialGadget\Flight%20mode\data\greenMax=100
-LineardialGadget\Flight%20mode\data\font=",12,-1,5,50,0,0,0,0,0"
-LineardialGadget\Flight%20mode\data\decimalPlaces=0
-LineardialGadget\Flight%20mode\data\factor=1
-LineardialGadget\Flight%20mode\data\useOpenGLFlag=false
-LineardialGadget\Flight%20mode\configInfo\version=0.0.0
-LineardialGadget\Flight%20mode\configInfo\locked=false
-LineardialGadget\GPS%20Sats\data\dFile=%%DATAPATH%%dials/default/gps-signal.svg
-LineardialGadget\GPS%20Sats\data\sourceDataObject=GPSPosition
-LineardialGadget\GPS%20Sats\data\sourceObjectField=Satellites
-LineardialGadget\GPS%20Sats\data\minValue=0
-LineardialGadget\GPS%20Sats\data\maxValue=12
-LineardialGadget\GPS%20Sats\data\redMin=0
-LineardialGadget\GPS%20Sats\data\redMax=0
-LineardialGadget\GPS%20Sats\data\yellowMin=0
-LineardialGadget\GPS%20Sats\data\yellowMax=0
-LineardialGadget\GPS%20Sats\data\greenMin=0
-LineardialGadget\GPS%20Sats\data\greenMax=0
-LineardialGadget\GPS%20Sats\data\font=",12,-1,5,50,0,0,0,0,0"
-LineardialGadget\GPS%20Sats\data\decimalPlaces=0
-LineardialGadget\GPS%20Sats\data\factor=1
-LineardialGadget\GPS%20Sats\data\useOpenGLFlag=false
-LineardialGadget\GPS%20Sats\configInfo\version=0.0.0
-LineardialGadget\GPS%20Sats\configInfo\locked=false
-LineardialGadget\GPS%20Status\data\dFile=%%DATAPATH%%dials/default/gps-status.svg
-LineardialGadget\GPS%20Status\data\sourceDataObject=GPSPosition
-LineardialGadget\GPS%20Status\data\sourceObjectField=Status
-LineardialGadget\GPS%20Status\data\minValue=0
-LineardialGadget\GPS%20Status\data\maxValue=100
-LineardialGadget\GPS%20Status\data\redMin=0
-LineardialGadget\GPS%20Status\data\redMax=33
-LineardialGadget\GPS%20Status\data\yellowMin=33
-LineardialGadget\GPS%20Status\data\yellowMax=66
-LineardialGadget\GPS%20Status\data\greenMin=66
-LineardialGadget\GPS%20Status\data\greenMax=100
-LineardialGadget\GPS%20Status\data\font=",12,-1,5,50,0,0,0,0,0"
-LineardialGadget\GPS%20Status\data\decimalPlaces=0
-LineardialGadget\GPS%20Status\data\factor=1
-LineardialGadget\GPS%20Status\data\useOpenGLFlag=false
-LineardialGadget\GPS%20Status\configInfo\version=0.0.0
-LineardialGadget\GPS%20Status\configInfo\locked=false
-LineardialGadget\Mainboard%20CPU\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
-LineardialGadget\Mainboard%20CPU\data\sourceDataObject=SystemStats
-LineardialGadget\Mainboard%20CPU\data\sourceObjectField=CPULoad
-LineardialGadget\Mainboard%20CPU\data\minValue=0
-LineardialGadget\Mainboard%20CPU\data\maxValue=100
-LineardialGadget\Mainboard%20CPU\data\redMin=80
-LineardialGadget\Mainboard%20CPU\data\redMax=100
-LineardialGadget\Mainboard%20CPU\data\yellowMin=50
-LineardialGadget\Mainboard%20CPU\data\yellowMax=80
-LineardialGadget\Mainboard%20CPU\data\greenMin=0
-LineardialGadget\Mainboard%20CPU\data\greenMax=50
-LineardialGadget\Mainboard%20CPU\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
-LineardialGadget\Mainboard%20CPU\data\decimalPlaces=0
-LineardialGadget\Mainboard%20CPU\data\factor=1
-LineardialGadget\Mainboard%20CPU\data\useOpenGLFlag=false
-LineardialGadget\Mainboard%20CPU\configInfo\version=0.0.0
-LineardialGadget\Mainboard%20CPU\configInfo\locked=false
-LineardialGadget\PitchActual\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
-LineardialGadget\PitchActual\data\sourceDataObject=AttitudeActual
-LineardialGadget\PitchActual\data\sourceObjectField=Pitch
-LineardialGadget\PitchActual\data\minValue=-90
-LineardialGadget\PitchActual\data\maxValue=90
-LineardialGadget\PitchActual\data\redMin=0
-LineardialGadget\PitchActual\data\redMax=1
-LineardialGadget\PitchActual\data\yellowMin=0.1
-LineardialGadget\PitchActual\data\yellowMax=0.9
-LineardialGadget\PitchActual\data\greenMin=0.3
-LineardialGadget\PitchActual\data\greenMax=0.8
-LineardialGadget\PitchActual\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
-LineardialGadget\PitchActual\data\decimalPlaces=2
-LineardialGadget\PitchActual\data\factor=1
-LineardialGadget\PitchActual\data\useOpenGLFlag=false
-LineardialGadget\PitchActual\configInfo\version=0.0.0
-LineardialGadget\PitchActual\configInfo\locked=false
-LineardialGadget\PitchCommand\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
-LineardialGadget\PitchCommand\data\sourceDataObject=ManualControlCommand
-LineardialGadget\PitchCommand\data\sourceObjectField=Pitch
-LineardialGadget\PitchCommand\data\minValue=-1
-LineardialGadget\PitchCommand\data\maxValue=1
-LineardialGadget\PitchCommand\data\redMin=0
-LineardialGadget\PitchCommand\data\redMax=1
-LineardialGadget\PitchCommand\data\yellowMin=0.1
-LineardialGadget\PitchCommand\data\yellowMax=0.9
-LineardialGadget\PitchCommand\data\greenMin=0.3
-LineardialGadget\PitchCommand\data\greenMax=0.8
-LineardialGadget\PitchCommand\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
-LineardialGadget\PitchCommand\data\decimalPlaces=2
-LineardialGadget\PitchCommand\data\factor=1
-LineardialGadget\PitchCommand\data\useOpenGLFlag=false
-LineardialGadget\PitchCommand\configInfo\version=0.0.0
-LineardialGadget\PitchCommand\configInfo\locked=false
-LineardialGadget\PitchDesired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
-LineardialGadget\PitchDesired\data\sourceDataObject=ActuatorDesired
-LineardialGadget\PitchDesired\data\sourceObjectField=Pitch
-LineardialGadget\PitchDesired\data\minValue=-1
-LineardialGadget\PitchDesired\data\maxValue=1
-LineardialGadget\PitchDesired\data\redMin=0
-LineardialGadget\PitchDesired\data\redMax=1
-LineardialGadget\PitchDesired\data\yellowMin=0.1
-LineardialGadget\PitchDesired\data\yellowMax=0.9
-LineardialGadget\PitchDesired\data\greenMin=0.3
-LineardialGadget\PitchDesired\data\greenMax=0.8
-LineardialGadget\PitchDesired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
-LineardialGadget\PitchDesired\data\decimalPlaces=2
-LineardialGadget\PitchDesired\data\factor=1
-LineardialGadget\PitchDesired\data\useOpenGLFlag=false
-LineardialGadget\PitchDesired\configInfo\version=0.0.0
-LineardialGadget\PitchDesired\configInfo\locked=false
-LineardialGadget\Roll\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
-LineardialGadget\Roll\data\sourceDataObject=ManualControlCommand
-LineardialGadget\Roll\data\sourceObjectField=Roll
-LineardialGadget\Roll\data\minValue=0
-LineardialGadget\Roll\data\maxValue=1
-LineardialGadget\Roll\data\redMin=0
-LineardialGadget\Roll\data\redMax=1
-LineardialGadget\Roll\data\yellowMin=0.1
-LineardialGadget\Roll\data\yellowMax=0.9
-LineardialGadget\Roll\data\greenMin=0.3
-LineardialGadget\Roll\data\greenMax=0.8
-LineardialGadget\Roll\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
-LineardialGadget\Roll\data\decimalPlaces=2
-LineardialGadget\Roll\data\factor=1
-LineardialGadget\Roll\data\useOpenGLFlag=false
-LineardialGadget\Roll\configInfo\version=0.0.0
-LineardialGadget\Roll\configInfo\locked=false
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\sourceDataObject=GCSTelemetryStats
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\sourceObjectField=RxDataRate
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\minValue=0
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\maxValue=1200
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\redMin=900
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\redMax=1200
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\yellowMin=650
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\yellowMax=900
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\greenMin=0
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\greenMax=650
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\decimalPlaces=0
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\factor=1
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\useOpenGLFlag=false
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\configInfo\version=0.0.0
-LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\configInfo\locked=false
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\sourceDataObject=GCSTelemetryStats
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\sourceObjectField=TxDataRate
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\minValue=0
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\maxValue=1200
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\redMin=900
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\redMax=1200
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\yellowMin=650
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\yellowMax=900
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\greenMin=0
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\greenMax=650
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\decimalPlaces=0
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\factor=1
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\useOpenGLFlag=false
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\configInfo\version=0.0.0
-LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\configInfo\locked=false
-LineardialGadget\Throttle\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
-LineardialGadget\Throttle\data\sourceDataObject=ManualControlCommand
-LineardialGadget\Throttle\data\sourceObjectField=Throttle
-LineardialGadget\Throttle\data\minValue=0
-LineardialGadget\Throttle\data\maxValue=1
-LineardialGadget\Throttle\data\redMin=0
-LineardialGadget\Throttle\data\redMax=1
-LineardialGadget\Throttle\data\yellowMin=0.1
-LineardialGadget\Throttle\data\yellowMax=0.9
-LineardialGadget\Throttle\data\greenMin=0.3
-LineardialGadget\Throttle\data\greenMax=0.8
-LineardialGadget\Throttle\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
-LineardialGadget\Throttle\data\decimalPlaces=2
-LineardialGadget\Throttle\data\factor=1
-LineardialGadget\Throttle\data\useOpenGLFlag=false
-LineardialGadget\Throttle\configInfo\version=0.0.0
-LineardialGadget\Throttle\configInfo\locked=false
-LineardialGadget\Yaw\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
-LineardialGadget\Yaw\data\sourceDataObject=ManualControlCommand
-LineardialGadget\Yaw\data\sourceObjectField=Yaw
-LineardialGadget\Yaw\data\minValue=0
-LineardialGadget\Yaw\data\maxValue=1
-LineardialGadget\Yaw\data\redMin=0
-LineardialGadget\Yaw\data\redMax=1
-LineardialGadget\Yaw\data\yellowMin=0.1
-LineardialGadget\Yaw\data\yellowMax=0.9
-LineardialGadget\Yaw\data\greenMin=0.3
-LineardialGadget\Yaw\data\greenMax=0.8
-LineardialGadget\Yaw\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
-LineardialGadget\Yaw\data\decimalPlaces=2
-LineardialGadget\Yaw\data\factor=1
-LineardialGadget\Yaw\data\useOpenGLFlag=false
-LineardialGadget\Yaw\configInfo\version=0.0.0
-LineardialGadget\Yaw\configInfo\locked=false
-ModelViewGadget\Aeroquad%20%2B\data\acFilename=%%DATAPATH%%models/multi/aeroquad/aeroquad_+.3ds
-ModelViewGadget\Aeroquad%20%2B\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
-ModelViewGadget\Aeroquad%20%2B\data\enableVbo=false
-ModelViewGadget\Aeroquad%20%2B\configInfo\version=0.0.0
-ModelViewGadget\Aeroquad%20%2B\configInfo\locked=false
-ModelViewGadget\Easyquad%20X\data\acFilename=%%DATAPATH%%models/multi/easy_quad/easy_quad_X.3ds
-ModelViewGadget\Easyquad%20X\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
-ModelViewGadget\Easyquad%20X\data\enableVbo=false
-ModelViewGadget\Easyquad%20X\configInfo\version=0.0.0
-ModelViewGadget\Easyquad%20X\configInfo\locked=false
-ModelViewGadget\Easystar\data\acFilename=%%DATAPATH%%models/planes/Easystar/easystar.3ds
-ModelViewGadget\Easystar\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
-ModelViewGadget\Easystar\data\enableVbo=false
-ModelViewGadget\Easystar\configInfo\version=0.0.0
-ModelViewGadget\Easystar\configInfo\locked=false
-ModelViewGadget\Firecracker\data\acFilename=%%DATAPATH%%models/planes/firecracker/firecracker.3ds
-ModelViewGadget\Firecracker\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
-ModelViewGadget\Firecracker\data\enableVbo=false
-ModelViewGadget\Firecracker\configInfo\version=0.0.0
-ModelViewGadget\Firecracker\configInfo\locked=false
-ModelViewGadget\Funjet\data\acFilename=%%DATAPATH%%models/planes/funjet/funjet.3ds
-ModelViewGadget\Funjet\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
-ModelViewGadget\Funjet\data\enableVbo=false
-ModelViewGadget\Funjet\configInfo\version=0.0.0
-ModelViewGadget\Funjet\configInfo\locked=false
-ModelViewGadget\Gaui%20330X\data\acFilename=%%DATAPATH%%models/multi/gaui_330x/gaui_330x.3ds
-ModelViewGadget\Gaui%20330X\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
-ModelViewGadget\Gaui%20330X\data\enableVbo=false
-ModelViewGadget\Gaui%20330X\configInfo\version=0.0.0
-ModelViewGadget\Gaui%20330X\configInfo\locked=false
-ModelViewGadget\Helicopter%20-%20TRex%20450\data\acFilename=%%DATAPATH%%models/helis/t-rex/t-rex_450_xl.3ds
-ModelViewGadget\Helicopter%20-%20TRex%20450\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
-ModelViewGadget\Helicopter%20-%20TRex%20450\data\enableVbo=false
-ModelViewGadget\Helicopter%20-%20TRex%20450\configInfo\version=0.0.0
-ModelViewGadget\Helicopter%20-%20TRex%20450\configInfo\locked=false
-ModelViewGadget\Hexacopter\data\acFilename=%%DATAPATH%%models/multi/mikrokopter/MK_Hexa.3ds
-ModelViewGadget\Hexacopter\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
-ModelViewGadget\Hexacopter\data\enableVbo=false
-ModelViewGadget\Hexacopter\configInfo\version=0.0.0
-ModelViewGadget\Hexacopter\configInfo\locked=false
-ModelViewGadget\Quadcopter\data\acFilename=%%DATAPATH%%models/multi/mikrokopter/MK_L4-ME.3ds
-ModelViewGadget\Quadcopter\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
-ModelViewGadget\Quadcopter\data\enableVbo=false
-ModelViewGadget\Quadcopter\configInfo\version=0.0.0
-ModelViewGadget\Quadcopter\configInfo\locked=false
-ModelViewGadget\Scorpion%20Tricopter\data\acFilename=%%DATAPATH%%models/multi/scorpion_tricopter/scorpion_tricopter.3ds
-ModelViewGadget\Scorpion%20Tricopter\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
-ModelViewGadget\Scorpion%20Tricopter\data\enableVbo=false
-ModelViewGadget\Scorpion%20Tricopter\configInfo\version=0.0.0
-ModelViewGadget\Scorpion%20Tricopter\configInfo\locked=false
-ModelViewGadget\Test%20Quad%20%2B\data\acFilename=%%DATAPATH%%models/multi/test_quad/test_quad_+.3ds
-ModelViewGadget\Test%20Quad%20%2B\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
-ModelViewGadget\Test%20Quad%20%2B\data\enableVbo=false
-ModelViewGadget\Test%20Quad%20%2B\configInfo\version=0.0.0
-ModelViewGadget\Test%20Quad%20%2B\configInfo\locked=false
-ModelViewGadget\Test%20Quad%20X\data\acFilename=%%DATAPATH%%models/multi/test_quad/test_quad_X.3ds
-ModelViewGadget\Test%20Quad%20X\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
-ModelViewGadget\Test%20Quad%20X\data\enableVbo=false
-ModelViewGadget\Test%20Quad%20X\configInfo\version=0.0.0
-ModelViewGadget\Test%20Quad%20X\configInfo\locked=false
-OPMapGadget\Google%20Sat\data\mapProvider=GoogleSatellite
-OPMapGadget\Google%20Sat\data\defaultZoom=2
-OPMapGadget\Google%20Sat\data\defaultLatitude=0
-OPMapGadget\Google%20Sat\data\defaultLongitude=0
-OPMapGadget\Google%20Sat\data\useOpenGL=true
-OPMapGadget\Google%20Sat\data\showTileGridLines=false
-OPMapGadget\Google%20Sat\data\accessMode=ServerAndCache
-OPMapGadget\Google%20Sat\data\useMemoryCache=true
-OPMapGadget\Google%20Sat\data\cacheLocation=%%STOREPATH%%mapscache-sat/
-OPMapGadget\Google%20Sat\configInfo\version=0.0.0
-OPMapGadget\Google%20Sat\configInfo\locked=false
-OPMapGadget\Memory%20Only\data\mapProvider=GoogleMap
-OPMapGadget\Memory%20Only\data\defaultZoom=2
-OPMapGadget\Memory%20Only\data\defaultLatitude=0
-OPMapGadget\Memory%20Only\data\defaultLongitude=0
-OPMapGadget\Memory%20Only\data\useOpenGL=true
-OPMapGadget\Memory%20Only\data\showTileGridLines=false
-OPMapGadget\Memory%20Only\data\accessMode=CacheOnly
-OPMapGadget\Memory%20Only\data\useMemoryCache=true
-OPMapGadget\Memory%20Only\data\cacheLocation=%%STOREPATH%%mapscache/
-OPMapGadget\Memory%20Only\configInfo\version=0.0.0
-OPMapGadget\Memory%20Only\configInfo\locked=false
-OPMapGadget\default\data\mapProvider=GoogleMap
-OPMapGadget\default\data\defaultZoom=2
-OPMapGadget\default\data\defaultLatitude=0
-OPMapGadget\default\data\defaultLongitude=0
-OPMapGadget\default\data\useOpenGL=false
-OPMapGadget\default\data\showTileGridLines=false
-OPMapGadget\default\data\accessMode=ServerAndCache
-OPMapGadget\default\data\useMemoryCache=true
-OPMapGadget\default\data\cacheLocation=%%STOREPATH%%mapscache/
-OPMapGadget\default\configInfo\version=0.0.0
-OPMapGadget\default\configInfo\locked=false
-PFDGadget\raw\data\dialFile=%%DATAPATH%%pfd/default/pfd.svg
-PFDGadget\raw\data\useOpenGLFlag=false
-PFDGadget\raw\data\hqFonts=false
-PFDGadget\raw\data\beSmooth=false
-PFDGadget\raw\configInfo\version=0.0.0
-PFDGadget\raw\configInfo\locked=false
-PFDGadget\smooth\data\dialFile=%%DATAPATH%%pfd/default/pfd.svg
-PFDGadget\smooth\data\useOpenGLFlag=false
-PFDGadget\smooth\data\hqFonts=false
-PFDGadget\smooth\data\beSmooth=true
-PFDGadget\smooth\configInfo\version=0.0.0
-PFDGadget\smooth\configInfo\locked=false
-PipXtreme\default\configInfo\version=0.0.0
-PipXtreme\default\configInfo\locked=false
-ScopeGadget\Accel\data\configurationStreamVersion=1000
-ScopeGadget\Accel\data\plotType=1
-ScopeGadget\Accel\data\dataSize=60
-ScopeGadget\Accel\data\refreshInterval=100
-ScopeGadget\Accel\data\plotCurveCount=3
-ScopeGadget\Accel\data\plotCurve0\uavObject=AttitudeRaw
-ScopeGadget\Accel\data\plotCurve0\uavField=accels-X
-ScopeGadget\Accel\data\plotCurve0\color=4294901760
-ScopeGadget\Accel\data\plotCurve0\yScalePower=0
-ScopeGadget\Accel\data\plotCurve0\yMinimum=0
-ScopeGadget\Accel\data\plotCurve0\yMaximum=0
-ScopeGadget\Accel\data\plotCurve1\uavObject=AttitudeRaw
-ScopeGadget\Accel\data\plotCurve1\uavField=accels-Y
-ScopeGadget\Accel\data\plotCurve1\color=4283782655
-ScopeGadget\Accel\data\plotCurve1\yScalePower=0
-ScopeGadget\Accel\data\plotCurve1\yMinimum=0
-ScopeGadget\Accel\data\plotCurve1\yMaximum=0
-ScopeGadget\Accel\data\plotCurve2\uavObject=AttitudeRaw
-ScopeGadget\Accel\data\plotCurve2\uavField=accels-Z
-ScopeGadget\Accel\data\plotCurve2\color=4283804160
-ScopeGadget\Accel\data\plotCurve2\yScalePower=0
-ScopeGadget\Accel\data\plotCurve2\yMinimum=0
-ScopeGadget\Accel\data\plotCurve2\yMaximum=0
-ScopeGadget\Accel\data\LoggingEnabled=false
-ScopeGadget\Accel\data\LoggingNewFileOnConnect=false
-ScopeGadget\Accel\data\LoggingPath=
-ScopeGadget\Accel\configInfo\version=0.0.0
-ScopeGadget\Accel\configInfo\locked=false
-ScopeGadget\Actuators\data\configurationStreamVersion=1000
-ScopeGadget\Actuators\data\plotType=1
-ScopeGadget\Actuators\data\dataSize=20
-ScopeGadget\Actuators\data\refreshInterval=100
-ScopeGadget\Actuators\data\plotCurveCount=4
-ScopeGadget\Actuators\data\plotCurve0\uavObject=ActuatorCommand
-ScopeGadget\Actuators\data\plotCurve0\uavField=Channel-4
-ScopeGadget\Actuators\data\plotCurve0\color=4294901760
-ScopeGadget\Actuators\data\plotCurve0\yScalePower=0
-ScopeGadget\Actuators\data\plotCurve0\yMinimum=0
-ScopeGadget\Actuators\data\plotCurve0\yMaximum=0
-ScopeGadget\Actuators\data\plotCurve1\uavObject=ActuatorCommand
-ScopeGadget\Actuators\data\plotCurve1\uavField=Channel-5
-ScopeGadget\Actuators\data\plotCurve1\color=4294901760
-ScopeGadget\Actuators\data\plotCurve1\yScalePower=0
-ScopeGadget\Actuators\data\plotCurve1\yMinimum=0
-ScopeGadget\Actuators\data\plotCurve1\yMaximum=0
-ScopeGadget\Actuators\data\plotCurve2\uavObject=ActuatorCommand
-ScopeGadget\Actuators\data\plotCurve2\uavField=Channel-6
-ScopeGadget\Actuators\data\plotCurve2\color=4289374847
-ScopeGadget\Actuators\data\plotCurve2\yScalePower=0
-ScopeGadget\Actuators\data\plotCurve2\yMinimum=0
-ScopeGadget\Actuators\data\plotCurve2\yMaximum=0
-ScopeGadget\Actuators\data\plotCurve3\uavObject=ActuatorCommand
-ScopeGadget\Actuators\data\plotCurve3\uavField=Channel-7
-ScopeGadget\Actuators\data\plotCurve3\color=4289374847
-ScopeGadget\Actuators\data\plotCurve3\yScalePower=0
-ScopeGadget\Actuators\data\plotCurve3\yMinimum=0
-ScopeGadget\Actuators\data\plotCurve3\yMaximum=0
-ScopeGadget\Actuators\data\LoggingEnabled=false
-ScopeGadget\Actuators\data\LoggingNewFileOnConnect=false
-ScopeGadget\Actuators\data\LoggingPath=
-ScopeGadget\Actuators\configInfo\version=0.0.0
-ScopeGadget\Actuators\configInfo\locked=false
-ScopeGadget\Attitude\data\configurationStreamVersion=1000
-ScopeGadget\Attitude\data\plotType=1
-ScopeGadget\Attitude\data\dataSize=60
-ScopeGadget\Attitude\data\refreshInterval=100
-ScopeGadget\Attitude\data\plotCurveCount=3
-ScopeGadget\Attitude\data\plotCurve0\uavObject=AttitudeActual
-ScopeGadget\Attitude\data\plotCurve0\uavField=Roll
-ScopeGadget\Attitude\data\plotCurve0\color=4283760895
-ScopeGadget\Attitude\data\plotCurve0\yScalePower=0
-ScopeGadget\Attitude\data\plotCurve0\yMinimum=0
-ScopeGadget\Attitude\data\plotCurve0\yMaximum=0
-ScopeGadget\Attitude\data\plotCurve1\uavObject=AttitudeActual
-ScopeGadget\Attitude\data\plotCurve1\uavField=Yaw
-ScopeGadget\Attitude\data\plotCurve1\color=4278233600
-ScopeGadget\Attitude\data\plotCurve1\yScalePower=0
-ScopeGadget\Attitude\data\plotCurve1\yMinimum=0
-ScopeGadget\Attitude\data\plotCurve1\yMaximum=0
-ScopeGadget\Attitude\data\plotCurve2\uavObject=AttitudeActual
-ScopeGadget\Attitude\data\plotCurve2\uavField=Pitch
-ScopeGadget\Attitude\data\plotCurve2\color=4294901760
-ScopeGadget\Attitude\data\plotCurve2\yScalePower=0
-ScopeGadget\Attitude\data\plotCurve2\yMinimum=0
-ScopeGadget\Attitude\data\plotCurve2\yMaximum=0
-ScopeGadget\Attitude\data\LoggingEnabled=false
-ScopeGadget\Attitude\data\LoggingNewFileOnConnect=false
-ScopeGadget\Attitude\data\LoggingPath=
-ScopeGadget\Attitude\configInfo\version=0.0.0
-ScopeGadget\Attitude\configInfo\locked=false
-ScopeGadget\Barometer\data\configurationStreamVersion=1000
-ScopeGadget\Barometer\data\plotType=1
-ScopeGadget\Barometer\data\dataSize=60
-ScopeGadget\Barometer\data\refreshInterval=1000
-ScopeGadget\Barometer\data\plotCurveCount=1
-ScopeGadget\Barometer\data\plotCurve0\uavObject=BaroAltitude
-ScopeGadget\Barometer\data\plotCurve0\uavField=Pressure
-ScopeGadget\Barometer\data\plotCurve0\color=4278190080
-ScopeGadget\Barometer\data\plotCurve0\yScalePower=0
-ScopeGadget\Barometer\data\plotCurve0\yMinimum=0
-ScopeGadget\Barometer\data\plotCurve0\yMaximum=0
-ScopeGadget\Barometer\data\LoggingEnabled=false
-ScopeGadget\Barometer\data\LoggingNewFileOnConnect=false
-ScopeGadget\Barometer\data\LoggingPath=
-ScopeGadget\Barometer\configInfo\version=0.0.0
-ScopeGadget\Barometer\configInfo\locked=false
-ScopeGadget\Inputs\data\configurationStreamVersion=1000
-ScopeGadget\Inputs\data\plotType=1
-ScopeGadget\Inputs\data\dataSize=40
-ScopeGadget\Inputs\data\refreshInterval=200
-ScopeGadget\Inputs\data\plotCurveCount=8
-ScopeGadget\Inputs\data\plotCurve0\uavObject=ManualControlCommand
-ScopeGadget\Inputs\data\plotCurve0\uavField=Channel-1
-ScopeGadget\Inputs\data\plotCurve0\color=4278190207
-ScopeGadget\Inputs\data\plotCurve0\yScalePower=0
-ScopeGadget\Inputs\data\plotCurve0\yMinimum=0
-ScopeGadget\Inputs\data\plotCurve0\yMaximum=0
-ScopeGadget\Inputs\data\plotCurve1\uavObject=ManualControlCommand
-ScopeGadget\Inputs\data\plotCurve1\uavField=Channel-4
-ScopeGadget\Inputs\data\plotCurve1\color=4294901760
-ScopeGadget\Inputs\data\plotCurve1\yScalePower=0
-ScopeGadget\Inputs\data\plotCurve1\yMinimum=0
-ScopeGadget\Inputs\data\plotCurve1\yMaximum=0
-ScopeGadget\Inputs\data\plotCurve2\uavObject=ManualControlCommand
-ScopeGadget\Inputs\data\plotCurve2\uavField=Channel-5
-ScopeGadget\Inputs\data\plotCurve2\color=4294901760
-ScopeGadget\Inputs\data\plotCurve2\yScalePower=0
-ScopeGadget\Inputs\data\plotCurve2\yMinimum=0
-ScopeGadget\Inputs\data\plotCurve2\yMaximum=0
-ScopeGadget\Inputs\data\plotCurve3\uavObject=ManualControlCommand
-ScopeGadget\Inputs\data\plotCurve3\uavField=Channel-6
-ScopeGadget\Inputs\data\plotCurve3\color=4294901760
-ScopeGadget\Inputs\data\plotCurve3\yScalePower=0
-ScopeGadget\Inputs\data\plotCurve3\yMinimum=0
-ScopeGadget\Inputs\data\plotCurve3\yMaximum=0
-ScopeGadget\Inputs\data\plotCurve4\uavObject=ManualControlCommand
-ScopeGadget\Inputs\data\plotCurve4\uavField=Channel-7
-ScopeGadget\Inputs\data\plotCurve4\color=4294901760
-ScopeGadget\Inputs\data\plotCurve4\yScalePower=0
-ScopeGadget\Inputs\data\plotCurve4\yMinimum=0
-ScopeGadget\Inputs\data\plotCurve4\yMaximum=0
-ScopeGadget\Inputs\data\plotCurve5\uavObject=ManualControlCommand
-ScopeGadget\Inputs\data\plotCurve5\uavField=Channel-2
-ScopeGadget\Inputs\data\plotCurve5\color=4283825920
-ScopeGadget\Inputs\data\plotCurve5\yScalePower=0
-ScopeGadget\Inputs\data\plotCurve5\yMinimum=0
-ScopeGadget\Inputs\data\plotCurve5\yMaximum=0
-ScopeGadget\Inputs\data\plotCurve6\uavObject=ManualControlCommand
-ScopeGadget\Inputs\data\plotCurve6\uavField=Channel-3
-ScopeGadget\Inputs\data\plotCurve6\color=4294923520
-ScopeGadget\Inputs\data\plotCurve6\yScalePower=0
-ScopeGadget\Inputs\data\plotCurve6\yMinimum=0
-ScopeGadget\Inputs\data\plotCurve6\yMaximum=0
-ScopeGadget\Inputs\data\plotCurve7\uavObject=ManualControlCommand
-ScopeGadget\Inputs\data\plotCurve7\uavField=Channel-0
-ScopeGadget\Inputs\data\plotCurve7\color=4294967040
-ScopeGadget\Inputs\data\plotCurve7\yScalePower=0
-ScopeGadget\Inputs\data\plotCurve7\yMinimum=0
-ScopeGadget\Inputs\data\plotCurve7\yMaximum=0
-ScopeGadget\Inputs\data\LoggingEnabled=false
-ScopeGadget\Inputs\data\LoggingNewFileOnConnect=false
-ScopeGadget\Inputs\data\LoggingPath=
-ScopeGadget\Inputs\configInfo\version=0.0.0
-ScopeGadget\Inputs\configInfo\locked=false
-ScopeGadget\Pitch%20behaviour\data\configurationStreamVersion=1000
-ScopeGadget\Pitch%20behaviour\data\plotType=1
-ScopeGadget\Pitch%20behaviour\data\dataSize=60
-ScopeGadget\Pitch%20behaviour\data\refreshInterval=500
-ScopeGadget\Pitch%20behaviour\data\plotCurveCount=5
-ScopeGadget\Pitch%20behaviour\data\plotCurve0\uavObject=AttitudeActual
-ScopeGadget\Pitch%20behaviour\data\plotCurve0\uavField=Pitch
-ScopeGadget\Pitch%20behaviour\data\plotCurve0\color=4294901760
-ScopeGadget\Pitch%20behaviour\data\plotCurve0\yScalePower=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve0\yMinimum=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve0\yMaximum=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve1\uavObject=AttitudeDesired
-ScopeGadget\Pitch%20behaviour\data\plotCurve1\uavField=Pitch
-ScopeGadget\Pitch%20behaviour\data\plotCurve1\color=4283760895
-ScopeGadget\Pitch%20behaviour\data\plotCurve1\yScalePower=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve1\yMinimum=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve1\yMaximum=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve2\uavObject=ManualControlCommand
-ScopeGadget\Pitch%20behaviour\data\plotCurve2\uavField=Pitch
-ScopeGadget\Pitch%20behaviour\data\plotCurve2\color=4283826047
-ScopeGadget\Pitch%20behaviour\data\plotCurve2\yScalePower=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve2\yMinimum=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve2\yMaximum=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve3\uavObject=AttitudeRaw
-ScopeGadget\Pitch%20behaviour\data\plotCurve3\uavField=accels-X
-ScopeGadget\Pitch%20behaviour\data\plotCurve3\color=4278233600
-ScopeGadget\Pitch%20behaviour\data\plotCurve3\yScalePower=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve3\yMinimum=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve3\yMaximum=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve4\uavObject=ActuatorDesired
-ScopeGadget\Pitch%20behaviour\data\plotCurve4\uavField=Pitch
-ScopeGadget\Pitch%20behaviour\data\plotCurve4\color=4289374847
-ScopeGadget\Pitch%20behaviour\data\plotCurve4\yScalePower=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve4\yMinimum=0
-ScopeGadget\Pitch%20behaviour\data\plotCurve4\yMaximum=0
-ScopeGadget\Pitch%20behaviour\data\LoggingEnabled=false
-ScopeGadget\Pitch%20behaviour\data\LoggingNewFileOnConnect=false
-ScopeGadget\Pitch%20behaviour\data\LoggingPath=
-ScopeGadget\Pitch%20behaviour\configInfo\version=0.0.0
-ScopeGadget\Pitch%20behaviour\configInfo\locked=false
-ScopeGadget\Raw%20Accels\data\configurationStreamVersion=1000
-ScopeGadget\Raw%20Accels\data\plotType=1
-ScopeGadget\Raw%20Accels\data\dataSize=60
-ScopeGadget\Raw%20Accels\data\refreshInterval=500
-ScopeGadget\Raw%20Accels\data\plotCurveCount=3
-ScopeGadget\Raw%20Accels\data\plotCurve0\uavObject=AttitudeRaw
-ScopeGadget\Raw%20Accels\data\plotCurve0\uavField=accels-X
-ScopeGadget\Raw%20Accels\data\plotCurve0\color=4294901760
-ScopeGadget\Raw%20Accels\data\plotCurve0\yScalePower=0
-ScopeGadget\Raw%20Accels\data\plotCurve0\yMinimum=0
-ScopeGadget\Raw%20Accels\data\plotCurve0\yMaximum=0
-ScopeGadget\Raw%20Accels\data\plotCurve1\uavObject=AttitudeRaw
-ScopeGadget\Raw%20Accels\data\plotCurve1\uavField=accels-Y
-ScopeGadget\Raw%20Accels\data\plotCurve1\color=4283782655
-ScopeGadget\Raw%20Accels\data\plotCurve1\yScalePower=0
-ScopeGadget\Raw%20Accels\data\plotCurve1\yMinimum=0
-ScopeGadget\Raw%20Accels\data\plotCurve1\yMaximum=0
-ScopeGadget\Raw%20Accels\data\plotCurve2\uavObject=AttitudeRaw
-ScopeGadget\Raw%20Accels\data\plotCurve2\uavField=accels-Z
-ScopeGadget\Raw%20Accels\data\plotCurve2\color=4283804160
-ScopeGadget\Raw%20Accels\data\plotCurve2\yScalePower=0
-ScopeGadget\Raw%20Accels\data\plotCurve2\yMinimum=0
-ScopeGadget\Raw%20Accels\data\plotCurve2\yMaximum=0
-ScopeGadget\Raw%20Accels\data\LoggingEnabled=false
-ScopeGadget\Raw%20Accels\data\LoggingNewFileOnConnect=false
-ScopeGadget\Raw%20Accels\data\LoggingPath=
-ScopeGadget\Raw%20Accels\configInfo\version=0.0.0
-ScopeGadget\Raw%20Accels\configInfo\locked=false
-ScopeGadget\Raw%20Gyros\data\configurationStreamVersion=1000
-ScopeGadget\Raw%20Gyros\data\plotType=1
-ScopeGadget\Raw%20Gyros\data\dataSize=60
-ScopeGadget\Raw%20Gyros\data\refreshInterval=500
-ScopeGadget\Raw%20Gyros\data\plotCurveCount=3
-ScopeGadget\Raw%20Gyros\data\plotCurve0\uavObject=AttitudeRaw
-ScopeGadget\Raw%20Gyros\data\plotCurve0\uavField=gyros-Z
-ScopeGadget\Raw%20Gyros\data\plotCurve0\color=4283804160
-ScopeGadget\Raw%20Gyros\data\plotCurve0\yScalePower=0
-ScopeGadget\Raw%20Gyros\data\plotCurve0\yMinimum=0
-ScopeGadget\Raw%20Gyros\data\plotCurve0\yMaximum=0
-ScopeGadget\Raw%20Gyros\data\plotCurve1\uavObject=AttitudeRaw
-ScopeGadget\Raw%20Gyros\data\plotCurve1\uavField=gyros-Y
-ScopeGadget\Raw%20Gyros\data\plotCurve1\color=4283782655
-ScopeGadget\Raw%20Gyros\data\plotCurve1\yScalePower=0
-ScopeGadget\Raw%20Gyros\data\plotCurve1\yMinimum=0
-ScopeGadget\Raw%20Gyros\data\plotCurve1\yMaximum=0
-ScopeGadget\Raw%20Gyros\data\plotCurve2\uavObject=AttitudeRaw
-ScopeGadget\Raw%20Gyros\data\plotCurve2\uavField=gyros-X
-ScopeGadget\Raw%20Gyros\data\plotCurve2\color=4294901760
-ScopeGadget\Raw%20Gyros\data\plotCurve2\yScalePower=0
-ScopeGadget\Raw%20Gyros\data\plotCurve2\yMinimum=0
-ScopeGadget\Raw%20Gyros\data\plotCurve2\yMaximum=0
-ScopeGadget\Raw%20Gyros\data\LoggingEnabled=false
-ScopeGadget\Raw%20Gyros\data\LoggingNewFileOnConnect=false
-ScopeGadget\Raw%20Gyros\data\LoggingPath=
-ScopeGadget\Raw%20Gyros\configInfo\version=0.0.0
-ScopeGadget\Raw%20Gyros\configInfo\locked=false
-ScopeGadget\Raw%20magnetometers\data\configurationStreamVersion=1000
-ScopeGadget\Raw%20magnetometers\data\plotType=1
-ScopeGadget\Raw%20magnetometers\data\dataSize=60
-ScopeGadget\Raw%20magnetometers\data\refreshInterval=500
-ScopeGadget\Raw%20magnetometers\data\plotCurveCount=3
-ScopeGadget\Raw%20magnetometers\data\plotCurve0\uavObject=AttitudeRaw
-ScopeGadget\Raw%20magnetometers\data\plotCurve0\uavField=magnetometers-X
-ScopeGadget\Raw%20magnetometers\data\plotCurve0\color=4294901760
-ScopeGadget\Raw%20magnetometers\data\plotCurve0\yScalePower=0
-ScopeGadget\Raw%20magnetometers\data\plotCurve0\yMinimum=0
-ScopeGadget\Raw%20magnetometers\data\plotCurve0\yMaximum=0
-ScopeGadget\Raw%20magnetometers\data\plotCurve1\uavObject=AttitudeRaw
-ScopeGadget\Raw%20magnetometers\data\plotCurve1\uavField=magnetometers-Y
-ScopeGadget\Raw%20magnetometers\data\plotCurve1\color=4283782655
-ScopeGadget\Raw%20magnetometers\data\plotCurve1\yScalePower=0
-ScopeGadget\Raw%20magnetometers\data\plotCurve1\yMinimum=0
-ScopeGadget\Raw%20magnetometers\data\plotCurve1\yMaximum=0
-ScopeGadget\Raw%20magnetometers\data\plotCurve2\uavObject=AttitudeRaw
-ScopeGadget\Raw%20magnetometers\data\plotCurve2\uavField=magnetometers-Z
-ScopeGadget\Raw%20magnetometers\data\plotCurve2\color=4283804160
-ScopeGadget\Raw%20magnetometers\data\plotCurve2\yScalePower=0
-ScopeGadget\Raw%20magnetometers\data\plotCurve2\yMinimum=0
-ScopeGadget\Raw%20magnetometers\data\plotCurve2\yMaximum=0
-ScopeGadget\Raw%20magnetometers\data\LoggingEnabled=false
-ScopeGadget\Raw%20magnetometers\data\LoggingNewFileOnConnect=false
-ScopeGadget\Raw%20magnetometers\data\LoggingPath=
-ScopeGadget\Raw%20magnetometers\configInfo\version=0.0.0
-ScopeGadget\Raw%20magnetometers\configInfo\locked=false
-ScopeGadget\Stacks%20monitor\data\configurationStreamVersion=1000
-ScopeGadget\Stacks%20monitor\data\plotType=1
-ScopeGadget\Stacks%20monitor\data\dataSize=240
-ScopeGadget\Stacks%20monitor\data\refreshInterval=1000
-ScopeGadget\Stacks%20monitor\data\plotCurveCount=12
-ScopeGadget\Stacks%20monitor\data\plotCurve0\uavObject=TaskInfo
-ScopeGadget\Stacks%20monitor\data\plotCurve0\uavField=StackRemaining-System
-ScopeGadget\Stacks%20monitor\data\plotCurve0\color=4294945280
-ScopeGadget\Stacks%20monitor\data\plotCurve0\yScalePower=0
-ScopeGadget\Stacks%20monitor\data\plotCurve0\yMinimum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve0\yMaximum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve1\uavObject=TaskInfo
-ScopeGadget\Stacks%20monitor\data\plotCurve1\uavField=StackRemaining-Actuator
-ScopeGadget\Stacks%20monitor\data\plotCurve1\color=4294945280
-ScopeGadget\Stacks%20monitor\data\plotCurve1\yScalePower=0
-ScopeGadget\Stacks%20monitor\data\plotCurve1\yMinimum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve1\yMaximum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve2\uavObject=TaskInfo
-ScopeGadget\Stacks%20monitor\data\plotCurve2\uavField=StackRemaining-TelemetryTx
-ScopeGadget\Stacks%20monitor\data\plotCurve2\color=4294945280
-ScopeGadget\Stacks%20monitor\data\plotCurve2\yScalePower=0
-ScopeGadget\Stacks%20monitor\data\plotCurve2\yMinimum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve2\yMaximum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve3\uavObject=TaskInfo
-ScopeGadget\Stacks%20monitor\data\plotCurve3\uavField=StackRemaining-TelemetryTxPri
-ScopeGadget\Stacks%20monitor\data\plotCurve3\color=4294945280
-ScopeGadget\Stacks%20monitor\data\plotCurve3\yScalePower=0
-ScopeGadget\Stacks%20monitor\data\plotCurve3\yMinimum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve3\yMaximum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve4\uavObject=TaskInfo
-ScopeGadget\Stacks%20monitor\data\plotCurve4\uavField=StackRemaining-TelemetryRx
-ScopeGadget\Stacks%20monitor\data\plotCurve4\color=4294945280
-ScopeGadget\Stacks%20monitor\data\plotCurve4\yScalePower=0
-ScopeGadget\Stacks%20monitor\data\plotCurve4\yMinimum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve4\yMaximum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve5\uavObject=TaskInfo
-ScopeGadget\Stacks%20monitor\data\plotCurve5\uavField=StackRemaining-GPS
-ScopeGadget\Stacks%20monitor\data\plotCurve5\color=4294945280
-ScopeGadget\Stacks%20monitor\data\plotCurve5\yScalePower=0
-ScopeGadget\Stacks%20monitor\data\plotCurve5\yMinimum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve5\yMaximum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve6\uavObject=TaskInfo
-ScopeGadget\Stacks%20monitor\data\plotCurve6\uavField=StackRemaining-ManualControl
-ScopeGadget\Stacks%20monitor\data\plotCurve6\color=4294945280
-ScopeGadget\Stacks%20monitor\data\plotCurve6\yScalePower=0
-ScopeGadget\Stacks%20monitor\data\plotCurve6\yMinimum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve6\yMaximum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve7\uavObject=TaskInfo
-ScopeGadget\Stacks%20monitor\data\plotCurve7\uavField=StackRemaining-Altitude
-ScopeGadget\Stacks%20monitor\data\plotCurve7\color=4294945280
-ScopeGadget\Stacks%20monitor\data\plotCurve7\yScalePower=0
-ScopeGadget\Stacks%20monitor\data\plotCurve7\yMinimum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve7\yMaximum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve8\uavObject=TaskInfo
-ScopeGadget\Stacks%20monitor\data\plotCurve8\uavField=StackRemaining-AHRSComms
-ScopeGadget\Stacks%20monitor\data\plotCurve8\color=4294945280
-ScopeGadget\Stacks%20monitor\data\plotCurve8\yScalePower=0
-ScopeGadget\Stacks%20monitor\data\plotCurve8\yMinimum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve8\yMaximum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve9\uavObject=TaskInfo
-ScopeGadget\Stacks%20monitor\data\plotCurve9\uavField=StackRemaining-Stabilization
-ScopeGadget\Stacks%20monitor\data\plotCurve9\color=4294945280
-ScopeGadget\Stacks%20monitor\data\plotCurve9\yScalePower=0
-ScopeGadget\Stacks%20monitor\data\plotCurve9\yMinimum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve9\yMaximum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve10\uavObject=TaskInfo
-ScopeGadget\Stacks%20monitor\data\plotCurve10\uavField=StackRemaining-Guidance
-ScopeGadget\Stacks%20monitor\data\plotCurve10\color=4294945280
-ScopeGadget\Stacks%20monitor\data\plotCurve10\yScalePower=0
-ScopeGadget\Stacks%20monitor\data\plotCurve10\yMinimum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve10\yMaximum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve11\uavObject=TaskInfo
-ScopeGadget\Stacks%20monitor\data\plotCurve11\uavField=StackRemaining-Watchdog
-ScopeGadget\Stacks%20monitor\data\plotCurve11\color=4294945280
-ScopeGadget\Stacks%20monitor\data\plotCurve11\yScalePower=0
-ScopeGadget\Stacks%20monitor\data\plotCurve11\yMinimum=0
-ScopeGadget\Stacks%20monitor\data\plotCurve11\yMaximum=0
-ScopeGadget\Stacks%20monitor\data\LoggingEnabled=false
-ScopeGadget\Stacks%20monitor\data\LoggingNewFileOnConnect=false
-ScopeGadget\Stacks%20monitor\data\LoggingPath=
-ScopeGadget\Stacks%20monitor\configInfo\version=0.0.0
-ScopeGadget\Stacks%20monitor\configInfo\locked=false
-ScopeGadget\Telemetry%20quality\data\configurationStreamVersion=1000
-ScopeGadget\Telemetry%20quality\data\plotType=1
-ScopeGadget\Telemetry%20quality\data\dataSize=20
-ScopeGadget\Telemetry%20quality\data\refreshInterval=100
-ScopeGadget\Telemetry%20quality\data\plotCurveCount=3
-ScopeGadget\Telemetry%20quality\data\plotCurve0\uavObject=GCSTelemetryStats
-ScopeGadget\Telemetry%20quality\data\plotCurve0\uavField=TxFailures
-ScopeGadget\Telemetry%20quality\data\plotCurve0\color=4289374847
-ScopeGadget\Telemetry%20quality\data\plotCurve0\yScalePower=0
-ScopeGadget\Telemetry%20quality\data\plotCurve0\yMinimum=0
-ScopeGadget\Telemetry%20quality\data\plotCurve0\yMaximum=0
-ScopeGadget\Telemetry%20quality\data\plotCurve1\uavObject=GCSTelemetryStats
-ScopeGadget\Telemetry%20quality\data\plotCurve1\uavField=RxFailures
-ScopeGadget\Telemetry%20quality\data\plotCurve1\color=4283782655
-ScopeGadget\Telemetry%20quality\data\plotCurve1\yScalePower=0
-ScopeGadget\Telemetry%20quality\data\plotCurve1\yMinimum=0
-ScopeGadget\Telemetry%20quality\data\plotCurve1\yMaximum=0
-ScopeGadget\Telemetry%20quality\data\plotCurve2\uavObject=GCSTelemetryStats
-ScopeGadget\Telemetry%20quality\data\plotCurve2\uavField=TxRetries
-ScopeGadget\Telemetry%20quality\data\plotCurve2\color=4294901760
-ScopeGadget\Telemetry%20quality\data\plotCurve2\yScalePower=0
-ScopeGadget\Telemetry%20quality\data\plotCurve2\yMinimum=0
-ScopeGadget\Telemetry%20quality\data\plotCurve2\yMaximum=0
-ScopeGadget\Telemetry%20quality\data\LoggingEnabled=false
-ScopeGadget\Telemetry%20quality\data\LoggingNewFileOnConnect=false
-ScopeGadget\Telemetry%20quality\data\LoggingPath=
-ScopeGadget\Telemetry%20quality\configInfo\version=0.0.0
-ScopeGadget\Telemetry%20quality\configInfo\locked=false
-ScopeGadget\Uptimes\data\configurationStreamVersion=1000
-ScopeGadget\Uptimes\data\plotType=1
-ScopeGadget\Uptimes\data\dataSize=240
-ScopeGadget\Uptimes\data\refreshInterval=800
-ScopeGadget\Uptimes\data\plotCurveCount=2
-ScopeGadget\Uptimes\data\plotCurve0\uavObject=AhrsStatus
-ScopeGadget\Uptimes\data\plotCurve0\uavField=RunningTime
-ScopeGadget\Uptimes\data\plotCurve0\color=4289374847
-ScopeGadget\Uptimes\data\plotCurve0\yScalePower=0
-ScopeGadget\Uptimes\data\plotCurve0\yMinimum=0
-ScopeGadget\Uptimes\data\plotCurve0\yMaximum=0
-ScopeGadget\Uptimes\data\plotCurve1\uavObject=SystemStats
-ScopeGadget\Uptimes\data\plotCurve1\uavField=FlightTime
-ScopeGadget\Uptimes\data\plotCurve1\color=4294945407
-ScopeGadget\Uptimes\data\plotCurve1\yScalePower=0
-ScopeGadget\Uptimes\data\plotCurve1\yMinimum=0
-ScopeGadget\Uptimes\data\plotCurve1\yMaximum=0
-ScopeGadget\Uptimes\data\LoggingEnabled=false
-ScopeGadget\Uptimes\data\LoggingNewFileOnConnect=false
-ScopeGadget\Uptimes\data\LoggingPath=
-ScopeGadget\Uptimes\configInfo\version=0.0.0
-ScopeGadget\Uptimes\configInfo\locked=false
-SystemHealthGadget\default\data\diagram=%%DATAPATH%%diagrams/default/system-health.svg
-SystemHealthGadget\default\configInfo\version=0.0.0
-SystemHealthGadget\default\configInfo\locked=false
-UAVObjectBrowser\default\data\recentlyUpdatedColor=@Variant(\0\0\0\x43\x1\xff\xff\xff\xffyyWW\0\0)
-UAVObjectBrowser\default\data\manuallyChangedColor=@Variant(\0\0\0\x43\x1\xff\xff[[\xaa\xaaVV\0\0)
-UAVObjectBrowser\default\data\recentlyUpdatedTimeout=500
-UAVObjectBrowser\default\configInfo\version=0.0.0
-UAVObjectBrowser\default\configInfo\locked=false
-Uploader\default\data\defaultSpeed=14
-Uploader\default\data\defaultDataBits=3
-Uploader\default\data\defaultFlow=0
-Uploader\default\data\defaultParity=0
-Uploader\default\data\defaultStopBits=0
-Uploader\default\data\defaultPort=/dev/ttyS0
-Uploader\default\configInfo\version=0.0.0
-Uploader\default\configInfo\locked=false
-
-[Plugins]
-SoundNotifyPlugin\data\Current\1\SoundCollectionPath=
-SoundNotifyPlugin\data\Current\1\CurrentLanguage=
-SoundNotifyPlugin\data\Current\1\ObjectField=
-SoundNotifyPlugin\data\Current\1\DataObject=
-SoundNotifyPlugin\data\Current\1\Value=
-SoundNotifyPlugin\data\Current\1\ValueSpinBox=0
-SoundNotifyPlugin\data\Current\1\Sound1=
-SoundNotifyPlugin\data\Current\1\Sound2=
-SoundNotifyPlugin\data\Current\1\Sound3=
-SoundNotifyPlugin\data\Current\1\SayOrder=
-SoundNotifyPlugin\data\Current\1\Repeat=
-SoundNotifyPlugin\data\Current\1\ExpireTimeout=0
-SoundNotifyPlugin\data\Current\size=1
-SoundNotifyPlugin\data\listNotifies\size=0
-SoundNotifyPlugin\data\EnableSound=false
-SoundNotifyPlugin\configInfo\version=1.0.0
-SoundNotifyPlugin\configInfo\locked=false
+[General]
+ViewGroup_Default=@ByteArray(\0\0\0\xff\0\0\0\0\xfd\0\0\0\0\0\0\x5\xa0\0\0\x3/\0\0\0\x4\0\0\0\x4\0\0\0\x1\0\0\0\b\xfc\0\0\0\0)
+
+[Workspace]
+NumberOfWorkspaces=6
+Workspace1=Flight data
+Icon1=:/core/images/ah.png
+Workspace2=Configuration
+Icon2=:/core/images/config.png
+Workspace3=Large Map
+Icon3=:/core/images/world.png
+Workspace4=Scopes
+Icon4=:/core/images/scopes.png
+Workspace5=HITL
+Icon5=:/core/images/joystick.png
+Workspace6=Firmware
+Icon6=:/core/images/cog.png
+Workspace7=Workspace7
+Icon7=:/core/images/openpilot_logo_64.png
+Workspace8=Workspace8
+Icon8=:/core/images/openpilot_logo_64.png
+Workspace9=Workspace9
+Icon9=:/core/images/openpilot_logo_64.png
+Workspace10=Workspace10
+Icon10=:/core/images/openpilot_logo_64.png
+
+[MainWindow]
+Color=@Variant(\0\0\0\x43\x1\xff\xff\x66\x66\x66\x66\x66\x66\0\0)
+Maximized=true
+FullScreen=false
+
+[UAVGadgetManager]
+Mode1\version=UAVGadgetManagerV1
+Mode1\showToolbars=false
+Mode1\splitter\type=splitter
+Mode1\splitter\splitterOrientation=1
+Mode1\splitter\splitterSizes=738, 701
+Mode1\splitter\side0\type=splitter
+Mode1\splitter\side0\splitterOrientation=2
+Mode1\splitter\side0\splitterSizes=453, 327
+Mode1\splitter\side0\side0\type=splitter
+Mode1\splitter\side0\side0\splitterOrientation=1
+Mode1\splitter\side0\side0\splitterSizes=144, 608
+Mode1\splitter\side0\side0\side0\type=splitter
+Mode1\splitter\side0\side0\side1\type=uavGadget
+Mode1\splitter\side0\side1\type=splitter
+Mode1\splitter\side1\type=splitter
+Mode1\splitter\side1\splitterOrientation=2
+Mode1\splitter\side1\splitterSizes=492, 288
+Mode1\splitter\side1\side0\type=uavGadget
+Mode1\splitter\side1\side1\type=splitter
+Mode1\splitter\side1\side1\splitterOrientation=1
+Mode1\splitter\side1\side1\splitterSizes=441, 259
+Mode1\splitter\side1\side1\side0\type=splitter
+Mode1\splitter\side1\side1\side1\type=splitter
+Mode2\version=UAVGadgetManagerV1
+Mode2\showToolbars=false
+Mode2\splitter\type=splitter
+Mode2\splitter\splitterOrientation=1
+Mode2\splitter\splitterSizes=734, 631
+Mode2\splitter\side0\type=splitter
+Mode2\splitter\side0\splitterOrientation=2
+Mode2\splitter\side0\splitterSizes=565, 66
+Mode2\splitter\side0\side0\type=uavGadget
+Mode2\splitter\side0\side0\classId=ConfigGadget
+Mode2\splitter\side0\side0\gadget\activeConfiguration=default
+Mode2\splitter\side0\side1\type=splitter
+Mode2\splitter\side0\side1\splitterOrientation=1
+Mode2\splitter\side0\side1\splitterSizes=@Invalid()
+Mode2\splitter\side0\side1\side0\type=uavGadget
+Mode2\splitter\side0\side1\side0\classId=LineardialGadget
+Mode2\splitter\side0\side1\side0\gadget\activeConfiguration=Telemetry RX Rate Horizontal
+Mode2\splitter\side0\side1\side1\type=uavGadget
+Mode2\splitter\side0\side1\side1\classId=LineardialGadget
+Mode2\splitter\side0\side1\side1\gadget\activeConfiguration=Telemetry TX Rate Horizontal
+Mode2\splitter\side1\type=splitter
+Mode2\splitter\side1\splitterOrientation=2
+Mode2\splitter\side1\splitterSizes=433, 347
+Mode2\splitter\side1\side0\type=uavGadget
+Mode2\splitter\side1\side0\classId=UAVObjectBrowser
+Mode2\splitter\side1\side0\gadget\activeConfiguration=default
+Mode2\splitter\side1\side1\type=uavGadget
+Mode2\splitter\side1\side1\classId=GCSControlGadget
+Mode2\splitter\side1\side1\gadget\activeConfiguration=MS Sidewinder
+Mode3\version=UAVGadgetManagerV1
+Mode3\showToolbars=false
+Mode3\splitter\type=splitter
+Mode3\splitter\splitterOrientation=1
+Mode3\splitter\splitterSizes=980, 385
+Mode3\splitter\side0\type=uavGadget
+Mode3\splitter\side0\classId=OPMapGadget
+Mode3\splitter\side0\gadget\activeConfiguration=default
+Mode3\splitter\side1\type=splitter
+Mode3\splitter\side1\splitterOrientation=2
+Mode3\splitter\side1\splitterSizes=395, 236
+Mode3\splitter\side1\side0\type=uavGadget
+Mode3\splitter\side1\side0\classId=ModelViewGadget
+Mode3\splitter\side1\side0\gadget\activeConfiguration=Test Quad X
+Mode3\splitter\side1\side1\type=splitter
+Mode3\splitter\side1\side1\splitterOrientation=1
+Mode3\splitter\side1\side1\splitterSizes=@Invalid()
+Mode3\splitter\side1\side1\side0\type=uavGadget
+Mode3\splitter\side1\side1\side0\classId=DialGadget
+Mode3\splitter\side1\side1\side0\gadget\activeConfiguration=Attitude
+Mode3\splitter\side1\side1\side1\type=uavGadget
+Mode3\splitter\side1\side1\side1\classId=DialGadget
+Mode3\splitter\side1\side1\side1\gadget\activeConfiguration=Compass
+Mode4\version=UAVGadgetManagerV1
+Mode4\showToolbars=false
+Mode4\splitter\type=splitter
+Mode4\splitter\splitterOrientation=1
+Mode4\splitter\splitterSizes=653, 660
+Mode4\splitter\side0\type=splitter
+Mode4\splitter\side1\type=splitter
+Mode4\splitter\side1\splitterOrientation=2
+Mode4\splitter\side1\splitterSizes=661, 119
+Mode4\splitter\side1\side0\type=splitter
+Mode4\splitter\side1\side1\type=uavGadget
+Mode5\version=UAVGadgetManagerV1
+Mode5\showToolbars=false
+Mode5\splitter\type=splitter
+Mode5\splitter\splitterOrientation=1
+Mode5\splitter\splitterSizes=780, 585
+Mode5\splitter\side0\type=splitter
+Mode5\splitter\side0\splitterOrientation=2
+Mode5\splitter\side0\splitterSizes=361, 270
+Mode5\splitter\side0\side0\type=uavGadget
+Mode5\splitter\side0\side0\classId=HITL
+Mode5\splitter\side0\side0\gadget\activeConfiguration=XPlane HITL
+Mode5\splitter\side0\side1\type=splitter
+Mode5\splitter\side0\side1\splitterOrientation=1
+Mode5\splitter\side0\side1\splitterSizes=488, 194
+Mode5\splitter\side0\side1\side0\type=uavGadget
+Mode5\splitter\side0\side1\side0\classId=GCSControlGadget
+Mode5\splitter\side0\side1\side0\gadget\activeConfiguration=MS Sidewinder
+Mode5\splitter\side0\side1\side1\type=splitter
+Mode5\splitter\side0\side1\side1\splitterOrientation=1
+Mode5\splitter\side0\side1\side1\splitterSizes=276, 64
+Mode5\splitter\side0\side1\side1\side0\type=splitter
+Mode5\splitter\side0\side1\side1\side0\splitterOrientation=1
+Mode5\splitter\side0\side1\side1\side0\splitterSizes=@Invalid()
+Mode5\splitter\side0\side1\side1\side0\side0\type=uavGadget
+Mode5\splitter\side0\side1\side1\side0\side0\classId=LineardialGadget
+Mode5\splitter\side0\side1\side1\side0\side0\gadget\activeConfiguration=PitchDesired
+Mode5\splitter\side0\side1\side1\side0\side1\type=uavGadget
+Mode5\splitter\side0\side1\side1\side0\side1\classId=LineardialGadget
+Mode5\splitter\side0\side1\side1\side0\side1\gadget\activeConfiguration=PitchActual
+Mode5\splitter\side0\side1\side1\side1\type=uavGadget
+Mode5\splitter\side0\side1\side1\side1\classId=LineardialGadget
+Mode5\splitter\side0\side1\side1\side1\gadget\activeConfiguration=PitchCommand
+Mode5\splitter\side1\type=uavGadget
+Mode5\splitter\side1\classId=UAVObjectBrowser
+Mode5\splitter\side1\gadget\activeConfiguration=default
+Mode1\splitter\side0\side0\side0\splitterOrientation=2
+Mode1\splitter\side0\side0\side0\splitterSizes=215, 237
+Mode1\splitter\side0\side0\side0\side0\type=splitter
+Mode1\splitter\side0\side0\side0\side1\type=splitter
+Mode1\splitter\side0\side0\side0\side1\splitterOrientation=2
+Mode1\splitter\side0\side0\side0\side1\splitterSizes=@Invalid()
+Mode1\splitter\side0\side0\side0\side1\side0\type=uavGadget
+Mode1\splitter\side0\side0\side0\side1\side0\classId=LineardialGadget
+Mode1\splitter\side0\side0\side0\side1\side0\gadget\activeConfiguration=Flight mode
+Mode1\splitter\side0\side0\side0\side1\side1\type=uavGadget
+Mode1\splitter\side0\side0\side0\side1\side1\classId=LineardialGadget
+Mode1\splitter\side0\side0\side0\side1\side1\gadget\activeConfiguration=Arm Status
+Mode1\splitter\side1\side0\classId=OPMapGadget
+Mode1\splitter\side1\side0\gadget\activeConfiguration=Google Sat
+Mode1\splitter\side1\side1\side0\splitterOrientation=1
+Mode1\splitter\side1\side1\side0\splitterSizes=277, 135
+Mode1\splitter\side1\side1\side0\side0\type=splitter
+Mode1\splitter\side1\side1\side0\side1\type=splitter
+Mode1\splitter\side0\side1\splitterOrientation=1
+Mode1\splitter\side0\side1\splitterSizes=304, 433
+Mode1\splitter\side0\side1\side0\type=uavGadget
+Mode1\splitter\side0\side1\side1\type=splitter
+Mode1\splitter\side0\side1\side1\splitterOrientation=2
+Mode1\splitter\side0\side1\side1\splitterSizes=293, 64
+Mode1\splitter\side0\side1\side1\side0\type=splitter
+Mode1\splitter\side0\side1\side1\side1\type=splitter
+Mode1\splitter\side1\side1\side0\side0\splitterOrientation=1
+Mode1\splitter\side1\side1\side0\side0\splitterSizes=131, 138
+Mode1\splitter\side1\side1\side0\side0\side0\type=splitter
+Mode1\splitter\side1\side1\side0\side0\side1\type=splitter
+Mode1\splitter\side0\side1\side0\classId=ModelViewGadget
+Mode1\splitter\side0\side1\side0\gadget\activeConfiguration=Test Quad X
+Mode1\splitter\side0\side1\side1\side0\splitterOrientation=1
+Mode1\splitter\side0\side1\side1\side0\splitterSizes=291, 141
+Mode1\splitter\side0\side1\side1\side0\side0\type=uavGadget
+Mode1\splitter\side0\side1\side1\side0\side0\classId=SystemHealthGadget
+Mode1\splitter\side0\side1\side1\side0\side0\gadget\activeConfiguration=default
+Mode1\splitter\side0\side1\side1\side0\side1\type=splitter
+Mode1\splitter\side0\side1\side1\side1\splitterOrientation=1
+Mode1\splitter\side0\side1\side1\side1\splitterSizes=@Invalid()
+Mode1\splitter\side0\side1\side1\side1\side0\type=uavGadget
+Mode1\splitter\side0\side1\side1\side1\side0\classId=LineardialGadget
+Mode1\splitter\side0\side1\side1\side1\side0\gadget\activeConfiguration=Telemetry RX Rate Horizontal
+Mode1\splitter\side0\side1\side1\side1\side1\type=uavGadget
+Mode1\splitter\side0\side1\side1\side1\side1\classId=LineardialGadget
+Mode1\splitter\side0\side1\side1\side1\side1\gadget\activeConfiguration=Telemetry TX Rate Horizontal
+Mode1\splitter\side0\side1\side1\side0\side1\splitterOrientation=1
+Mode1\splitter\side0\side1\side1\side0\side1\splitterSizes=64, 64
+Mode1\splitter\side0\side1\side1\side0\side1\side0\type=uavGadget
+Mode1\splitter\side0\side1\side1\side0\side1\side0\classId=LineardialGadget
+Mode1\splitter\side0\side1\side1\side0\side1\side0\gadget\activeConfiguration=Mainboard CPU
+Mode1\splitter\side0\side1\side1\side0\side1\side1\type=uavGadget
+Mode1\splitter\side0\side1\side1\side0\side1\side1\classId=LineardialGadget
+Mode1\splitter\side0\side1\side1\side0\side1\side1\gadget\activeConfiguration=AHRS CPU
+Mode1\splitter\side1\side1\side0\side0\side0\splitterOrientation=2
+Mode1\splitter\side1\side1\side0\side0\side0\splitterSizes=@Invalid()
+Mode1\splitter\side1\side1\side0\side0\side0\side0\type=uavGadget
+Mode1\splitter\side1\side1\side0\side0\side0\side0\classId=DialGadget
+Mode1\splitter\side1\side1\side0\side0\side0\side0\gadget\activeConfiguration=Deluxe Groundspeed kph
+Mode1\splitter\side1\side1\side0\side0\side0\side1\type=uavGadget
+Mode1\splitter\side1\side1\side0\side0\side0\side1\classId=DialGadget
+Mode1\splitter\side1\side1\side0\side0\side0\side1\gadget\activeConfiguration=Deluxe Barometer
+Mode1\splitter\side1\side1\side0\side0\side1\splitterOrientation=2
+Mode1\splitter\side1\side1\side0\side0\side1\splitterSizes=@Invalid()
+Mode1\splitter\side1\side1\side0\side0\side1\side0\type=uavGadget
+Mode1\splitter\side1\side1\side0\side0\side1\side0\classId=DialGadget
+Mode1\splitter\side1\side1\side0\side0\side1\side0\gadget\activeConfiguration=Deluxe Attitude
+Mode1\splitter\side1\side1\side0\side0\side1\side1\type=uavGadget
+Mode1\splitter\side1\side1\side0\side0\side1\side1\classId=DialGadget
+Mode1\splitter\side1\side1\side0\side0\side1\side1\gadget\activeConfiguration=Deluxe Compass
+Mode1\splitter\side1\side1\side0\side1\splitterOrientation=2
+Mode1\splitter\side1\side1\side0\side1\splitterSizes=@Invalid()
+Mode1\splitter\side1\side1\side0\side1\side0\type=uavGadget
+Mode1\splitter\side1\side1\side0\side1\side0\classId=DialGadget
+Mode1\splitter\side1\side1\side0\side1\side0\gadget\activeConfiguration=Deluxe Baro Altimeter
+Mode1\splitter\side1\side1\side0\side1\side1\type=uavGadget
+Mode1\splitter\side1\side1\side0\side1\side1\classId=DialGadget
+Mode1\splitter\side1\side1\side0\side1\side1\gadget\activeConfiguration=Deluxe Climbrate
+Mode1\splitter\side0\side0\side0\side0\splitterOrientation=2
+Mode1\splitter\side0\side0\side0\side0\splitterSizes=@Invalid()
+Mode1\splitter\side0\side0\side0\side0\side0\type=uavGadget
+Mode1\splitter\side0\side0\side0\side0\side0\classId=LineardialGadget
+Mode1\splitter\side0\side0\side0\side0\side0\gadget\activeConfiguration=Flight Time
+Mode1\splitter\side0\side0\side0\side0\side1\type=uavGadget
+Mode1\splitter\side0\side0\side0\side0\side1\classId=LineardialGadget
+Mode1\splitter\side0\side0\side0\side0\side1\gadget\activeConfiguration=GPS Sats
+Mode1\splitter\side0\side0\side1\classId=PFDGadget
+Mode1\splitter\side0\side0\side1\gadget\activeConfiguration=raw
+Mode1\splitter\side1\side1\side1\splitterOrientation=1
+Mode1\splitter\side1\side1\side1\splitterSizes=64, 441
+Mode1\splitter\side1\side1\side1\side0\type=uavGadget
+Mode1\splitter\side1\side1\side1\side0\classId=LineardialGadget
+Mode1\splitter\side1\side1\side1\side0\gadget\activeConfiguration=Throttle
+Mode1\splitter\side1\side1\side1\side1\type=splitter
+Mode1\splitter\side1\side1\side1\side1\splitterOrientation=1
+Mode1\splitter\side1\side1\side1\side1\splitterSizes=64, 376
+Mode1\splitter\side1\side1\side1\side1\side0\type=uavGadget
+Mode1\splitter\side1\side1\side1\side1\side0\classId=LineardialGadget
+Mode1\splitter\side1\side1\side1\side1\side0\gadget\activeConfiguration=Roll
+Mode1\splitter\side1\side1\side1\side1\side1\type=splitter
+Mode1\splitter\side1\side1\side1\side1\side1\splitterOrientation=1
+Mode1\splitter\side1\side1\side1\side1\side1\splitterSizes=64, 311
+Mode1\splitter\side1\side1\side1\side1\side1\side0\type=uavGadget
+Mode1\splitter\side1\side1\side1\side1\side1\side0\classId=LineardialGadget
+Mode1\splitter\side1\side1\side1\side1\side1\side0\gadget\activeConfiguration=PitchActual
+Mode1\splitter\side1\side1\side1\side1\side1\side1\type=uavGadget
+Mode1\splitter\side1\side1\side1\side1\side1\side1\classId=LineardialGadget
+Mode1\splitter\side1\side1\side1\side1\side1\side1\gadget\activeConfiguration=Yaw
+Mode6\version=UAVGadgetManagerV1
+Mode6\showToolbars=false
+Mode6\splitter\type=splitter
+Mode4\splitter\side0\splitterOrientation=2
+Mode4\splitter\side0\splitterSizes=@Invalid()
+Mode4\splitter\side0\side0\type=uavGadget
+Mode4\splitter\side0\side0\classId=ScopeGadget
+Mode4\splitter\side0\side0\gadget\activeConfiguration=Accel
+Mode4\splitter\side0\side1\type=uavGadget
+Mode4\splitter\side0\side1\classId=ScopeGadget
+Mode4\splitter\side0\side1\gadget\activeConfiguration=Raw Gyros
+Mode4\splitter\side1\side0\splitterOrientation=2
+Mode4\splitter\side1\side0\splitterSizes=390, 270
+Mode4\splitter\side1\side0\side0\type=uavGadget
+Mode4\splitter\side1\side0\side0\classId=ScopeGadget
+Mode4\splitter\side1\side0\side0\gadget\activeConfiguration=Attitude
+Mode4\splitter\side1\side0\side1\type=uavGadget
+Mode4\splitter\side1\side0\side1\classId=ScopeGadget
+Mode4\splitter\side1\side0\side1\gadget\activeConfiguration=Uptimes
+Mode4\splitter\side1\side1\classId=LoggingGadget
+Mode6\splitter\splitterOrientation=1
+Mode6\splitter\splitterSizes=@Invalid()
+Mode6\splitter\side0\type=uavGadget
+Mode6\splitter\side0\classId=Uploader
+Mode6\splitter\side0\gadget\activeConfiguration=default
+Mode6\splitter\side1\type=splitter
+Mode6\splitter\side1\splitterOrientation=2
+Mode6\splitter\side1\splitterSizes=274, 506
+Mode6\splitter\side1\side0\type=splitter
+Mode6\splitter\side1\side1\type=uavGadget
+Mode6\splitter\side1\side1\classId=ScopeGadget
+Mode6\splitter\side1\side1\gadget\activeConfiguration=Uptimes
+Mode6\splitter\side1\side0\splitterOrientation=1
+Mode6\splitter\side1\side0\splitterSizes=322, 396
+Mode6\splitter\side1\side0\side0\type=uavGadget
+Mode6\splitter\side1\side0\side0\classId=SystemHealthGadget
+Mode6\splitter\side1\side0\side0\gadget\activeConfiguration=default
+Mode6\splitter\side1\side0\side1\type=uavGadget
+Mode6\splitter\side1\side0\side1\classId=PFDGadget
+Mode6\splitter\side1\side0\side1\gadget\activeConfiguration=raw
+
+[KeyBindings]
+size=0
+
+[%General]
+SaveSettingsOnExit=true
+LastPreferenceCategory=OPMapGadget
+LastPreferencePage=default
+SettingsWindowWidth=697
+SettingsWindowHeight=476
+OverrideLanguage=en_AU
+
+[UAVGadgetConfigurations]
+configInfo\version=1.2.0
+configInfo\locked=false
+ConfigGadget\default\configInfo\version=0.0.0
+ConfigGadget\default\configInfo\locked=false
+DialGadget\Attitude\data\dialFile=%%DATAPATH%%dials/default/attitude.svg
+DialGadget\Attitude\data\dialBackgroundID=background
+DialGadget\Attitude\data\dialForegroundID=foreground
+DialGadget\Attitude\data\dialNeedleID1=needle
+DialGadget\Attitude\data\dialNeedleID2=needle
+DialGadget\Attitude\data\dialNeedleID3=needle3
+DialGadget\Attitude\data\needle1MinValue=0
+DialGadget\Attitude\data\needle1MaxValue=360
+DialGadget\Attitude\data\needle2MinValue=0
+DialGadget\Attitude\data\needle2MaxValue=20
+DialGadget\Attitude\data\needle3MinValue=0
+DialGadget\Attitude\data\needle3MaxValue=360
+DialGadget\Attitude\data\needle1DataObject=AttitudeActual
+DialGadget\Attitude\data\needle1ObjectField=Roll
+DialGadget\Attitude\data\needle2DataObject=AttitudeActual
+DialGadget\Attitude\data\needle2ObjectField=Pitch
+DialGadget\Attitude\data\needle3DataObject=AttitudeActual
+DialGadget\Attitude\data\needle3ObjectField=Roll
+DialGadget\Attitude\data\needle1Factor=-1
+DialGadget\Attitude\data\needle2Factor=75
+DialGadget\Attitude\data\needle3Factor=-1
+DialGadget\Attitude\data\needle1Move=Rotate
+DialGadget\Attitude\data\needle2Move=Vertical
+DialGadget\Attitude\data\needle3Move=Rotate
+DialGadget\Attitude\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Attitude\data\useOpenGLFlag=false
+DialGadget\Attitude\data\beSmooth=false
+DialGadget\Attitude\configInfo\version=0.0.0
+DialGadget\Attitude\configInfo\locked=false
+DialGadget\Baro%20Altimeter\data\dialFile=%%DATAPATH%%dials/default/altimeter.svg
+DialGadget\Baro%20Altimeter\data\dialBackgroundID=background
+DialGadget\Baro%20Altimeter\data\dialForegroundID=foreground
+DialGadget\Baro%20Altimeter\data\dialNeedleID1=needle
+DialGadget\Baro%20Altimeter\data\dialNeedleID2=needle2
+DialGadget\Baro%20Altimeter\data\dialNeedleID3=needle3
+DialGadget\Baro%20Altimeter\data\needle1MinValue=0
+DialGadget\Baro%20Altimeter\data\needle1MaxValue=10
+DialGadget\Baro%20Altimeter\data\needle2MinValue=0
+DialGadget\Baro%20Altimeter\data\needle2MaxValue=100
+DialGadget\Baro%20Altimeter\data\needle3MinValue=0
+DialGadget\Baro%20Altimeter\data\needle3MaxValue=1000
+DialGadget\Baro%20Altimeter\data\needle1DataObject=BaroAltitude
+DialGadget\Baro%20Altimeter\data\needle1ObjectField=Altitude
+DialGadget\Baro%20Altimeter\data\needle2DataObject=BaroAltitude
+DialGadget\Baro%20Altimeter\data\needle2ObjectField=Altitude
+DialGadget\Baro%20Altimeter\data\needle3DataObject=BaroAltitude
+DialGadget\Baro%20Altimeter\data\needle3ObjectField=Altitude
+DialGadget\Baro%20Altimeter\data\needle1Factor=1
+DialGadget\Baro%20Altimeter\data\needle2Factor=1
+DialGadget\Baro%20Altimeter\data\needle3Factor=1
+DialGadget\Baro%20Altimeter\data\needle1Move=Rotate
+DialGadget\Baro%20Altimeter\data\needle2Move=Rotate
+DialGadget\Baro%20Altimeter\data\needle3Move=Rotate
+DialGadget\Baro%20Altimeter\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Baro%20Altimeter\data\useOpenGLFlag=false
+DialGadget\Baro%20Altimeter\data\beSmooth=false
+DialGadget\Baro%20Altimeter\configInfo\version=0.0.0
+DialGadget\Baro%20Altimeter\configInfo\locked=false
+DialGadget\Barometer\data\dialFile=%%DATAPATH%%dials/default/barometer.svg
+DialGadget\Barometer\data\dialBackgroundID=background
+DialGadget\Barometer\data\dialForegroundID=
+DialGadget\Barometer\data\dialNeedleID1=needle
+DialGadget\Barometer\data\dialNeedleID2=
+DialGadget\Barometer\data\dialNeedleID3=
+DialGadget\Barometer\data\needle1MinValue=1000
+DialGadget\Barometer\data\needle1MaxValue=1120
+DialGadget\Barometer\data\needle2MinValue=0
+DialGadget\Barometer\data\needle2MaxValue=100
+DialGadget\Barometer\data\needle3MinValue=0
+DialGadget\Barometer\data\needle3MaxValue=1000
+DialGadget\Barometer\data\needle1DataObject=BaroAltitude
+DialGadget\Barometer\data\needle1ObjectField=Pressure
+DialGadget\Barometer\data\needle2DataObject=BaroAltitude
+DialGadget\Barometer\data\needle2ObjectField=Altitude
+DialGadget\Barometer\data\needle3DataObject=BaroAltitude
+DialGadget\Barometer\data\needle3ObjectField=Altitude
+DialGadget\Barometer\data\needle1Factor=10
+DialGadget\Barometer\data\needle2Factor=1
+DialGadget\Barometer\data\needle3Factor=1
+DialGadget\Barometer\data\needle1Move=Rotate
+DialGadget\Barometer\data\needle2Move=Rotate
+DialGadget\Barometer\data\needle3Move=Rotate
+DialGadget\Barometer\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Barometer\data\useOpenGLFlag=false
+DialGadget\Barometer\data\beSmooth=false
+DialGadget\Barometer\configInfo\version=0.0.0
+DialGadget\Barometer\configInfo\locked=false
+DialGadget\Climbrate\data\dialFile=%%DATAPATH%%dials/default/vsi.svg
+DialGadget\Climbrate\data\dialBackgroundID=background
+DialGadget\Climbrate\data\dialForegroundID=
+DialGadget\Climbrate\data\dialNeedleID1=needle
+DialGadget\Climbrate\data\dialNeedleID2=
+DialGadget\Climbrate\data\dialNeedleID3=
+DialGadget\Climbrate\data\needle1MinValue=-12
+DialGadget\Climbrate\data\needle1MaxValue=12
+DialGadget\Climbrate\data\needle2MinValue=0
+DialGadget\Climbrate\data\needle2MaxValue=100
+DialGadget\Climbrate\data\needle3MinValue=0
+DialGadget\Climbrate\data\needle3MaxValue=1000
+DialGadget\Climbrate\data\needle1DataObject=VelocityActual
+DialGadget\Climbrate\data\needle1ObjectField=Down
+DialGadget\Climbrate\data\needle2DataObject=BaroAltitude
+DialGadget\Climbrate\data\needle2ObjectField=Altitude
+DialGadget\Climbrate\data\needle3DataObject=BaroAltitude
+DialGadget\Climbrate\data\needle3ObjectField=Altitude
+DialGadget\Climbrate\data\needle1Factor=0.01
+DialGadget\Climbrate\data\needle2Factor=1
+DialGadget\Climbrate\data\needle3Factor=1
+DialGadget\Climbrate\data\needle1Move=Rotate
+DialGadget\Climbrate\data\needle2Move=Rotate
+DialGadget\Climbrate\data\needle3Move=Rotate
+DialGadget\Climbrate\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Climbrate\data\useOpenGLFlag=false
+DialGadget\Climbrate\data\beSmooth=false
+DialGadget\Climbrate\configInfo\version=0.0.0
+DialGadget\Climbrate\configInfo\locked=false
+DialGadget\Compass\data\dialFile=%%DATAPATH%%dials/default/compass.svg
+DialGadget\Compass\data\dialBackgroundID=background
+DialGadget\Compass\data\dialForegroundID=foreground
+DialGadget\Compass\data\dialNeedleID1=needle
+DialGadget\Compass\data\dialNeedleID2=
+DialGadget\Compass\data\dialNeedleID3=
+DialGadget\Compass\data\needle1MinValue=0
+DialGadget\Compass\data\needle1MaxValue=360
+DialGadget\Compass\data\needle2MinValue=0
+DialGadget\Compass\data\needle2MaxValue=100
+DialGadget\Compass\data\needle3MinValue=0
+DialGadget\Compass\data\needle3MaxValue=1000
+DialGadget\Compass\data\needle1DataObject=AttitudeActual
+DialGadget\Compass\data\needle1ObjectField=Yaw
+DialGadget\Compass\data\needle2DataObject=BaroAltitude
+DialGadget\Compass\data\needle2ObjectField=Altitude
+DialGadget\Compass\data\needle3DataObject=BaroAltitude
+DialGadget\Compass\data\needle3ObjectField=Altitude
+DialGadget\Compass\data\needle1Factor=-1
+DialGadget\Compass\data\needle2Factor=1
+DialGadget\Compass\data\needle3Factor=1
+DialGadget\Compass\data\needle1Move=Rotate
+DialGadget\Compass\data\needle2Move=Rotate
+DialGadget\Compass\data\needle3Move=Rotate
+DialGadget\Compass\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Compass\data\useOpenGLFlag=false
+DialGadget\Compass\data\beSmooth=false
+DialGadget\Compass\configInfo\version=0.0.0
+DialGadget\Compass\configInfo\locked=false
+DialGadget\Deluxe%20Attitude\data\dialFile=%%DATAPATH%%dials/deluxe/attitude.svg
+DialGadget\Deluxe%20Attitude\data\dialBackgroundID=background
+DialGadget\Deluxe%20Attitude\data\dialForegroundID=foreground
+DialGadget\Deluxe%20Attitude\data\dialNeedleID1=needle
+DialGadget\Deluxe%20Attitude\data\dialNeedleID2=needle
+DialGadget\Deluxe%20Attitude\data\dialNeedleID3=needle3
+DialGadget\Deluxe%20Attitude\data\needle1MinValue=0
+DialGadget\Deluxe%20Attitude\data\needle1MaxValue=360
+DialGadget\Deluxe%20Attitude\data\needle2MinValue=0
+DialGadget\Deluxe%20Attitude\data\needle2MaxValue=20
+DialGadget\Deluxe%20Attitude\data\needle3MinValue=0
+DialGadget\Deluxe%20Attitude\data\needle3MaxValue=360
+DialGadget\Deluxe%20Attitude\data\needle1DataObject=AttitudeActual
+DialGadget\Deluxe%20Attitude\data\needle1ObjectField=Roll
+DialGadget\Deluxe%20Attitude\data\needle2DataObject=AttitudeActual
+DialGadget\Deluxe%20Attitude\data\needle2ObjectField=Pitch
+DialGadget\Deluxe%20Attitude\data\needle3DataObject=AttitudeActual
+DialGadget\Deluxe%20Attitude\data\needle3ObjectField=Roll
+DialGadget\Deluxe%20Attitude\data\needle1Factor=-1
+DialGadget\Deluxe%20Attitude\data\needle2Factor=75
+DialGadget\Deluxe%20Attitude\data\needle3Factor=-1
+DialGadget\Deluxe%20Attitude\data\needle1Move=Rotate
+DialGadget\Deluxe%20Attitude\data\needle2Move=Vertical
+DialGadget\Deluxe%20Attitude\data\needle3Move=Rotate
+DialGadget\Deluxe%20Attitude\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Deluxe%20Attitude\data\useOpenGLFlag=false
+DialGadget\Deluxe%20Attitude\data\beSmooth=false
+DialGadget\Deluxe%20Attitude\configInfo\version=0.0.0
+DialGadget\Deluxe%20Attitude\configInfo\locked=false
+DialGadget\Deluxe%20Baro%20Altimeter\data\dialFile=%%DATAPATH%%dials/deluxe/altimeter.svg
+DialGadget\Deluxe%20Baro%20Altimeter\data\dialBackgroundID=background
+DialGadget\Deluxe%20Baro%20Altimeter\data\dialForegroundID=foreground
+DialGadget\Deluxe%20Baro%20Altimeter\data\dialNeedleID1=needle
+DialGadget\Deluxe%20Baro%20Altimeter\data\dialNeedleID2=needle2
+DialGadget\Deluxe%20Baro%20Altimeter\data\dialNeedleID3=needle3
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle1MinValue=0
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle1MaxValue=10
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle2MinValue=0
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle2MaxValue=100
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle3MinValue=0
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle3MaxValue=1000
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle1DataObject=BaroAltitude
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle1ObjectField=Altitude
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle2DataObject=BaroAltitude
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle2ObjectField=Altitude
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle3DataObject=BaroAltitude
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle3ObjectField=Altitude
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle1Factor=1
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle2Factor=1
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle3Factor=1
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle1Move=Rotate
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle2Move=Rotate
+DialGadget\Deluxe%20Baro%20Altimeter\data\needle3Move=Rotate
+DialGadget\Deluxe%20Baro%20Altimeter\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Deluxe%20Baro%20Altimeter\data\useOpenGLFlag=false
+DialGadget\Deluxe%20Baro%20Altimeter\data\beSmooth=false
+DialGadget\Deluxe%20Baro%20Altimeter\configInfo\version=0.0.0
+DialGadget\Deluxe%20Baro%20Altimeter\configInfo\locked=false
+DialGadget\Deluxe%20Barometer\data\dialFile=%%DATAPATH%%dials/deluxe/barometer.svg
+DialGadget\Deluxe%20Barometer\data\dialBackgroundID=background
+DialGadget\Deluxe%20Barometer\data\dialForegroundID=foreground
+DialGadget\Deluxe%20Barometer\data\dialNeedleID1=needle
+DialGadget\Deluxe%20Barometer\data\dialNeedleID2=
+DialGadget\Deluxe%20Barometer\data\dialNeedleID3=
+DialGadget\Deluxe%20Barometer\data\needle1MinValue=1000
+DialGadget\Deluxe%20Barometer\data\needle1MaxValue=1120
+DialGadget\Deluxe%20Barometer\data\needle2MinValue=0
+DialGadget\Deluxe%20Barometer\data\needle2MaxValue=100
+DialGadget\Deluxe%20Barometer\data\needle3MinValue=0
+DialGadget\Deluxe%20Barometer\data\needle3MaxValue=1000
+DialGadget\Deluxe%20Barometer\data\needle1DataObject=BaroAltitude
+DialGadget\Deluxe%20Barometer\data\needle1ObjectField=Pressure
+DialGadget\Deluxe%20Barometer\data\needle2DataObject=BaroAltitude
+DialGadget\Deluxe%20Barometer\data\needle2ObjectField=Altitude
+DialGadget\Deluxe%20Barometer\data\needle3DataObject=BaroAltitude
+DialGadget\Deluxe%20Barometer\data\needle3ObjectField=Altitude
+DialGadget\Deluxe%20Barometer\data\needle1Factor=10
+DialGadget\Deluxe%20Barometer\data\needle2Factor=1
+DialGadget\Deluxe%20Barometer\data\needle3Factor=1
+DialGadget\Deluxe%20Barometer\data\needle1Move=Rotate
+DialGadget\Deluxe%20Barometer\data\needle2Move=Rotate
+DialGadget\Deluxe%20Barometer\data\needle3Move=Rotate
+DialGadget\Deluxe%20Barometer\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Deluxe%20Barometer\data\useOpenGLFlag=false
+DialGadget\Deluxe%20Barometer\data\beSmooth=false
+DialGadget\Deluxe%20Barometer\configInfo\version=0.0.0
+DialGadget\Deluxe%20Barometer\configInfo\locked=false
+DialGadget\Deluxe%20Climbrate\data\dialFile=%%DATAPATH%%dials/deluxe/vsi.svg
+DialGadget\Deluxe%20Climbrate\data\dialBackgroundID=background
+DialGadget\Deluxe%20Climbrate\data\dialForegroundID=foreground
+DialGadget\Deluxe%20Climbrate\data\dialNeedleID1=needle
+DialGadget\Deluxe%20Climbrate\data\dialNeedleID2=
+DialGadget\Deluxe%20Climbrate\data\dialNeedleID3=
+DialGadget\Deluxe%20Climbrate\data\needle1MinValue=-11.2
+DialGadget\Deluxe%20Climbrate\data\needle1MaxValue=11.2
+DialGadget\Deluxe%20Climbrate\data\needle2MinValue=0
+DialGadget\Deluxe%20Climbrate\data\needle2MaxValue=100
+DialGadget\Deluxe%20Climbrate\data\needle3MinValue=0
+DialGadget\Deluxe%20Climbrate\data\needle3MaxValue=1000
+DialGadget\Deluxe%20Climbrate\data\needle1DataObject=VelocityActual
+DialGadget\Deluxe%20Climbrate\data\needle1ObjectField=Down
+DialGadget\Deluxe%20Climbrate\data\needle2DataObject=BaroAltitude
+DialGadget\Deluxe%20Climbrate\data\needle2ObjectField=Altitude
+DialGadget\Deluxe%20Climbrate\data\needle3DataObject=BaroAltitude
+DialGadget\Deluxe%20Climbrate\data\needle3ObjectField=Altitude
+DialGadget\Deluxe%20Climbrate\data\needle1Factor=0.01
+DialGadget\Deluxe%20Climbrate\data\needle2Factor=1
+DialGadget\Deluxe%20Climbrate\data\needle3Factor=1
+DialGadget\Deluxe%20Climbrate\data\needle1Move=Rotate
+DialGadget\Deluxe%20Climbrate\data\needle2Move=Rotate
+DialGadget\Deluxe%20Climbrate\data\needle3Move=Rotate
+DialGadget\Deluxe%20Climbrate\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Deluxe%20Climbrate\data\useOpenGLFlag=false
+DialGadget\Deluxe%20Climbrate\data\beSmooth=false
+DialGadget\Deluxe%20Climbrate\configInfo\version=0.0.0
+DialGadget\Deluxe%20Climbrate\configInfo\locked=false
+DialGadget\Deluxe%20Compass\data\dialFile=%%DATAPATH%%dials/deluxe/compass.svg
+DialGadget\Deluxe%20Compass\data\dialBackgroundID=background
+DialGadget\Deluxe%20Compass\data\dialForegroundID=foreground
+DialGadget\Deluxe%20Compass\data\dialNeedleID1=needle
+DialGadget\Deluxe%20Compass\data\dialNeedleID2=
+DialGadget\Deluxe%20Compass\data\dialNeedleID3=
+DialGadget\Deluxe%20Compass\data\needle1MinValue=0
+DialGadget\Deluxe%20Compass\data\needle1MaxValue=360
+DialGadget\Deluxe%20Compass\data\needle2MinValue=0
+DialGadget\Deluxe%20Compass\data\needle2MaxValue=100
+DialGadget\Deluxe%20Compass\data\needle3MinValue=0
+DialGadget\Deluxe%20Compass\data\needle3MaxValue=1000
+DialGadget\Deluxe%20Compass\data\needle1DataObject=AttitudeActual
+DialGadget\Deluxe%20Compass\data\needle1ObjectField=Yaw
+DialGadget\Deluxe%20Compass\data\needle2DataObject=BaroAltitude
+DialGadget\Deluxe%20Compass\data\needle2ObjectField=Altitude
+DialGadget\Deluxe%20Compass\data\needle3DataObject=BaroAltitude
+DialGadget\Deluxe%20Compass\data\needle3ObjectField=Altitude
+DialGadget\Deluxe%20Compass\data\needle1Factor=-1
+DialGadget\Deluxe%20Compass\data\needle2Factor=1
+DialGadget\Deluxe%20Compass\data\needle3Factor=1
+DialGadget\Deluxe%20Compass\data\needle1Move=Rotate
+DialGadget\Deluxe%20Compass\data\needle2Move=Rotate
+DialGadget\Deluxe%20Compass\data\needle3Move=Rotate
+DialGadget\Deluxe%20Compass\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Deluxe%20Compass\data\useOpenGLFlag=false
+DialGadget\Deluxe%20Compass\data\beSmooth=false
+DialGadget\Deluxe%20Compass\configInfo\version=0.0.0
+DialGadget\Deluxe%20Compass\configInfo\locked=false
+DialGadget\Deluxe%20Groundspeed%20kph\data\dialFile=%%DATAPATH%%dials/deluxe/speed.svg
+DialGadget\Deluxe%20Groundspeed%20kph\data\dialBackgroundID=background
+DialGadget\Deluxe%20Groundspeed%20kph\data\dialForegroundID=foreground
+DialGadget\Deluxe%20Groundspeed%20kph\data\dialNeedleID1=needle
+DialGadget\Deluxe%20Groundspeed%20kph\data\dialNeedleID2=
+DialGadget\Deluxe%20Groundspeed%20kph\data\dialNeedleID3=
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle1MinValue=0
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle1MaxValue=120
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle2MinValue=0
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle2MaxValue=100
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle3MinValue=0
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle3MaxValue=1000
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle1DataObject=GPSPosition
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle1ObjectField=Groundspeed
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle2DataObject=BaroAltitude
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle2ObjectField=Altitude
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle3DataObject=BaroAltitude
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle3ObjectField=Altitude
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle1Factor=3.6
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle2Factor=1
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle3Factor=1
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle1Move=Rotate
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle2Move=Rotate
+DialGadget\Deluxe%20Groundspeed%20kph\data\needle3Move=Rotate
+DialGadget\Deluxe%20Groundspeed%20kph\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Deluxe%20Groundspeed%20kph\data\useOpenGLFlag=false
+DialGadget\Deluxe%20Groundspeed%20kph\data\beSmooth=false
+DialGadget\Deluxe%20Groundspeed%20kph\configInfo\version=0.0.0
+DialGadget\Deluxe%20Groundspeed%20kph\configInfo\locked=false
+DialGadget\Deluxe%20Temperature\data\dialFile=%%DATAPATH%%dials/deluxe/thermometer.svg
+DialGadget\Deluxe%20Temperature\data\dialBackgroundID=background
+DialGadget\Deluxe%20Temperature\data\dialForegroundID=foreground
+DialGadget\Deluxe%20Temperature\data\dialNeedleID1=needle
+DialGadget\Deluxe%20Temperature\data\dialNeedleID2=needle2
+DialGadget\Deluxe%20Temperature\data\dialNeedleID3=needle3
+DialGadget\Deluxe%20Temperature\data\needle1MinValue=0
+DialGadget\Deluxe%20Temperature\data\needle1MaxValue=120
+DialGadget\Deluxe%20Temperature\data\needle2MinValue=0
+DialGadget\Deluxe%20Temperature\data\needle2MaxValue=100
+DialGadget\Deluxe%20Temperature\data\needle3MinValue=0
+DialGadget\Deluxe%20Temperature\data\needle3MaxValue=1000
+DialGadget\Deluxe%20Temperature\data\needle1DataObject=BaroAltitude
+DialGadget\Deluxe%20Temperature\data\needle1ObjectField=Temperature
+DialGadget\Deluxe%20Temperature\data\needle2DataObject=BaroAltitude
+DialGadget\Deluxe%20Temperature\data\needle2ObjectField=Altitude
+DialGadget\Deluxe%20Temperature\data\needle3DataObject=BaroAltitude
+DialGadget\Deluxe%20Temperature\data\needle3ObjectField=Altitude
+DialGadget\Deluxe%20Temperature\data\needle1Factor=1
+DialGadget\Deluxe%20Temperature\data\needle2Factor=1
+DialGadget\Deluxe%20Temperature\data\needle3Factor=1
+DialGadget\Deluxe%20Temperature\data\needle1Move=Rotate
+DialGadget\Deluxe%20Temperature\data\needle2Move=Rotate
+DialGadget\Deluxe%20Temperature\data\needle3Move=Rotate
+DialGadget\Deluxe%20Temperature\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Deluxe%20Temperature\data\useOpenGLFlag=false
+DialGadget\Deluxe%20Temperature\data\beSmooth=false
+DialGadget\Deluxe%20Temperature\configInfo\version=0.0.0
+DialGadget\Deluxe%20Temperature\configInfo\locked=false
+DialGadget\Deluxe%20Turn%20Coordinator\data\dialFile=/home/lafargue/OP/OpenPilot/trunk/artwork/Dials/deluxe/turncoordinator.svg
+DialGadget\Deluxe%20Turn%20Coordinator\data\dialBackgroundID=background
+DialGadget\Deluxe%20Turn%20Coordinator\data\dialForegroundID=foreground
+DialGadget\Deluxe%20Turn%20Coordinator\data\dialNeedleID1=needle
+DialGadget\Deluxe%20Turn%20Coordinator\data\dialNeedleID2=needle2
+DialGadget\Deluxe%20Turn%20Coordinator\data\dialNeedleID3=needle2
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle1MinValue=0
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle1MaxValue=360
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle2MinValue=-20
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle2MaxValue=20
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle3MinValue=0
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle3MaxValue=360
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle1DataObject=AttitudeActual
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle1ObjectField=Roll
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle2DataObject=AttitudeRaw
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle2ObjectField=accels-X
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle3DataObject=AttitudeRaw
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle3ObjectField=accels-X
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle1Factor=-1
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle2Factor=1
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle3Factor=-1
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle1Move=Rotate
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle2Move=Horizontal
+DialGadget\Deluxe%20Turn%20Coordinator\data\needle3Move=Rotate
+DialGadget\Deluxe%20Turn%20Coordinator\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Deluxe%20Turn%20Coordinator\data\useOpenGLFlag=false
+DialGadget\Deluxe%20Turn%20Coordinator\data\beSmooth=false
+DialGadget\Deluxe%20Turn%20Coordinator\configInfo\version=0.0.0
+DialGadget\Deluxe%20Turn%20Coordinator\configInfo\locked=false
+DialGadget\Groundspeed%20kph\data\dialFile=%%DATAPATH%%dials/default/speed.svg
+DialGadget\Groundspeed%20kph\data\dialBackgroundID=background
+DialGadget\Groundspeed%20kph\data\dialForegroundID=
+DialGadget\Groundspeed%20kph\data\dialNeedleID1=needle
+DialGadget\Groundspeed%20kph\data\dialNeedleID2=
+DialGadget\Groundspeed%20kph\data\dialNeedleID3=
+DialGadget\Groundspeed%20kph\data\needle1MinValue=0
+DialGadget\Groundspeed%20kph\data\needle1MaxValue=120
+DialGadget\Groundspeed%20kph\data\needle2MinValue=0
+DialGadget\Groundspeed%20kph\data\needle2MaxValue=100
+DialGadget\Groundspeed%20kph\data\needle3MinValue=0
+DialGadget\Groundspeed%20kph\data\needle3MaxValue=1000
+DialGadget\Groundspeed%20kph\data\needle1DataObject=GPSPosition
+DialGadget\Groundspeed%20kph\data\needle1ObjectField=Groundspeed
+DialGadget\Groundspeed%20kph\data\needle2DataObject=BaroAltitude
+DialGadget\Groundspeed%20kph\data\needle2ObjectField=Altitude
+DialGadget\Groundspeed%20kph\data\needle3DataObject=BaroAltitude
+DialGadget\Groundspeed%20kph\data\needle3ObjectField=Altitude
+DialGadget\Groundspeed%20kph\data\needle1Factor=3.6
+DialGadget\Groundspeed%20kph\data\needle2Factor=1
+DialGadget\Groundspeed%20kph\data\needle3Factor=1
+DialGadget\Groundspeed%20kph\data\needle1Move=Rotate
+DialGadget\Groundspeed%20kph\data\needle2Move=Rotate
+DialGadget\Groundspeed%20kph\data\needle3Move=Rotate
+DialGadget\Groundspeed%20kph\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Groundspeed%20kph\data\useOpenGLFlag=false
+DialGadget\Groundspeed%20kph\data\beSmooth=false
+DialGadget\Groundspeed%20kph\configInfo\version=0.0.0
+DialGadget\Groundspeed%20kph\configInfo\locked=false
+DialGadget\HiContrast%20Attitude\data\dialFile=%%DATAPATH%%dials/hi-contrast/attitude.svg
+DialGadget\HiContrast%20Attitude\data\dialBackgroundID=background
+DialGadget\HiContrast%20Attitude\data\dialForegroundID=foreground
+DialGadget\HiContrast%20Attitude\data\dialNeedleID1=needle
+DialGadget\HiContrast%20Attitude\data\dialNeedleID2=needle
+DialGadget\HiContrast%20Attitude\data\dialNeedleID3=needle3
+DialGadget\HiContrast%20Attitude\data\needle1MinValue=0
+DialGadget\HiContrast%20Attitude\data\needle1MaxValue=360
+DialGadget\HiContrast%20Attitude\data\needle2MinValue=0
+DialGadget\HiContrast%20Attitude\data\needle2MaxValue=20
+DialGadget\HiContrast%20Attitude\data\needle3MinValue=0
+DialGadget\HiContrast%20Attitude\data\needle3MaxValue=360
+DialGadget\HiContrast%20Attitude\data\needle1DataObject=AttitudeActual
+DialGadget\HiContrast%20Attitude\data\needle1ObjectField=Roll
+DialGadget\HiContrast%20Attitude\data\needle2DataObject=AttitudeActual
+DialGadget\HiContrast%20Attitude\data\needle2ObjectField=Pitch
+DialGadget\HiContrast%20Attitude\data\needle3DataObject=AttitudeActual
+DialGadget\HiContrast%20Attitude\data\needle3ObjectField=Roll
+DialGadget\HiContrast%20Attitude\data\needle1Factor=-1
+DialGadget\HiContrast%20Attitude\data\needle2Factor=75
+DialGadget\HiContrast%20Attitude\data\needle3Factor=-1
+DialGadget\HiContrast%20Attitude\data\needle1Move=Rotate
+DialGadget\HiContrast%20Attitude\data\needle2Move=Vertical
+DialGadget\HiContrast%20Attitude\data\needle3Move=Rotate
+DialGadget\HiContrast%20Attitude\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\HiContrast%20Attitude\data\useOpenGLFlag=false
+DialGadget\HiContrast%20Attitude\data\beSmooth=false
+DialGadget\HiContrast%20Attitude\configInfo\version=0.0.0
+DialGadget\HiContrast%20Attitude\configInfo\locked=false
+DialGadget\HiContrast%20Baro%20Altimeter\data\dialFile=%%DATAPATH%%dials/hi-contrast/altimeter.svg
+DialGadget\HiContrast%20Baro%20Altimeter\data\dialBackgroundID=background
+DialGadget\HiContrast%20Baro%20Altimeter\data\dialForegroundID=foreground
+DialGadget\HiContrast%20Baro%20Altimeter\data\dialNeedleID1=needle
+DialGadget\HiContrast%20Baro%20Altimeter\data\dialNeedleID2=needle2
+DialGadget\HiContrast%20Baro%20Altimeter\data\dialNeedleID3=needle3
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle1MinValue=0
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle1MaxValue=10
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle2MinValue=0
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle2MaxValue=100
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle3MinValue=0
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle3MaxValue=1000
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle1DataObject=BaroAltitude
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle1ObjectField=Altitude
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle2DataObject=BaroAltitude
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle2ObjectField=Altitude
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle3DataObject=BaroAltitude
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle3ObjectField=Altitude
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle1Factor=1
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle2Factor=1
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle3Factor=1
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle1Move=Rotate
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle2Move=Rotate
+DialGadget\HiContrast%20Baro%20Altimeter\data\needle3Move=Rotate
+DialGadget\HiContrast%20Baro%20Altimeter\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\HiContrast%20Baro%20Altimeter\data\useOpenGLFlag=false
+DialGadget\HiContrast%20Baro%20Altimeter\data\beSmooth=false
+DialGadget\HiContrast%20Baro%20Altimeter\configInfo\version=0.0.0
+DialGadget\HiContrast%20Baro%20Altimeter\configInfo\locked=false
+DialGadget\HiContrast%20Barometer\data\dialFile=%%DATAPATH%%dials/hi-contrast/barometer.svg
+DialGadget\HiContrast%20Barometer\data\dialBackgroundID=background
+DialGadget\HiContrast%20Barometer\data\dialForegroundID=
+DialGadget\HiContrast%20Barometer\data\dialNeedleID1=needle
+DialGadget\HiContrast%20Barometer\data\dialNeedleID2=
+DialGadget\HiContrast%20Barometer\data\dialNeedleID3=
+DialGadget\HiContrast%20Barometer\data\needle1MinValue=1000
+DialGadget\HiContrast%20Barometer\data\needle1MaxValue=1120
+DialGadget\HiContrast%20Barometer\data\needle2MinValue=0
+DialGadget\HiContrast%20Barometer\data\needle2MaxValue=100
+DialGadget\HiContrast%20Barometer\data\needle3MinValue=0
+DialGadget\HiContrast%20Barometer\data\needle3MaxValue=1000
+DialGadget\HiContrast%20Barometer\data\needle1DataObject=BaroAltitude
+DialGadget\HiContrast%20Barometer\data\needle1ObjectField=Pressure
+DialGadget\HiContrast%20Barometer\data\needle2DataObject=BaroAltitude
+DialGadget\HiContrast%20Barometer\data\needle2ObjectField=Altitude
+DialGadget\HiContrast%20Barometer\data\needle3DataObject=BaroAltitude
+DialGadget\HiContrast%20Barometer\data\needle3ObjectField=Altitude
+DialGadget\HiContrast%20Barometer\data\needle1Factor=10
+DialGadget\HiContrast%20Barometer\data\needle2Factor=1
+DialGadget\HiContrast%20Barometer\data\needle3Factor=1
+DialGadget\HiContrast%20Barometer\data\needle1Move=Rotate
+DialGadget\HiContrast%20Barometer\data\needle2Move=Rotate
+DialGadget\HiContrast%20Barometer\data\needle3Move=Rotate
+DialGadget\HiContrast%20Barometer\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\HiContrast%20Barometer\data\useOpenGLFlag=false
+DialGadget\HiContrast%20Barometer\data\beSmooth=false
+DialGadget\HiContrast%20Barometer\configInfo\version=0.0.0
+DialGadget\HiContrast%20Barometer\configInfo\locked=false
+DialGadget\HiContrast%20Climbrate\data\dialFile=%%DATAPATH%%dials/hi-contrast/vsi.svg
+DialGadget\HiContrast%20Climbrate\data\dialBackgroundID=background
+DialGadget\HiContrast%20Climbrate\data\dialForegroundID=
+DialGadget\HiContrast%20Climbrate\data\dialNeedleID1=needle
+DialGadget\HiContrast%20Climbrate\data\dialNeedleID2=
+DialGadget\HiContrast%20Climbrate\data\dialNeedleID3=
+DialGadget\HiContrast%20Climbrate\data\needle1MinValue=-12
+DialGadget\HiContrast%20Climbrate\data\needle1MaxValue=12
+DialGadget\HiContrast%20Climbrate\data\needle2MinValue=0
+DialGadget\HiContrast%20Climbrate\data\needle2MaxValue=100
+DialGadget\HiContrast%20Climbrate\data\needle3MinValue=0
+DialGadget\HiContrast%20Climbrate\data\needle3MaxValue=1000
+DialGadget\HiContrast%20Climbrate\data\needle1DataObject=VelocityActual
+DialGadget\HiContrast%20Climbrate\data\needle1ObjectField=Down
+DialGadget\HiContrast%20Climbrate\data\needle2DataObject=BaroAltitude
+DialGadget\HiContrast%20Climbrate\data\needle2ObjectField=Altitude
+DialGadget\HiContrast%20Climbrate\data\needle3DataObject=BaroAltitude
+DialGadget\HiContrast%20Climbrate\data\needle3ObjectField=Altitude
+DialGadget\HiContrast%20Climbrate\data\needle1Factor=0.01
+DialGadget\HiContrast%20Climbrate\data\needle2Factor=1
+DialGadget\HiContrast%20Climbrate\data\needle3Factor=1
+DialGadget\HiContrast%20Climbrate\data\needle1Move=Rotate
+DialGadget\HiContrast%20Climbrate\data\needle2Move=Rotate
+DialGadget\HiContrast%20Climbrate\data\needle3Move=Rotate
+DialGadget\HiContrast%20Climbrate\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\HiContrast%20Climbrate\data\useOpenGLFlag=false
+DialGadget\HiContrast%20Climbrate\data\beSmooth=false
+DialGadget\HiContrast%20Climbrate\configInfo\version=0.0.0
+DialGadget\HiContrast%20Climbrate\configInfo\locked=false
+DialGadget\HiContrast%20Compass\data\dialFile=%%DATAPATH%%dials/hi-contrast/compass.svg
+DialGadget\HiContrast%20Compass\data\dialBackgroundID=background
+DialGadget\HiContrast%20Compass\data\dialForegroundID=foreground
+DialGadget\HiContrast%20Compass\data\dialNeedleID1=needle
+DialGadget\HiContrast%20Compass\data\dialNeedleID2=
+DialGadget\HiContrast%20Compass\data\dialNeedleID3=
+DialGadget\HiContrast%20Compass\data\needle1MinValue=0
+DialGadget\HiContrast%20Compass\data\needle1MaxValue=360
+DialGadget\HiContrast%20Compass\data\needle2MinValue=0
+DialGadget\HiContrast%20Compass\data\needle2MaxValue=100
+DialGadget\HiContrast%20Compass\data\needle3MinValue=0
+DialGadget\HiContrast%20Compass\data\needle3MaxValue=1000
+DialGadget\HiContrast%20Compass\data\needle1DataObject=AttitudeActual
+DialGadget\HiContrast%20Compass\data\needle1ObjectField=Yaw
+DialGadget\HiContrast%20Compass\data\needle2DataObject=BaroAltitude
+DialGadget\HiContrast%20Compass\data\needle2ObjectField=Altitude
+DialGadget\HiContrast%20Compass\data\needle3DataObject=BaroAltitude
+DialGadget\HiContrast%20Compass\data\needle3ObjectField=Altitude
+DialGadget\HiContrast%20Compass\data\needle1Factor=-1
+DialGadget\HiContrast%20Compass\data\needle2Factor=1
+DialGadget\HiContrast%20Compass\data\needle3Factor=1
+DialGadget\HiContrast%20Compass\data\needle1Move=Rotate
+DialGadget\HiContrast%20Compass\data\needle2Move=Rotate
+DialGadget\HiContrast%20Compass\data\needle3Move=Rotate
+DialGadget\HiContrast%20Compass\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\HiContrast%20Compass\data\useOpenGLFlag=false
+DialGadget\HiContrast%20Compass\data\beSmooth=false
+DialGadget\HiContrast%20Compass\configInfo\version=0.0.0
+DialGadget\HiContrast%20Compass\configInfo\locked=false
+DialGadget\HiContrast%20Groundspeed%20kph\data\dialFile=%%DATAPATH%%dials/hi-contrast/speed.svg
+DialGadget\HiContrast%20Groundspeed%20kph\data\dialBackgroundID=background
+DialGadget\HiContrast%20Groundspeed%20kph\data\dialForegroundID=
+DialGadget\HiContrast%20Groundspeed%20kph\data\dialNeedleID1=needle
+DialGadget\HiContrast%20Groundspeed%20kph\data\dialNeedleID2=
+DialGadget\HiContrast%20Groundspeed%20kph\data\dialNeedleID3=
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle1MinValue=0
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle1MaxValue=120
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle2MinValue=0
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle2MaxValue=100
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle3MinValue=0
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle3MaxValue=1000
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle1DataObject=GPSPosition
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle1ObjectField=Groundspeed
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle2DataObject=BaroAltitude
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle2ObjectField=Altitude
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle3DataObject=BaroAltitude
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle3ObjectField=Altitude
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle1Factor=3.6
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle2Factor=1
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle3Factor=1
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle1Move=Rotate
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle2Move=Rotate
+DialGadget\HiContrast%20Groundspeed%20kph\data\needle3Move=Rotate
+DialGadget\HiContrast%20Groundspeed%20kph\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\HiContrast%20Groundspeed%20kph\data\useOpenGLFlag=false
+DialGadget\HiContrast%20Groundspeed%20kph\data\beSmooth=false
+DialGadget\HiContrast%20Groundspeed%20kph\configInfo\version=0.0.0
+DialGadget\HiContrast%20Groundspeed%20kph\configInfo\locked=false
+DialGadget\HiContrast%20Temperature\data\dialFile=%%DATAPATH%%dials/hi-contrast/thermometer.svg
+DialGadget\HiContrast%20Temperature\data\dialBackgroundID=background
+DialGadget\HiContrast%20Temperature\data\dialForegroundID=
+DialGadget\HiContrast%20Temperature\data\dialNeedleID1=needle
+DialGadget\HiContrast%20Temperature\data\dialNeedleID2=needle2
+DialGadget\HiContrast%20Temperature\data\dialNeedleID3=needle3
+DialGadget\HiContrast%20Temperature\data\needle1MinValue=0
+DialGadget\HiContrast%20Temperature\data\needle1MaxValue=120
+DialGadget\HiContrast%20Temperature\data\needle2MinValue=0
+DialGadget\HiContrast%20Temperature\data\needle2MaxValue=100
+DialGadget\HiContrast%20Temperature\data\needle3MinValue=0
+DialGadget\HiContrast%20Temperature\data\needle3MaxValue=1000
+DialGadget\HiContrast%20Temperature\data\needle1DataObject=BaroAltitude
+DialGadget\HiContrast%20Temperature\data\needle1ObjectField=Temperature
+DialGadget\HiContrast%20Temperature\data\needle2DataObject=BaroAltitude
+DialGadget\HiContrast%20Temperature\data\needle2ObjectField=Altitude
+DialGadget\HiContrast%20Temperature\data\needle3DataObject=BaroAltitude
+DialGadget\HiContrast%20Temperature\data\needle3ObjectField=Altitude
+DialGadget\HiContrast%20Temperature\data\needle1Factor=1
+DialGadget\HiContrast%20Temperature\data\needle2Factor=1
+DialGadget\HiContrast%20Temperature\data\needle3Factor=1
+DialGadget\HiContrast%20Temperature\data\needle1Move=Rotate
+DialGadget\HiContrast%20Temperature\data\needle2Move=Rotate
+DialGadget\HiContrast%20Temperature\data\needle3Move=Rotate
+DialGadget\HiContrast%20Temperature\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\HiContrast%20Temperature\data\useOpenGLFlag=false
+DialGadget\HiContrast%20Temperature\data\beSmooth=false
+DialGadget\HiContrast%20Temperature\configInfo\version=0.0.0
+DialGadget\HiContrast%20Temperature\configInfo\locked=false
+DialGadget\Servo%20Channel%201\data\dialFile=%%DATAPATH%%dials/default/thermometer.svg
+DialGadget\Servo%20Channel%201\data\dialBackgroundID=background
+DialGadget\Servo%20Channel%201\data\dialForegroundID=
+DialGadget\Servo%20Channel%201\data\dialNeedleID1=needle
+DialGadget\Servo%20Channel%201\data\dialNeedleID2=needle2
+DialGadget\Servo%20Channel%201\data\dialNeedleID3=needle3
+DialGadget\Servo%20Channel%201\data\needle1MinValue=1000
+DialGadget\Servo%20Channel%201\data\needle1MaxValue=2000
+DialGadget\Servo%20Channel%201\data\needle2MinValue=0
+DialGadget\Servo%20Channel%201\data\needle2MaxValue=100
+DialGadget\Servo%20Channel%201\data\needle3MinValue=0
+DialGadget\Servo%20Channel%201\data\needle3MaxValue=1000
+DialGadget\Servo%20Channel%201\data\needle1DataObject=ManualControlCommand
+DialGadget\Servo%20Channel%201\data\needle1ObjectField=Channel-3
+DialGadget\Servo%20Channel%201\data\needle2DataObject=BaroAltitude
+DialGadget\Servo%20Channel%201\data\needle2ObjectField=Altitude
+DialGadget\Servo%20Channel%201\data\needle3DataObject=BaroAltitude
+DialGadget\Servo%20Channel%201\data\needle3ObjectField=Altitude
+DialGadget\Servo%20Channel%201\data\needle1Factor=1
+DialGadget\Servo%20Channel%201\data\needle2Factor=1
+DialGadget\Servo%20Channel%201\data\needle3Factor=1
+DialGadget\Servo%20Channel%201\data\needle1Move=Rotate
+DialGadget\Servo%20Channel%201\data\needle2Move=Rotate
+DialGadget\Servo%20Channel%201\data\needle3Move=Rotate
+DialGadget\Servo%20Channel%201\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Servo%20Channel%201\data\useOpenGLFlag=false
+DialGadget\Servo%20Channel%201\data\beSmooth=false
+DialGadget\Servo%20Channel%201\configInfo\version=0.0.0
+DialGadget\Servo%20Channel%201\configInfo\locked=false
+DialGadget\Temperature\data\dialFile=%%DATAPATH%%dials/default/thermometer.svg
+DialGadget\Temperature\data\dialBackgroundID=background
+DialGadget\Temperature\data\dialForegroundID=
+DialGadget\Temperature\data\dialNeedleID1=needle
+DialGadget\Temperature\data\dialNeedleID2=needle2
+DialGadget\Temperature\data\dialNeedleID3=needle3
+DialGadget\Temperature\data\needle1MinValue=0
+DialGadget\Temperature\data\needle1MaxValue=120
+DialGadget\Temperature\data\needle2MinValue=0
+DialGadget\Temperature\data\needle2MaxValue=100
+DialGadget\Temperature\data\needle3MinValue=0
+DialGadget\Temperature\data\needle3MaxValue=1000
+DialGadget\Temperature\data\needle1DataObject=BaroAltitude
+DialGadget\Temperature\data\needle1ObjectField=Temperature
+DialGadget\Temperature\data\needle2DataObject=BaroAltitude
+DialGadget\Temperature\data\needle2ObjectField=Altitude
+DialGadget\Temperature\data\needle3DataObject=BaroAltitude
+DialGadget\Temperature\data\needle3ObjectField=Altitude
+DialGadget\Temperature\data\needle1Factor=1
+DialGadget\Temperature\data\needle2Factor=1
+DialGadget\Temperature\data\needle3Factor=1
+DialGadget\Temperature\data\needle1Move=Rotate
+DialGadget\Temperature\data\needle2Move=Rotate
+DialGadget\Temperature\data\needle3Move=Rotate
+DialGadget\Temperature\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0"
+DialGadget\Temperature\data\useOpenGLFlag=false
+DialGadget\Temperature\data\beSmooth=false
+DialGadget\Temperature\configInfo\version=0.0.0
+DialGadget\Temperature\configInfo\locked=false
+GCSControlGadget\MS%20Sidewinder\data\controlsMode=2
+GCSControlGadget\MS%20Sidewinder\data\rollChannel=0
+GCSControlGadget\MS%20Sidewinder\data\pitchChannel=1
+GCSControlGadget\MS%20Sidewinder\data\yawChannel=3
+GCSControlGadget\MS%20Sidewinder\data\throttleChannel=2
+GCSControlGadget\MS%20Sidewinder\data\button0Action=0
+GCSControlGadget\MS%20Sidewinder\data\button0Function=0
+GCSControlGadget\MS%20Sidewinder\data\button0Amount=0
+GCSControlGadget\MS%20Sidewinder\data\channel0Reverse=false
+GCSControlGadget\MS%20Sidewinder\data\button1Action=0
+GCSControlGadget\MS%20Sidewinder\data\button1Function=0
+GCSControlGadget\MS%20Sidewinder\data\button1Amount=0
+GCSControlGadget\MS%20Sidewinder\data\channel1Reverse=false
+GCSControlGadget\MS%20Sidewinder\data\button2Action=0
+GCSControlGadget\MS%20Sidewinder\data\button2Function=3
+GCSControlGadget\MS%20Sidewinder\data\button2Amount=0.1
+GCSControlGadget\MS%20Sidewinder\data\channel2Reverse=true
+GCSControlGadget\MS%20Sidewinder\data\button3Action=0
+GCSControlGadget\MS%20Sidewinder\data\button3Function=3
+GCSControlGadget\MS%20Sidewinder\data\button3Amount=0.1
+GCSControlGadget\MS%20Sidewinder\data\channel3Reverse=false
+GCSControlGadget\MS%20Sidewinder\data\button4Action=0
+GCSControlGadget\MS%20Sidewinder\data\button4Function=0
+GCSControlGadget\MS%20Sidewinder\data\button4Amount=0
+GCSControlGadget\MS%20Sidewinder\data\channel4Reverse=false
+GCSControlGadget\MS%20Sidewinder\data\button5Action=0
+GCSControlGadget\MS%20Sidewinder\data\button5Function=0
+GCSControlGadget\MS%20Sidewinder\data\button5Amount=0
+GCSControlGadget\MS%20Sidewinder\data\channel5Reverse=false
+GCSControlGadget\MS%20Sidewinder\data\button6Action=0
+GCSControlGadget\MS%20Sidewinder\data\button6Function=0
+GCSControlGadget\MS%20Sidewinder\data\button6Amount=0
+GCSControlGadget\MS%20Sidewinder\data\channel6Reverse=false
+GCSControlGadget\MS%20Sidewinder\data\button7Action=0
+GCSControlGadget\MS%20Sidewinder\data\button7Function=0
+GCSControlGadget\MS%20Sidewinder\data\button7Amount=0
+GCSControlGadget\MS%20Sidewinder\data\channel7Reverse=false
+GCSControlGadget\MS%20Sidewinder\configInfo\version=0.0.0
+GCSControlGadget\MS%20Sidewinder\configInfo\locked=false
+GpsDisplayGadget\Flight%20GPS\data\defaultSpeed=11
+GpsDisplayGadget\Flight%20GPS\data\defaultDataBits=3
+GpsDisplayGadget\Flight%20GPS\data\defaultFlow=0
+GpsDisplayGadget\Flight%20GPS\data\defaultParity=0
+GpsDisplayGadget\Flight%20GPS\data\defaultStopBits=0
+GpsDisplayGadget\Flight%20GPS\data\defaultPort=Communications Port (COM1)
+GpsDisplayGadget\Flight%20GPS\data\connectionMode=Telemetry
+GpsDisplayGadget\Flight%20GPS\configInfo\version=0.0.0
+GpsDisplayGadget\Flight%20GPS\configInfo\locked=false
+GpsDisplayGadget\GPS%20Mouse\data\defaultSpeed=17
+GpsDisplayGadget\GPS%20Mouse\data\defaultDataBits=3
+GpsDisplayGadget\GPS%20Mouse\data\defaultFlow=0
+GpsDisplayGadget\GPS%20Mouse\data\defaultParity=0
+GpsDisplayGadget\GPS%20Mouse\data\defaultStopBits=0
+GpsDisplayGadget\GPS%20Mouse\data\defaultPort=Communications Port (COM1)
+GpsDisplayGadget\GPS%20Mouse\data\connectionMode=Serial
+GpsDisplayGadget\GPS%20Mouse\configInfo\version=0.0.0
+GpsDisplayGadget\GPS%20Mouse\configInfo\locked=false
+HITL\Flightgear%20HITL\data\simulatorId=FG
+HITL\Flightgear%20HITL\data\binPath=\\usr\\games\\fgfs
+HITL\Flightgear%20HITL\data\dataPath=\\usr\\share\\games\\FlightGear
+HITL\Flightgear%20HITL\data\manual=false
+HITL\Flightgear%20HITL\data\startSim=true
+HITL\Flightgear%20HITL\data\hostAddress=127.0.0.1
+HITL\Flightgear%20HITL\data\remoteHostAddress=127.0.0.1
+HITL\Flightgear%20HITL\data\outPort=9010
+HITL\Flightgear%20HITL\data\inPort=9009
+HITL\Flightgear%20HITL\data\latitude=
+HITL\Flightgear%20HITL\data\longitude=
+HITL\Flightgear%20HITL\configInfo\version=0.0.0
+HITL\Flightgear%20HITL\configInfo\locked=false
+HITL\XPlane%20HITL\data\simulatorId=X-Plane
+HITL\XPlane%20HITL\data\binPath=\\home\\lafargue\\X-Plane 9\\X-Plane-i686
+HITL\XPlane%20HITL\data\dataPath=\\usr\\share\\games\\FlightGear
+HITL\XPlane%20HITL\data\manual=false
+HITL\XPlane%20HITL\data\startSim=false
+HITL\XPlane%20HITL\data\hostAddress=127.0.0.3
+HITL\XPlane%20HITL\data\remoteHostAddress=127.0.0.1
+HITL\XPlane%20HITL\data\outPort=49000
+HITL\XPlane%20HITL\data\inPort=6756
+HITL\XPlane%20HITL\data\latitude=
+HITL\XPlane%20HITL\data\longitude=
+HITL\XPlane%20HITL\configInfo\version=0.0.0
+HITL\XPlane%20HITL\configInfo\locked=false
+ImportExportGadget\default\data\iniFile=gcs.ini
+ImportExportGadget\default\configInfo\version=1.0.1
+ImportExportGadget\default\configInfo\locked=false
+LineardialGadget\AHRS%20CPU\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
+LineardialGadget\AHRS%20CPU\data\sourceDataObject=AhrsStatus
+LineardialGadget\AHRS%20CPU\data\sourceObjectField=CPULoad
+LineardialGadget\AHRS%20CPU\data\minValue=0
+LineardialGadget\AHRS%20CPU\data\maxValue=100
+LineardialGadget\AHRS%20CPU\data\redMin=80
+LineardialGadget\AHRS%20CPU\data\redMax=100
+LineardialGadget\AHRS%20CPU\data\yellowMin=50
+LineardialGadget\AHRS%20CPU\data\yellowMax=80
+LineardialGadget\AHRS%20CPU\data\greenMin=0
+LineardialGadget\AHRS%20CPU\data\greenMax=50
+LineardialGadget\AHRS%20CPU\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
+LineardialGadget\AHRS%20CPU\data\decimalPlaces=0
+LineardialGadget\AHRS%20CPU\data\factor=1
+LineardialGadget\AHRS%20CPU\data\useOpenGLFlag=false
+LineardialGadget\AHRS%20CPU\configInfo\version=0.0.0
+LineardialGadget\AHRS%20CPU\configInfo\locked=false
+LineardialGadget\Accel%20Horizontal%20X\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg
+LineardialGadget\Accel%20Horizontal%20X\data\sourceDataObject=AttitudeRaw
+LineardialGadget\Accel%20Horizontal%20X\data\sourceObjectField=accels-X
+LineardialGadget\Accel%20Horizontal%20X\data\minValue=-11
+LineardialGadget\Accel%20Horizontal%20X\data\maxValue=11
+LineardialGadget\Accel%20Horizontal%20X\data\redMin=-11
+LineardialGadget\Accel%20Horizontal%20X\data\redMax=11
+LineardialGadget\Accel%20Horizontal%20X\data\yellowMin=-11
+LineardialGadget\Accel%20Horizontal%20X\data\yellowMax=-5
+LineardialGadget\Accel%20Horizontal%20X\data\greenMin=-10
+LineardialGadget\Accel%20Horizontal%20X\data\greenMax=-9
+LineardialGadget\Accel%20Horizontal%20X\data\font="Andale Mono,8,-1,5,50,0,0,0,0,0"
+LineardialGadget\Accel%20Horizontal%20X\data\decimalPlaces=2
+LineardialGadget\Accel%20Horizontal%20X\data\factor=1
+LineardialGadget\Accel%20Horizontal%20X\data\useOpenGLFlag=false
+LineardialGadget\Accel%20Horizontal%20X\configInfo\version=0.0.0
+LineardialGadget\Accel%20Horizontal%20X\configInfo\locked=false
+LineardialGadget\Accel%20Horizontal%20Y\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg
+LineardialGadget\Accel%20Horizontal%20Y\data\sourceDataObject=AttitudeRaw
+LineardialGadget\Accel%20Horizontal%20Y\data\sourceObjectField=accels-Y
+LineardialGadget\Accel%20Horizontal%20Y\data\minValue=-11
+LineardialGadget\Accel%20Horizontal%20Y\data\maxValue=11
+LineardialGadget\Accel%20Horizontal%20Y\data\redMin=-11
+LineardialGadget\Accel%20Horizontal%20Y\data\redMax=11
+LineardialGadget\Accel%20Horizontal%20Y\data\yellowMin=-11
+LineardialGadget\Accel%20Horizontal%20Y\data\yellowMax=-5
+LineardialGadget\Accel%20Horizontal%20Y\data\greenMin=-10
+LineardialGadget\Accel%20Horizontal%20Y\data\greenMax=-9
+LineardialGadget\Accel%20Horizontal%20Y\data\font="Andale Mono,6,-1,5,50,0,0,0,0,0"
+LineardialGadget\Accel%20Horizontal%20Y\data\decimalPlaces=2
+LineardialGadget\Accel%20Horizontal%20Y\data\factor=1
+LineardialGadget\Accel%20Horizontal%20Y\data\useOpenGLFlag=false
+LineardialGadget\Accel%20Horizontal%20Y\configInfo\version=0.0.0
+LineardialGadget\Accel%20Horizontal%20Y\configInfo\locked=false
+LineardialGadget\Accel%20Horizontal%20Z\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg
+LineardialGadget\Accel%20Horizontal%20Z\data\sourceDataObject=AttitudeRaw
+LineardialGadget\Accel%20Horizontal%20Z\data\sourceObjectField=accels-Z
+LineardialGadget\Accel%20Horizontal%20Z\data\minValue=-11
+LineardialGadget\Accel%20Horizontal%20Z\data\maxValue=11
+LineardialGadget\Accel%20Horizontal%20Z\data\redMin=-11
+LineardialGadget\Accel%20Horizontal%20Z\data\redMax=11
+LineardialGadget\Accel%20Horizontal%20Z\data\yellowMin=-11
+LineardialGadget\Accel%20Horizontal%20Z\data\yellowMax=-5
+LineardialGadget\Accel%20Horizontal%20Z\data\greenMin=-10
+LineardialGadget\Accel%20Horizontal%20Z\data\greenMax=-9
+LineardialGadget\Accel%20Horizontal%20Z\data\font="Andale Mono,8,-1,5,50,0,0,0,0,0"
+LineardialGadget\Accel%20Horizontal%20Z\data\decimalPlaces=2
+LineardialGadget\Accel%20Horizontal%20Z\data\factor=1
+LineardialGadget\Accel%20Horizontal%20Z\data\useOpenGLFlag=false
+LineardialGadget\Accel%20Horizontal%20Z\configInfo\version=0.0.0
+LineardialGadget\Accel%20Horizontal%20Z\configInfo\locked=false
+LineardialGadget\Arm%20Status\data\dFile=%%DATAPATH%%dials/default/arm-status.svg
+LineardialGadget\Arm%20Status\data\sourceDataObject=ManualControlCommand
+LineardialGadget\Arm%20Status\data\sourceObjectField=Armed
+LineardialGadget\Arm%20Status\data\minValue=0
+LineardialGadget\Arm%20Status\data\maxValue=100
+LineardialGadget\Arm%20Status\data\redMin=0
+LineardialGadget\Arm%20Status\data\redMax=33
+LineardialGadget\Arm%20Status\data\yellowMin=33
+LineardialGadget\Arm%20Status\data\yellowMax=66
+LineardialGadget\Arm%20Status\data\greenMin=66
+LineardialGadget\Arm%20Status\data\greenMax=100
+LineardialGadget\Arm%20Status\data\font=",12,-1,5,50,0,0,0,0,0"
+LineardialGadget\Arm%20Status\data\decimalPlaces=0
+LineardialGadget\Arm%20Status\data\factor=1
+LineardialGadget\Arm%20Status\data\useOpenGLFlag=false
+LineardialGadget\Arm%20Status\configInfo\version=0.0.0
+LineardialGadget\Arm%20Status\configInfo\locked=false
+LineardialGadget\Flight%20Time\data\dFile=%%DATAPATH%%dials/default/textonly.svg
+LineardialGadget\Flight%20Time\data\sourceDataObject=SystemStats
+LineardialGadget\Flight%20Time\data\sourceObjectField=FlightTime
+LineardialGadget\Flight%20Time\data\minValue=0
+LineardialGadget\Flight%20Time\data\maxValue=100
+LineardialGadget\Flight%20Time\data\redMin=0
+LineardialGadget\Flight%20Time\data\redMax=33
+LineardialGadget\Flight%20Time\data\yellowMin=33
+LineardialGadget\Flight%20Time\data\yellowMax=66
+LineardialGadget\Flight%20Time\data\greenMin=66
+LineardialGadget\Flight%20Time\data\greenMax=100
+LineardialGadget\Flight%20Time\data\font=",12,-1,5,50,0,0,0,0,0"
+LineardialGadget\Flight%20Time\data\decimalPlaces=0
+LineardialGadget\Flight%20Time\data\factor=0.001
+LineardialGadget\Flight%20Time\data\useOpenGLFlag=false
+LineardialGadget\Flight%20Time\configInfo\version=0.0.0
+LineardialGadget\Flight%20Time\configInfo\locked=false
+LineardialGadget\Flight%20mode\data\dFile=%%DATAPATH%%dials/default/flightmode-status.svg
+LineardialGadget\Flight%20mode\data\sourceDataObject=ManualControlCommand
+LineardialGadget\Flight%20mode\data\sourceObjectField=FlightMode
+LineardialGadget\Flight%20mode\data\minValue=0
+LineardialGadget\Flight%20mode\data\maxValue=100
+LineardialGadget\Flight%20mode\data\redMin=0
+LineardialGadget\Flight%20mode\data\redMax=33
+LineardialGadget\Flight%20mode\data\yellowMin=33
+LineardialGadget\Flight%20mode\data\yellowMax=66
+LineardialGadget\Flight%20mode\data\greenMin=66
+LineardialGadget\Flight%20mode\data\greenMax=100
+LineardialGadget\Flight%20mode\data\font=",12,-1,5,50,0,0,0,0,0"
+LineardialGadget\Flight%20mode\data\decimalPlaces=0
+LineardialGadget\Flight%20mode\data\factor=1
+LineardialGadget\Flight%20mode\data\useOpenGLFlag=false
+LineardialGadget\Flight%20mode\configInfo\version=0.0.0
+LineardialGadget\Flight%20mode\configInfo\locked=false
+LineardialGadget\GPS%20Sats\data\dFile=%%DATAPATH%%dials/default/gps-signal.svg
+LineardialGadget\GPS%20Sats\data\sourceDataObject=GPSPosition
+LineardialGadget\GPS%20Sats\data\sourceObjectField=Satellites
+LineardialGadget\GPS%20Sats\data\minValue=0
+LineardialGadget\GPS%20Sats\data\maxValue=12
+LineardialGadget\GPS%20Sats\data\redMin=0
+LineardialGadget\GPS%20Sats\data\redMax=0
+LineardialGadget\GPS%20Sats\data\yellowMin=0
+LineardialGadget\GPS%20Sats\data\yellowMax=0
+LineardialGadget\GPS%20Sats\data\greenMin=0
+LineardialGadget\GPS%20Sats\data\greenMax=0
+LineardialGadget\GPS%20Sats\data\font=",12,-1,5,50,0,0,0,0,0"
+LineardialGadget\GPS%20Sats\data\decimalPlaces=0
+LineardialGadget\GPS%20Sats\data\factor=1
+LineardialGadget\GPS%20Sats\data\useOpenGLFlag=false
+LineardialGadget\GPS%20Sats\configInfo\version=0.0.0
+LineardialGadget\GPS%20Sats\configInfo\locked=false
+LineardialGadget\GPS%20Status\data\dFile=%%DATAPATH%%dials/default/gps-status.svg
+LineardialGadget\GPS%20Status\data\sourceDataObject=GPSPosition
+LineardialGadget\GPS%20Status\data\sourceObjectField=Status
+LineardialGadget\GPS%20Status\data\minValue=0
+LineardialGadget\GPS%20Status\data\maxValue=100
+LineardialGadget\GPS%20Status\data\redMin=0
+LineardialGadget\GPS%20Status\data\redMax=33
+LineardialGadget\GPS%20Status\data\yellowMin=33
+LineardialGadget\GPS%20Status\data\yellowMax=66
+LineardialGadget\GPS%20Status\data\greenMin=66
+LineardialGadget\GPS%20Status\data\greenMax=100
+LineardialGadget\GPS%20Status\data\font=",12,-1,5,50,0,0,0,0,0"
+LineardialGadget\GPS%20Status\data\decimalPlaces=0
+LineardialGadget\GPS%20Status\data\factor=1
+LineardialGadget\GPS%20Status\data\useOpenGLFlag=false
+LineardialGadget\GPS%20Status\configInfo\version=0.0.0
+LineardialGadget\GPS%20Status\configInfo\locked=false
+LineardialGadget\Mainboard%20CPU\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
+LineardialGadget\Mainboard%20CPU\data\sourceDataObject=SystemStats
+LineardialGadget\Mainboard%20CPU\data\sourceObjectField=CPULoad
+LineardialGadget\Mainboard%20CPU\data\minValue=0
+LineardialGadget\Mainboard%20CPU\data\maxValue=100
+LineardialGadget\Mainboard%20CPU\data\redMin=80
+LineardialGadget\Mainboard%20CPU\data\redMax=100
+LineardialGadget\Mainboard%20CPU\data\yellowMin=50
+LineardialGadget\Mainboard%20CPU\data\yellowMax=80
+LineardialGadget\Mainboard%20CPU\data\greenMin=0
+LineardialGadget\Mainboard%20CPU\data\greenMax=50
+LineardialGadget\Mainboard%20CPU\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
+LineardialGadget\Mainboard%20CPU\data\decimalPlaces=0
+LineardialGadget\Mainboard%20CPU\data\factor=1
+LineardialGadget\Mainboard%20CPU\data\useOpenGLFlag=false
+LineardialGadget\Mainboard%20CPU\configInfo\version=0.0.0
+LineardialGadget\Mainboard%20CPU\configInfo\locked=false
+LineardialGadget\PitchActual\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
+LineardialGadget\PitchActual\data\sourceDataObject=AttitudeActual
+LineardialGadget\PitchActual\data\sourceObjectField=Pitch
+LineardialGadget\PitchActual\data\minValue=-90
+LineardialGadget\PitchActual\data\maxValue=90
+LineardialGadget\PitchActual\data\redMin=0
+LineardialGadget\PitchActual\data\redMax=1
+LineardialGadget\PitchActual\data\yellowMin=0.1
+LineardialGadget\PitchActual\data\yellowMax=0.9
+LineardialGadget\PitchActual\data\greenMin=0.3
+LineardialGadget\PitchActual\data\greenMax=0.8
+LineardialGadget\PitchActual\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
+LineardialGadget\PitchActual\data\decimalPlaces=2
+LineardialGadget\PitchActual\data\factor=1
+LineardialGadget\PitchActual\data\useOpenGLFlag=false
+LineardialGadget\PitchActual\configInfo\version=0.0.0
+LineardialGadget\PitchActual\configInfo\locked=false
+LineardialGadget\PitchCommand\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
+LineardialGadget\PitchCommand\data\sourceDataObject=ManualControlCommand
+LineardialGadget\PitchCommand\data\sourceObjectField=Pitch
+LineardialGadget\PitchCommand\data\minValue=-1
+LineardialGadget\PitchCommand\data\maxValue=1
+LineardialGadget\PitchCommand\data\redMin=0
+LineardialGadget\PitchCommand\data\redMax=1
+LineardialGadget\PitchCommand\data\yellowMin=0.1
+LineardialGadget\PitchCommand\data\yellowMax=0.9
+LineardialGadget\PitchCommand\data\greenMin=0.3
+LineardialGadget\PitchCommand\data\greenMax=0.8
+LineardialGadget\PitchCommand\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
+LineardialGadget\PitchCommand\data\decimalPlaces=2
+LineardialGadget\PitchCommand\data\factor=1
+LineardialGadget\PitchCommand\data\useOpenGLFlag=false
+LineardialGadget\PitchCommand\configInfo\version=0.0.0
+LineardialGadget\PitchCommand\configInfo\locked=false
+LineardialGadget\PitchDesired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
+LineardialGadget\PitchDesired\data\sourceDataObject=ActuatorDesired
+LineardialGadget\PitchDesired\data\sourceObjectField=Pitch
+LineardialGadget\PitchDesired\data\minValue=-1
+LineardialGadget\PitchDesired\data\maxValue=1
+LineardialGadget\PitchDesired\data\redMin=0
+LineardialGadget\PitchDesired\data\redMax=1
+LineardialGadget\PitchDesired\data\yellowMin=0.1
+LineardialGadget\PitchDesired\data\yellowMax=0.9
+LineardialGadget\PitchDesired\data\greenMin=0.3
+LineardialGadget\PitchDesired\data\greenMax=0.8
+LineardialGadget\PitchDesired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
+LineardialGadget\PitchDesired\data\decimalPlaces=2
+LineardialGadget\PitchDesired\data\factor=1
+LineardialGadget\PitchDesired\data\useOpenGLFlag=false
+LineardialGadget\PitchDesired\configInfo\version=0.0.0
+LineardialGadget\PitchDesired\configInfo\locked=false
+LineardialGadget\Roll\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
+LineardialGadget\Roll\data\sourceDataObject=ManualControlCommand
+LineardialGadget\Roll\data\sourceObjectField=Roll
+LineardialGadget\Roll\data\minValue=0
+LineardialGadget\Roll\data\maxValue=1
+LineardialGadget\Roll\data\redMin=0
+LineardialGadget\Roll\data\redMax=1
+LineardialGadget\Roll\data\yellowMin=0.1
+LineardialGadget\Roll\data\yellowMax=0.9
+LineardialGadget\Roll\data\greenMin=0.3
+LineardialGadget\Roll\data\greenMax=0.8
+LineardialGadget\Roll\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
+LineardialGadget\Roll\data\decimalPlaces=2
+LineardialGadget\Roll\data\factor=1
+LineardialGadget\Roll\data\useOpenGLFlag=false
+LineardialGadget\Roll\configInfo\version=0.0.0
+LineardialGadget\Roll\configInfo\locked=false
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\sourceDataObject=GCSTelemetryStats
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\sourceObjectField=RxDataRate
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\minValue=0
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\maxValue=1200
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\redMin=900
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\redMax=1200
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\yellowMin=650
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\yellowMax=900
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\greenMin=0
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\greenMax=650
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\decimalPlaces=0
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\factor=1
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\useOpenGLFlag=false
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\configInfo\version=0.0.0
+LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\configInfo\locked=false
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\sourceDataObject=GCSTelemetryStats
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\sourceObjectField=TxDataRate
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\minValue=0
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\maxValue=1200
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\redMin=900
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\redMax=1200
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\yellowMin=650
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\yellowMax=900
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\greenMin=0
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\greenMax=650
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\decimalPlaces=0
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\factor=1
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\data\useOpenGLFlag=false
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\configInfo\version=0.0.0
+LineardialGadget\Telemetry%20TX%20Rate%20Horizontal\configInfo\locked=false
+LineardialGadget\Throttle\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
+LineardialGadget\Throttle\data\sourceDataObject=ManualControlCommand
+LineardialGadget\Throttle\data\sourceObjectField=Throttle
+LineardialGadget\Throttle\data\minValue=0
+LineardialGadget\Throttle\data\maxValue=1
+LineardialGadget\Throttle\data\redMin=0
+LineardialGadget\Throttle\data\redMax=1
+LineardialGadget\Throttle\data\yellowMin=0.1
+LineardialGadget\Throttle\data\yellowMax=0.9
+LineardialGadget\Throttle\data\greenMin=0.3
+LineardialGadget\Throttle\data\greenMax=0.8
+LineardialGadget\Throttle\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
+LineardialGadget\Throttle\data\decimalPlaces=2
+LineardialGadget\Throttle\data\factor=1
+LineardialGadget\Throttle\data\useOpenGLFlag=false
+LineardialGadget\Throttle\configInfo\version=0.0.0
+LineardialGadget\Throttle\configInfo\locked=false
+LineardialGadget\Yaw\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg
+LineardialGadget\Yaw\data\sourceDataObject=ManualControlCommand
+LineardialGadget\Yaw\data\sourceObjectField=Yaw
+LineardialGadget\Yaw\data\minValue=0
+LineardialGadget\Yaw\data\maxValue=1
+LineardialGadget\Yaw\data\redMin=0
+LineardialGadget\Yaw\data\redMax=1
+LineardialGadget\Yaw\data\yellowMin=0.1
+LineardialGadget\Yaw\data\yellowMax=0.9
+LineardialGadget\Yaw\data\greenMin=0.3
+LineardialGadget\Yaw\data\greenMax=0.8
+LineardialGadget\Yaw\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0"
+LineardialGadget\Yaw\data\decimalPlaces=2
+LineardialGadget\Yaw\data\factor=1
+LineardialGadget\Yaw\data\useOpenGLFlag=false
+LineardialGadget\Yaw\configInfo\version=0.0.0
+LineardialGadget\Yaw\configInfo\locked=false
+ModelViewGadget\Aeroquad%20%2B\data\acFilename=%%DATAPATH%%models/multi/aeroquad/aeroquad_+.3ds
+ModelViewGadget\Aeroquad%20%2B\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
+ModelViewGadget\Aeroquad%20%2B\data\enableVbo=false
+ModelViewGadget\Aeroquad%20%2B\configInfo\version=0.0.0
+ModelViewGadget\Aeroquad%20%2B\configInfo\locked=false
+ModelViewGadget\Easyquad%20X\data\acFilename=%%DATAPATH%%models/multi/easy_quad/easy_quad_X.3ds
+ModelViewGadget\Easyquad%20X\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
+ModelViewGadget\Easyquad%20X\data\enableVbo=false
+ModelViewGadget\Easyquad%20X\configInfo\version=0.0.0
+ModelViewGadget\Easyquad%20X\configInfo\locked=false
+ModelViewGadget\Easystar\data\acFilename=%%DATAPATH%%models/planes/Easystar/easystar.3ds
+ModelViewGadget\Easystar\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
+ModelViewGadget\Easystar\data\enableVbo=false
+ModelViewGadget\Easystar\configInfo\version=0.0.0
+ModelViewGadget\Easystar\configInfo\locked=false
+ModelViewGadget\Firecracker\data\acFilename=%%DATAPATH%%models/planes/firecracker/firecracker.3ds
+ModelViewGadget\Firecracker\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
+ModelViewGadget\Firecracker\data\enableVbo=false
+ModelViewGadget\Firecracker\configInfo\version=0.0.0
+ModelViewGadget\Firecracker\configInfo\locked=false
+ModelViewGadget\Funjet\data\acFilename=%%DATAPATH%%models/planes/funjet/funjet.3ds
+ModelViewGadget\Funjet\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
+ModelViewGadget\Funjet\data\enableVbo=false
+ModelViewGadget\Funjet\configInfo\version=0.0.0
+ModelViewGadget\Funjet\configInfo\locked=false
+ModelViewGadget\Gaui%20330X\data\acFilename=%%DATAPATH%%models/multi/gaui_330x/gaui_330x.3ds
+ModelViewGadget\Gaui%20330X\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
+ModelViewGadget\Gaui%20330X\data\enableVbo=false
+ModelViewGadget\Gaui%20330X\configInfo\version=0.0.0
+ModelViewGadget\Gaui%20330X\configInfo\locked=false
+ModelViewGadget\Helicopter%20-%20TRex%20450\data\acFilename=%%DATAPATH%%models/helis/t-rex/t-rex_450_xl.3ds
+ModelViewGadget\Helicopter%20-%20TRex%20450\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
+ModelViewGadget\Helicopter%20-%20TRex%20450\data\enableVbo=false
+ModelViewGadget\Helicopter%20-%20TRex%20450\configInfo\version=0.0.0
+ModelViewGadget\Helicopter%20-%20TRex%20450\configInfo\locked=false
+ModelViewGadget\Hexacopter\data\acFilename=%%DATAPATH%%models/multi/mikrokopter/MK_Hexa.3ds
+ModelViewGadget\Hexacopter\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
+ModelViewGadget\Hexacopter\data\enableVbo=false
+ModelViewGadget\Hexacopter\configInfo\version=0.0.0
+ModelViewGadget\Hexacopter\configInfo\locked=false
+ModelViewGadget\Quadcopter\data\acFilename=%%DATAPATH%%models/multi/mikrokopter/MK_L4-ME.3ds
+ModelViewGadget\Quadcopter\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
+ModelViewGadget\Quadcopter\data\enableVbo=false
+ModelViewGadget\Quadcopter\configInfo\version=0.0.0
+ModelViewGadget\Quadcopter\configInfo\locked=false
+ModelViewGadget\Scorpion%20Tricopter\data\acFilename=%%DATAPATH%%models/multi/scorpion_tricopter/scorpion_tricopter.3ds
+ModelViewGadget\Scorpion%20Tricopter\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
+ModelViewGadget\Scorpion%20Tricopter\data\enableVbo=false
+ModelViewGadget\Scorpion%20Tricopter\configInfo\version=0.0.0
+ModelViewGadget\Scorpion%20Tricopter\configInfo\locked=false
+ModelViewGadget\Test%20Quad%20%2B\data\acFilename=%%DATAPATH%%models/multi/test_quad/test_quad_+.3ds
+ModelViewGadget\Test%20Quad%20%2B\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
+ModelViewGadget\Test%20Quad%20%2B\data\enableVbo=false
+ModelViewGadget\Test%20Quad%20%2B\configInfo\version=0.0.0
+ModelViewGadget\Test%20Quad%20%2B\configInfo\locked=false
+ModelViewGadget\Test%20Quad%20X\data\acFilename=%%DATAPATH%%models/multi/test_quad/test_quad_X.3ds
+ModelViewGadget\Test%20Quad%20X\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png
+ModelViewGadget\Test%20Quad%20X\data\enableVbo=false
+ModelViewGadget\Test%20Quad%20X\configInfo\version=0.0.0
+ModelViewGadget\Test%20Quad%20X\configInfo\locked=false
+OPMapGadget\Google%20Sat\data\mapProvider=GoogleSatellite
+OPMapGadget\Google%20Sat\data\defaultZoom=2
+OPMapGadget\Google%20Sat\data\defaultLatitude=0
+OPMapGadget\Google%20Sat\data\defaultLongitude=0
+OPMapGadget\Google%20Sat\data\useOpenGL=true
+OPMapGadget\Google%20Sat\data\showTileGridLines=false
+OPMapGadget\Google%20Sat\data\accessMode=ServerAndCache
+OPMapGadget\Google%20Sat\data\useMemoryCache=true
+OPMapGadget\Google%20Sat\data\uavSymbol=mapquad.png
+OPMapGadget\Google%20Sat\data\cacheLocation=%%STOREPATH%%mapscache-sat/
+OPMapGadget\Google%20Sat\configInfo\version=0.0.0
+OPMapGadget\Google%20Sat\configInfo\locked=false
+OPMapGadget\Memory%20Only\data\mapProvider=GoogleMap
+OPMapGadget\Memory%20Only\data\defaultZoom=2
+OPMapGadget\Memory%20Only\data\defaultLatitude=0
+OPMapGadget\Memory%20Only\data\defaultLongitude=0
+OPMapGadget\Memory%20Only\data\useOpenGL=true
+OPMapGadget\Memory%20Only\data\showTileGridLines=false
+OPMapGadget\Memory%20Only\data\accessMode=CacheOnly
+OPMapGadget\Memory%20Only\data\useMemoryCache=true
+OPMapGadget\Memory%20Only\data\uavSymbol=airplanepip.png
+OPMapGadget\Memory%20Only\data\cacheLocation=%%STOREPATH%%mapscache/
+OPMapGadget\Memory%20Only\configInfo\version=0.0.0
+OPMapGadget\Memory%20Only\configInfo\locked=false
+OPMapGadget\default\data\mapProvider=GoogleMap
+OPMapGadget\default\data\defaultZoom=2
+OPMapGadget\default\data\defaultLatitude=0
+OPMapGadget\default\data\defaultLongitude=0
+OPMapGadget\default\data\useOpenGL=false
+OPMapGadget\default\data\showTileGridLines=false
+OPMapGadget\default\data\accessMode=ServerAndCache
+OPMapGadget\default\data\useMemoryCache=true
+OPMapGadget\default\data\uavSymbol=mapquad.png
+OPMapGadget\default\data\cacheLocation=%%STOREPATH%%mapscache/
+OPMapGadget\default\configInfo\version=0.0.0
+OPMapGadget\default\configInfo\locked=false
+PFDGadget\raw\data\dialFile=%%DATAPATH%%pfd/default/pfd.svg
+PFDGadget\raw\data\useOpenGLFlag=false
+PFDGadget\raw\data\hqFonts=false
+PFDGadget\raw\data\beSmooth=false
+PFDGadget\raw\configInfo\version=0.0.0
+PFDGadget\raw\configInfo\locked=false
+PFDGadget\smooth\data\dialFile=%%DATAPATH%%pfd/default/pfd.svg
+PFDGadget\smooth\data\useOpenGLFlag=false
+PFDGadget\smooth\data\hqFonts=false
+PFDGadget\smooth\data\beSmooth=true
+PFDGadget\smooth\configInfo\version=0.0.0
+PFDGadget\smooth\configInfo\locked=false
+PipXtreme\default\configInfo\version=0.0.0
+PipXtreme\default\configInfo\locked=false
+ScopeGadget\Accel\data\configurationStreamVersion=1000
+ScopeGadget\Accel\data\plotType=1
+ScopeGadget\Accel\data\dataSize=60
+ScopeGadget\Accel\data\refreshInterval=100
+ScopeGadget\Accel\data\plotCurveCount=3
+ScopeGadget\Accel\data\plotCurve0\uavObject=AttitudeRaw
+ScopeGadget\Accel\data\plotCurve0\uavField=accels-X
+ScopeGadget\Accel\data\plotCurve0\color=4294901760
+ScopeGadget\Accel\data\plotCurve0\yScalePower=0
+ScopeGadget\Accel\data\plotCurve0\yMinimum=0
+ScopeGadget\Accel\data\plotCurve0\yMaximum=0
+ScopeGadget\Accel\data\plotCurve1\uavObject=AttitudeRaw
+ScopeGadget\Accel\data\plotCurve1\uavField=accels-Y
+ScopeGadget\Accel\data\plotCurve1\color=4283782655
+ScopeGadget\Accel\data\plotCurve1\yScalePower=0
+ScopeGadget\Accel\data\plotCurve1\yMinimum=0
+ScopeGadget\Accel\data\plotCurve1\yMaximum=0
+ScopeGadget\Accel\data\plotCurve2\uavObject=AttitudeRaw
+ScopeGadget\Accel\data\plotCurve2\uavField=accels-Z
+ScopeGadget\Accel\data\plotCurve2\color=4283804160
+ScopeGadget\Accel\data\plotCurve2\yScalePower=0
+ScopeGadget\Accel\data\plotCurve2\yMinimum=0
+ScopeGadget\Accel\data\plotCurve2\yMaximum=0
+ScopeGadget\Accel\data\LoggingEnabled=false
+ScopeGadget\Accel\data\LoggingNewFileOnConnect=false
+ScopeGadget\Accel\data\LoggingPath=
+ScopeGadget\Accel\configInfo\version=0.0.0
+ScopeGadget\Accel\configInfo\locked=false
+ScopeGadget\Actuators\data\configurationStreamVersion=1000
+ScopeGadget\Actuators\data\plotType=1
+ScopeGadget\Actuators\data\dataSize=20
+ScopeGadget\Actuators\data\refreshInterval=100
+ScopeGadget\Actuators\data\plotCurveCount=4
+ScopeGadget\Actuators\data\plotCurve0\uavObject=ActuatorCommand
+ScopeGadget\Actuators\data\plotCurve0\uavField=Channel-4
+ScopeGadget\Actuators\data\plotCurve0\color=4294901760
+ScopeGadget\Actuators\data\plotCurve0\yScalePower=0
+ScopeGadget\Actuators\data\plotCurve0\yMinimum=0
+ScopeGadget\Actuators\data\plotCurve0\yMaximum=0
+ScopeGadget\Actuators\data\plotCurve1\uavObject=ActuatorCommand
+ScopeGadget\Actuators\data\plotCurve1\uavField=Channel-5
+ScopeGadget\Actuators\data\plotCurve1\color=4294901760
+ScopeGadget\Actuators\data\plotCurve1\yScalePower=0
+ScopeGadget\Actuators\data\plotCurve1\yMinimum=0
+ScopeGadget\Actuators\data\plotCurve1\yMaximum=0
+ScopeGadget\Actuators\data\plotCurve2\uavObject=ActuatorCommand
+ScopeGadget\Actuators\data\plotCurve2\uavField=Channel-6
+ScopeGadget\Actuators\data\plotCurve2\color=4289374847
+ScopeGadget\Actuators\data\plotCurve2\yScalePower=0
+ScopeGadget\Actuators\data\plotCurve2\yMinimum=0
+ScopeGadget\Actuators\data\plotCurve2\yMaximum=0
+ScopeGadget\Actuators\data\plotCurve3\uavObject=ActuatorCommand
+ScopeGadget\Actuators\data\plotCurve3\uavField=Channel-7
+ScopeGadget\Actuators\data\plotCurve3\color=4289374847
+ScopeGadget\Actuators\data\plotCurve3\yScalePower=0
+ScopeGadget\Actuators\data\plotCurve3\yMinimum=0
+ScopeGadget\Actuators\data\plotCurve3\yMaximum=0
+ScopeGadget\Actuators\data\LoggingEnabled=false
+ScopeGadget\Actuators\data\LoggingNewFileOnConnect=false
+ScopeGadget\Actuators\data\LoggingPath=
+ScopeGadget\Actuators\configInfo\version=0.0.0
+ScopeGadget\Actuators\configInfo\locked=false
+ScopeGadget\Attitude\data\configurationStreamVersion=1000
+ScopeGadget\Attitude\data\plotType=1
+ScopeGadget\Attitude\data\dataSize=60
+ScopeGadget\Attitude\data\refreshInterval=100
+ScopeGadget\Attitude\data\plotCurveCount=3
+ScopeGadget\Attitude\data\plotCurve0\uavObject=AttitudeActual
+ScopeGadget\Attitude\data\plotCurve0\uavField=Roll
+ScopeGadget\Attitude\data\plotCurve0\color=4283760895
+ScopeGadget\Attitude\data\plotCurve0\yScalePower=0
+ScopeGadget\Attitude\data\plotCurve0\yMinimum=0
+ScopeGadget\Attitude\data\plotCurve0\yMaximum=0
+ScopeGadget\Attitude\data\plotCurve1\uavObject=AttitudeActual
+ScopeGadget\Attitude\data\plotCurve1\uavField=Yaw
+ScopeGadget\Attitude\data\plotCurve1\color=4278233600
+ScopeGadget\Attitude\data\plotCurve1\yScalePower=0
+ScopeGadget\Attitude\data\plotCurve1\yMinimum=0
+ScopeGadget\Attitude\data\plotCurve1\yMaximum=0
+ScopeGadget\Attitude\data\plotCurve2\uavObject=AttitudeActual
+ScopeGadget\Attitude\data\plotCurve2\uavField=Pitch
+ScopeGadget\Attitude\data\plotCurve2\color=4294901760
+ScopeGadget\Attitude\data\plotCurve2\yScalePower=0
+ScopeGadget\Attitude\data\plotCurve2\yMinimum=0
+ScopeGadget\Attitude\data\plotCurve2\yMaximum=0
+ScopeGadget\Attitude\data\LoggingEnabled=false
+ScopeGadget\Attitude\data\LoggingNewFileOnConnect=false
+ScopeGadget\Attitude\data\LoggingPath=
+ScopeGadget\Attitude\configInfo\version=0.0.0
+ScopeGadget\Attitude\configInfo\locked=false
+ScopeGadget\Barometer\data\configurationStreamVersion=1000
+ScopeGadget\Barometer\data\plotType=1
+ScopeGadget\Barometer\data\dataSize=60
+ScopeGadget\Barometer\data\refreshInterval=1000
+ScopeGadget\Barometer\data\plotCurveCount=1
+ScopeGadget\Barometer\data\plotCurve0\uavObject=BaroAltitude
+ScopeGadget\Barometer\data\plotCurve0\uavField=Pressure
+ScopeGadget\Barometer\data\plotCurve0\color=4278190080
+ScopeGadget\Barometer\data\plotCurve0\yScalePower=0
+ScopeGadget\Barometer\data\plotCurve0\yMinimum=0
+ScopeGadget\Barometer\data\plotCurve0\yMaximum=0
+ScopeGadget\Barometer\data\LoggingEnabled=false
+ScopeGadget\Barometer\data\LoggingNewFileOnConnect=false
+ScopeGadget\Barometer\data\LoggingPath=
+ScopeGadget\Barometer\configInfo\version=0.0.0
+ScopeGadget\Barometer\configInfo\locked=false
+ScopeGadget\Inputs\data\configurationStreamVersion=1000
+ScopeGadget\Inputs\data\plotType=1
+ScopeGadget\Inputs\data\dataSize=40
+ScopeGadget\Inputs\data\refreshInterval=200
+ScopeGadget\Inputs\data\plotCurveCount=8
+ScopeGadget\Inputs\data\plotCurve0\uavObject=ManualControlCommand
+ScopeGadget\Inputs\data\plotCurve0\uavField=Channel-1
+ScopeGadget\Inputs\data\plotCurve0\color=4278190207
+ScopeGadget\Inputs\data\plotCurve0\yScalePower=0
+ScopeGadget\Inputs\data\plotCurve0\yMinimum=0
+ScopeGadget\Inputs\data\plotCurve0\yMaximum=0
+ScopeGadget\Inputs\data\plotCurve1\uavObject=ManualControlCommand
+ScopeGadget\Inputs\data\plotCurve1\uavField=Channel-4
+ScopeGadget\Inputs\data\plotCurve1\color=4294901760
+ScopeGadget\Inputs\data\plotCurve1\yScalePower=0
+ScopeGadget\Inputs\data\plotCurve1\yMinimum=0
+ScopeGadget\Inputs\data\plotCurve1\yMaximum=0
+ScopeGadget\Inputs\data\plotCurve2\uavObject=ManualControlCommand
+ScopeGadget\Inputs\data\plotCurve2\uavField=Channel-5
+ScopeGadget\Inputs\data\plotCurve2\color=4294901760
+ScopeGadget\Inputs\data\plotCurve2\yScalePower=0
+ScopeGadget\Inputs\data\plotCurve2\yMinimum=0
+ScopeGadget\Inputs\data\plotCurve2\yMaximum=0
+ScopeGadget\Inputs\data\plotCurve3\uavObject=ManualControlCommand
+ScopeGadget\Inputs\data\plotCurve3\uavField=Channel-6
+ScopeGadget\Inputs\data\plotCurve3\color=4294901760
+ScopeGadget\Inputs\data\plotCurve3\yScalePower=0
+ScopeGadget\Inputs\data\plotCurve3\yMinimum=0
+ScopeGadget\Inputs\data\plotCurve3\yMaximum=0
+ScopeGadget\Inputs\data\plotCurve4\uavObject=ManualControlCommand
+ScopeGadget\Inputs\data\plotCurve4\uavField=Channel-7
+ScopeGadget\Inputs\data\plotCurve4\color=4294901760
+ScopeGadget\Inputs\data\plotCurve4\yScalePower=0
+ScopeGadget\Inputs\data\plotCurve4\yMinimum=0
+ScopeGadget\Inputs\data\plotCurve4\yMaximum=0
+ScopeGadget\Inputs\data\plotCurve5\uavObject=ManualControlCommand
+ScopeGadget\Inputs\data\plotCurve5\uavField=Channel-2
+ScopeGadget\Inputs\data\plotCurve5\color=4283825920
+ScopeGadget\Inputs\data\plotCurve5\yScalePower=0
+ScopeGadget\Inputs\data\plotCurve5\yMinimum=0
+ScopeGadget\Inputs\data\plotCurve5\yMaximum=0
+ScopeGadget\Inputs\data\plotCurve6\uavObject=ManualControlCommand
+ScopeGadget\Inputs\data\plotCurve6\uavField=Channel-3
+ScopeGadget\Inputs\data\plotCurve6\color=4294923520
+ScopeGadget\Inputs\data\plotCurve6\yScalePower=0
+ScopeGadget\Inputs\data\plotCurve6\yMinimum=0
+ScopeGadget\Inputs\data\plotCurve6\yMaximum=0
+ScopeGadget\Inputs\data\plotCurve7\uavObject=ManualControlCommand
+ScopeGadget\Inputs\data\plotCurve7\uavField=Channel-0
+ScopeGadget\Inputs\data\plotCurve7\color=4294967040
+ScopeGadget\Inputs\data\plotCurve7\yScalePower=0
+ScopeGadget\Inputs\data\plotCurve7\yMinimum=0
+ScopeGadget\Inputs\data\plotCurve7\yMaximum=0
+ScopeGadget\Inputs\data\LoggingEnabled=false
+ScopeGadget\Inputs\data\LoggingNewFileOnConnect=false
+ScopeGadget\Inputs\data\LoggingPath=
+ScopeGadget\Inputs\configInfo\version=0.0.0
+ScopeGadget\Inputs\configInfo\locked=false
+ScopeGadget\Raw%20Accels\data\configurationStreamVersion=1000
+ScopeGadget\Raw%20Accels\data\plotType=1
+ScopeGadget\Raw%20Accels\data\dataSize=60
+ScopeGadget\Raw%20Accels\data\refreshInterval=500
+ScopeGadget\Raw%20Accels\data\plotCurveCount=3
+ScopeGadget\Raw%20Accels\data\plotCurve0\uavObject=AttitudeRaw
+ScopeGadget\Raw%20Accels\data\plotCurve0\uavField=accels-X
+ScopeGadget\Raw%20Accels\data\plotCurve0\color=4294901760
+ScopeGadget\Raw%20Accels\data\plotCurve0\yScalePower=0
+ScopeGadget\Raw%20Accels\data\plotCurve0\yMinimum=0
+ScopeGadget\Raw%20Accels\data\plotCurve0\yMaximum=0
+ScopeGadget\Raw%20Accels\data\plotCurve1\uavObject=AttitudeRaw
+ScopeGadget\Raw%20Accels\data\plotCurve1\uavField=accels-Y
+ScopeGadget\Raw%20Accels\data\plotCurve1\color=4283782655
+ScopeGadget\Raw%20Accels\data\plotCurve1\yScalePower=0
+ScopeGadget\Raw%20Accels\data\plotCurve1\yMinimum=0
+ScopeGadget\Raw%20Accels\data\plotCurve1\yMaximum=0
+ScopeGadget\Raw%20Accels\data\plotCurve2\uavObject=AttitudeRaw
+ScopeGadget\Raw%20Accels\data\plotCurve2\uavField=accels-Z
+ScopeGadget\Raw%20Accels\data\plotCurve2\color=4283804160
+ScopeGadget\Raw%20Accels\data\plotCurve2\yScalePower=0
+ScopeGadget\Raw%20Accels\data\plotCurve2\yMinimum=0
+ScopeGadget\Raw%20Accels\data\plotCurve2\yMaximum=0
+ScopeGadget\Raw%20Accels\data\LoggingEnabled=false
+ScopeGadget\Raw%20Accels\data\LoggingNewFileOnConnect=false
+ScopeGadget\Raw%20Accels\data\LoggingPath=
+ScopeGadget\Raw%20Accels\configInfo\version=0.0.0
+ScopeGadget\Raw%20Accels\configInfo\locked=false
+ScopeGadget\Raw%20Gyros\data\configurationStreamVersion=1000
+ScopeGadget\Raw%20Gyros\data\plotType=1
+ScopeGadget\Raw%20Gyros\data\dataSize=60
+ScopeGadget\Raw%20Gyros\data\refreshInterval=500
+ScopeGadget\Raw%20Gyros\data\plotCurveCount=3
+ScopeGadget\Raw%20Gyros\data\plotCurve0\uavObject=AttitudeRaw
+ScopeGadget\Raw%20Gyros\data\plotCurve0\uavField=gyros-Z
+ScopeGadget\Raw%20Gyros\data\plotCurve0\color=4283804160
+ScopeGadget\Raw%20Gyros\data\plotCurve0\yScalePower=0
+ScopeGadget\Raw%20Gyros\data\plotCurve0\yMinimum=0
+ScopeGadget\Raw%20Gyros\data\plotCurve0\yMaximum=0
+ScopeGadget\Raw%20Gyros\data\plotCurve1\uavObject=AttitudeRaw
+ScopeGadget\Raw%20Gyros\data\plotCurve1\uavField=gyros-Y
+ScopeGadget\Raw%20Gyros\data\plotCurve1\color=4283782655
+ScopeGadget\Raw%20Gyros\data\plotCurve1\yScalePower=0
+ScopeGadget\Raw%20Gyros\data\plotCurve1\yMinimum=0
+ScopeGadget\Raw%20Gyros\data\plotCurve1\yMaximum=0
+ScopeGadget\Raw%20Gyros\data\plotCurve2\uavObject=AttitudeRaw
+ScopeGadget\Raw%20Gyros\data\plotCurve2\uavField=gyros-X
+ScopeGadget\Raw%20Gyros\data\plotCurve2\color=4294901760
+ScopeGadget\Raw%20Gyros\data\plotCurve2\yScalePower=0
+ScopeGadget\Raw%20Gyros\data\plotCurve2\yMinimum=0
+ScopeGadget\Raw%20Gyros\data\plotCurve2\yMaximum=0
+ScopeGadget\Raw%20Gyros\data\LoggingEnabled=false
+ScopeGadget\Raw%20Gyros\data\LoggingNewFileOnConnect=false
+ScopeGadget\Raw%20Gyros\data\LoggingPath=
+ScopeGadget\Raw%20Gyros\configInfo\version=0.0.0
+ScopeGadget\Raw%20Gyros\configInfo\locked=false
+ScopeGadget\Raw%20magnetometers\data\configurationStreamVersion=1000
+ScopeGadget\Raw%20magnetometers\data\plotType=1
+ScopeGadget\Raw%20magnetometers\data\dataSize=60
+ScopeGadget\Raw%20magnetometers\data\refreshInterval=500
+ScopeGadget\Raw%20magnetometers\data\plotCurveCount=3
+ScopeGadget\Raw%20magnetometers\data\plotCurve0\uavObject=AttitudeRaw
+ScopeGadget\Raw%20magnetometers\data\plotCurve0\uavField=magnetometers-X
+ScopeGadget\Raw%20magnetometers\data\plotCurve0\color=4294901760
+ScopeGadget\Raw%20magnetometers\data\plotCurve0\yScalePower=0
+ScopeGadget\Raw%20magnetometers\data\plotCurve0\yMinimum=0
+ScopeGadget\Raw%20magnetometers\data\plotCurve0\yMaximum=0
+ScopeGadget\Raw%20magnetometers\data\plotCurve1\uavObject=AttitudeRaw
+ScopeGadget\Raw%20magnetometers\data\plotCurve1\uavField=magnetometers-Y
+ScopeGadget\Raw%20magnetometers\data\plotCurve1\color=4283782655
+ScopeGadget\Raw%20magnetometers\data\plotCurve1\yScalePower=0
+ScopeGadget\Raw%20magnetometers\data\plotCurve1\yMinimum=0
+ScopeGadget\Raw%20magnetometers\data\plotCurve1\yMaximum=0
+ScopeGadget\Raw%20magnetometers\data\plotCurve2\uavObject=AttitudeRaw
+ScopeGadget\Raw%20magnetometers\data\plotCurve2\uavField=magnetometers-Z
+ScopeGadget\Raw%20magnetometers\data\plotCurve2\color=4283804160
+ScopeGadget\Raw%20magnetometers\data\plotCurve2\yScalePower=0
+ScopeGadget\Raw%20magnetometers\data\plotCurve2\yMinimum=0
+ScopeGadget\Raw%20magnetometers\data\plotCurve2\yMaximum=0
+ScopeGadget\Raw%20magnetometers\data\LoggingEnabled=false
+ScopeGadget\Raw%20magnetometers\data\LoggingNewFileOnConnect=false
+ScopeGadget\Raw%20magnetometers\data\LoggingPath=
+ScopeGadget\Raw%20magnetometers\configInfo\version=0.0.0
+ScopeGadget\Raw%20magnetometers\configInfo\locked=false
+ScopeGadget\Stacks%20monitor\data\configurationStreamVersion=1000
+ScopeGadget\Stacks%20monitor\data\plotType=1
+ScopeGadget\Stacks%20monitor\data\dataSize=240
+ScopeGadget\Stacks%20monitor\data\refreshInterval=1000
+ScopeGadget\Stacks%20monitor\data\plotCurveCount=12
+ScopeGadget\Stacks%20monitor\data\plotCurve0\uavObject=TaskInfo
+ScopeGadget\Stacks%20monitor\data\plotCurve0\uavField=StackRemaining-System
+ScopeGadget\Stacks%20monitor\data\plotCurve0\color=4294945280
+ScopeGadget\Stacks%20monitor\data\plotCurve0\yScalePower=0
+ScopeGadget\Stacks%20monitor\data\plotCurve0\yMinimum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve0\yMaximum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve1\uavObject=TaskInfo
+ScopeGadget\Stacks%20monitor\data\plotCurve1\uavField=StackRemaining-Actuator
+ScopeGadget\Stacks%20monitor\data\plotCurve1\color=4294945280
+ScopeGadget\Stacks%20monitor\data\plotCurve1\yScalePower=0
+ScopeGadget\Stacks%20monitor\data\plotCurve1\yMinimum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve1\yMaximum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve2\uavObject=TaskInfo
+ScopeGadget\Stacks%20monitor\data\plotCurve2\uavField=StackRemaining-TelemetryTx
+ScopeGadget\Stacks%20monitor\data\plotCurve2\color=4294945280
+ScopeGadget\Stacks%20monitor\data\plotCurve2\yScalePower=0
+ScopeGadget\Stacks%20monitor\data\plotCurve2\yMinimum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve2\yMaximum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve3\uavObject=TaskInfo
+ScopeGadget\Stacks%20monitor\data\plotCurve3\uavField=StackRemaining-TelemetryTxPri
+ScopeGadget\Stacks%20monitor\data\plotCurve3\color=4294945280
+ScopeGadget\Stacks%20monitor\data\plotCurve3\yScalePower=0
+ScopeGadget\Stacks%20monitor\data\plotCurve3\yMinimum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve3\yMaximum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve4\uavObject=TaskInfo
+ScopeGadget\Stacks%20monitor\data\plotCurve4\uavField=StackRemaining-TelemetryRx
+ScopeGadget\Stacks%20monitor\data\plotCurve4\color=4294945280
+ScopeGadget\Stacks%20monitor\data\plotCurve4\yScalePower=0
+ScopeGadget\Stacks%20monitor\data\plotCurve4\yMinimum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve4\yMaximum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve5\uavObject=TaskInfo
+ScopeGadget\Stacks%20monitor\data\plotCurve5\uavField=StackRemaining-GPS
+ScopeGadget\Stacks%20monitor\data\plotCurve5\color=4294945280
+ScopeGadget\Stacks%20monitor\data\plotCurve5\yScalePower=0
+ScopeGadget\Stacks%20monitor\data\plotCurve5\yMinimum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve5\yMaximum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve6\uavObject=TaskInfo
+ScopeGadget\Stacks%20monitor\data\plotCurve6\uavField=StackRemaining-ManualControl
+ScopeGadget\Stacks%20monitor\data\plotCurve6\color=4294945280
+ScopeGadget\Stacks%20monitor\data\plotCurve6\yScalePower=0
+ScopeGadget\Stacks%20monitor\data\plotCurve6\yMinimum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve6\yMaximum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve7\uavObject=TaskInfo
+ScopeGadget\Stacks%20monitor\data\plotCurve7\uavField=StackRemaining-Altitude
+ScopeGadget\Stacks%20monitor\data\plotCurve7\color=4294945280
+ScopeGadget\Stacks%20monitor\data\plotCurve7\yScalePower=0
+ScopeGadget\Stacks%20monitor\data\plotCurve7\yMinimum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve7\yMaximum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve8\uavObject=TaskInfo
+ScopeGadget\Stacks%20monitor\data\plotCurve8\uavField=StackRemaining-AHRSComms
+ScopeGadget\Stacks%20monitor\data\plotCurve8\color=4294945280
+ScopeGadget\Stacks%20monitor\data\plotCurve8\yScalePower=0
+ScopeGadget\Stacks%20monitor\data\plotCurve8\yMinimum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve8\yMaximum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve9\uavObject=TaskInfo
+ScopeGadget\Stacks%20monitor\data\plotCurve9\uavField=StackRemaining-Stabilization
+ScopeGadget\Stacks%20monitor\data\plotCurve9\color=4294945280
+ScopeGadget\Stacks%20monitor\data\plotCurve9\yScalePower=0
+ScopeGadget\Stacks%20monitor\data\plotCurve9\yMinimum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve9\yMaximum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve10\uavObject=TaskInfo
+ScopeGadget\Stacks%20monitor\data\plotCurve10\uavField=StackRemaining-Guidance
+ScopeGadget\Stacks%20monitor\data\plotCurve10\color=4294945280
+ScopeGadget\Stacks%20monitor\data\plotCurve10\yScalePower=0
+ScopeGadget\Stacks%20monitor\data\plotCurve10\yMinimum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve10\yMaximum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve11\uavObject=TaskInfo
+ScopeGadget\Stacks%20monitor\data\plotCurve11\uavField=StackRemaining-Watchdog
+ScopeGadget\Stacks%20monitor\data\plotCurve11\color=4294945280
+ScopeGadget\Stacks%20monitor\data\plotCurve11\yScalePower=0
+ScopeGadget\Stacks%20monitor\data\plotCurve11\yMinimum=0
+ScopeGadget\Stacks%20monitor\data\plotCurve11\yMaximum=0
+ScopeGadget\Stacks%20monitor\data\LoggingEnabled=false
+ScopeGadget\Stacks%20monitor\data\LoggingNewFileOnConnect=false
+ScopeGadget\Stacks%20monitor\data\LoggingPath=
+ScopeGadget\Stacks%20monitor\configInfo\version=0.0.0
+ScopeGadget\Stacks%20monitor\configInfo\locked=false
+ScopeGadget\Telemetry%20quality\data\configurationStreamVersion=1000
+ScopeGadget\Telemetry%20quality\data\plotType=1
+ScopeGadget\Telemetry%20quality\data\dataSize=20
+ScopeGadget\Telemetry%20quality\data\refreshInterval=100
+ScopeGadget\Telemetry%20quality\data\plotCurveCount=3
+ScopeGadget\Telemetry%20quality\data\plotCurve0\uavObject=GCSTelemetryStats
+ScopeGadget\Telemetry%20quality\data\plotCurve0\uavField=TxFailures
+ScopeGadget\Telemetry%20quality\data\plotCurve0\color=4289374847
+ScopeGadget\Telemetry%20quality\data\plotCurve0\yScalePower=0
+ScopeGadget\Telemetry%20quality\data\plotCurve0\yMinimum=0
+ScopeGadget\Telemetry%20quality\data\plotCurve0\yMaximum=0
+ScopeGadget\Telemetry%20quality\data\plotCurve1\uavObject=GCSTelemetryStats
+ScopeGadget\Telemetry%20quality\data\plotCurve1\uavField=RxFailures
+ScopeGadget\Telemetry%20quality\data\plotCurve1\color=4283782655
+ScopeGadget\Telemetry%20quality\data\plotCurve1\yScalePower=0
+ScopeGadget\Telemetry%20quality\data\plotCurve1\yMinimum=0
+ScopeGadget\Telemetry%20quality\data\plotCurve1\yMaximum=0
+ScopeGadget\Telemetry%20quality\data\plotCurve2\uavObject=GCSTelemetryStats
+ScopeGadget\Telemetry%20quality\data\plotCurve2\uavField=TxRetries
+ScopeGadget\Telemetry%20quality\data\plotCurve2\color=4294901760
+ScopeGadget\Telemetry%20quality\data\plotCurve2\yScalePower=0
+ScopeGadget\Telemetry%20quality\data\plotCurve2\yMinimum=0
+ScopeGadget\Telemetry%20quality\data\plotCurve2\yMaximum=0
+ScopeGadget\Telemetry%20quality\data\LoggingEnabled=false
+ScopeGadget\Telemetry%20quality\data\LoggingNewFileOnConnect=false
+ScopeGadget\Telemetry%20quality\data\LoggingPath=
+ScopeGadget\Telemetry%20quality\configInfo\version=0.0.0
+ScopeGadget\Telemetry%20quality\configInfo\locked=false
+ScopeGadget\Uptimes\data\configurationStreamVersion=1000
+ScopeGadget\Uptimes\data\plotType=1
+ScopeGadget\Uptimes\data\dataSize=240
+ScopeGadget\Uptimes\data\refreshInterval=800
+ScopeGadget\Uptimes\data\plotCurveCount=2
+ScopeGadget\Uptimes\data\plotCurve0\uavObject=AhrsStatus
+ScopeGadget\Uptimes\data\plotCurve0\uavField=RunningTime
+ScopeGadget\Uptimes\data\plotCurve0\color=4289374847
+ScopeGadget\Uptimes\data\plotCurve0\yScalePower=0
+ScopeGadget\Uptimes\data\plotCurve0\yMinimum=0
+ScopeGadget\Uptimes\data\plotCurve0\yMaximum=0
+ScopeGadget\Uptimes\data\plotCurve1\uavObject=SystemStats
+ScopeGadget\Uptimes\data\plotCurve1\uavField=FlightTime
+ScopeGadget\Uptimes\data\plotCurve1\color=4294945407
+ScopeGadget\Uptimes\data\plotCurve1\yScalePower=0
+ScopeGadget\Uptimes\data\plotCurve1\yMinimum=0
+ScopeGadget\Uptimes\data\plotCurve1\yMaximum=0
+ScopeGadget\Uptimes\data\LoggingEnabled=false
+ScopeGadget\Uptimes\data\LoggingNewFileOnConnect=false
+ScopeGadget\Uptimes\data\LoggingPath=
+ScopeGadget\Uptimes\configInfo\version=0.0.0
+ScopeGadget\Uptimes\configInfo\locked=false
+SystemHealthGadget\default\data\diagram=%%DATAPATH%%diagrams/default/system-health.svg
+SystemHealthGadget\default\configInfo\version=0.0.0
+SystemHealthGadget\default\configInfo\locked=false
+UAVObjectBrowser\default\data\recentlyUpdatedColor=@Variant(\0\0\0\x43\x1\xff\xff\xff\xffyyWW\0\0)
+UAVObjectBrowser\default\data\manuallyChangedColor=@Variant(\0\0\0\x43\x1\xff\xff[[\xaa\xaaVV\0\0)
+UAVObjectBrowser\default\data\recentlyUpdatedTimeout=500
+UAVObjectBrowser\default\configInfo\version=0.0.0
+UAVObjectBrowser\default\configInfo\locked=false
+Uploader\default\data\defaultSpeed=14
+Uploader\default\data\defaultDataBits=3
+Uploader\default\data\defaultFlow=0
+Uploader\default\data\defaultParity=0
+Uploader\default\data\defaultStopBits=0
+Uploader\default\data\defaultPort=/dev/ttyS0
+Uploader\default\configInfo\version=0.0.0
+Uploader\default\configInfo\locked=false
+
+[Plugins]
+SoundNotifyPlugin\data\Current\1\SoundCollectionPath=%%DATAPATH%%sounds
+SoundNotifyPlugin\data\Current\1\CurrentLanguage=default
+SoundNotifyPlugin\data\Current\1\ObjectField=Channel
+SoundNotifyPlugin\data\Current\1\DataObject=ActuatorCommand
+SoundNotifyPlugin\data\Current\1\Value=Equal to
+SoundNotifyPlugin\data\Current\1\ValueSpinBox=0
+SoundNotifyPlugin\data\Current\1\Sound1=
+SoundNotifyPlugin\data\Current\1\Sound2=
+SoundNotifyPlugin\data\Current\1\Sound3=
+SoundNotifyPlugin\data\Current\1\SayOrder=Never
+SoundNotifyPlugin\data\Current\1\Repeat=
+SoundNotifyPlugin\data\Current\1\ExpireTimeout=0
+SoundNotifyPlugin\data\Current\size=1
+SoundNotifyPlugin\data\listNotifies\size=0
+SoundNotifyPlugin\data\EnableSound=false
+SoundNotifyPlugin\configInfo\version=1.0.0
+SoundNotifyPlugin\configInfo\locked=false
+
+[IPconnection]
+Current\1\HostName=
+Current\1\Port=1
+Current\1\UseTCP=0
+Current\size=1
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/core.qrc b/ground/openpilotgcs/src/plugins/coreplugin/core.qrc
index aa4787ea6..917018476 100644
--- a/ground/openpilotgcs/src/plugins/coreplugin/core.qrc
+++ b/ground/openpilotgcs/src/plugins/coreplugin/core.qrc
@@ -52,5 +52,13 @@
images/openpiloticon.png
OpenPilotGCS.ini
CREDITS.html
+ images/ah.png
+ images/config.png
+ images/flight.png
+ images/home.png
+ images/joystick.png
+ images/scopes.png
+ images/world.png
+ images/cog.png
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h b/ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h
index b282d3afa..f02315d2f 100644
--- a/ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h
+++ b/ground/openpilotgcs/src/plugins/coreplugin/coreconstants.h
@@ -35,7 +35,7 @@ namespace Constants {
#define GCS_VERSION_MAJOR 1
#define GCS_VERSION_MINOR 0
#define GCS_VERSION_RELEASE 0
-const char * const GCS_VERSION_TYPE = "Beta";
+const char * const GCS_VERSION_TYPE = "Alpha";
const char * const GCS_VERSION_CODENAME = "Pascal";
#define STRINGIFY_INTERNAL(x) #x
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/ah.png b/ground/openpilotgcs/src/plugins/coreplugin/images/ah.png
new file mode 100644
index 000000000..a0be19bed
Binary files /dev/null and b/ground/openpilotgcs/src/plugins/coreplugin/images/ah.png differ
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/cog.png b/ground/openpilotgcs/src/plugins/coreplugin/images/cog.png
new file mode 100644
index 000000000..67de2c6cc
Binary files /dev/null and b/ground/openpilotgcs/src/plugins/coreplugin/images/cog.png differ
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/config.png b/ground/openpilotgcs/src/plugins/coreplugin/images/config.png
new file mode 100644
index 000000000..5c8213fef
Binary files /dev/null and b/ground/openpilotgcs/src/plugins/coreplugin/images/config.png differ
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/flight.png b/ground/openpilotgcs/src/plugins/coreplugin/images/flight.png
new file mode 100644
index 000000000..419a0b7af
Binary files /dev/null and b/ground/openpilotgcs/src/plugins/coreplugin/images/flight.png differ
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/home.png b/ground/openpilotgcs/src/plugins/coreplugin/images/home.png
new file mode 100644
index 000000000..fed62219f
Binary files /dev/null and b/ground/openpilotgcs/src/plugins/coreplugin/images/home.png differ
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/joystick.png b/ground/openpilotgcs/src/plugins/coreplugin/images/joystick.png
new file mode 100644
index 000000000..62168f56f
Binary files /dev/null and b/ground/openpilotgcs/src/plugins/coreplugin/images/joystick.png differ
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/scopes.png b/ground/openpilotgcs/src/plugins/coreplugin/images/scopes.png
new file mode 100644
index 000000000..01e933a61
Binary files /dev/null and b/ground/openpilotgcs/src/plugins/coreplugin/images/scopes.png differ
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/world.png b/ground/openpilotgcs/src/plugins/coreplugin/images/world.png
new file mode 100644
index 000000000..68f21d301
Binary files /dev/null and b/ground/openpilotgcs/src/plugins/coreplugin/images/world.png differ
diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp
index 3519f03e8..6dc549ba1 100644
--- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp
+++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.cpp
@@ -183,6 +183,9 @@ void ScopeGadgetOptionsPage::on_cmbUAVObjects_currentIndexChanged(QString val)
UAVObjectManager *objManager = pm->getObject();
UAVDataObject* obj = dynamic_cast( objManager->getObject(val) );
+ if (obj == NULL)
+ return; // Rare case: the config contained a UAVObject name which does not exist anymore.
+
QList fieldList = obj->getFields();
foreach (UAVObjectField* field, fieldList) {
if(field->getType() == UAVObjectField::STRING || field->getType() == UAVObjectField::ENUM )
diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp
index 9d3a16451..8841429fa 100644
--- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp
+++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp
@@ -552,6 +552,7 @@ void UAVObjectField::setValue(const QVariant& value, quint32 index)
case ENUM:
{
qint8 tmpenum = options.indexOf( value.toString() );
+ Q_ASSERT(tmpenum >= 0); // To catch any programming errors where we set invalid values
memcpy(&data[offset + numBytesPerElement*index], &tmpenum, numBytesPerElement);
break;
}
diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.ui b/ground/openpilotgcs/src/plugins/uploader/devicewidget.ui
index 5b662a3ce..5007ed0b9 100644
--- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.ui
+++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.ui
@@ -48,6 +48,12 @@
160
+
+ background: transparent
+
+
+ QFrame::NoFrame
+
-
diff --git a/make/win32/README.txt b/make/win32/README.txt
new file mode 100644
index 000000000..c7b3a0143
--- /dev/null
+++ b/make/win32/README.txt
@@ -0,0 +1,192 @@
+This set of scripts is to provide a unix-like build environment on Windows.
+---------------------------------------------------------------------------
+
+1. Why do I need it?
+2. How to install?
+3. How to use it?
+3.1. Interactive mode
+3.2. Batch mode
+4. Advanced usage
+5. Limitations of use
+6. Credits and license
+
+
+1. Why do I need it?
+--------------------
+It allows to use the "Big Hammer", that is, to build whole OpenPilot system
+with a single command "make all" using the top level Makefile originally
+written for Linux and Mac only.
+
+Also any routine task automation could use the same set of scripts and commands
+on all platforms (Linux, Mac and Windows) if scripts are written in the shell
+language. It is particularly important for cross-paltform projects like the
+OpenPilot.
+
+
+2. How to install?
+------------------
+Fortunately, it requires only few small text files since all others components
+should already be installed on your system as parts of msysGit, QtSDK and
+CodeSourcery G++ packages required to build the OpenPilot.
+
+It is expected that you have the following tools installed into the listed
+locations (but any other locations are fine as well):
+
+ - Python in C:\Python27
+ - CodeSourcery G++ in C:\CodeSourcery
+ - QtSDK in C:\Qt\2010.05
+ - msysGit in %ProgramFiles%\Git
+ - Unicode NSIS in %ProgramFiles%\NSIS\Unicode
+
+Also it is assumed that you have the C:\Program Files\Git\cmd\ directory in
+the PATH. Usually this is the case for msysGit installation if you have chosen
+the 2nd option: put only git and gitk in the PATH (it is recommended option).
+
+Now you need to copy two files to your msysGit installation folders.
+Assuming that you installed the msysGit into C:\Program Files\Git\,
+you have to copy:
+
+ make\win32\make -> C:\Program Files\Git\bin\
+ make\win32\sh.cmd -> C:\Program Files\Git\cmd\
+
+If you have msysGit installed into another directory, you need to update paths
+accordingly. Also if you have tools installed into different directories and
+they are not in the PATH, then you may want to update paths in the sh.cmd
+script too (it is self-documented).
+
+
+3. How to use it?
+-----------------
+
+3.1. Interactive mode
+---------------------
+
+1) Type:
+
+ C:\> sh
+
+and the bash prompt should appear:
+
+ user@pc /
+ $
+
+2) Enter your OpenPilot directory:
+
+ user@pc /
+ $ cd D:/Work/OpenPilot/git
+
+ user@pc /d/Work/OpenPilot/git (master)
+ $
+
+Note the current git branch in parentheses (master), if it exists. The path
+format is also printed according to MSYS notation. And you have to use forward
+slashes in paths, not backslashes.
+
+3) Enter make command with required options and target list:
+
+ user@pc /d/Work/OpenPilot/git (master)
+ $ make all
+
+The building should be started, and you will have full system including ground
+software and flight firmware built in the end.
+
+4) To build parts of the system you can use, for example, such commands:
+
+ user@pc /d/Work/OpenPilot/git (master)
+ $ make -j2 USE_BOOTLOADER=YES GCS_BUIL_CONF=release gcs coptercontrol bl_coptercontrol
+
+or to completely remove the build directory:
+
+ user@pc /d/Work/OpenPilot/git (master)
+ $ make all_clean
+
+
+3.2. Batch mode
+---------------
+
+1) Create a shell script file containing all required commands, for instance:
+
+ #!/bin/sh
+ # This is the cc_make_release.sh file used to build CC release software
+ cd D:/Work/OpenPilot/git
+ make -j2 USE_BOOTLOADER=YES GCS_BUIL_CONF=release gcs coptercontrol bl_coptercontrol
+ echo RC=$?
+
+2) Run it typing:
+
+ C:\> sh cc_make_release.sh
+
+3) Of course, a lot of other shell commands can be used in scripts.
+
+
+4. Advanced usage
+-----------------
+
+It is possible to go further and integrate shell scripting into Windows system
+like any other executables. This allows:
+
+ - double click on any .sh file in the Explorer window to execute it;
+ - type name of .sh file with any arguments on the command line to run script;
+ - omit .sh extension typing names since it is now recognized automatically;
+ - call .sh scripts even from .bat and .cmd files as Windows command;
+ - execute scripts which are in any directory in the PATH;
+ - return and check exit code from .sh scripts to .bat or .cmd batch files.
+
+In short, you may have quite powerful and cross-platform bash scripting on
+Windows.
+
+In order to integrate bash scripting into Windows system you need to:
+
+ - double click on the included shell_script.reg file to register .sh
+ extension in the system. Thus, any click on .sh script will execute it
+ automatically assuming that the sh.cmd is in the PATH;
+ - register .sh extension as an executable file type, so you can omit the
+ .sh typing commands. To do so open "My Computer" properties dialog, choose
+ the "Advanced" tab, "Environment variables", in the "System variables"
+ find the variable called "PATHEXT". It contains the list of "executable"
+ file extensions separated by semicolon. You want to add a ";.SH" to the
+ end of its value. Then click OK to apply.
+
+Now any .sh script can be run just by typing its name, optionally with
+parameters.
+
+As an example, you can create a shell script named make.sh in the cmd/
+subdirectory of Git installation with the following content:
+
+ exec /bin/make $*
+
+and then build the OpenPilot software typing
+
+ make all
+
+directly from Windows command line or from a batch file.
+
+You also may want to rename or remove "C:\Program Files\Git\etc\motd" file
+to get rid of git bash welcome message on every script invocation.
+
+
+5. Limitations of use
+---------------------
+
+Currently there may be some problems running scripts which contain spaces in
+file names or located in directories which contain spaces in full paths.
+It results in in strange "file not found" or other errors.
+
+It is recommended to avoid using such names with spaces.
+
+
+6. Credits and license
+----------------------
+
+This set of scripts uses the MSYS package included into the msysGit
+distribution and MinGW make included into the QtSDK package.
+
+The sh.cmd, shell_script.reg and this README.txt files were written
+by Oleg Semyonov (os-openpilot-org@os-propo.info) for the OpenPilot
+project and are licensed under CC-BY-SA terms:
+
+ http://creativecommons.org/licenses/by-sa/3.0/
+
+Feel free to contact me for additions and improvements.
+
+Happy bashing!
diff --git a/make/win32/make b/make/win32/make
new file mode 100644
index 000000000..4d475bff6
--- /dev/null
+++ b/make/win32/make
@@ -0,0 +1,13 @@
+#!/bin/sh
+#
+# This file is to be put into C:\Program Files\Git\bin\ subdirectory
+# (or similar, depeding on where the msysGit package was installed)
+# to provide a make command to unix-like build environment on Windows.
+#
+# See also:
+# README.txt
+# http://wiki.openpilot.org/display/Doc/GCS+Development+on+Windows
+# http://wiki.openpilot.org/display/Doc/Firmware+Development+on+Windows
+#
+
+mingw32-make.exe $*
diff --git a/make/win32/sh.cmd b/make/win32/sh.cmd
new file mode 100644
index 000000000..b3b276fb2
--- /dev/null
+++ b/make/win32/sh.cmd
@@ -0,0 +1,127 @@
+@echo off
+rem
+rem This file is to be put into C:\Program Files\Git\cmd\ subdirectory
+rem (or similar, depeding on where the msysGit package was installed)
+rem to provide a shell prompt in the unix-like build environment on Windows.
+rem
+rem Currently supported on NT-class systems only (Windows XP and above).
+rem
+rem See also:
+rem README.txt
+rem http://wiki.openpilot.org/display/Doc/GCS+Development+on+Windows
+rem http://wiki.openpilot.org/display/Doc/Firmware+Development+on+Windows
+rem
+rem Based on the msys.bat file from the MSYS package
+rem http://www.mingw.org/wiki/msys
+rem
+
+rem this should let run MSYS shell on x64
+if "%PROCESSOR_ARCHITECTURE%" == "AMD64" (
+ SET COMSPEC=%WINDIR%\SysWOW64\cmd.exe
+)
+
+rem some MSYS environment variables
+if "x%MSYSTEM%" == "x" set MSYSTEM=MINGW32
+if not "x%DISPLAY%" == "x" set DISPLAY=
+
+rem --------------------------------------------------------------------------
+rem To build the OpenPilot software we need few tools in the PATH.
+rem Here we attempt to guess tools location searching in the given
+rem directories first, and in the PATH last, if not found where expected.
+rem
+rem Please note that if you have few similar tools installed somewhere but
+rem not in the expected location, and they are in the PATH, then the script
+rem can detect wrong directories. For instance, if you have QtSDK installed
+rem on the D: drive, but have separately installed MinGW toolkit which is
+rem in the PATH, then this script detects this MinGW instead of QtSDK's one.
+rem As a result, the SDL headers will not be found, if they were copied into
+rem QtSDK's MinGW directory. In that case make sure that you have correct
+rem directories specified here.
+rem
+rem Also you can add any paths below just by adding extra 'call :which'
+rem lines with the following parameters:
+rem - environment variable which will be set to the tool location, if found;
+rem - expected directory for the executable which will be searched first;
+rem - any executable file which will be searched in the given directory
+rem or in the PATH, if not found where expected.
+rem All they will be added to the PATH in order of appearance.
+rem --------------------------------------------------------------------------
+
+set NOT_FOUND=
+set PATH_DIRS=
+
+call :which MSYSGIT "%ProgramFiles%\Git\bin" git.exe
+call :which QTMINGW "C:\Qt\2010.05\mingw\bin" mingw32-make.exe
+call :which QTSDK "C:\Qt\2010.05\qt\bin" qmake.exe
+call :which CODESOURCERY "C:\CodeSourcery\bin" cs-make.exe
+call :which PYTHON "C:\Python27" python.exe
+call :which UNSIS "%ProgramFiles%\NSIS\Unicode" makensis.exe
+
+if "%NOT_FOUND%" == "" goto set_path
+
+echo:
+echo Some tools were not found in the PATH or expected location:
+for %%f in (%NOT_FOUND%) do echo %%f
+echo You may want to install them and/or update paths in the %0 file.
+echo:
+
+rem --------------------------------------------------------------------------
+rem Provide a clean environment for command line build. We remove the
+rem msysGit cmd subdirectory as well, so no recursive sh call can occur.
+rem --------------------------------------------------------------------------
+
+:set_path
+set PATH=%SYSTEMROOT%\system32;%SYSTEMROOT%
+set PATH=%PATH_DIRS%;%PATH%
+rem echo PATH: %PATH%
+
+rem --------------------------------------------------------------------------
+rem Start a shell.
+rem Any shell script can be passed to it via command line of this batch file.
+rem --------------------------------------------------------------------------
+
+if not exist "%MSYSGIT%\bash.exe" goto no_bash
+call "%MSYSGIT%\bash.exe" --login -i %*
+goto :eof
+
+:no_bash
+echo Cannot find bash, exiting with error
+exit 1
+
+rem --------------------------------------------------------------------------
+rem Attempt to find executable in the directory given or in the PATH
+rem --------------------------------------------------------------------------
+
+:which
+rem search in the directory given first
+for %%F in (%2) do set FP=%%~F\%3
+if exist "%FP%" goto found_directly
+
+rem search in the PATH last
+for %%F in (%3) do set FP=%%~$PATH:F
+if exist "%FP%" goto found_in_path
+
+:not_found
+for %%F in (%2) do set FP=%%~F
+rem echo %3: not found, expected in %FP%
+set FP=
+set NOT_FOUND=%NOT_FOUND% %3
+goto set
+
+:found_directly
+for %%F in ("%FP%") do set FP=%%~dpsF
+rem echo %3: found at: %FP%
+goto set
+
+:found_in_path
+for %%F in ("%FP%") do set FP=%%~dpsF
+rem echo %3: found in the PATH: %FP%
+
+:set
+rem set results regardless of was it found or not
+set %1=%FP%
+rem echo %1=%FP%
+if "%FP%" == "" goto :eof
+if not "%PATH_DIRS%" == "" set PATH_DIRS=%PATH_DIRS%;
+set PATH_DIRS=%PATH_DIRS%%FP%
+goto :eof
diff --git a/make/win32/shell_script.reg b/make/win32/shell_script.reg
new file mode 100644
index 000000000..547f2bf36
--- /dev/null
+++ b/make/win32/shell_script.reg
@@ -0,0 +1,19 @@
+REGEDIT4
+
+[HKEY_CLASSES_ROOT\.sh]
+@="shfile"
+
+[HKEY_CLASSES_ROOT\shfile]
+@="shell script"
+"AlwaysShowExt"=""
+"BrowserFlags"=dword:00000008
+"EditFlags"=dword:00000000
+
+[HKEY_CLASSES_ROOT\shfile\shell]
+@=""
+
+[HKEY_CLASSES_ROOT\shfile\shell\open]
+
+[HKEY_CLASSES_ROOT\shfile\shell\open\command]
+@="cmd.exe /c call sh \"%1\" %*"
+
diff --git a/shared/uavobjectdefinition/actuatorsettings.xml b/shared/uavobjectdefinition/actuatorsettings.xml
index 21b2c9454..a4cf3bc76 100644
--- a/shared/uavobjectdefinition/actuatorsettings.xml
+++ b/shared/uavobjectdefinition/actuatorsettings.xml
@@ -22,6 +22,7 @@
+