1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-29 14:52:12 +01:00

Merge branch 'CC3D_Release' into dmytro/pfd_qml

This commit is contained in:
Dmytro Poplavskiy 2012-07-31 23:43:16 +10:00
commit 4e28a529db
127 changed files with 34296 additions and 32817 deletions

View File

@ -1,4 +1,26 @@
Short summary of changes. For a complete list see the git log.
Short summary of changes. For a complete list see the git log.
2012-07-27
Added the ability to load stylesheets from external file according to operating system:
macos.qss, linux.qss, windows.qss
Files should be placed inside the app folder.
2012-07-27
Several UI changes.
MixerCurveWidget refactoring, now as a simple and advanced view.
2012-07-27
Added “advanced mode” option to general settings. Right now it only shows the hidden apply buttons.
To enable go to tools->options->General and click one of the checkboxes to give focus to the form,
then press F7
2012-07-27
Made the flight mode switch and accessory pots move according to user input on the input wizard.
2012-07-27
Changed the board pictures on the uploader widget
2012-07-27
Add more verbose debug output on the UAVOBJECTS saving code.
2012-07-20
AeroSimRC simulator plugin is now included into the Windows distribution

View File

@ -95,7 +95,7 @@
/* Task stack sizes */
#define PIOS_ACTUATOR_STACK_SIZE 1020
#define PIOS_MANUAL_STACK_SIZE 724
#define PIOS_SYSTEM_STACK_SIZE 460
#define PIOS_SYSTEM_STACK_SIZE 660
#define PIOS_STABILIZATION_STACK_SIZE 524
#define PIOS_TELEM_STACK_SIZE 500
#define PIOS_EVENTDISPATCHER_STACK_SIZE 130

View File

@ -73,6 +73,7 @@
static uint32_t idleCounter;
static uint32_t idleCounterClear;
static xTaskHandle systemTaskHandle;
static xQueueHandle objectPersistenceQueue;
static bool stackOverflow;
static bool mallocFailed;
@ -122,6 +123,10 @@ int32_t SystemModInitialize(void)
WatchdogStatusInitialize();
#endif
objectPersistenceQueue = xQueueCreate(1, sizeof(UAVObjEvent));
if (objectPersistenceQueue == NULL)
return -1;
SystemModStart();
return 0;
@ -133,8 +138,6 @@ MODULE_INITCALL(SystemModInitialize, 0)
*/
static void systemTask(void *parameters)
{
portTickType lastSysTime;
/* create all modules thread */
MODULE_TASKCREATE_ALL;
@ -154,10 +157,9 @@ static void systemTask(void *parameters)
// Initialize vars
idleCounter = 0;
idleCounterClear = 0;
lastSysTime = xTaskGetTickCount();
// Listen for SettingPersistance object updates, connect a callback function
ObjectPersistenceConnectCallback(&objectUpdatedCb);
ObjectPersistenceConnectQueue(objectPersistenceQueue);
// Main system loop
while (1) {
@ -193,11 +195,14 @@ static void systemTask(void *parameters)
FlightStatusData flightStatus;
FlightStatusGet(&flightStatus);
// Wait until next period
if(flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) {
vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2) );
} else {
vTaskDelayUntil(&lastSysTime, SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS);
UAVObjEvent ev;
int delayTime = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED ?
SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS / (LED_BLINK_RATE_HZ * 2) :
SYSTEM_UPDATE_PERIOD_MS / portTICK_RATE_MS;
if(xQueueReceive(objectPersistenceQueue, &ev, delayTime) == pdTRUE) {
// If object persistence is updated call the callback
objectUpdatedCb(&ev);
}
}
}

Binary file not shown.

View File

@ -9,9 +9,7 @@ equals(copydata, 1) {
win32:CONFIG(release, debug|release) {
# copy Qt DLLs and phonon4
QT_DLLS = libgcc_s_dw2-1.dll \
mingwm10.dll \
phonon4.dll \
QT_DLLS = phonon4.dll \
QtCore4.dll \
QtGui4.dll \
QtNetwork4.dll \
@ -27,6 +25,13 @@ equals(copydata, 1) {
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline()
}
# copy MinGW DLLs
MINGW_DLLS = libgcc_s_dw2-1.dll \
mingwm10.dll
for(dll, MINGW_DLLS) {
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/../../../../../mingw/bin/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline()
}
# copy iconengines
QT_ICONENGINE_DLLS = qsvgicon4.dll
data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/iconengines\") $$addNewline()

View File

@ -5,17 +5,13 @@ TEMPLATE = app
TARGET = $$GCS_APP_TARGET
DESTDIR = $$GCS_APP_PATH
QT += xml
SOURCES += main.cpp
include(../rpath.pri)
include(../libs/utils/utils.pri)
LIBS *= -l$$qtLibraryName(ExtensionSystem) -l$$qtLibraryName(Aggregation)
win32 {
# CONFIG(debug, debug|release):LIBS *= -lExtensionSystemd -lAggregationd -lQExtSerialPortd
# else:LIBS *= -lExtensionSystem -lAggregation -lQExtSerialPort
RC_FILE = openpilotgcs.rc
target.path = /bin
INSTALLS += target
@ -32,3 +28,15 @@ win32 {
}
OTHER_FILES += openpilotgcs.rc
STYLESHEETS = windows.qss \
macos.qss \
linux.qss
for(qss, STYLESHEETS) {
style_copy.commands += $(COPY_FILE) $$targetPath(\"$$GCS_SOURCE_TREE/src/app/stylesheets/$$qss\") $$targetPath(\"$$GCS_APP_PATH/$$qss\") $$addNewline()
}
style_copy.target = FORCE
QMAKE_EXTRA_TARGETS += style_copy

View File

@ -229,6 +229,30 @@ static void overrideSettings(QSettings &settings, int argc, char **argv){
settings.sync();
}
static inline void loadStyleSheet() {
/* Let's use QFile and point to a resource... */
#ifdef Q_OS_MAC
QFile data(QCoreApplication::applicationDirPath()+"/macos.qss");
#elif defined(Q_OS_LINUX)
QFile data(QCoreApplication::applicationDirPath()+"/linux.qss");
#else
QFile data(QCoreApplication::applicationDirPath()+"/windows.qss");
#endif
QString style;
/* ...to open the file */
if(data.open(QFile::ReadOnly)) {
/* QTextStream... */
QTextStream styleIn(&data);
/* ...read file to a string. */
style = styleIn.readAll();
data.close();
/* We'll use qApp macro to get the QApplication pointer
* and set the style sheet application wide. */
qApp->setStyleSheet(style);
qDebug()<<"Loaded stylesheet:"<<style;
}
}
int main(int argc, char **argv)
{
#ifdef Q_OS_MAC
@ -337,12 +361,12 @@ int main(int argc, char **argv)
printHelp(QFileInfo(app.applicationFilePath()).baseName(), pluginManager);
return 0;
}
const bool isFirstInstance = !app.isRunning();
if (!isFirstInstance && foundAppOptions.contains(QLatin1String(CLIENT_OPTION)))
return sendArguments(app, pluginManager.arguments()) ? 0 : -1;
pluginManager.loadPlugins();
loadStyleSheet();
if (coreplugin->hasError()) {
displayError(msgCoreLoadFailure(coreplugin->errorString()));
return 1;

View File

@ -33,7 +33,7 @@
#include <QSvgRenderer>
#include <QMap>
class SvgImageProvider : public QObject, public QDeclarativeImageProvider
class Q_DECL_EXPORT SvgImageProvider : public QObject, public QDeclarativeImageProvider
{
Q_OBJECT
public:

View File

@ -6,14 +6,14 @@
<rect>
<x>0</x>
<y>0</y>
<width>796</width>
<height>618</height>
<width>833</width>
<height>852</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<layout class="QVBoxLayout" name="verticalLayout_12">
<item>
<widget class="QTabWidget" name="tabWidget">
<property name="currentIndex">
@ -23,581 +23,193 @@
<attribute name="title">
<string>Mixer Settings</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_2" stretch="0,0,0">
<layout class="QVBoxLayout" name="verticalLayout_2" stretch="0">
<property name="margin">
<number>5</number>
<number>12</number>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="label">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Vehicle type:</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="aircraftType">
<property name="toolTip">
<string>Select aircraft type here</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Horizontal</enum>
<widget class="QScrollArea" name="scrollArea">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
</widget>
</item>
<item>
<widget class="QStackedWidget" name="airframesWidget">
<property name="currentIndex">
<number>0</number>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<widget class="QWidget" name="fixedWing">
<property name="enabled">
<bool>true</bool>
<property name="palette">
<palette>
<active>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>779</width>
<height>691</height>
</rect>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3" stretch="0">
<item>
<layout class="QVBoxLayout" name="verticalLayout_6">
<layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="0">
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="sizeConstraint">
<enum>QLayout::SetFixedSize</enum>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QLabel" name="label_5">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Airplane type:</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fixedWingType"/>
</item>
<item>
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
<widget class="QLabel" name="label">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Vehicle type:</string>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_23"/>
<widget class="QComboBox" name="aircraftType">
<property name="toolTip">
<string>Select aircraft type here</string>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_4">
<item>
<widget class="QGroupBox" name="groupBox_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>230</width>
<height>100</height>
</size>
</property>
<property name="title">
<string>Output Channel Assignments</string>
</property>
<layout class="QFormLayout" name="formLayout_3">
<item row="1" column="0">
<widget class="QLabel" name="fwEngineLabel">
<property name="text">
<string>Engine</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="fwEngineChannelBox">
<property name="toolTip">
<string>Select output channel for the engine</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="fwAileron1Label">
<property name="minimumSize">
<size>
<width>60</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Aileron 1</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="fwAileron1ChannelBox">
<property name="toolTip">
<string>Select output channel for the first aileron (or elevon)</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="fwAileron2Label">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>60</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Aileron 2</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="fwAileron2ChannelBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Select output channel for the second aileron (or elevon)</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="fwElevator1Label">
<property name="minimumSize">
<size>
<width>67</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Elevator 1</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="fwElevator1ChannelBox">
<property name="toolTip">
<string>Select output channel for the first elevator</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="fwElevator2Label">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>67</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Elevator 2</string>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QComboBox" name="fwElevator2ChannelBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Select output channel for a secondary elevator</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="fwRudder1Label">
<property name="text">
<string>Rudder 1</string>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QComboBox" name="fwRudder1ChannelBox">
<property name="toolTip">
<string>Select output channel for the first rudder</string>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="fwRudder2Label">
<property name="text">
<string>Rudder 2</string>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QComboBox" name="fwRudder2ChannelBox">
<property name="toolTip">
<string>Select output channel for a secondary rudder</string>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="elevonMixBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Elevon Mix</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_13">
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_8">
<item>
<layout class="QVBoxLayout" name="verticalLayout_14">
<item>
<widget class="QLabel" name="elevonLabel1">
<property name="minimumSize">
<size>
<width>65</width>
<height>0</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Rudder %</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="elevonSlider1">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="elevonSliderLabel1">
<property name="text">
<string>50</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_15">
<item>
<widget class="QLabel" name="elevonLabel2">
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Pitch %</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="elevonSlider2">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="elevonSliderLabel2">
<property name="text">
<string>50</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox_3">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>100</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Throttle Curve</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_16">
<item>
<spacer name="verticalSpacer_6">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="MixerCurveWidget" name="fixedWingThrottle" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>100</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="fwThrottleReset">
<property name="maximumSize">
<size>
<width>200</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>Reset</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="fwThrottleCurveItemValue">
<property name="text">
<string>Val: 0.00</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Expanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
<width>2</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_13">
<item>
<spacer name="horizontalSpacer_11">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="fwStatusLabel">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Mixer OK</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
<widget class="QWidget" name="multiRotor">
<layout class="QVBoxLayout" name="verticalLayout_4" stretch="1">
<item>
<layout class="QVBoxLayout" name="verticalLayout_8" stretch="0,0,0">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_7" stretch="0,0,0">
<item row="3" column="0">
<widget class="QStackedWidget" name="airframesWidget">
<property name="sizePolicy">
<sizepolicy hsizetype="Maximum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>775</width>
<height>16777215</height>
</size>
</property>
<property name="currentIndex">
<number>1</number>
</property>
<widget class="QWidget" name="fixedWing">
<property name="enabled">
<bool>true</bool>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3" stretch="0">
<item>
<layout class="QVBoxLayout" name="verticalLayout_24">
<layout class="QVBoxLayout" name="verticalLayout_6">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QLabel" name="label_15">
<widget class="QLabel" name="label_5">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
@ -605,19 +217,15 @@ margin:1px;</string>
</font>
</property>
<property name="text">
<string>Frame type:</string>
<string>Airplane type:</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="multirotorFrameType">
<property name="toolTip">
<string>Select the Multirotor frame type here.</string>
</property>
</widget>
<widget class="QComboBox" name="fixedWingType"/>
</item>
<item>
<spacer name="horizontalSpacer_5">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
@ -632,13 +240,448 @@ margin:1px;</string>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_22">
<layout class="QHBoxLayout" name="horizontalLayout_23"/>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_4">
<item>
<layout class="QVBoxLayout" name="verticalLayout_20">
<widget class="QGroupBox" name="groupBox_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>230</width>
<height>100</height>
</size>
</property>
<property name="title">
<string>Output Channel Assignments</string>
</property>
<layout class="QFormLayout" name="formLayout_3">
<item row="1" column="0">
<widget class="QLabel" name="fwEngineLabel">
<property name="text">
<string>Engine</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="fwEngineChannelBox">
<property name="toolTip">
<string>Select output channel for the engine</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="fwAileron1Label">
<property name="minimumSize">
<size>
<width>60</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Aileron 1</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="fwAileron1ChannelBox">
<property name="toolTip">
<string>Select output channel for the first aileron (or elevon)</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="fwAileron2Label">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>60</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Aileron 2</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="fwAileron2ChannelBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Select output channel for the second aileron (or elevon)</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="fwElevator1Label">
<property name="minimumSize">
<size>
<width>67</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Elevator 1</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="fwElevator1ChannelBox">
<property name="toolTip">
<string>Select output channel for the first elevator</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="fwElevator2Label">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>67</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Elevator 2</string>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QComboBox" name="fwElevator2ChannelBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Select output channel for a secondary elevator</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="fwRudder1Label">
<property name="text">
<string>Rudder 1</string>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QComboBox" name="fwRudder1ChannelBox">
<property name="toolTip">
<string>Select output channel for the first rudder</string>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="fwRudder2Label">
<property name="text">
<string>Rudder 2</string>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QComboBox" name="fwRudder2ChannelBox">
<property name="toolTip">
<string>Select output channel for a secondary rudder</string>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="elevonMixBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Elevon Mix</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_13">
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_8">
<item>
<layout class="QVBoxLayout" name="verticalLayout_14">
<item>
<widget class="QLabel" name="elevonLabel1">
<property name="minimumSize">
<size>
<width>65</width>
<height>0</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Rudder %</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="elevonSlider1">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="elevonSliderLabel1">
<property name="text">
<string>50</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_15">
<item>
<widget class="QLabel" name="elevonLabel2">
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Pitch %</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="elevonSlider2">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="elevonSliderLabel2">
<property name="text">
<string>50</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox_3">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>100</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Throttle Curve</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_16">
<item>
<widget class="MixerCurve" name="fixedWingThrottle" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>1</horstretch>
<verstretch>1</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>500</width>
<height>500</height>
</size>
</property>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="baseSize">
<size>
<width>300</width>
<height>350</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_13">
<item>
<spacer name="horizontalSpacer_11">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="fwStatusLabel">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Mixer OK</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
<widget class="QWidget" name="multiRotor">
<layout class="QVBoxLayout" name="verticalLayout_4" stretch="1">
<item>
<layout class="QVBoxLayout" name="verticalLayout_8" stretch="0,0,0">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_7" stretch="0,0">
<item>
<layout class="QVBoxLayout" name="verticalLayout_24">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_25">
<layout class="QHBoxLayout" name="horizontalLayout_5">
<item>
<widget class="QLabel" name="label_4">
<widget class="QLabel" name="label_15">
<property name="font">
<font>
<weight>75</weight>
@ -646,12 +689,19 @@ margin:1px;</string>
</font>
</property>
<property name="text">
<string>Mix Level</string>
<string>Frame type:</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_17">
<widget class="QComboBox" name="multirotorFrameType">
<property name="toolTip">
<string>Select the Multirotor frame type here.</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_5">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
@ -666,322 +716,702 @@ margin:1px;</string>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_19">
<layout class="QHBoxLayout" name="horizontalLayout_22">
<item>
<layout class="QVBoxLayout" name="verticalLayout_22">
<layout class="QVBoxLayout" name="verticalLayout_20">
<item>
<widget class="QLabel" name="mrRollMixValue">
<property name="minimumSize">
<size>
<width>30</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>100</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
<layout class="QHBoxLayout" name="horizontalLayout_25">
<item>
<widget class="QLabel" name="label_4">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Mix Level</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_17">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QSlider" name="mrRollMixLevel">
<property name="minimumSize">
<size>
<width>35</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Weight of Roll mixing in percent.
<layout class="QHBoxLayout" name="horizontalLayout_19">
<item>
<layout class="QVBoxLayout" name="verticalLayout_22">
<item>
<widget class="QLabel" name="mrRollMixValue">
<property name="minimumSize">
<size>
<width>30</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>100</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="mrRollMixLevel">
<property name="minimumSize">
<size>
<width>35</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Weight of Roll mixing in percent.
Typical values are 100% for + configuration and 50% for X configuration on quads.</string>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>100</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_42">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>100</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_42">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>R</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_23">
<item>
<widget class="QLabel" name="mrPitchMixValue">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>100</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="mrPitchMixLevel">
<property name="minimumSize">
<size>
<width>35</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Weight of Pitch mixing in percent.
</property>
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_23">
<item>
<widget class="QLabel" name="mrPitchMixValue">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>100</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="mrPitchMixLevel">
<property name="minimumSize">
<size>
<width>35</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Weight of Pitch mixing in percent.
Typical values are 100% for + configuration and 50% for X configuration on quads.</string>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>100</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_40">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>100</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_40">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>P</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_21">
<item>
<widget class="QLabel" name="mrYawMixValue">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>50</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="mrYawMixLevel">
<property name="minimumSize">
<size>
<width>40</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Weight of Yaw mixing in percent.
</property>
<property name="text">
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_21">
<item>
<widget class="QLabel" name="mrYawMixValue">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>50</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="mrYawMixLevel">
<property name="minimumSize">
<size>
<width>40</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Weight of Yaw mixing in percent.
Typical value is 50% for + or X configuration on quads.</string>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_6">
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_6">
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Y</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</property>
<property name="text">
<string>Yaw</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</item>
<item>
<widget class="QGraphicsView" name="quadShape">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>80</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background:transparent</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item>
<widget class="QGraphicsView" name="quadShape">
<widget class="QGroupBox" name="groupBox_6">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<sizepolicy hsizetype="Maximum" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>110</width>
<height>110</height>
<width>300</width>
<height>300</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background:transparent</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
<property name="title">
<string>Throttle Curve</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_9">
<item>
<widget class="MixerCurve" name="multiThrottleCurve" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="baseSize">
<size>
<width>300</width>
<height>350</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background:transparent</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item>
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox_6">
<property name="title">
<string>Throtte Curve</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_9">
<item>
<spacer name="verticalSpacer_7">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="MixerCurveWidget" name="multiThrottleCurve" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>120</width>
<height>120</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background:transparent</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="mrThrottleCurveReset">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>200</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>Reset</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="mrThrottleCurveItemValue">
<property name="text">
<string>Val: 0.00</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_6" stretch="1,3">
<property name="spacing">
<number>10</number>
</property>
<item>
<layout class="QVBoxLayout" name="verticalLayout_10">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_26">
<layout class="QHBoxLayout" name="horizontalLayout_6" stretch="1,0,3">
<property name="spacing">
<number>10</number>
</property>
<item>
<widget class="QLabel" name="label_23">
<layout class="QVBoxLayout" name="verticalLayout_10">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_26">
<item>
<widget class="QLabel" name="label_23">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Tricopter Yaw</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_18">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="label_2">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>channel:</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="triYawChannelBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>40</width>
<height>0</height>
</size>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_4">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<spacer name="horizontalSpacer_9">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>Motor output channels</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_10">
<property name="spacing">
<number>1</number>
</property>
<property name="margin">
<number>1</number>
</property>
<item>
<layout class="QFormLayout" name="formLayout_2">
<property name="sizeConstraint">
<enum>QLayout::SetMaximumSize</enum>
</property>
<property name="fieldGrowthPolicy">
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
</property>
<property name="verticalSpacing">
<number>3</number>
</property>
<item row="1" column="0">
<widget class="QLabel" name="MotorOutputLabel1">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>1</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="multiMotorChannelBox1">
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_8">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>2</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="multiMotorChannelBox2">
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_9">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>3</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="multiMotorChannelBox3">
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_10">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>4</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="multiMotorChannelBox4">
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="verticalSpacer_8">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<layout class="QFormLayout" name="formLayout_4">
<property name="sizeConstraint">
<enum>QLayout::SetMaximumSize</enum>
</property>
<property name="fieldGrowthPolicy">
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
</property>
<property name="verticalSpacing">
<number>3</number>
</property>
<item row="1" column="0">
<widget class="QLabel" name="label_11">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>5</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="multiMotorChannelBox5">
<property name="enabled">
<bool>false</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_12">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>6</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="multiMotorChannelBox6">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_16">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>7</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="multiMotorChannelBox7">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_17">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>8</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="multiMotorChannelBox8">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="verticalSpacer_9">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_20">
<item>
<spacer name="horizontalSpacer_12">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Expanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="mrStatusLabel">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
@ -989,12 +1419,72 @@ margin:1px;</string>
</font>
</property>
<property name="text">
<string>Tricopter Yaw</string>
<string>Mixer OK</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
<widget class="QWidget" name="ccpmHeli">
<layout class="QVBoxLayout" name="verticalLayout_5" stretch="1">
<property name="spacing">
<number>0</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<layout class="QVBoxLayout" name="verticalLayout_19">
<property name="spacing">
<number>0</number>
</property>
<item>
<widget class="ConfigCcpmWidget" name="widget_3" native="true"/>
</item>
</layout>
</item>
</layout>
</widget>
<widget class="QWidget" name="groundVehicle">
<property name="enabled">
<bool>true</bool>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_31" stretch="0">
<item>
<layout class="QVBoxLayout" name="verticalLayout_61">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_31">
<item>
<widget class="QLabel" name="label_51">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Vehicle type:</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_18">
<widget class="QComboBox" name="groundVehicleType"/>
</item>
<item>
<spacer name="horizontalSpacer_31">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
@ -1009,40 +1499,402 @@ margin:1px;</string>
</layout>
</item>
<item>
<widget class="QLabel" name="label_2">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>channel:</string>
</property>
</widget>
<layout class="QHBoxLayout" name="horizontalLayout_33">
<item>
<widget class="QLabel" name="label_7">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Channel Assignment</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_15">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QComboBox" name="triYawChannelBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>40</width>
<height>0</height>
</size>
</property>
</widget>
<layout class="QHBoxLayout" name="horizontalLayout_41">
<item>
<widget class="QGroupBox" name="groupBox_7">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="title">
<string>Output channel asignmets</string>
</property>
<layout class="QFormLayout" name="formLayout_5">
<item row="0" column="0">
<widget class="QLabel" name="gvEngineLabel">
<property name="minimumSize">
<size>
<width>77</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Engine</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QComboBox" name="gvEngineChannelBox">
<property name="toolTip">
<string>Select output channel for the engine</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="gvAileron1Label">
<property name="minimumSize">
<size>
<width>60</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Aileron 1</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="gvAileron1ChannelBox">
<property name="toolTip">
<string>Select output channel for the first aileron (or elevon)</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="gvAileron2Label">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>60</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Aileron 2</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="gvAileron2ChannelBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Select output channel for the second aileron (or elevon)</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="gvMotor1Label">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Motor</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="gvMotor1ChannelBox">
<property name="toolTip">
<string>Select output channel for the first motor</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="gvMotor2Label">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>47</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Motor 2</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="gvMotor2ChannelBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Select output channel for a second motor</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="gvSteering1Label">
<property name="text">
<string>Front Steering</string>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QComboBox" name="gvSteering1ChannelBox">
<property name="toolTip">
<string>Select output channel for the first steering actuator</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="gvSteering2Label">
<property name="text">
<string>Rear Steering</string>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QComboBox" name="gvSteering2ChannelBox">
<property name="toolTip">
<string>Select output channel for a second steering actuator</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="differentialSteeringMixBox">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Differential Steering Mix</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_33">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_30">
<item>
<layout class="QVBoxLayout" name="verticalLayout_34">
<item>
<widget class="QLabel" name="differentialSteeringLabel1">
<property name="minimumSize">
<size>
<width>65</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Left %</string>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="differentialSteeringSlider1">
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="gvDiffSteering1Label">
<property name="text">
<string>50</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_35">
<item>
<widget class="QLabel" name="differentialSteeringLabel2">
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Right %</string>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="differentialSteeringSlider2">
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="gvDiffSteering2Label">
<property name="text">
<string>50</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="gvThrottleCurve1GroupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>100</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Front throttle curve</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_36">
<item>
<widget class="MixerCurve" name="groundVehicleThrottle1" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>500</width>
<height>500</height>
</size>
</property>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="baseSize">
<size>
<width>300</width>
<height>350</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="gvThrottleCurve2GroupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Rear throttle curve</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_37">
<item>
<widget class="MixerCurve" name="groundVehicleThrottle2" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>500</width>
<height>500</height>
</size>
</property>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="baseSize">
<size>
<width>300</width>
<height>350</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_4">
<spacer name="verticalSpacer_1">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
@ -1054,1428 +1906,760 @@ margin:1px;</string>
</property>
</spacer>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_28">
<item>
<spacer name="horizontalSpacer_21">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="gvStatusLabel">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Mixer OK</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item>
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>Motor output channels</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_10">
<property name="spacing">
<number>1</number>
</property>
<property name="margin">
<number>1</number>
</property>
<item>
<layout class="QFormLayout" name="formLayout_2">
<property name="fieldGrowthPolicy">
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
</property>
<property name="verticalSpacing">
<number>3</number>
</property>
<item row="1" column="0">
<widget class="QLabel" name="MotorOutputLabel1">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>1</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="multiMotorChannelBox1">
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_8">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>2</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="multiMotorChannelBox2">
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_9">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>3</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="multiMotorChannelBox3">
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_10">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>4</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="multiMotorChannelBox4">
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="verticalSpacer_8">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<layout class="QFormLayout" name="formLayout_4">
<property name="fieldGrowthPolicy">
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
</property>
<property name="verticalSpacing">
<number>3</number>
</property>
<item row="1" column="0">
<widget class="QLabel" name="label_11">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>5</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="multiMotorChannelBox5">
<property name="enabled">
<bool>false</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_12">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>6</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="multiMotorChannelBox6">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_16">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>7</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="multiMotorChannelBox7">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_17">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>8</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="multiMotorChannelBox8">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Assign your motor output channels using the drawing above as a reference. Respect propeller rotation.</string>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="verticalSpacer_9">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_20">
</widget>
<widget class="QWidget" name="custom">
<layout class="QHBoxLayout" name="horizontalLayout_15">
<item>
<spacer name="horizontalSpacer_12">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="mrStatusLabel">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Mixer OK</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
<widget class="QWidget" name="ccpmHeli">
<layout class="QVBoxLayout" name="verticalLayout_5" stretch="1">
<property name="spacing">
<number>0</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<layout class="QVBoxLayout" name="verticalLayout_19">
<property name="spacing">
<number>0</number>
</property>
<item>
<widget class="ConfigCcpmWidget" name="widget_3" native="true"/>
</item>
</layout>
</item>
</layout>
</widget>
<widget class="QWidget" name="groundVehicle">
<property name="enabled">
<bool>true</bool>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_31" stretch="0">
<item>
<layout class="QVBoxLayout" name="verticalLayout_61">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_31">
<item>
<widget class="QLabel" name="label_51">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Vehicle type:</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="groundVehicleType"/>
</item>
<item>
<spacer name="horizontalSpacer_31">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_33">
<item>
<widget class="QLabel" name="label_7">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Channel Assignment</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_15">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_41">
<item>
<widget class="QGroupBox" name="groupBox_7">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="title">
<string>Output channel asignmets</string>
</property>
<layout class="QFormLayout" name="formLayout_5">
<item row="0" column="0">
<widget class="QLabel" name="gvEngineLabel">
<property name="minimumSize">
<size>
<width>77</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Engine</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QComboBox" name="gvEngineChannelBox">
<property name="toolTip">
<string>Select output channel for the engine</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="gvAileron1Label">
<property name="minimumSize">
<size>
<width>60</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Aileron 1</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="gvAileron1ChannelBox">
<property name="toolTip">
<string>Select output channel for the first aileron (or elevon)</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="gvAileron2Label">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>60</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Aileron 2</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="gvAileron2ChannelBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Select output channel for the second aileron (or elevon)</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="gvMotor1Label">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Motor</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="gvMotor1ChannelBox">
<property name="toolTip">
<string>Select output channel for the first motor</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="gvMotor2Label">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>47</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Motor 2</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="gvMotor2ChannelBox">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Select output channel for a second motor</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="gvSteering1Label">
<property name="text">
<string>Front Steering</string>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QComboBox" name="gvSteering1ChannelBox">
<property name="toolTip">
<string>Select output channel for the first steering actuator</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="gvSteering2Label">
<property name="text">
<string>Rear Steering</string>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QComboBox" name="gvSteering2ChannelBox">
<property name="toolTip">
<string>Select output channel for a second steering actuator</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="differentialSteeringMixBox">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Differential Steering Mix</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_33">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_30">
<item>
<layout class="QVBoxLayout" name="verticalLayout_34">
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_14">
<item>
<widget class="QGroupBox" name="groupBox_4">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Curve 1</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_7">
<item>
<widget class="QLabel" name="differentialSteeringLabel1">
<property name="minimumSize">
<size>
<width>65</width>
<height>0</height>
</size>
<widget class="MixerCurve" name="customThrottle1Curve" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>1</horstretch>
<verstretch>1</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Left %</string>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="differentialSteeringSlider1">
<property name="maximum">
<number>100</number>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="gvDiffSteering1Label">
<property name="text">
<string>50</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_35">
<item>
<widget class="QLabel" name="differentialSteeringLabel2">
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
<height>50</height>
</size>
</property>
<property name="text">
<string>Right %</string>
<property name="maximumSize">
<size>
<width>1000</width>
<height>1000</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QSlider" name="differentialSteeringSlider2">
<property name="maximum">
<number>100</number>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="value">
<number>50</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="gvDiffSteering2Label">
<property name="text">
<string>50</string>
<property name="baseSize">
<size>
<width>300</width>
<height>350</height>
</size>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_24">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="gvThrottleCurve1GroupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>100</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Front throttle curve</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_36">
<item>
<widget class="MixerCurveWidget" name="groundVehicleThrottle1" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>100</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="gvThrottleCurve1Reset">
<property name="maximumSize">
<size>
<width>200</width>
<height>16777215</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox_5">
<property name="title">
<string>Curve 2</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_17">
<item>
<widget class="MixerCurve" name="customThrottle2Curve" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>1</horstretch>
<verstretch>1</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>1000</height>
</size>
</property>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="baseSize">
<size>
<width>300</width>
<height>350</height>
</size>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item row="1" column="0">
<widget class="QTableWidget" name="customMixerTable">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="alternatingRowColors">
<bool>true</bool>
</property>
<attribute name="horizontalHeaderDefaultSectionSize">
<number>50</number>
</attribute>
<attribute name="horizontalHeaderStretchLastSection">
<bool>false</bool>
</attribute>
<row>
<property name="text">
<string>Reset</string>
<string>Type</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="gvThrottleCurve1ItemValue">
</row>
<row>
<property name="text">
<string>Val: 0.00</string>
<string>Curve 1</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="gvThrottleCurve2GroupBox">
<property name="title">
<string>Rear throttle curve</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_37">
<item>
<widget class="MixerCurveWidget" name="groundVehicleThrottle2" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>100</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="gvThrottleCurve2Reset">
</row>
<row>
<property name="text">
<string>Reset</string>
<string>Curve 2</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="gvThrottleCurve2ItemValue">
</row>
<row>
<property name="text">
<string>Val: 0.00</string>
<string>Roll</string>
</property>
</widget>
</item>
</layout>
</widget>
</row>
<row>
<property name="text">
<string>Pitch</string>
</property>
</row>
<row>
<property name="text">
<string>Yaw</string>
</property>
</row>
<column>
<property name="text">
<string>Ch 1</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 2</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 3</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 4</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 5</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 6</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 7</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 8</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 9</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 10</string>
</property>
</column>
<item row="0" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="2">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="3">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="4">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="5">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="6">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="7">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="8">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="9">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="2">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="3">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="4">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="5">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="6">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="7">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="8">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="9">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="2">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="3">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="4">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="5">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="6">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="7">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="8">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="9">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="2">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="3">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="4">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="5">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="6">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="7">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="8">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="9">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="2">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="3">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="4">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="5">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="6">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="7">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="8">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="9">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="2">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="3">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="4">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="5">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="6">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="7">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="8">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="9">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_1">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_28">
<item>
<spacer name="horizontalSpacer_21">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="gvStatusLabel">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Mixer OK</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="custom">
<layout class="QHBoxLayout" name="horizontalLayout_15">
<item>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_14">
<item>
<widget class="QGroupBox" name="groupBox_4">
<property name="title">
<string>Curve 1</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_7">
<item>
<widget class="MixerCurveWidget" name="customThrottle1Curve" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>100</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="customReset1">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Reset</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="customThrottleCurve1Value">
<property name="text">
<string>Val: 0.00</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_9">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox_5">
<property name="title">
<string>Curve 2</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_17">
<item>
<widget class="MixerCurveWidget" name="customThrottle2Curve" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>100</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="customReset2">
<property name="text">
<string>Reset</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="customThrottleCurve2Value">
<property name="text">
<string>Val: 0.00</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item row="1" column="0">
<widget class="QTableWidget" name="customMixerTable">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="alternatingRowColors">
<bool>true</bool>
</property>
<attribute name="horizontalHeaderDefaultSectionSize">
<number>50</number>
</attribute>
<attribute name="horizontalHeaderStretchLastSection">
<bool>false</bool>
</attribute>
<row>
<property name="text">
<string>Type</string>
</property>
</row>
<row>
<property name="text">
<string>Curve 1</string>
</property>
</row>
<row>
<property name="text">
<string>Curve 2</string>
</property>
</row>
<row>
<property name="text">
<string>Roll</string>
</property>
</row>
<row>
<property name="text">
<string>Pitch</string>
</property>
</row>
<row>
<property name="text">
<string>Yaw</string>
</property>
</row>
<column>
<property name="text">
<string>Ch 1</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 2</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 3</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 4</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 5</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 6</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 7</string>
</property>
</column>
<column>
<property name="text">
<string>Ch 8</string>
</property>
</column>
<item row="0" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="2">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="3">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="4">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="5">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="6">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="7">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="2">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="3">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="4">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="5">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="6">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="7">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="2">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="3">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="4">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="5">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="6">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="7">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="2">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="3">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="4">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="5">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="6">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="7">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="2">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="3">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="4">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="5">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="6">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="7">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="2">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="3">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="4">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="5">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="6">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="7">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
</widget>
</item>
</layout>
<item row="1" column="0">
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="3" column="1">
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Expanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
@ -2488,416 +2672,538 @@ margin:1px;</string>
<string>Advanced Settings</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_25">
<property name="margin">
<number>12</number>
</property>
<item>
<layout class="QVBoxLayout" name="verticalLayout_11" stretch="0,1,0,0,0">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_24">
<widget class="QScrollArea" name="scrollArea_2">
<property name="palette">
<palette>
<active>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_2">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>247</width>
<height>301</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_18">
<item>
<widget class="QLabel" name="label_19">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Feed Forward</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_16">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<layout class="QFormLayout" name="formLayout_7">
<property name="fieldGrowthPolicy">
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
</property>
<item row="2" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_12">
<layout class="QHBoxLayout" name="horizontalLayout_24">
<item>
<widget class="QLabel" name="label_20">
<widget class="QLabel" name="label_19">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>FeedForward </string>
<string>Feed Forward</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="feedForwardSliderValue">
<property name="minimumSize">
<spacer name="horizontalSpacer_16">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>30</width>
<height>0</height>
<width>40</width>
<height>20</height>
</size>
</property>
<property name="text">
<string>000</string>
</property>
</widget>
</spacer>
</item>
</layout>
</item>
<item row="2" column="1">
<widget class="QSlider" name="feedForwardSlider">
<property name="enabled">
<bool>true</bool>
<item>
<layout class="QFormLayout" name="formLayout_7">
<property name="fieldGrowthPolicy">
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Overall level of feed forward (in percentage).</string>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>1</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="tickPosition">
<enum>QSlider::NoTicks</enum>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_21">
<property name="text">
<string>Accel Time Constant</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QDoubleSpinBox" name="accelTime">
<property name="enabled">
<bool>true</bool>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>In miliseconds.
<item row="2" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_12">
<item>
<widget class="QLabel" name="label_20">
<property name="text">
<string>FeedForward </string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="feedForwardSliderValue">
<property name="minimumSize">
<size>
<width>30</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>000</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="2" column="1">
<widget class="QSlider" name="feedForwardSlider">
<property name="enabled">
<bool>true</bool>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Overall level of feed forward (in percentage).</string>
</property>
<property name="maximum">
<number>100</number>
</property>
<property name="singleStep">
<number>1</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="tickPosition">
<enum>QSlider::NoTicks</enum>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_21">
<property name="text">
<string>Accel Time Constant</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QDoubleSpinBox" name="accelTime">
<property name="enabled">
<bool>true</bool>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>In miliseconds.
When tuning: Slowly raise accel time from zero to just
under the level where the motor starts to overshoot
its target speed.</string>
</property>
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_22">
<property name="text">
<string>Decel Time Constant</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QDoubleSpinBox" name="decelTime">
<property name="enabled">
<bool>true</bool>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>When tuning: Slowly raise decel time from zero to just
</property>
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_22">
<property name="text">
<string>Decel Time Constant</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QDoubleSpinBox" name="decelTime">
<property name="enabled">
<bool>true</bool>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>When tuning: Slowly raise decel time from zero to just
under the level where the motor starts to undershoot
its target speed when decelerating.
Do it after accel time is setup.</string>
</property>
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="5" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_16">
<item>
<widget class="QLabel" name="label_37">
<property name="text">
<string>MaxAccel</string>
</property>
<property name="decimals">
<number>3</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="maxAccelSliderValue">
<property name="text">
<string>1000</string>
<item row="5" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_16">
<item>
<widget class="QLabel" name="label_37">
<property name="text">
<string>MaxAccel</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="maxAccelSliderValue">
<property name="text">
<string>1000</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="5" column="1">
<widget class="QSlider" name="maxAccelSlider">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Limits how much the engines can accelerate or decelerate.
In 'units per second', a sound default is 1000.</string>
</property>
<property name="minimum">
<number>500</number>
</property>
<property name="maximum">
<number>2000</number>
</property>
<property name="value">
<number>1000</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
</layout>
</item>
<item row="5" column="1">
<widget class="QSlider" name="maxAccelSlider">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Limits how much the engines can accelerate or decelerate.
In 'units per second', a sound default is 1000.</string>
</property>
<property name="minimum">
<number>500</number>
</property>
<property name="maximum">
<number>2000</number>
</property>
<property name="value">
<number>1000</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_9">
<item>
<spacer name="horizontalSpacer_8">
<spacer name="verticalSpacer_5">
<property name="orientation">
<enum>Qt::Horizontal</enum>
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QCheckBox" name="ffTestBox1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
<layout class="QHBoxLayout" name="horizontalLayout_9">
<item>
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QCheckBox" name="ffTestBox1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt;&quot;&gt;Beware! Check &lt;/span&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt; font-weight:600;&quot;&gt;all three&lt;/span&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt;&quot;&gt; checkboxes to test Feed Forward.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt;&quot;&gt;It will run only if your airframe armed.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="ffTestBox2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="ffTestBox2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt;&quot;&gt;Beware! Check &lt;/span&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt; font-weight:600;&quot;&gt;all three&lt;/span&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt;&quot;&gt; checkboxes to test Feed Forward.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt;&quot;&gt;It will run only if your airframe armed.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="ffTestBox3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="ffTestBox3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt;&quot;&gt;Beware! Check &lt;/span&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt; font-weight:600;&quot;&gt;all three&lt;/span&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt;&quot;&gt; checkboxes to test Feed Forward.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt;&quot;&gt;It will run only if your airframe armed.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="text">
<string>Enable FF tuning</string>
</property>
</widget>
</property>
<property name="text">
<string>Enable FF tuning</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
<widget class="QTextBrowser" name="textBrowser">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="sizeHint" stdset="0">
<property name="minimumSize">
<size>
<width>40</width>
<height>20</height>
<width>0</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QTextBrowser" name="textBrowser">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>40</height>
</size>
</property>
<property name="html">
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
<property name="html">
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt;
&lt;tr&gt;
&lt;td style=&quot;border: none;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;SETTING UP FEED FORWARD NEEDS CAUTION&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;SETTING UP FEED FORWARD REQUIRES CAUTION&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;&lt;br /&gt;&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!&lt;/p&gt;
&lt;p style=&quot; margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_5">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</property>
</widget>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_11"/>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="airframeHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveAircraftToRAM">
<property name="toolTip">
<string>Send to board, but don't save permanently (flash or SD).</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveAircraftToSD">
<property name="toolTip">
<string>Applies and Saves all settings to flash or SD depending on board.</string>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
<widget class="QGroupBox" name="groupBox_8">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>75</height>
</size>
</property>
<property name="title">
<string/>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="spacing">
<number>4</number>
</property>
<property name="sizeConstraint">
<enum>QLayout::SetFixedSize</enum>
</property>
<item>
<spacer name="horizontalSpacer_10">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="airframeHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="toolTip">
<string>Takes you to the wiki page</string>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveAircraftToRAM">
<property name="toolTip">
<string>Send to board, but don't save permanently (flash or SD).</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveAircraftToSD">
<property name="toolTip">
<string>Applies and Saves all settings to flash or SD depending on board.</string>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
<customwidgets>
<customwidget>
<class>MixerCurveWidget</class>
<extends>QWidget</extends>
<header>mixercurvewidget.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>ConfigCcpmWidget</class>
<extends>QWidget</extends>
<header>cfg_vehicletypes/configccpmwidget.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>MixerCurve</class>
<extends>QWidget</extends>
<header location="global">mixercurve.h</header>
<container>1</container>
</customwidget>
</customwidgets>
<resources>
<include location="../coreplugin/core.qrc"/>

View File

@ -6,640 +6,852 @@
<rect>
<x>0</x>
<y>0</y>
<width>720</width>
<height>739</height>
<width>820</width>
<height>845</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
<property name="autoFillBackground">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_6">
<property name="spacing">
<number>12</number>
</property>
<property name="margin">
<number>12</number>
</property>
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
<widget class="QTabWidget" name="tabWidget">
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="widgetResizable">
<bool>true</bool>
<property name="currentIndex">
<number>0</number>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_2">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>696</width>
<height>635</height>
</rect>
<property name="elideMode">
<enum>Qt::ElideMiddle</enum>
</property>
<widget class="QWidget" name="CameraStabilization">
<property name="autoFillBackground">
<bool>false</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<attribute name="title">
<string>Camera Stabilization</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_5">
<property name="spacing">
<number>12</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QCheckBox" name="enableCameraStabilization">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
<widget class="QScrollArea" name="scrollArea">
<property name="palette">
<palette>
<active>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="text">
<string>Enable CameraStabilization module</string>
<property name="autoFillBackground">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>After enabling the module, you must power cycle before using and configuring.</string>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
</widget>
</item>
<item>
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Horizontal</enum>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
<property name="widgetResizable">
<bool>true</bool>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox_5">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="title">
<string>Basic Settings (Stabilization)</string>
</property>
<layout class="QGridLayout" name="gridLayout_9">
<item row="2" column="3">
<widget class="QSpinBox" name="yawOutputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Camera yaw angle for 100% output value, deg.
<widget class="QWidget" name="scrollAreaWidgetContents_2">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>792</width>
<height>677</height>
</rect>
</property>
<property name="autoFillBackground">
<bool>true</bool>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
<property name="spacing">
<number>12</number>
</property>
<item>
<widget class="QGroupBox" name="groupBox_4">
<property name="title">
<string/>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<property name="leftMargin">
<number>12</number>
</property>
<item>
<widget class="QCheckBox" name="enableCameraStabilization">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="text">
<string>Enable CameraStabilization module</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>After enabling you must power cycle your board before using and configuring</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox_5">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>131</height>
</size>
</property>
<property name="title">
<string>Basic Settings (Stabilization)</string>
</property>
<property name="flat">
<bool>false</bool>
</property>
<layout class="QGridLayout" name="gridLayout_9">
<property name="leftMargin">
<number>12</number>
</property>
<property name="rightMargin">
<number>12</number>
</property>
<item row="3" column="3">
<widget class="QSpinBox" name="yawOutputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Camera yaw angle for 100% output value, deg.
This value should be tuned for particular gimbal and servo. You also
have to define channel output range using Output configuration tab.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QSpinBox" name="pitchOutputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Camera pitch angle for 100% output value, deg.
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QSpinBox" name="pitchOutputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Camera pitch angle for 100% output value, deg.
This value should be tuned for particular gimbal and servo. You also
have to define channel output range using Output configuration tab.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QSpinBox" name="rollOutputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Camera roll angle for 100% output value, deg.
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QSpinBox" name="rollOutputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Camera roll angle for 100% output value, deg.
This value should be tuned for particular gimbal and servo. You also
have to define channel output range using Output configuration tab.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QComboBox" name="yawChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Yaw output channel for camera gimbal</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QComboBox" name="yawChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Yaw output channel for camera gimbal</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="pitchChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Pitch output channel for camera gimbal</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="rollChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Roll output channel for camera gimbal</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_42">
<property name="text">
<string>Output Channel</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_43">
<property name="text">
<string>Output Range</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="label_44">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Yaw</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="label_45">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLabel" name="label_46">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="Line" name="line">
<property name="enabled">
<bool>true</bool>
</property>
</item>
</widget>
</item>
<item row="1" column="2">
<widget class="QComboBox" name="pitchChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Pitch output channel for camera gimbal</string>
</property>
<item>
<property name="text">
<string>None</string>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</item>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="rollChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Roll output channel for camera gimbal</string>
</property>
<item>
<property name="text">
<string>None</string>
</widget>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</item>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_42">
<property name="text">
<string>Output Channel</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_43">
<property name="text">
<string>Output Range</string>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="label_44">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>266</height>
</size>
</property>
<property name="title">
<string>Advanced Settings (Control)</string>
</property>
<layout class="QGridLayout" name="gridLayout_8">
<property name="leftMargin">
<number>12</number>
</property>
<property name="rightMargin">
<number>12</number>
</property>
<item row="1" column="3">
<widget class="QLabel" name="label_32">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Yaw</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_45">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
</property>
<property name="text">
<string>Yaw</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="label_33">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_46">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
</property>
<property name="text">
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLabel" name="label_34">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>204</height>
</size>
</property>
<property name="title">
<string>Advanced Settings (Control)</string>
</property>
<layout class="QGridLayout" name="gridLayout_8">
<item row="0" column="3">
<widget class="QLabel" name="label_32">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Yaw</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_33">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_34">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QComboBox" name="yawInputChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input channel to control camera yaw
</property>
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QComboBox" name="yawInputChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input channel to control camera yaw
Don't forget to map this channel using Input configuration tab.</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="1" column="2">
<widget class="QComboBox" name="pitchInputChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input channel to control camera pitch
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="pitchInputChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input channel to control camera pitch
Don't forget to map this channel using Input configuration tab.</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="rollInputChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input channel to control camera roll
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="rollInputChannel">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input channel to control camera roll
Don't forget to map this channel using Input configuration tab.</string>
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_35">
<property name="text">
<string>Input Channel</string>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QComboBox" name="yawStabilizationMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Axis stabilization mode
</property>
<item>
<property name="text">
<string>None</string>
</property>
</item>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_35">
<property name="text">
<string>Input Channel</string>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QComboBox" name="yawStabilizationMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Axis stabilization mode
Attitude: camera tracks level for the axis. Input controls the deflection.
AxisLock: camera remembers tracking attitude. Input controls the rate of deflection.</string>
</property>
<item>
<property name="text">
<string>Attitude</string>
</property>
</item>
</widget>
</item>
<item row="3" column="3">
<widget class="QSpinBox" name="yawInputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera yaw deflection for 100% input in Attitude mode, deg.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="4" column="3">
<widget class="QSpinBox" name="yawInputRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera yaw rate for 100% input in AxisLock mode, deg/s.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="5" column="3">
<widget class="QSpinBox" name="yawResponseTime">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input low-pass filter response time for yaw axis, ms.
</property>
<item>
<property name="text">
<string>Attitude</string>
</property>
</item>
</widget>
</item>
<item row="4" column="3">
<widget class="QSpinBox" name="yawInputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera yaw deflection for 100% input in Attitude mode, deg.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="5" column="3">
<widget class="QSpinBox" name="yawInputRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera yaw rate for 100% input in AxisLock mode, deg/s.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="6" column="3">
<widget class="QSpinBox" name="yawResponseTime">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input low-pass filter response time for yaw axis, ms.
This option smoothes the stick input. Zero value disables LPF.</string>
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="value">
<number>150</number>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="pitchStabilizationMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Axis stabilization mode
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="value">
<number>150</number>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QComboBox" name="pitchStabilizationMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Axis stabilization mode
Attitude: camera tracks level for the axis. Input controls the deflection.
AxisLock: camera remembers tracking attitude. Input controls the rate of deflection.</string>
</property>
<item>
<property name="text">
<string>Attitude</string>
</property>
</item>
</widget>
</item>
<item row="3" column="2">
<widget class="QSpinBox" name="pitchInputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera pitch deflection for 100% input in Attitude mode, deg.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QSpinBox" name="pitchInputRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera pitch rate for 100% input in AxisLock mode, deg/s.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="5" column="2">
<widget class="QSpinBox" name="pitchResponseTime">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input low-pass filter response time for pitch axis, ms.
</property>
<item>
<property name="text">
<string>Attitude</string>
</property>
</item>
</widget>
</item>
<item row="4" column="2">
<widget class="QSpinBox" name="pitchInputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera pitch deflection for 100% input in Attitude mode, deg.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="5" column="2">
<widget class="QSpinBox" name="pitchInputRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera pitch rate for 100% input in AxisLock mode, deg/s.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="6" column="2">
<widget class="QSpinBox" name="pitchResponseTime">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input low-pass filter response time for pitch axis, ms.
This option smoothes the stick input. Zero value disables LPF.</string>
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="value">
<number>150</number>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="rollStabilizationMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Axis stabilization mode
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="value">
<number>150</number>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="rollStabilizationMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Axis stabilization mode
Attitude: camera tracks level for the axis. Input controls the deflection.
AxisLock: camera remembers tracking attitude. Input controls the rate of deflection.</string>
</property>
<item>
<property name="text">
<string>Attitude</string>
</property>
</item>
</widget>
</item>
<item row="3" column="1">
<widget class="QSpinBox" name="rollInputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera roll deflection for 100% input in Attitude mode, deg.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QSpinBox" name="rollInputRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera roll rate for 100% input in AxisLock mode, deg/s.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QSpinBox" name="rollResponseTime">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input low-pass filter response time for roll axis, ms.
</property>
<item>
<property name="text">
<string>Attitude</string>
</property>
</item>
</widget>
</item>
<item row="4" column="1">
<widget class="QSpinBox" name="rollInputRange">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera roll deflection for 100% input in Attitude mode, deg.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>20</number>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QSpinBox" name="rollInputRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum camera roll rate for 100% input in AxisLock mode, deg/s.</string>
</property>
<property name="maximum">
<number>180</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QSpinBox" name="rollResponseTime">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Input low-pass filter response time for roll axis, ms.
This option smoothes the stick input. Zero value disables LPF.</string>
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="value">
<number>150</number>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="label_36">
<property name="text">
<string>MaxAxisLockRate</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="label_37">
<property name="text">
<string>Response Time</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_38">
<property name="text">
<string>Input Rate</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_39">
<property name="text">
<string>Input Range</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_40">
<property name="text">
<string>Stabilization Mode</string>
</property>
</widget>
</item>
<item row="6" column="2" colspan="2">
<widget class="QLabel" name="label_41">
<property name="text">
<string>(the same value for Roll, Pitch, Yaw)</string>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QDoubleSpinBox" name="MaxAxisLockRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Stick input deadband for all axes in AxisLock mode, deg/s.
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="value">
<number>150</number>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="label_36">
<property name="text">
<string>MaxAxisLockRate</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QLabel" name="label_37">
<property name="text">
<string>Response Time</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="label_38">
<property name="text">
<string>Input Rate</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_39">
<property name="text">
<string>Input Range</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_40">
<property name="text">
<string>Stabilization Mode</string>
</property>
</widget>
</item>
<item row="7" column="2" colspan="2">
<widget class="QLabel" name="label_41">
<property name="text">
<string>(the same value for Roll, Pitch, Yaw)</string>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QDoubleSpinBox" name="MaxAxisLockRate">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Stick input deadband for all axes in AxisLock mode, deg/s.
When stick input is within the MaxAxisLockRate range, camera tracks
current attitude. Otherwise it starts moving according to input with
@ -647,159 +859,199 @@ rate depending on input value.
If you have drift in your Tx controls, you may want to increase this
value.</string>
</property>
<property name="decimals">
<number>1</number>
</property>
<property name="singleStep">
<double>0.100000000000000</double>
</property>
<property name="value">
<double>1.000000000000000</double>
</property>
</widget>
</item>
</layout>
</property>
<property name="decimals">
<number>1</number>
</property>
<property name="singleStep">
<double>0.100000000000000</double>
</property>
<property name="value">
<double>1.000000000000000</double>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout">
<widget class="QGroupBox" name="groupBox_3">
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="title">
<string>Messages</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="leftMargin">
<number>9</number>
</property>
<item>
<widget class="QLabel" name="message">
<property name="text">
<string/>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="spacing">
<number>4</number>
</property>
<item>
<widget class="QLabel" name="message">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>425</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<kerning>true</kerning>
</font>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="shortcut">
<string>Ctrl+S</string>
</property>
<property name="default">
<bool>false</bool>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>button:help</string>
<string>url:http://wiki.openpilot.org/x/cACrAQ</string>
</stringlist>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="submitButtons">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="font">
<font>
<kerning>true</kerning>
</font>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="shortcut">
<string>Ctrl+S</string>
</property>
<property name="default">
<bool>false</bool>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationResetToDefaults">
<property name="toolTip">
<string>Load default CameraStabilization settings except output channels
<widget class="QPushButton" name="camerastabilizationResetToDefaults">
<property name="minimumSize">
<size>
<width>140</width>
<height>28</height>
</size>
</property>
<property name="toolTip">
<string>Load default CameraStabilization settings except output channels
Loaded settings are not applied automatically. You have to click the
Apply or Save button afterwards.</string>
</property>
<property name="text">
<string>Reset To Defaults</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationSaveRAM">
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationSaveSD">
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Reset To Defaults</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationSaveRAM">
<property name="minimumSize">
<size>
<width>78</width>
<height>28</height>
</size>
</property>
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="camerastabilizationSaveSD">
<property name="minimumSize">
<size>
<width>71</width>
<height>28</height>
</size>
</property>
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<tabstops>
<tabstop>enableCameraStabilization</tabstop>
<tabstop>rollChannel</tabstop>
<tabstop>pitchChannel</tabstop>
<tabstop>yawChannel</tabstop>
@ -822,7 +1074,6 @@ Apply or Save button afterwards.</string>
<tabstop>pitchResponseTime</tabstop>
<tabstop>yawResponseTime</tabstop>
<tabstop>MaxAxisLockRate</tabstop>
<tabstop>camerastabilizationHelp</tabstop>
<tabstop>camerastabilizationResetToDefaults</tabstop>
<tabstop>camerastabilizationSaveRAM</tabstop>
<tabstop>camerastabilizationSaveSD</tabstop>

View File

@ -6,210 +6,360 @@
<rect>
<x>0</x>
<y>0</y>
<width>517</width>
<height>487</height>
<width>592</width>
<height>763</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
<widget class="QTabWidget" name="tabWidget">
<property name="currentIndex">
<number>0</number>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
<widget class="QWidget" name="tab">
<attribute name="title">
<string>HW settings</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_3">
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="palette">
<palette>
<active>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>562</width>
<height>567</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<layout class="QGridLayout" name="gridLayout">
<item row="1" column="1" rowspan="5" colspan="3">
<widget class="QLabel" name="label_2">
<property name="text">
<string/>
</property>
<property name="scaledContents">
<bool>true</bool>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QComboBox" name="cbFlexi"/>
</item>
<item row="4" column="0">
<widget class="QComboBox" name="cbTele"/>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_3">
<property name="text">
<string>MainPort</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="label_4">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_5">
<property name="text">
<string>FlexiPort</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item row="1" column="5">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="4">
<widget class="QLabel" name="label_8">
<property name="text">
<string>USB HID Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QComboBox" name="cbUsbHid"/>
</item>
<item row="3" column="4">
<widget class="QLabel" name="label_9">
<property name="text">
<string>USB VCP Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item row="4" column="4">
<widget class="QComboBox" name="cbUsbVcp"/>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_7">
<property name="text">
<string>RcvrPort</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QComboBox" name="cbRcvr"/>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="0">
<widget class="QLabel" name="telemetrySpeedLabel">
<property name="text">
<string>Telemetry speed:</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="GpsSpeedLabel">
<property name="minimumSize">
<size>
<width>55</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>GPS speed:</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="ComUsbBridgeSpeedLabel">
<property name="minimumSize">
<size>
<width>55</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>ComUsbBridge speed:</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QComboBox" name="telemetrySpeed">
<property name="toolTip">
<string>Select the speed here.</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="gpsSpeed">
<property name="toolTip">
<string>Select the speed here.</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="comUsbBridgeSpeed">
<property name="toolTip">
<string>Select the speed here.</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="label_6">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Changes on this page only take effect after board reset or power cycle</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>25</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QGridLayout" name="gridLayout">
<item row="1" column="1" rowspan="5" colspan="3">
<widget class="QLabel" name="label_2">
<property name="text">
<string/>
</property>
<property name="scaledContents">
<bool>true</bool>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QComboBox" name="cbFlexi"/>
</item>
<item row="4" column="0">
<widget class="QComboBox" name="cbTele"/>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_3">
<property name="text">
<string>MainPort</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="label_4">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_5">
<property name="text">
<string>FlexiPort</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item row="1" column="5">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="4">
<widget class="QLabel" name="label_8">
<property name="text">
<string>USB HID Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QComboBox" name="cbUsbHid"/>
</item>
<item row="3" column="4">
<widget class="QLabel" name="label_9">
<property name="text">
<string>USB VCP Port</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item row="4" column="4">
<widget class="QComboBox" name="cbUsbVcp"/>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_7">
<property name="text">
<string>RcvrPort</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QComboBox" name="cbRcvr"/>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="0">
<widget class="QLabel" name="telemetrySpeedLabel">
<property name="text">
<string>Telemetry speed:</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="GpsSpeedLabel">
<property name="minimumSize">
<size>
<width>55</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>GPS speed:</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="ComUsbBridgeSpeedLabel">
<property name="minimumSize">
<size>
<width>55</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>ComUsbBridge speed:</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QComboBox" name="telemetrySpeed">
<property name="toolTip">
<string>Select the speed here.</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="gpsSpeed">
<property name="toolTip">
<string>Select the speed here.</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="comUsbBridgeSpeed">
<property name="toolTip">
<string>Select the speed here.</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<property name="minimumSize">
<size>
<width>0</width>
<height>50</height>
</size>
</property>
<property name="title">
<string>Messages</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QLabel" name="problems">
<property name="font">
@ -229,24 +379,32 @@
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_6">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Changes on this page only take effect after board reset or power cycle</string>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>75</height>
</size>
</property>
<property name="title">
<string/>
</property>
<layout class="QVBoxLayout" name="verticalLayout_4">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="spacing">
<number>4</number>
</property>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
@ -280,6 +438,9 @@
<height>32</height>
</size>
</property>
<property name="toolTip">
<string>Takes you to the wiki page</string>
</property>
<property name="text">
<string/>
</property>
@ -300,12 +461,76 @@
</item>
<item>
<widget class="QPushButton" name="saveTelemetryToRAM">
<property name="palette">
<palette>
<active>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="toolTip">
<string>Send to OpenPilot but don't write in SD.
Beware of not locking yourself out!</string>
</property>
<property name="autoFillBackground">
<bool>true</bool>
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true"/>

View File

@ -6,226 +6,359 @@
<rect>
<x>0</x>
<y>0</y>
<width>455</width>
<height>428</height>
<width>606</width>
<height>576</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="0">
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>Rotate virtual attitude relative to board</string>
<layout class="QVBoxLayout" name="verticalLayout_5">
<item>
<widget class="QTabWidget" name="tabWidget">
<property name="currentIndex">
<number>0</number>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QSpinBox" name="rollBias">
<property name="minimum">
<number>-180</number>
</property>
<property name="maximum">
<number>180</number>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QSpinBox" name="pitchBias">
<property name="minimum">
<number>-90</number>
</property>
<property name="maximum">
<number>90</number>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_4">
<property name="text">
<string>Yaw</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QSpinBox" name="yawBias">
<property name="minimum">
<number>-180</number>
</property>
<property name="maximum">
<number>180</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item row="1" column="0">
<widget class="QGroupBox" name="groupBox_2">
<property name="title">
<string>Calibration</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QLabel" name="label">
<property name="text">
<string>Place aircraft very flat, and then click level to compute the accelerometer and gyro bias</string>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="zeroBias">
<property name="toolTip">
<string>Launch horizontal calibration.</string>
</property>
<property name="text">
<string>Level</string>
</property>
</widget>
</item>
<item>
<widget class="QProgressBar" name="zeroBiasProgress">
<property name="value">
<number>0</number>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>0</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QCheckBox" name="zeroGyroBiasOnArming">
<property name="toolTip">
<string>If enabled, a fast recalibration of gyro zero point will be done
<widget class="QWidget" name="Attitude">
<attribute name="title">
<string>Attitude</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_3">
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="palette">
<palette>
<active>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Plain</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>576</width>
<height>439</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QGroupBox" name="groupBox">
<property name="title">
<string>Rotate virtual attitude relative to board</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QSpinBox" name="rollBias">
<property name="minimum">
<number>-180</number>
</property>
<property name="maximum">
<number>180</number>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QSpinBox" name="pitchBias">
<property name="minimum">
<number>-90</number>
</property>
<property name="maximum">
<number>90</number>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_4">
<property name="text">
<string>Yaw</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QSpinBox" name="yawBias">
<property name="minimum">
<number>-180</number>
</property>
<property name="maximum">
<number>180</number>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox_2">
<property name="title">
<string>Calibration</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QLabel" name="label">
<property name="text">
<string>Place aircraft very flat, and then click level to compute the accelerometer and gyro bias</string>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="zeroBias">
<property name="toolTip">
<string>Launch horizontal calibration.</string>
</property>
<property name="text">
<string>Level</string>
</property>
</widget>
</item>
<item>
<widget class="QProgressBar" name="zeroBiasProgress">
<property name="value">
<number>0</number>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>0</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QCheckBox" name="zeroGyroBiasOnArming">
<property name="toolTip">
<string>If enabled, a fast recalibration of gyro zero point will be done
whenever the frame is armed. Do not move the airframe while
arming it in that case!</string>
</property>
<property name="text">
<string>Zero gyros while arming aircraft</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>91</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox_3">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>75</height>
</size>
</property>
<property name="title">
<string/>
</property>
<layout class="QVBoxLayout" name="verticalLayout_4">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="spacing">
<number>4</number>
</property>
<property name="text">
<string>Zero gyros while arming aircraft</string>
</property>
</widget>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="ccAttitudeHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="toolTip">
<string>Takes you to the wiki page</string>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="applyButton">
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveButton">
<property name="toolTip">
<string>Click to permanently save the accel bias in the CopterControl Flash.</string>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item row="2" column="0">
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item row="3" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="ccAttitudeHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="applyButton">
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveButton">
<property name="toolTip">
<string>Click to permanently save the accel bias in the CopterControl Flash.</string>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<resources>

View File

@ -2770,537 +2770,13 @@ margin:1px;</string>
<number>3</number>
</property>
<item row="0" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_5">
<item>
<widget class="QComboBox" name="CurveType">
<property name="minimumSize">
<size>
<width>150</width>
<height>0</height>
</size>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
</font>
</property>
<property name="toolTip">
<string>Select aircraft type here</string>
</property>
<item>
<property name="text">
<string>Linear</string>
</property>
</item>
<item>
<property name="text">
<string>Flat</string>
</property>
</item>
<item>
<property name="text">
<string>Step</string>
</property>
</item>
<item>
<property name="text">
<string>Exp</string>
</property>
</item>
<item>
<property name="text">
<string>Log</string>
</property>
</item>
<item>
<property name="text">
<string>Custom</string>
</property>
</item>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="label_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Number of points</string>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="NumCurvePoints">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimum">
<number>2</number>
</property>
<property name="maximum">
<number>10</number>
</property>
<property name="value">
<number>5</number>
</property>
</widget>
</item>
</layout>
<layout class="QHBoxLayout" name="horizontalLayout_6"/>
</item>
<item row="1" column="0">
<layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="0">
<widget class="QLabel" name="CurveLabel1">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Min</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="CurveLabel2">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Max</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="CurveLabel3">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Step point</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QDoubleSpinBox" name="CurveValue1">
<property name="decimals">
<number>1</number>
</property>
<property name="maximum">
<double>10.000000000000000</double>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QDoubleSpinBox" name="CurveValue2">
<property name="decimals">
<number>1</number>
</property>
<property name="maximum">
<double>10.000000000000000</double>
</property>
<property name="value">
<double>1.000000000000000</double>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QDoubleSpinBox" name="CurveValue3">
<property name="decimals">
<number>1</number>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
<property name="value">
<double>50.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
<item row="2" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_6">
<item>
<widget class="QComboBox" name="CurveToGenerate">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>150</width>
<height>0</height>
</size>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
</font>
</property>
<property name="toolTip">
<string>Select aircraft type here</string>
</property>
<item>
<property name="text">
<string>Throttle</string>
</property>
</item>
<item>
<property name="text">
<string>Pitch</string>
</property>
</item>
</widget>
</item>
<item>
<widget class="QPushButton" name="ccpmGenerateCurve">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>150</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Generate curves based on settings</string>
</property>
<property name="text">
<string>&lt;-- Generate Curve</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item row="3" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_3">
<property name="spacing">
<number>3</number>
</property>
<item>
<widget class="QTableWidget" name="CurveSettings">
<property name="sizePolicy">
<sizepolicy hsizetype="Maximum" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>250</width>
<height>200</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>250</width>
<height>273</height>
</size>
</property>
<property name="verticalScrollBarPolicy">
<enum>Qt::ScrollBarAsNeeded</enum>
</property>
<property name="horizontalScrollBarPolicy">
<enum>Qt::ScrollBarAsNeeded</enum>
</property>
<property name="autoScroll">
<bool>true</bool>
</property>
<property name="alternatingRowColors">
<bool>true</bool>
</property>
<property name="cornerButtonEnabled">
<bool>true</bool>
</property>
<attribute name="horizontalHeaderCascadingSectionResizes">
<bool>true</bool>
</attribute>
<attribute name="horizontalHeaderStretchLastSection">
<bool>true</bool>
</attribute>
<attribute name="verticalHeaderDefaultSectionSize">
<number>25</number>
</attribute>
<attribute name="verticalHeaderMinimumSectionSize">
<number>25</number>
</attribute>
<row>
<property name="text">
<string>0%</string>
</property>
</row>
<row>
<property name="text">
<string>25%</string>
</property>
</row>
<row>
<property name="text">
<string>50%</string>
</property>
</row>
<row>
<property name="text">
<string>75%</string>
</property>
</row>
<row>
<property name="text">
<string>100%</string>
</property>
</row>
<row>
<property name="text">
<string>none</string>
</property>
</row>
<row>
<property name="text">
<string>none</string>
</property>
</row>
<row>
<property name="text">
<string>none</string>
</property>
</row>
<row>
<property name="text">
<string>none</string>
</property>
</row>
<row>
<property name="text">
<string>none</string>
</property>
</row>
<column>
<property name="text">
<string>Throttle Curve</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</column>
<column>
<property name="text">
<string>Blade Pitch Curve</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</column>
<item row="0" column="0">
<property name="text">
<string>0.000</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="0" column="1">
<property name="text">
<string>0.000</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="0">
<property name="text">
<string>0.250</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="1" column="1">
<property name="text">
<string>0.250</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="0">
<property name="text">
<string>0.500</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="2" column="1">
<property name="text">
<string>0.500</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="0">
<property name="text">
<string>0.750</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="3" column="1">
<property name="text">
<string>0.750</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="0">
<property name="text">
<string>1.000</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="4" column="1">
<property name="text">
<string>1.000</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="5" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="6" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="6" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="7" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="7" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="8" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="8" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="9" column="0">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
<item row="9" column="1">
<property name="text">
<string>-</string>
</property>
<property name="textAlignment">
<set>AlignHCenter|AlignVCenter|AlignCenter</set>
</property>
</item>
</widget>
</item>
<item>
<widget class="QGroupBox" name="ThrottleCurveBox">
<property name="sizePolicy">
@ -3331,7 +2807,7 @@ margin:1px;</string>
<enum>Qt::LeftToRight</enum>
</property>
<property name="title">
<string>Throttle Curve</string>
<string/>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
@ -3347,7 +2823,7 @@ margin:1px;</string>
<number>0</number>
</property>
<item row="0" column="0">
<widget class="MixerCurveWidget" name="ThrottleCurve" native="true">
<widget class="MixerCurve" name="ThrottleCurve" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>1</horstretch>
@ -3410,7 +2886,7 @@ margin:1px;</string>
</size>
</property>
<property name="title">
<string>Pitch Curve</string>
<string/>
</property>
<layout class="QGridLayout" name="gridLayout_5">
<property name="margin">
@ -3420,7 +2896,7 @@ margin:1px;</string>
<number>0</number>
</property>
<item row="0" column="0">
<widget class="MixerCurveWidget" name="PitchCurve" native="true">
<widget class="MixerCurve" name="PitchCurve" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Expanding">
<horstretch>1</horstretch>
@ -3458,7 +2934,7 @@ margin:1px;</string>
</item>
</layout>
</item>
<item row="4" column="0">
<item row="2" column="0">
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
@ -3910,9 +3386,9 @@ margin:1px;</string>
</widget>
<customwidgets>
<customwidget>
<class>MixerCurveWidget</class>
<class>MixerCurve</class>
<extends>QWidget</extends>
<header>mixercurvewidget.h</header>
<header location="global">mixercurve.h</header>
<container>1</container>
</customwidget>
</customwidgets>
@ -3945,14 +3421,6 @@ margin:1px;</string>
<tabstop>SwashLvlPositionSlider</tabstop>
<tabstop>SwashLvlPositionSpinBox</tabstop>
<tabstop>SwashLvlSwashplateImage</tabstop>
<tabstop>CurveType</tabstop>
<tabstop>NumCurvePoints</tabstop>
<tabstop>CurveValue1</tabstop>
<tabstop>CurveValue2</tabstop>
<tabstop>CurveValue3</tabstop>
<tabstop>CurveToGenerate</tabstop>
<tabstop>ccpmGenerateCurve</tabstop>
<tabstop>CurveSettings</tabstop>
<tabstop>ccpmAdvancedSettingsTable</tabstop>
</tabstops>
<resources/>

View File

@ -133,8 +133,12 @@ ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) : VehicleConfig(parent)
}
//initialize our two mixer curves
// mixercurve defaults to mixercurve_throttle
m_ccpm->ThrottleCurve->initLinearCurve(5, 1.0, 0.0);
// tell mixercurve this is a pitch curve
m_ccpm->PitchCurve->setMixerType(MixerCurve::MIXERCURVE_PITCH);
m_ccpm->PitchCurve->initLinearCurve(5, 1.0, -1.0);
m_ccpm->ThrottleCurve->initLinearCurve(5, 1.0);
//initialize channel names
m_ccpm->ccpmEngineChannel->addItems(channelNames);
@ -158,22 +162,10 @@ ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) : VehicleConfig(parent)
m_ccpm->ccpmType->addItems(Types);
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->count() - 1);
UpdateCurveSettings();
//disable changing number of points in curves until UAVObjects have more than 5
m_ccpm->NumCurvePoints->setEnabled(0);
refreshWidgetsValues(QString("HeliCP"));
UpdateType();
//connect(m_ccpm->saveccpmToSD, SIGNAL(clicked()), this, SLOT(saveccpmUpdate()));
//connect(m_ccpm->saveccpmToRAM, SIGNAL(clicked()), this, SLOT(sendccpmUpdate()));
//connect(m_ccpm->getccpmCurrent, SIGNAL(clicked()), this, SLOT(requestccpmUpdate()));
connect(m_ccpm->ccpmGenerateCurve, SIGNAL(clicked()), this, SLOT(GenerateCurve()));
connect(m_ccpm->NumCurvePoints, SIGNAL(valueChanged(int)), this, SLOT(UpdateCurveSettings()));
connect(m_ccpm->CurveToGenerate, SIGNAL(currentIndexChanged(int)), this, SLOT(UpdateCurveSettings()));
connect(m_ccpm->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(UpdateCurveSettings()));
connect(m_ccpm->ccpmAngleW, SIGNAL(valueChanged(double)), this, SLOT(ccpmSwashplateUpdate()));
connect(m_ccpm->ccpmAngleX, SIGNAL(valueChanged(double)), this, SLOT(ccpmSwashplateUpdate()));
connect(m_ccpm->ccpmAngleY, SIGNAL(valueChanged(double)), this, SLOT(ccpmSwashplateUpdate()));
@ -191,12 +183,8 @@ ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) : VehicleConfig(parent)
connect(m_ccpm->ccpmCollectivespinBox, SIGNAL(valueChanged(int)), this, SLOT(UpdateMixer()));
connect(m_ccpm->ccpmType, SIGNAL(currentIndexChanged(int)), this, SLOT(UpdateType()));
connect(m_ccpm->ccpmSingleServo, SIGNAL(currentIndexChanged(int)), this, SLOT(UpdateType()));
connect(m_ccpm->CurveSettings, SIGNAL(cellChanged (int, int)), this, SLOT(UpdateCurveWidgets()));
connect(m_ccpm->TabObject, SIGNAL(currentChanged ( QWidget * )), this, SLOT(UpdateType()));
connect(m_ccpm->PitchCurve, SIGNAL(curveUpdated(QList<double>,double)), this, SLOT(updatePitchCurveValue(QList<double>,double)));
connect(m_ccpm->ThrottleCurve, SIGNAL(curveUpdated(QList<double>,double)), this, SLOT(updateThrottleCurveValue(QList<double>,double)));
connect(m_ccpm->SwashLvlStartButton, SIGNAL(clicked()), this, SLOT(SwashLvlStartButtonPressed()));
connect(m_ccpm->SwashLvlNextButton, SIGNAL(clicked()), this, SLOT(SwashLvlNextButtonPressed()));
connect(m_ccpm->SwashLvlCancelButton, SIGNAL(clicked()), this, SLOT(SwashLvlCancelButtonPressed()));
@ -332,8 +320,6 @@ void ConfigCcpmWidget::UpdateType()
AdjustmentAngle=SingleServoIndex*90;
m_ccpm->CurveToGenerate->setEnabled(1);
m_ccpm->CurveSettings->setColumnHidden(1,0);
m_ccpm->PitchCurve->setVisible(1);
//m_ccpm->customThrottleCurve2Value->setVisible(1);
//m_ccpm->label_41->setVisible(1);
@ -425,9 +411,6 @@ void ConfigCcpmWidget::UpdateType()
m_ccpm->ccpmCollectiveSlider->setEnabled(0);
m_ccpm->ccpmCollectivespinBox->setValue(0);
m_ccpm->ccpmCollectiveSlider->setValue(0);
m_ccpm->CurveToGenerate->setCurrentIndex(0);
m_ccpm->CurveToGenerate->setEnabled(0);
m_ccpm->CurveSettings->setColumnHidden(1,1);
m_ccpm->PitchCurve->setVisible(0);
//m_ccpm->customThrottleCurve2Value->setVisible(0);
//m_ccpm->label_41->setVisible(0);
@ -469,271 +452,7 @@ void ConfigCcpmWidget::UpdateType()
}
void ConfigCcpmWidget::UpdateCurveWidgets()
{
int NumCurvePoints,i,Changed;
QList<double> curveValues;
QList<double> OldCurveValues;
double ThisValue;
//get the user settings
NumCurvePoints=m_ccpm->NumCurvePoints->value();
curveValues.clear();
Changed=0;
OldCurveValues=m_ccpm->ThrottleCurve->getCurve();
for (i=0; i<NumCurvePoints; i++)
{
ThisValue=m_ccpm->CurveSettings->item(i, 0 )->text().toDouble();
curveValues.append(ThisValue);
if (ThisValue!=OldCurveValues.at(i))Changed=1;
}
// Setup all Throttle1 curves for all types of airframes
if (Changed==1)
m_ccpm->ThrottleCurve->setCurve(&curveValues);
curveValues.clear();
Changed=0;
OldCurveValues=m_ccpm->PitchCurve->getCurve();
for (i=0; i<NumCurvePoints; i++)
{
ThisValue=m_ccpm->CurveSettings->item(i, 1 )->text().toDouble();
curveValues.append(ThisValue);
if (ThisValue!=OldCurveValues.at(i))Changed=1;
}
// Setup all Throttle1 curves for all types of airframes
if (Changed==1)
m_ccpm->PitchCurve->setCurve(&curveValues);
}
void ConfigCcpmWidget::updatePitchCurveValue(QList<double> curveValues0,double Value0)
{
Q_UNUSED(curveValues0);
Q_UNUSED(Value0);
int NumCurvePoints,i;
double CurrentValue;
QList<double> internalCurveValues;
//get the user settings
NumCurvePoints=m_ccpm->NumCurvePoints->value();
internalCurveValues=m_ccpm->PitchCurve->getCurve();
for (i=0; i<internalCurveValues.length(); i++)
{
CurrentValue=m_ccpm->CurveSettings->item(i, 1 )->text().toDouble();
if (CurrentValue!=internalCurveValues[i])
{
m_ccpm->CurveSettings->item(i, 1)->setText(QString().sprintf("%.3f",internalCurveValues.at(i)));
}
}
}
void ConfigCcpmWidget::updateThrottleCurveValue(QList<double> curveValues0,double Value0)
{
Q_UNUSED(curveValues0);
Q_UNUSED(Value0);
int NumCurvePoints,i;
double CurrentValue;
QList<double> internalCurveValues;
//get the user settings
NumCurvePoints=m_ccpm->NumCurvePoints->value();
internalCurveValues=m_ccpm->ThrottleCurve->getCurve();
for (i=0; i<internalCurveValues.length(); i++)
{
CurrentValue=m_ccpm->CurveSettings->item(i, 0 )->text().toDouble();
if (CurrentValue!=internalCurveValues[i])
{
m_ccpm->CurveSettings->item(i, 0)->setText(QString().sprintf("%.3f",internalCurveValues.at(i)));
}
}
}
void ConfigCcpmWidget::UpdateCurveSettings()
{
int NumCurvePoints,i;
double scale;
QString CurveType;
QStringList vertHeaders;
//get the user settings
NumCurvePoints=m_ccpm->NumCurvePoints->value();
CurveType=m_ccpm->CurveType->currentText();
vertHeaders << "-" << "-" << "-" << "-" << "-" << "-" << "-" << "-" << "-" << "-" ;
for (i=0;i<NumCurvePoints;i++)
{
scale =((double)i/(double)(NumCurvePoints-1));
vertHeaders[i] = tr( "%1%" ).arg(100.00*scale, 0, 'f', 1);
}
m_ccpm->CurveSettings->setVerticalHeaderLabels( vertHeaders );
if (m_ccpm->CurveToGenerate->currentIndex()==0)
{
m_ccpm->CurveValue1->setMinimum(0.0);
m_ccpm->CurveValue2->setMinimum(0.0);
m_ccpm->CurveValue3->setMinimum(0.0);
}
else
{
m_ccpm->CurveValue1->setMinimum(-1.0);
m_ccpm->CurveValue2->setMinimum(-1.0);
m_ccpm->CurveValue3->setMinimum(0.0);
}
m_ccpm->CurveValue1->setMaximum(1.0);
m_ccpm->CurveValue2->setMaximum(1.0);
m_ccpm->CurveValue3->setMaximum(100.0);
m_ccpm->CurveValue1->setSingleStep(0.1);
m_ccpm->CurveValue2->setSingleStep(0.1);
m_ccpm->CurveValue3->setSingleStep(1.0);
m_ccpm->CurveValue1->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue);;
m_ccpm->CurveValue2->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue);
m_ccpm->CurveValue3->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue);
//set default visible
m_ccpm->CurveLabel1->setVisible(true);
m_ccpm->CurveValue1->setVisible(true);
m_ccpm->CurveLabel2->setVisible(false);
m_ccpm->CurveValue2->setVisible(false);
m_ccpm->CurveLabel3->setVisible(false);
m_ccpm->CurveValue3->setVisible(false);
m_ccpm->ccpmGenerateCurve->setVisible(true);
m_ccpm->CurveToGenerate->setVisible(true);
if ( CurveType.compare("Flat")==0)
{
m_ccpm->CurveLabel1->setText("Value");
}
if ( CurveType.compare("Linear")==0)
{
m_ccpm->CurveLabel1->setText("Min");
m_ccpm->CurveLabel2->setText("Max");
m_ccpm->CurveLabel2->setVisible(true);
m_ccpm->CurveValue2->setVisible(true);
}
if ( CurveType.compare("Step")==0)
{
m_ccpm->CurveLabel1->setText("Min");
m_ccpm->CurveLabel2->setText("Max");
m_ccpm->CurveLabel2->setVisible(true);
m_ccpm->CurveValue2->setVisible(true);
m_ccpm->CurveLabel3->setText("Step at");
m_ccpm->CurveLabel3->setVisible(true);
m_ccpm->CurveValue3->setVisible(true);
}
if ( CurveType.compare("Exp")==0)
{
m_ccpm->CurveLabel1->setText("Min");
m_ccpm->CurveLabel2->setText("Max");
m_ccpm->CurveLabel2->setVisible(true);
m_ccpm->CurveValue2->setVisible(true);
m_ccpm->CurveLabel3->setText("Strength");
m_ccpm->CurveLabel3->setVisible(true);
m_ccpm->CurveValue3->setVisible(true);
m_ccpm->CurveValue3->setMinimum(1.0);
m_ccpm->CurveValue3->setMaximum(100.0);
m_ccpm->CurveValue3->setSingleStep(1.0);
m_ccpm->CurveValue3->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue);;
}
if ( CurveType.compare("Log")==0)
{
m_ccpm->CurveLabel1->setText("Min");
m_ccpm->CurveLabel2->setText("Max");
m_ccpm->CurveLabel2->setVisible(true);
m_ccpm->CurveValue2->setVisible(true);
m_ccpm->CurveLabel3->setText("Strength");
m_ccpm->CurveLabel3->setVisible(true);
m_ccpm->CurveValue3->setVisible(true);
m_ccpm->CurveValue3->setMinimum(1.0);
m_ccpm->CurveValue3->setMaximum(100.0);
m_ccpm->CurveValue3->setSingleStep(1.0);
m_ccpm->CurveValue3->setCorrectionMode(QAbstractSpinBox::CorrectToNearestValue);
}
if ( CurveType.compare("Custom")==0)
{
m_ccpm->CurveLabel1->setVisible(false);
m_ccpm->CurveValue1->setVisible(false);
m_ccpm->ccpmGenerateCurve->setVisible(false);
m_ccpm->CurveToGenerate->setVisible(false);
}
UpdateCurveWidgets();
}
void ConfigCcpmWidget::GenerateCurve()
{
int NumCurvePoints,CurveToGenerate,i;
double value1, value2, value3, scale;
QString CurveType;
QTableWidgetItem *item;
double newValue;
//get the user settings
NumCurvePoints=m_ccpm->NumCurvePoints->value();
value1=m_ccpm->CurveValue1->value();
value2=m_ccpm->CurveValue2->value();
value3=m_ccpm->CurveValue3->value();
CurveToGenerate=m_ccpm->CurveToGenerate->currentIndex();
CurveType=m_ccpm->CurveType->currentText();
for (i=0;i<NumCurvePoints;i++)
{
scale =((double)i/(double)(NumCurvePoints-1));
item =m_ccpm->CurveSettings->item(i, CurveToGenerate );
if ( CurveType.compare("Flat")==0)
{
//item->setText( tr( "%1" ).arg( value1 ) );
item->setText(QString().sprintf("%.3f",value1));
}
if ( CurveType.compare("Linear")==0)
{
newValue =value1 +(scale*(value2-value1));
//item->setText( tr( "%1" ).arg(value1 +(scale*(value2-value1))) );
item->setText(QString().sprintf("%.3f",newValue));
}
if ( CurveType.compare("Step")==0)
{
if (scale*100<value3)
{
//item->setText( tr( "%1" ).arg(value1) );
item->setText(QString().sprintf("%.3f",value1));
}
else
{
//item->setText( tr( "%1" ).arg(value2) );
item->setText(QString().sprintf("%.3f",value2));
}
}
if ( CurveType.compare("Exp")==0)
{
newValue =value1 +(((exp(scale*(value3/10))-1))/(exp((value3/10))-1)*(value2-value1));
//item->setText( tr( "%1" ).arg(value1 +(((exp(scale*(value3/10))-1))/(exp((value3/10))-1)*(value2-value1))) );
item->setText(QString().sprintf("%.3f",newValue));
}
if ( CurveType.compare("Log")==0)
{
newValue = value1 +(((log(scale*(value3*2)+1))/(log(1+(value3*2))))*(value2-value1));
//item->setText( tr( "%1" ).arg(value1 +(((log(scale*(value3*2)+1))/(log(1+(value3*2))))*(value2-value1))) );
item->setText(QString().sprintf("%.3f",newValue));
}
}
for (i=NumCurvePoints;i<10;i++)
{
item =m_ccpm->CurveSettings->item(i, CurveToGenerate );
item->setText( tr( "" ) );
}
UpdateCurveWidgets();
}
void ConfigCcpmWidget::ccpmSwashplateRedraw()
{
@ -1111,21 +830,33 @@ void ConfigCcpmWidget::getMixer()
{
if (SwashLvlConfigurationInProgress)return;
if (updatingToHardware)return;
updatingFromHardware=TRUE;
int i;
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
// Get existing mixer settings
MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager());
MixerSettings::DataFields mixerSettingsData = mixerSettings->getData();
QPointer<VehicleConfig> vconfig = new VehicleConfig();
//get the settings for the curve from the mixer settings
for (i=0;i<5;i++)
{
m_ccpm->CurveSettings->item(i, 0)->setText(QString().sprintf("%.3f",
mixerSettingsData.ThrottleCurve1[i]));
m_ccpm->CurveSettings->item(i, 1)->setText(QString().sprintf("%.3f",
mixerSettingsData.ThrottleCurve2[i]));
QList<double> curveValues;
vconfig->getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, &curveValues);
// is at least one of the curve values != 0?
if (vconfig->isValidThrottleCurve(&curveValues)) {
m_ccpm->ThrottleCurve->setCurve(&curveValues);
}
else {
m_ccpm->ThrottleCurve->ResetCurve();
}
vconfig->getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, &curveValues);
// is at least one of the curve values != 0?
if (vconfig->isValidThrottleCurve(&curveValues)) {
m_ccpm->PitchCurve->setCurve(&curveValues);
}
else {
m_ccpm->PitchCurve->ResetCurve();
}
updatingFromHardware=FALSE;
@ -1195,9 +926,11 @@ void ConfigCcpmWidget::setMixer()
}
//get the user data for the curve into the mixer settings
QList<double> curve1 = m_ccpm->ThrottleCurve->getCurve();
QList<double> curve2 = m_ccpm->PitchCurve->getCurve();
for (i=0;i<5;i++) {
mixerSettingsData.ThrottleCurve1[i] = m_ccpm->CurveSettings->item(i, 0)->text().toDouble();
mixerSettingsData.ThrottleCurve2[i] = m_ccpm->CurveSettings->item(i, 1)->text().toDouble();
mixerSettingsData.ThrottleCurve1[i] = curve1.at(i);
mixerSettingsData.ThrottleCurve2[i] = curve2.at(i);
}
//mapping of collective input to curve 2...

View File

@ -88,7 +88,7 @@ private:
bool updatingToHardware;
virtual void ResetActuators(GUIConfigDataUnion* configData);
virtual QStringList getChannelDescriptions();
static QStringList getChannelDescriptions();
QString updateConfigObjects();
private slots:
@ -99,13 +99,8 @@ private:
void ccpmSwashplateUpdate();
void ccpmSwashplateRedraw();
void UpdateCurveSettings();
void GenerateCurve();
void UpdateMixer();
void UpdateType();
void UpdateCurveWidgets();
void updatePitchCurveValue(QList<double>,double);
void updateThrottleCurveValue(QList<double>,double);
void SwashLvlStartButtonPressed();
void SwashLvlNextButtonPressed();

View File

@ -186,8 +186,7 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets()
Q_ASSERT(mixer);
// Remove Feed Forward, it is pointless on a plane:
UAVObjectField* field = mixer->getField(QString("FeedForward"));
field->setDouble(0);
setMixerValue(mixer, "FeedForward", 0.0);
// Set the throttle curve
setThrottleCurve(mixer,VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->fixedWingThrottle->getCurve());
@ -291,7 +290,7 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType)
int channel;
//disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++)
for (channel=0; channel<(int)VehicleConfig::CHANNEL_NUMELEM; channel++)
{
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
@ -371,7 +370,7 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType)
int channel;
double value;
//disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++)
for (channel=0; channel<(int)VehicleConfig::CHANNEL_NUMELEM; channel++)
{
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
@ -449,7 +448,7 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType)
int channel;
double value;
//disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++)
for (channel=0; channel<(int)VehicleConfig::CHANNEL_NUMELEM; channel++)
{
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);

View File

@ -57,7 +57,7 @@ private:
bool setupFrameVtail(QString airframeType);
virtual void ResetActuators(GUIConfigDataUnion* configData);
virtual QStringList getChannelDescriptions();
static QStringList getChannelDescriptions();
private slots:
virtual void setupUI(QString airframeType);

View File

@ -198,24 +198,15 @@ QString ConfigGroundVehicleWidget::updateConfigObjectsFromWidgets()
QString airframeType = "GroundVehicleCar";
// Save the curve (common to all ground vehicle frames)
UAVDataObject *obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVDataObject *mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
// Remove Feed Forward, it is pointless on a ground vehicle:
UAVObjectField* field = obj->getField(QString("FeedForward"));
field->setDouble(0);
field = obj->getField("ThrottleCurve1");
QList<double> curve = m_aircraft->groundVehicleThrottle1->getCurve();
for (int i=0;i<curve.length();i++) {
field->setValue(curve.at(i),i);
}
setMixerValue(mixer, "FeedForward", 0.0);
// set the throttle curves
setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->groundVehicleThrottle1->getCurve() );
setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, m_aircraft->groundVehicleThrottle2->getCurve() );
field = obj->getField("ThrottleCurve2");
curve = m_aircraft->groundVehicleThrottle2->getCurve();
for (int i=0;i<curve.length();i++) {
field->setValue(curve.at(i),i);
}
//All airframe types must start with "GroundVehicle"
if (m_aircraft->groundVehicleType->currentText() == "Turnable (car)" ) {
airframeType = "GroundVehicleCar";
@ -307,7 +298,7 @@ bool ConfigGroundVehicleWidget::setupGroundVehicleMotorcycle(QString airframeTyp
int channel;
//disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++) {
for (channel=0; channel<(int)VehicleConfig::CHANNEL_NUMELEM; channel++) {
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
}
@ -364,7 +355,7 @@ bool ConfigGroundVehicleWidget::setupGroundVehicleDifferential(QString airframeT
int channel;
//disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++) {
for (channel=0; channel<(int)VehicleConfig::CHANNEL_NUMELEM; channel++) {
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
}
@ -419,7 +410,7 @@ bool ConfigGroundVehicleWidget::setupGroundVehicleCar(QString airframeType)
int channel;
//disable all
for (channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++) {
for (channel=0; channel<(int)VehicleConfig::CHANNEL_NUMELEM; channel++) {
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
}

View File

@ -57,7 +57,7 @@ private:
bool setupGroundVehicleMotorcycle(QString airframeType);
virtual void ResetActuators(GUIConfigDataUnion* configData);
virtual QStringList getChannelDescriptions();
static QStringList getChannelDescriptions();
private slots:
virtual void setupUI(QString airframeType);

View File

@ -42,7 +42,8 @@
#include "actuatorsettings.h"
#include "actuatorcommand.h"
//#define Pi 3.14159265358979323846
const QString ConfigMultiRotorWidget::CHANNELBOXNAME = QString("multiMotorChannelBox");
/**
@ -58,7 +59,7 @@ ConfigMultiRotorWidget::ConfigMultiRotorWidget(Ui_AircraftWidget *aircraft, QWid
*/
ConfigMultiRotorWidget::~ConfigMultiRotorWidget()
{
// Do nothing
// Do nothing
}
@ -86,13 +87,11 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
if (frameType == "Tri" || frameType == "Tricopter Y") {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y"));
quad->setElementId("tri");
quad->setElementId("tri");
//Enable all necessary motor channel boxes...
enableComboBoxes(uiowner, CHANNELBOXNAME, 3, true);
//Enable all necessary motor channel boxes...
for (i=1; i <=3; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
m_aircraft->mrYawMixLevel->setValue(50);
@ -102,132 +101,113 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
else if (frameType == "QuadX" || frameType == "Quad X") {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X"));
quad->setElementId("quad-x");
//Enable all necessary motor channel boxes...
for (i=1; i <=4; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
//Enable all necessary motor channel boxes...
enableComboBoxes(uiowner, CHANNELBOXNAME, 4, true);
// init mixer levels
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(50);
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(50);
}
else if (frameType == "QuadP" || frameType == "Quad +") {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +"));
quad->setElementId("quad-plus");
//Enable all necessary motor channel boxes...
for (i=1; i <=4; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
quad->setElementId("quad-plus");
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
m_aircraft->mrYawMixLevel->setValue(50);
//Enable all necessary motor channel boxes...
enableComboBoxes(uiowner, CHANNELBOXNAME, 4, true);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
m_aircraft->mrYawMixLevel->setValue(50);
}
else if (frameType == "Hexa" || frameType == "Hexacopter")
{
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter"));
quad->setElementId("quad-hexa");
//Enable all necessary motor channel boxes...
for (i=1; i <=6; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
quad->setElementId("quad-hexa");
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(33);
m_aircraft->mrYawMixLevel->setValue(33);
//Enable all necessary motor channel boxes...
enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true);
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(33);
m_aircraft->mrYawMixLevel->setValue(33);
}
else if (frameType == "HexaX" || frameType == "Hexacopter X" ) {
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter X"));
quad->setElementId("quad-hexa-H");
//Enable all necessary motor channel boxes...
for (i=1; i <=6; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
quad->setElementId("quad-hexa-H");
//Enable all necessary motor channel boxes...
enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true);
m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(33);
m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(33);
}
else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6")
{
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter Y6"));
quad->setElementId("hexa-coax");
//Enable all necessary motor channel boxes...
for (i=1; i <=6; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
quad->setElementId("hexa-coax");
//Enable all necessary motor channel boxes...
enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(66);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(66);
}
else if (frameType == "Octo" || frameType == "Octocopter")
{
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter"));
quad->setElementId("quad-octo");
//Enable all necessary motor channel boxes
for (i=1; i <=8; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
quad->setElementId("quad-octo");
m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(33);
m_aircraft->mrYawMixLevel->setValue(25);
//Enable all necessary motor channel boxes
enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(33);
m_aircraft->mrPitchMixLevel->setValue(33);
m_aircraft->mrYawMixLevel->setValue(25);
}
else if (frameType == "OctoV" || frameType == "Octocopter V")
{
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter V"));
quad->setElementId("quad-octo-v");
quad->setElementId("quad-octo-v");
//Enable all necessary motor channel boxes
for (i=1; i <=8; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
//Enable all necessary motor channel boxes
enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(25);
m_aircraft->mrPitchMixLevel->setValue(25);
m_aircraft->mrYawMixLevel->setValue(25);
m_aircraft->mrRollMixLevel->setValue(25);
m_aircraft->mrPitchMixLevel->setValue(25);
m_aircraft->mrYawMixLevel->setValue(25);
}
else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +")
{
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +"));
quad->setElementId("octo-coax-P");
quad->setElementId("octo-coax-P");
//Enable all necessary motor channel boxes
for (int i=1; i <=8; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
//Enable all necessary motor channel boxes
enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
m_aircraft->mrYawMixLevel->setValue(50);
m_aircraft->mrRollMixLevel->setValue(100);
m_aircraft->mrPitchMixLevel->setValue(100);
m_aircraft->mrYawMixLevel->setValue(50);
}
else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X")
{
setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X"));
quad->setElementId("octo-coax-X");
quad->setElementId("octo-coax-X");
//Enable all necessary motor channel boxes
for (int i=1; i <=8; i++) {
enableComboBox(uiowner, QString("multiMotorChannelBox%0").arg(i), true);
}
enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true);
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(50);
}
m_aircraft->mrRollMixLevel->setValue(50);
m_aircraft->mrPitchMixLevel->setValue(50);
m_aircraft->mrYawMixLevel->setValue(50);
}
}
void ConfigMultiRotorWidget::ResetActuators(GUIConfigDataUnion* configData)
@ -245,11 +225,10 @@ void ConfigMultiRotorWidget::ResetActuators(GUIConfigDataUnion* configData)
QStringList ConfigMultiRotorWidget::getChannelDescriptions()
{
int i;
QStringList channelDesc;
// init a channel_numelem list of channel desc defaults
for (i=0; i < (int)(ConfigMultiRotorWidget::CHANNEL_NUMELEM); i++)
for (int i=0; i < (int)(ConfigMultiRotorWidget::CHANNEL_NUMELEM); i++)
{
channelDesc.append(QString("-"));
}
@ -258,21 +237,21 @@ QStringList ConfigMultiRotorWidget::getChannelDescriptions()
GUIConfigDataUnion configData = GetConfigData();
multiGUISettingsStruct multi = configData.multi;
if (multi.VTOLMotorN > 0 && multi.VTOLMotorN < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
if (multi.VTOLMotorN > 0 && multi.VTOLMotorN <= ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorN-1] = QString("VTOLMotorN");
if (multi.VTOLMotorNE > 0 && multi.VTOLMotorNE < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
if (multi.VTOLMotorNE > 0 && multi.VTOLMotorNE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorNE-1] = QString("VTOLMotorNE");
if (multi.VTOLMotorNW > 0 && multi.VTOLMotorNW < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
if (multi.VTOLMotorNW > 0 && multi.VTOLMotorNW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorNW-1] = QString("VTOLMotorNW");
if (multi.VTOLMotorS > 0 && multi.VTOLMotorS < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
if (multi.VTOLMotorS > 0 && multi.VTOLMotorS <= ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorS-1] = QString("VTOLMotorS");
if (multi.VTOLMotorSE > 0 && multi.VTOLMotorSE < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
if (multi.VTOLMotorSE > 0 && multi.VTOLMotorSE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorSE-1] = QString("VTOLMotorSE");
if (multi.VTOLMotorSW > 0 && multi.VTOLMotorSW < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
if (multi.VTOLMotorSW > 0 && multi.VTOLMotorSW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorSW-1] = QString("VTOLMotorSW");
if (multi.VTOLMotorW > 0 && multi.VTOLMotorW < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
if (multi.VTOLMotorW > 0 && multi.VTOLMotorW <= ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorW-1] = QString("VTOLMotorW");
if (multi.VTOLMotorE > 0 && multi.VTOLMotorE < ConfigMultiRotorWidget::CHANNEL_NUMELEM)
if (multi.VTOLMotorE > 0 && multi.VTOLMotorE <= ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.VTOLMotorE-1] = QString("VTOLMotorE");
if (multi.TRIYaw > 0 && multi.TRIYaw <= ConfigMultiRotorWidget::CHANNEL_NUMELEM)
channelDesc[multi.TRIYaw-1] = QString("Tri-Yaw");
@ -288,188 +267,188 @@ QStringList ConfigMultiRotorWidget::getChannelDescriptions()
*/
QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
{
QString airframeType;
QList<QString> motorList;
QString airframeType;
QList<QString> motorList;
UAVDataObject* mixerObj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixerObj);
// Curve is also common to all quads:
setThrottleCurve(mixerObj, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->multiThrottleCurve->getCurve() );
if (m_aircraft->multirotorFrameType->currentText() == "Quad +") {
airframeType = "QuadP";
setupQuad(true);
} else if (m_aircraft->multirotorFrameType->currentText() == "Quad X") {
airframeType = "QuadX";
setupQuad(false);
} else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter") {
airframeType = "Hexa";
setupHexa(true);
} else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter X") {
airframeType = "HexaX";
setupHexa(false);
} else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter Y6") {
airframeType = "HexaCoax";
//Show any config errors in GUI
if (m_aircraft->multirotorFrameType->currentText() == "Quad +") {
airframeType = "QuadP";
setupQuad(true);
} else if (m_aircraft->multirotorFrameType->currentText() == "Quad X") {
airframeType = "QuadX";
setupQuad(false);
} else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter") {
airframeType = "Hexa";
setupHexa(true);
} else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter X") {
airframeType = "HexaX";
setupHexa(false);
} else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter Y6") {
airframeType = "HexaCoax";
//Show any config errors in GUI
if (throwConfigError(6)) {
return airframeType;
}
motorList << "VTOLMotorNW" << "VTOLMotorW" << "VTOLMotorNE" << "VTOLMotorE"
<< "VTOLMotorS" << "VTOLMotorSE";
setupMotors(motorList);
// Motor 1 to 6, Y6 Layout:
// pitch roll yaw
double mixer [8][3] = {
{ 0.5, 1, -1},
{ 0.5, 1, 1},
{ 0.5, -1, -1},
{ 0.5, -1, 1},
{ -1, 0, -1},
{ -1, 0, 1},
{ 0, 0, 0},
{ 0, 0, 0}
};
setupMultiRotorMixer(mixer);
m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK");
} else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter") {
airframeType = "Octo";
//Show any config errors in GUI
if (throwConfigError(8)) {
return airframeType;
return airframeType;
}
motorList << "VTOLMotorNW" << "VTOLMotorW" << "VTOLMotorNE" << "VTOLMotorE"
<< "VTOLMotorS" << "VTOLMotorSE";
setupMotors(motorList);
}
motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE"
<< "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW";
setupMotors(motorList);
// Motor 1 to 8:
// pitch roll yaw
double mixer [8][3] = {
{ 1, 0, -1},
{ 1, -1, 1},
{ 0, -1, -1},
{ -1, -1, 1},
{ -1, 0, -1},
{ -1, 1, 1},
{ 0, 1, -1},
{ 1, 1, 1}
};
setupMultiRotorMixer(mixer);
m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK");
} else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter V") {
airframeType = "OctoV";
//Show any config errors in GUI
if (throwConfigError(8)) {
return airframeType;
}
motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE"
<< "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW";
setupMotors(motorList);
// Motor 1 to 8:
// IMPORTANT: Assumes evenly spaced engines
// pitch roll yaw
double mixer [8][3] = {
{ 0.33, -1, -1},
{ 1 , -1, 1},
{ -1 , -1, -1},
{ -0.33, -1, 1},
{ -0.33, 1, -1},
{ -1 , 1, 1},
{ 1 , 1, -1},
{ 0.33, 1, 1}
};
setupMultiRotorMixer(mixer);
m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK");
} else if (m_aircraft->multirotorFrameType->currentText() == "Octo Coax +") {
airframeType = "OctoCoaxP";
// Motor 1 to 6, Y6 Layout:
// pitch roll yaw
double mixer [8][3] = {
{ 0.5, 1, -1},
{ 0.5, 1, 1},
{ 0.5, -1, -1},
{ 0.5, -1, 1},
{ -1, 0, -1},
{ -1, 0, 1},
{ 0, 0, 0},
{ 0, 0, 0}
};
setupMultiRotorMixer(mixer);
m_aircraft->mrStatusLabel->setText("Configuration OK");
//Show any config errors in GUI
if (throwConfigError(8)) {
return airframeType;
}
motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE"
<< "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW";
setupMotors(motorList);
// Motor 1 to 8:
// pitch roll yaw
double mixer [8][3] = {
{ 1, 0, -1},
{ 1, 0, 1},
{ 0, -1, -1},
{ 0, -1, 1},
{ -1, 0, -1},
{ -1, 0, 1},
{ 0, 1, -1},
{ 0, 1, 1}
};
setupMultiRotorMixer(mixer);
m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK");
} else if (m_aircraft->multirotorFrameType->currentText() == "Octo Coax X") {
airframeType = "OctoCoaxX";
//Show any config errors in GUI
if (throwConfigError(8)) {
return airframeType;
}
motorList << "VTOLMotorNW" << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE"
<< "VTOLMotorSE" << "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW";
setupMotors(motorList);
// Motor 1 to 8:
// pitch roll yaw
double mixer [8][3] = {
{ 1, 1, -1},
{ 1, 1, 1},
{ 1, -1, -1},
{ 1, -1, 1},
{ -1, -1, -1},
{ -1, -1, 1},
{ -1, 1, -1},
{ -1, 1, 1}
};
setupMultiRotorMixer(mixer);
m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK");
} else if (m_aircraft->multirotorFrameType->currentText() == "Tricopter Y") {
airframeType = "Tri";
} else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter") {
airframeType = "Octo";
//Show any config errors in GUI
//Show any config errors in GUI
if (throwConfigError(8)) {
return airframeType;
}
motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE"
<< "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW";
setupMotors(motorList);
// Motor 1 to 8:
// pitch roll yaw
double mixer [8][3] = {
{ 1, 0, -1},
{ 1, -1, 1},
{ 0, -1, -1},
{ -1, -1, 1},
{ -1, 0, -1},
{ -1, 1, 1},
{ 0, 1, -1},
{ 1, 1, 1}
};
setupMultiRotorMixer(mixer);
m_aircraft->mrStatusLabel->setText("Configuration OK");
} else if (m_aircraft->multirotorFrameType->currentText() == "Octocopter V") {
airframeType = "OctoV";
//Show any config errors in GUI
if (throwConfigError(8)) {
return airframeType;
}
motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE"
<< "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW";
setupMotors(motorList);
// Motor 1 to 8:
// IMPORTANT: Assumes evenly spaced engines
// pitch roll yaw
double mixer [8][3] = {
{ 0.33, -1, -1},
{ 1 , -1, 1},
{ -1 , -1, -1},
{ -0.33, -1, 1},
{ -0.33, 1, -1},
{ -1 , 1, 1},
{ 1 , 1, -1},
{ 0.33, 1, 1}
};
setupMultiRotorMixer(mixer);
m_aircraft->mrStatusLabel->setText("Configuration OK");
} else if (m_aircraft->multirotorFrameType->currentText() == "Octo Coax +") {
airframeType = "OctoCoaxP";
//Show any config errors in GUI
if (throwConfigError(8)) {
return airframeType;
}
motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE"
<< "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW";
setupMotors(motorList);
// Motor 1 to 8:
// pitch roll yaw
double mixer [8][3] = {
{ 1, 0, -1},
{ 1, 0, 1},
{ 0, -1, -1},
{ 0, -1, 1},
{ -1, 0, -1},
{ -1, 0, 1},
{ 0, 1, -1},
{ 0, 1, 1}
};
setupMultiRotorMixer(mixer);
m_aircraft->mrStatusLabel->setText("Configuration OK");
} else if (m_aircraft->multirotorFrameType->currentText() == "Octo Coax X") {
airframeType = "OctoCoaxX";
//Show any config errors in GUI
if (throwConfigError(8)) {
return airframeType;
}
motorList << "VTOLMotorNW" << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorE"
<< "VTOLMotorSE" << "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorW";
setupMotors(motorList);
// Motor 1 to 8:
// pitch roll yaw
double mixer [8][3] = {
{ 1, 1, -1},
{ 1, 1, 1},
{ 1, -1, -1},
{ 1, -1, 1},
{ -1, -1, -1},
{ -1, -1, 1},
{ -1, 1, -1},
{ -1, 1, 1}
};
setupMultiRotorMixer(mixer);
m_aircraft->mrStatusLabel->setText("Configuration OK");
} else if (m_aircraft->multirotorFrameType->currentText() == "Tricopter Y") {
airframeType = "Tri";
//Show any config errors in GUI
if (throwConfigError(3)) {
return airframeType;
return airframeType;
}
if (m_aircraft->triYawChannelBox->currentText() == "None") {
m_aircraft->mrStatusLabel->setText("<font color='red'>Error: Assign a Yaw channel</font>");
return airframeType;
}
motorList << "VTOLMotorNW" << "VTOLMotorNE" << "VTOLMotorS";
setupMotors(motorList);
}
if (m_aircraft->triYawChannelBox->currentText() == "None") {
m_aircraft->mrStatusLabel->setText("<font color='red'>Error: Assign a Yaw channel</font>");
return airframeType;
}
motorList << "VTOLMotorNW" << "VTOLMotorNE" << "VTOLMotorS";
setupMotors(motorList);
GUIConfigDataUnion config = GetConfigData();
config.multi.TRIYaw = m_aircraft->triYawChannelBox->currentIndex();
SetConfigData(config);
// Motor 1 to 6, Y6 Layout:
// pitch roll yaw
double mixer [8][3] = {
{ 0.5, 1, 0},
{ 0.5, -1, 0},
{ -1, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0}
};
setupMultiRotorMixer(mixer);
// Motor 1 to 6, Y6 Layout:
// pitch roll yaw
double mixer [8][3] = {
{ 0.5, 1, 0},
{ 0.5, -1, 0},
{ -1, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0}
};
setupMultiRotorMixer(mixer);
//tell the mixer about tricopter yaw channel
@ -478,12 +457,12 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
setMixerType(mixerObj, channel, VehicleConfig::MIXERTYPE_SERVO);
setMixerVectorValue(mixerObj, channel, VehicleConfig::MIXERVECTOR_YAW, 127);
}
m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK");
m_aircraft->mrStatusLabel->setText(tr("Configuration OK"));
}
return airframeType;
return airframeType;
}
@ -502,16 +481,17 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
if (frameType == "QuadP") {
if (frameType == "QuadP")
{
// Motors 1/2/3/4 are: N / E / S / W
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorE);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3,multi.VTOLMotorS);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4,multi.VTOLMotorW);
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
// This assumes that all vectors are identical - if not, the user should use the
// "custom" setting.
channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
if (channel > -1)
@ -527,7 +507,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
m_aircraft->mrRollMixLevel->setValue( -value/1.27);
}
} else if (frameType == "QuadX") {
}
else if (frameType == "QuadX")
{
// Motors 1/2/3/4 are: NW / NE / SE / SW
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE);
@ -551,8 +533,10 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
}
} else if (frameType == "Hexa") {
// Motors 1/2/3 4/5/6 are: N / NE / SE / S / SW / NW
}
else if (frameType == "Hexa")
{
// Motors 1/2/3 4/5/6 are: N / NE / SE / S / SW / NW
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN);
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2,multi.VTOLMotorNE);
@ -582,7 +566,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
}
} else if (frameType == "HexaX") {
}
else if (frameType == "HexaX")
{
// Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNE);
@ -609,7 +595,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( floor(1-value/1.27) );
}
} else if (frameType == "HexaCoax") {
}
else if (frameType == "HexaCoax")
{
// Motors 1/2/3 4/5/6 are: NW/W NE/E S/SE
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW);
@ -635,8 +623,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( value/1.27);
}
} else if (frameType == "Octo" || frameType == "OctoV" ||
frameType == "OctoCoaxP") {
}
else if (frameType == "Octo" || frameType == "OctoV" || frameType == "OctoCoaxP")
{
// Motors 1 to 8 are N / NE / E / etc
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorN);
@ -692,7 +681,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
}
}
} else if (frameType == "OctoCoaxX") {
}
else if (frameType == "OctoCoaxX")
{
// Motors 1 to 8 are N / NE / E / etc
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW);
@ -719,7 +710,9 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) );
}
} else if (frameType == "Tri") {
}
else if (frameType == "Tri")
{
// Motors 1 to 8 are N / NE / E / etc
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1,multi.VTOLMotorNW);
@ -738,7 +731,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) );
}
}
}
}
@ -748,8 +741,6 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
*/
void ConfigMultiRotorWidget::setupQuadMotor(int channel, double pitch, double roll, double yaw)
{
qDebug()<<QString("Setup quad motor channel=%0 pitch=%1 roll=%2 yaw=%3").arg(channel).arg(pitch).arg(roll).arg(yaw);
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
@ -771,8 +762,8 @@ void ConfigMultiRotorWidget::setupMotors(QList<QString> motorList)
{
QList<QComboBox*> mmList;
mmList << m_aircraft->multiMotorChannelBox1 << m_aircraft->multiMotorChannelBox2 << m_aircraft->multiMotorChannelBox3
<< m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6
<< m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8;
<< m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6
<< m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8;
GUIConfigDataUnion configData = GetConfigData();
ResetActuators(&configData);
@ -782,8 +773,6 @@ void ConfigMultiRotorWidget::setupMotors(QList<QString> motorList)
index = mmList.takeFirst()->currentIndex();
//qDebug()<<QString("Setup motor: %0 = %1").arg(motor).arg(index);
if (motor == QString("VTOLMotorN"))
configData.multi.VTOLMotorN = index;
else if (motor == QString("VTOLMotorNE"))
@ -813,23 +802,23 @@ void ConfigMultiRotorWidget::setupMotors(QList<QString> motorList)
bool ConfigMultiRotorWidget::setupQuad(bool pLayout)
{
// Check coherence:
//Show any config errors in GUI
//Show any config errors in GUI
if (throwConfigError(4)) {
return false;
return false;
}
QList<QString> motorList;
if (pLayout) {
motorList << "VTOLMotorN" << "VTOLMotorE" << "VTOLMotorS"
<< "VTOLMotorW";
<< "VTOLMotorW";
} else {
motorList << "VTOLMotorNW" << "VTOLMotorNE" << "VTOLMotorSE"
<< "VTOLMotorSW";
<< "VTOLMotorSW";
}
setupMotors(motorList);
// Now, setup the mixer:
// Motor 1 to 4, X Layout:
// pitch roll yaw
@ -838,15 +827,15 @@ bool ConfigMultiRotorWidget::setupQuad(bool pLayout)
// {-0.5 ,-0.5 ,-0.5 //rear right motor (CW)
// {-0.5 ,0.5 ,0.5 //Rear left motor (CCW)
double xMixer [8][3] = {
{ 1, 1, -1},
{ 1, -1, 1},
{-1, -1, -1},
{-1, 1, 1},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0}
};
{ 1, 1, -1},
{ 1, -1, 1},
{-1, -1, -1},
{-1, 1, 1},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0}
};
//
// Motor 1 to 4, P Layout:
// pitch roll yaw
@ -855,22 +844,22 @@ bool ConfigMultiRotorWidget::setupQuad(bool pLayout)
// {-1 ,0 ,-0.5 //Rear motor (CW)
// {0 ,1 ,0.5 //Left motor (CCW)
double pMixer [8][3] = {
{ 1, 0, -1},
{ 0, -1, 1},
{-1, 0, -1},
{ 0, 1, 1},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0}
};
{ 1, 0, -1},
{ 0, -1, 1},
{-1, 0, -1},
{ 0, 1, 1},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0},
{ 0, 0, 0}
};
if (pLayout) {
setupMultiRotorMixer(pMixer);
} else {
setupMultiRotorMixer(xMixer);
}
m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK");
m_aircraft->mrStatusLabel->setText(tr("Configuration OK"));
return true;
}
@ -882,22 +871,22 @@ bool ConfigMultiRotorWidget::setupQuad(bool pLayout)
bool ConfigMultiRotorWidget::setupHexa(bool pLayout)
{
// Check coherence:
//Show any config errors in GUI
//Show any config errors in GUI
if (throwConfigError(6))
return false;
return false;
QList<QString> motorList;
if (pLayout) {
motorList << "VTOLMotorN" << "VTOLMotorNE" << "VTOLMotorSE"
<< "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorNW";
<< "VTOLMotorS" << "VTOLMotorSW" << "VTOLMotorNW";
} else {
motorList << "VTOLMotorNE" << "VTOLMotorE" << "VTOLMotorSE"
<< "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW";
<< "VTOLMotorSW" << "VTOLMotorW" << "VTOLMotorNW";
}
setupMotors(motorList);
// and set only the relevant channels:
// Motor 1 to 6, P Layout:
// pitch roll yaw
// 1 { 0.3 , 0 ,-0.3 // N CW
@ -906,8 +895,8 @@ bool ConfigMultiRotorWidget::setupHexa(bool pLayout)
// 4 {-0.3 , 0 , 0.3 // S CCW
// 5 {-0.3 , 0.5 ,-0.3 // SW CW
// 6 { 0.3 , 0.5 , 0.3 // NW CCW
double pMixer [8][3] = {
double pMixer [8][3] = {
{ 1, 0, -1},
{ 1, -1, 1},
{-1, -1, -1},
@ -917,8 +906,8 @@ bool ConfigMultiRotorWidget::setupHexa(bool pLayout)
{ 0, 0, 0},
{ 0, 0, 0}
};
//
//
// Motor 1 to 6, X Layout:
// 1 [ 0.5, -0.3, -0.3 ] NE
// 2 [ 0 , -0.3, 0.3 ] E
@ -926,24 +915,24 @@ bool ConfigMultiRotorWidget::setupHexa(bool pLayout)
// 4 [ -0.5, 0.3, 0.3 ] SW
// 5 [ 0 , 0.3, -0.3 ] W
// 6 [ 0.5, 0.3, 0.3 ] NW
double xMixer [8][3] = {
{ 1, -1, -1},
{ 0, -1, 1},
{ -1, -1, -1},
{ -1, 1, 1},
{ 0, 1, -1},
{ 1, 1, 1},
{ 0, 0, 0},
{ 0, 0, 0}
};
if (pLayout) {
setupMultiRotorMixer(pMixer);
} else {
setupMultiRotorMixer(xMixer);
}
m_aircraft->mrStatusLabel->setText("SUCCESS: Mixer Saved OK");
return true;
double xMixer [8][3] = {
{ 1, -1, -1},
{ 0, -1, 1},
{ -1, -1, -1},
{ -1, 1, 1},
{ 0, 1, -1},
{ 1, 1, 1},
{ 0, 0, 0},
{ 0, 0, 0}
};
if (pLayout) {
setupMultiRotorMixer(pMixer);
} else {
setupMultiRotorMixer(xMixer);
}
m_aircraft->mrStatusLabel->setText("Configuration OK");
return true;
}
@ -952,26 +941,16 @@ bool ConfigMultiRotorWidget::setupHexa(bool pLayout)
*/
bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3])
{
qDebug()<<"Mixer factors";
qDebug()<<mixerFactors[0][0]<<" "<<mixerFactors[0][1]<<" "<<mixerFactors[0][2];
qDebug()<<mixerFactors[1][0]<<" "<<mixerFactors[1][1]<<" "<<mixerFactors[1][2];
qDebug()<<mixerFactors[2][0]<<" "<<mixerFactors[2][1]<<" "<<mixerFactors[2][2];
qDebug()<<mixerFactors[3][0]<<" "<<mixerFactors[3][1]<<" "<<mixerFactors[3][2];
qDebug()<<mixerFactors[4][0]<<" "<<mixerFactors[4][1]<<" "<<mixerFactors[4][2];
qDebug()<<mixerFactors[5][0]<<" "<<mixerFactors[5][1]<<" "<<mixerFactors[5][2];
qDebug()<<mixerFactors[6][0]<<" "<<mixerFactors[6][1]<<" "<<mixerFactors[6][2];
qDebug()<<mixerFactors[7][0]<<" "<<mixerFactors[7][1]<<" "<<mixerFactors[7][2];
QList<QComboBox*> mmList;
mmList << m_aircraft->multiMotorChannelBox1 << m_aircraft->multiMotorChannelBox2 << m_aircraft->multiMotorChannelBox3
<< m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6
<< m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8;
<< m_aircraft->multiMotorChannelBox4 << m_aircraft->multiMotorChannelBox5 << m_aircraft->multiMotorChannelBox6
<< m_aircraft->multiMotorChannelBox7 << m_aircraft->multiMotorChannelBox8;
UAVDataObject* mixer = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
Q_ASSERT(mixer);
//disable all
for (int channel=0; channel<VehicleConfig::CHANNEL_NUMELEM; channel++)
for (int channel=0; channel<(int)VehicleConfig::CHANNEL_NUMELEM; channel++)
{
setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED);
resetMixerVector(mixer, channel);
@ -981,17 +960,15 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3])
double pFactor = (double)m_aircraft->mrPitchMixLevel->value()/100;
double rFactor = (double)m_aircraft->mrRollMixLevel->value()/100;
double yFactor = (double)m_aircraft->mrYawMixLevel->value()/100;
qDebug()<<QString("pFactor=%0 rFactor=%1 yFactor=%2").arg(pFactor).arg(rFactor).arg(yFactor);
for (int i=0 ; i<8; i++) {
if(mmList.at(i)->isEnabled())
{
int channel = mmList.at(i)->currentIndex()-1;
if (channel > -1)
setupQuadMotor(channel, mixerFactors[i][0]*pFactor,
rFactor*mixerFactors[i][1], yFactor*mixerFactors[i][2]);
rFactor*mixerFactors[i][1], yFactor*mixerFactors[i][2]);
}
}
// obj->updated();
return true;
}
@ -1001,31 +978,31 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3])
*/
bool ConfigMultiRotorWidget::throwConfigError(int numMotors)
{
//Initialize configuration error flag
bool error=false;
//Initialize configuration error flag
bool error=false;
//Iterate through all instances of multiMotorChannelBox
for (int i=0; i<numMotors; i++) {
//Fine widgets with text "multiMotorChannelBox.x", where x is an integer
//Iterate through all instances of multiMotorChannelBox
for (int i=0; i<numMotors; i++) {
//Fine widgets with text "multiMotorChannelBox.x", where x is an integer
QComboBox *combobox = qFindChild<QComboBox*>(uiowner, "multiMotorChannelBox" + QString::number(i+1));
if (combobox){
if (combobox->currentText() == "None") {
int size = combobox->style()->pixelMetric(QStyle::PM_SmallIconSize);
QPixmap pixmap(size,size);
pixmap.fill(QColor("red"));
int size = combobox->style()->pixelMetric(QStyle::PM_SmallIconSize);
QPixmap pixmap(size,size);
pixmap.fill(QColor("red"));
combobox->setItemData(0, pixmap, Qt::DecorationRole);//Set color palettes
error=true;
}
else {
error=true;
}
else {
combobox->setItemData(0, 0, Qt::DecorationRole);//Reset color palettes
}
}
}
}
}
}
if (error){
m_aircraft->mrStatusLabel->setText(QString("<font color='red'>ERROR: Assign all %1 motor channels</font>").arg(numMotors));
}
if (error){
m_aircraft->mrStatusLabel->setText(QString("<font color='red'>ERROR: Assign all %1 motor channels</font>").arg(numMotors));
}
return error;
}

View File

@ -65,7 +65,8 @@ private:
void setupQuadMotor(int channel, double roll, double pitch, double yaw);
virtual void ResetActuators(GUIConfigDataUnion* configData);
virtual QStringList getChannelDescriptions();
static QStringList getChannelDescriptions();
static const QString CHANNELBOXNAME;
private slots:
virtual void setupUI(QString airframeType);

View File

@ -44,11 +44,6 @@ VehicleConfig::VehicleConfig(QWidget *parent) : ConfigTaskWidget(parent)
channelNames << QString("Channel%1").arg(i+1);
}
// typedef enum { MIXERTYPE_DISABLED=0, MIXERTYPE_MOTOR=1, MIXERTYPE_SERVO=2,
//MIXERTYPE_CAMERAROLL=3, MIXERTYPE_CAMERAPITCH=4, MIXERTYPE_CAMERAYAW=5,
//MIXERTYPE_ACCESSORY0=6, MIXERTYPE_ACCESSORY1=7, MIXERTYPE_ACCESSORY2=8,
//MIXERTYPE_ACCESSORY3=9, MIXERTYPE_ACCESSORY4=10, MIXERTYPE_ACCESSORY5=11 } MixerTypeElem;
mixerTypeDescriptions << "Disabled" << "Motor" << "Servo" << "CameraRoll" << "CameraPitch"
<< "CameraYaw" << "Accessory0" << "Accessory1" << "Accessory2"
<< "Accessory3" << "Accessory4" << "Accessory5";
@ -100,30 +95,19 @@ void VehicleConfig::SetConfigData(GUIConfigDataUnion configData) {
Q_ASSERT(systemSettings);
SystemSettings::DataFields systemSettingsData = systemSettings->getData();
UAVObjectField* guiConfig = systemSettings->getField("GUIConfigData");
Q_ASSERT(guiConfig);
if(!guiConfig)
return;
// copy parameter configData -> systemsettings
for (i = 0; i < (int)(SystemSettings::GUICONFIGDATA_NUMELEM); i++)
systemSettingsData.GUIConfigData[i] = configData.UAVObject[i];
systemSettings->setData(systemSettingsData);
systemSettings->updated();
//emit ConfigurationChanged();
guiConfig->setValue(configData.UAVObject[i], i);
}
void VehicleConfig::ResetActuators(GUIConfigDataUnion* configData)
{
}
QStringList VehicleConfig::getChannelDescriptions()
{
QStringList channelDesc;
// init a channel_numelem list of channel desc defaults
for (int i=0; i < (int)(VehicleConfig::CHANNEL_NUMELEM); i++)
{
channelDesc.append(QString("-"));
}
return channelDesc;
}
/**
Helper function:
@ -140,15 +124,16 @@ void VehicleConfig::setComboCurrentIndex(QComboBox* box, int index)
/**
Helper function:
enables/disables the named combobox within supplied uiowner
enables/disables the named comboboxes within supplied uiowner
*/
void VehicleConfig::enableComboBox(QWidget* owner, QString boxName, bool enable)
void VehicleConfig::enableComboBoxes(QWidget* owner, QString boxName, int boxCount, bool enable)
{
QComboBox* box = qFindChild<QComboBox*>(owner, boxName);
if (box)
box->setEnabled(enable);
for (int i = 1; i <= boxCount; i++) {
QComboBox* box = qFindChild<QComboBox*>(owner, QString("%0%1").arg(boxName).arg(i));
if (box)
box->setEnabled(enable);
}
}
QString VehicleConfig::getMixerType(UAVDataObject* mixer, int channel)
{
Q_ASSERT(mixer);
@ -170,8 +155,6 @@ void VehicleConfig::setMixerType(UAVDataObject* mixer, int channel, MixerTypeEle
{
Q_ASSERT(mixer);
qDebug() << QString("setMixerType channel %0, type %1").arg(channel).arg(mixerType);
if (channel >= 0 && channel < mixerTypes.count()) {
UAVObjectField *field = mixer->getField(mixerTypes.at(channel));
Q_ASSERT(field);
@ -180,7 +163,6 @@ void VehicleConfig::setMixerType(UAVDataObject* mixer, int channel, MixerTypeEle
if (mixerType >= 0 && mixerType < mixerTypeDescriptions.count())
{
field->setValue(mixerTypeDescriptions[mixerType]);
mixer->updated();
}
}
}
@ -220,15 +202,12 @@ void VehicleConfig::setMixerVectorValue(UAVDataObject* mixer, int channel, Mixer
{
Q_ASSERT(mixer);
qDebug() << QString("setMixerVectorValue channel %0, name %1, value %2").arg(channel).arg(elementName).arg(value);
if (channel >= 0 && channel < mixerVectors.count()) {
UAVObjectField *field = mixer->getField(mixerVectors.at(channel));
Q_ASSERT(field);
if (field) {
field->setDouble(value, elementName);
mixer->updated();
}
}
}

View File

@ -123,8 +123,7 @@ class VehicleConfig: public ConfigTaskWidget
static void SetConfigData(GUIConfigDataUnion configData);
static void resetField(UAVObjectField * field);
static void setComboCurrentIndex(QComboBox* box, int index);
static void enableComboBox(QWidget* owner, QString boxName, bool enable);
static void enableComboBoxes(QWidget* owner, QString boxName, int boxCount, bool enable);
double getMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName);
void setMixerVectorValue(UAVDataObject* mixer, int channel, MixerVectorElem elementName, double value);
void resetMixerVector(UAVDataObject* mixer, int channel);
@ -138,7 +137,6 @@ class VehicleConfig: public ConfigTaskWidget
double getCurveMin(QList<double>* curve);
double getCurveMax(QList<double>* curve);
virtual void ResetActuators(GUIConfigDataUnion* configData);
virtual QStringList getChannelDescriptions();
QStringList channelNames;
QStringList mixerTypes;

View File

@ -36,7 +36,9 @@ HEADERS += configplugin.h \
cfg_vehicletypes/configfixedwingwidget.h \
cfg_vehicletypes/vehicleconfig.h \
configrevowidget.h \
config_global.h
config_global.h \
mixercurve.h \
dblspindelegate.h
SOURCES += configplugin.cpp \
configgadgetconfiguration.cpp \
configgadgetwidget.cpp \
@ -67,7 +69,9 @@ SOURCES += configplugin.cpp \
cfg_vehicletypes/configfixedwingwidget.cpp \
cfg_vehicletypes/configccpmwidget.cpp \
outputchannelform.cpp \
cfg_vehicletypes/vehicleconfig.cpp
cfg_vehicletypes/vehicleconfig.cpp \
mixercurve.cpp \
dblspindelegate.cpp
FORMS += airframe.ui \
cc_hw_settings.ui \
pro_hw_settings.ui \
@ -83,5 +87,6 @@ FORMS += airframe.ui \
outputchannelform.ui \
revosensors.ui \
txpid.ui \
pipxtreme.ui
pipxtreme.ui \
mixercurve.ui
RESOURCES += configgadget.qrc

View File

@ -35,14 +35,44 @@
#include <QtGui/QPushButton>
#include <QDesktopServices>
#include <QUrl>
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/generalsettings.h>
ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_telemetry = new Ui_CC_HW_Widget();
m_telemetry->setupUi(this);
m_telemetry->label_2->setPixmap(QPixmap(":/configgadget/images/coptercontrol.svg"));
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
m_telemetry->saveTelemetryToRAM->setVisible(false);
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
int id = utilMngr->getBoardModel();
switch (id) {
case 0x0101:
m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0101.svg"));
break;
case 0x0301:
m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0301.svg"));
break;
case 0x0401:
m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0401.svg"));
break;
case 0x0402:
m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0402.svg"));
break;
case 0x0201:
m_telemetry->label_2->setPixmap(QPixmap(":/uploader/images/deviceID-0201.svg"));
break;
default:
m_telemetry->label_2->setPixmap(QPixmap(":/configgadget/images/coptercontrol.svg"));
break;
}
addApplySaveButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
addUAVObjectToWidgetRelation("HwSettings","CC_FlexiPort",m_telemetry->cbFlexi);
addUAVObjectToWidgetRelation("HwSettings","CC_MainPort",m_telemetry->cbTele);
@ -98,7 +128,7 @@ void ConfigCCHWWidget::widgetsContentsChanged()
void ConfigCCHWWidget::openHelp()
{
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/CopterControl+HW+Settings", QUrl::StrictMode) );
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/D4AUAQ", QUrl::StrictMode) );
}
/**

View File

@ -33,12 +33,19 @@
#include <QDebug>
#include <QDesktopServices>
#include <QUrl>
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/generalsettings.h>
ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
// TODO: this widget should use the addUAVObjectToWidgetRelation()
m_camerastabilization = new Ui_CameraStabilizationWidget();
m_camerastabilization->setupUi(this);
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
m_camerastabilization->camerastabilizationSaveRAM->setVisible(false);
QComboBox *outputs[3] = {
m_camerastabilization->rollChannel,
@ -88,7 +95,7 @@ ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent
connect(m_camerastabilization->camerastabilizationResetToDefaults, SIGNAL(clicked()), this, SLOT(resetToDefaults()));
connect(m_camerastabilization->camerastabilizationSaveRAM, SIGNAL(clicked()), this, SLOT(applySettings()));
connect(m_camerastabilization->camerastabilizationSaveSD, SIGNAL(clicked()), this, SLOT(saveSettings()));
connect(m_camerastabilization->camerastabilizationHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
autoLoadWidgets();
disableMouseWheelEvents();
}
@ -326,11 +333,6 @@ void ConfigCameraStabilizationWidget::resetToDefaults()
refreshUIValues(defaults);
}
void ConfigCameraStabilizationWidget::openHelp()
{
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Camera+Stabilization+Configuration", QUrl::StrictMode) );
}
void ConfigCameraStabilizationWidget::enableControls(bool enable)
{
m_camerastabilization->camerastabilizationResetToDefaults->setEnabled(enable);

View File

@ -47,7 +47,6 @@ private:
void refreshUIValues(CameraStabSettings::DataFields &cameraStabData);
private slots:
void openHelp();
void resetToDefaults();
void applySettings();
void saveSettings();

View File

@ -35,6 +35,8 @@
#include <QUrl>
#include "accels.h"
#include "gyros.h"
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/generalsettings.h>
ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
ConfigTaskWidget(parent),
@ -43,7 +45,11 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) :
ui->setupUi(this);
connect(ui->zeroBias,SIGNAL(clicked()),this,SLOT(startAccelCalibration()));
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
ui->applyButton->setVisible(false);
addApplySaveButtons(ui->applyButton,ui->saveButton);
addUAVObject("AttitudeSettings");
@ -163,7 +169,7 @@ void ConfigCCAttitudeWidget::startAccelCalibration() {
void ConfigCCAttitudeWidget::openHelp()
{
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/CopterControl+Attitude+Configuration", QUrl::StrictMode) );
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/44Cf", QUrl::StrictMode) );
}
void ConfigCCAttitudeWidget::enableControls(bool enable)

View File

@ -41,6 +41,9 @@
#include <utils/stylehelper.h>
#include <QMessageBox>
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/generalsettings.h>
#define ACCESS_MIN_MOVE -3
#define ACCESS_MAX_MOVE 3
#define STICK_MIN_MOVE -8
@ -50,10 +53,18 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
manualCommandObj = ManualControlCommand::GetInstance(getObjectManager());
manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager());
flightStatusObj = FlightStatus::GetInstance(getObjectManager());
receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager());
m_config = new Ui_InputWidget();
m_config->setupUi(this);
addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD);
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
m_config->saveRCInputToRAM->setVisible(false);
addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD);
//Generate the rows of buttons in the input channel form GUI
@ -75,6 +86,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent)
addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", m_config->deadband, 0, 0.01f);
connect(m_config->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard()));
connect(m_config->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int)));
connect(m_config->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool)));
connect(m_config->wzNext,SIGNAL(clicked()),this,SLOT(wzNext()));
@ -278,7 +290,7 @@ void ConfigInputWidget::resizeEvent(QResizeEvent *event)
void ConfigInputWidget::openHelp()
{
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Input+Configuration", QUrl::StrictMode) );
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/04Cf", QUrl::StrictMode) );
}
void ConfigInputWidget::goToWizard()
{
@ -292,6 +304,14 @@ void ConfigInputWidget::goToWizard()
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio );
}
void ConfigInputWidget::disableWizardButton(int value)
{
if(value!=0)
m_config->configurationWizard->setVisible(false);
else
m_config->configurationWizard->setVisible(true);
}
void ConfigInputWidget::wzCancel()
{
dimOtherControls(false);
@ -393,6 +413,12 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
{
switch(step) {
case wizardWelcome:
foreach(QPointer<QWidget> wd,extraWidgets)
{
if(!wd.isNull())
delete wd;
}
extraWidgets.clear();
m_config->graphicsView->setVisible(false);
setTxMovement(nothing);
manualSettingsData=manualSettingsObj->getData();
@ -458,6 +484,9 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
break;
case wizardIdentifyLimits:
{
accessoryDesiredObj0 = AccessoryDesired::GetInstance(getObjectManager(),0);
accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(),1);
accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(),2);
setTxMovement(nothing);
m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions and press next when ready")));
fastMdata();
@ -476,6 +505,8 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
}
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
}
break;
case wizardIdentifyInverted:
@ -503,8 +534,10 @@ void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
fastMdata();
break;
case wizardFinish:
dimOtherControls(true);
dimOtherControls(false);
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture below mimics your sticks movement.\n"
"This new settings aren't saved to the board yet, after pressing next you will go to the initial screen where you can do that.")));
fastMdata();
@ -572,6 +605,8 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
case wizardIdentifyLimits:
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
disconnect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
manualSettingsObj->setData(manualSettingsData);
restoreMdata();
setTxMovement(nothing);
@ -595,6 +630,8 @@ void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
dimOtherControls(false);
setTxMovement(nothing);
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
disconnect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
restoreMdata();
break;
default:
@ -1060,6 +1097,11 @@ void ConfigInputWidget::moveSticks()
{
QTransform trans;
manualCommandData=manualCommandObj->getData();
flightStatusData=flightStatusObj->getData();
accessoryDesiredData0=accessoryDesiredObj0->getData();
accessoryDesiredData1=accessoryDesiredObj1->getData();
accessoryDesiredData2=accessoryDesiredObj2->getData();
if(transmitterMode==mode2)
{
trans=m_txLeftStickOrig;
@ -1074,6 +1116,24 @@ void ConfigInputWidget::moveSticks()
trans=m_txLeftStickOrig;
m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false);
}
if(flightStatusData.FlightMode==manualSettingsData.FlightModePosition[0])
{
m_txFlightMode->setElementId("flightModeLeft");
m_txFlightMode->setTransform(m_txFlightModeLOrig,false);
}
else if (flightStatusData.FlightMode==manualSettingsData.FlightModePosition[1])
{
m_txFlightMode->setElementId("flightModeCenter");
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
}
else if (flightStatusData.FlightMode==manualSettingsData.FlightModePosition[2])
{
m_txFlightMode->setElementId("flightModeRight");
m_txFlightMode->setTransform(m_txFlightModeROrig,false);
}
m_txAccess0->setTransform(QTransform(m_txAccess0Orig).translate(accessoryDesiredData0.AccessoryVal*ACCESS_MAX_MOVE*10,0),false);
m_txAccess1->setTransform(QTransform(m_txAccess1Orig).translate(accessoryDesiredData1.AccessoryVal*ACCESS_MAX_MOVE*10,0),false);
m_txAccess2->setTransform(QTransform(m_txAccess2Orig).translate(accessoryDesiredData2.AccessoryVal*ACCESS_MAX_MOVE*10,0),false);
}
void ConfigInputWidget::dimOtherControls(bool value)

View File

@ -43,6 +43,9 @@
#include <QGraphicsView>
#include <QtSvg/QSvgRenderer>
#include <QtSvg/QGraphicsSvgItem>
#include "flightstatus.h"
#include "accessorydesired.h"
#include <QPointer>
class Ui_InputWidget;
@ -67,7 +70,7 @@ private:
void setTxMovement(txMovements movement);
Ui_InputWidget *m_config;
wizardSteps wizardStep;
QList<QWidget*> extraWidgets;
QList<QPointer<QWidget> > extraWidgets;
txMode transmitterMode;
txType transmitterType;
struct channelsStruct
@ -91,6 +94,14 @@ private:
ManualControlCommand * manualCommandObj;
ManualControlCommand::DataFields manualCommandData;
FlightStatus * flightStatusObj;
FlightStatus::DataFields flightStatusData;
AccessoryDesired * accessoryDesiredObj0;
AccessoryDesired * accessoryDesiredObj1;
AccessoryDesired * accessoryDesiredObj2;
AccessoryDesired::DataFields accessoryDesiredData0;
AccessoryDesired::DataFields accessoryDesiredData1;
AccessoryDesired::DataFields accessoryDesiredData2;
UAVObject::Metadata manualControlMdata;
ManualControlSettings * manualSettingsObj;
ManualControlSettings::DataFields manualSettingsData;
@ -138,7 +149,7 @@ private slots:
void wzBack();
void wzCancel();
void goToWizard();
void disableWizardButton(int);
void openHelp();
void identifyControls();
void identifyLimits();

View File

@ -46,13 +46,21 @@
#include "systemalarms.h"
#include "systemsettings.h"
#include "uavsettingsimportexport/uavsettingsimportexportfactory.h"
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/generalsettings.h>
ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent),wasItMe(false)
{
m_config = new Ui_OutputWidget();
m_config->setupUi(this);
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
m_config->saveRCOutputToRAM->setVisible(false);
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVSettingsImportExportFactory * importexportplugin = pm->getObject<UAVSettingsImportExportFactory>();
connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(stopTests()));
@ -231,8 +239,6 @@ void ConfigOutputWidget::refreshWidgetsValues(UAVObject * obj)
{
Q_UNUSED(obj);
bool dirty=isDirty();
// Get Actuator Settings
ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager());
Q_ASSERT(actuatorSettings);
@ -365,7 +371,7 @@ void ConfigOutputWidget::updateObjectsFromWidgets()
void ConfigOutputWidget::openHelp()
{
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Output+Configuration", QUrl::StrictMode) );
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/WIGf", QUrl::StrictMode) );
}
void ConfigOutputWidget::stopTests()

View File

@ -52,7 +52,7 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
} else {
qDebug() << "Error: Object is unknown (PipXSettings).";
}
autoLoadWidgets();
addApplySaveButtons(m_pipx->Apply, m_pipx->Save);
addUAVObjectToWidgetRelation("PipXSettings", "TelemetryConfig", m_pipx->TelemPortConfig);

View File

@ -36,19 +36,27 @@
#include <QUrl>
#include <QList>
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/generalsettings.h>
ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_stabilization = new Ui_StabilizationWidget();
m_stabilization->setupUi(this);
// To bring old style sheet back without adding it manually do this:
// Alternatively apply a global stylesheet to the QGroupBox
// setStyleSheet("QGroupBox {background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0 rgba(243, 243, 243, 255), stop:1 rgba(250, 250, 250, 255)); border: 1px outset #999; border-radius: 3; }");
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
m_stabilization->saveStabilizationToRAM_6->setVisible(false);
autoLoadWidgets();
realtimeUpdates=new QTimer(this);
connect(m_stabilization->realTimeUpdates_6,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int)));
connect(m_stabilization->realTimeUpdates_7,SIGNAL(stateChanged(int)),this,SLOT(realtimeUpdatesSlot(int)));
connect(realtimeUpdates,SIGNAL(timeout()),this,SLOT(apply()));
connect(m_stabilization->checkBox_7,SIGNAL(stateChanged(int)),this,SLOT(linkCheckBoxes(int)));
@ -60,23 +68,7 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
disableMouseWheelEvents();
// This is needed because new style tries to compact things as much as possible in grid
// and on OSX the widget sizes of PushButtons is reported incorrectly:
// https://bugreports.qt-project.org/browse/QTBUG-14591
m_stabilization->saveStabilizationToRAM_6->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->saveStabilizationToSD_6->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->stabilizationReloadBoardData_6->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->saveStabilizationToRAM_7->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->saveStabilizationToSD_7->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_2->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_3->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_4->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_19->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_20->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_21->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_22->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_23->setAttribute(Qt::WA_LayoutUsesWidgetRect);
m_stabilization->pushButton_24->setAttribute(Qt::WA_LayoutUsesWidgetRect);
}
@ -88,7 +80,6 @@ ConfigStabilizationWidget::~ConfigStabilizationWidget()
void ConfigStabilizationWidget::realtimeUpdatesSlot(int value)
{
m_stabilization->realTimeUpdates_6->setCheckState((Qt::CheckState)value);
m_stabilization->realTimeUpdates_7->setCheckState((Qt::CheckState)value);
if(value==Qt::Checked && !realtimeUpdates->isActive())
realtimeUpdates->start(300);
else if(value==Qt::Unchecked)
@ -135,6 +126,14 @@ void ConfigStabilizationWidget::processLinkedWidgets(QWidget * widget)
{
m_stabilization->RateRollILimit_2->setValue(m_stabilization->RatePitchILimit->value());
}
else if(widget== m_stabilization->RollRateKd)
{
m_stabilization->PitchRateKd->setValue(m_stabilization->RollRateKd->value());
}
else if(widget== m_stabilization->PitchRateKd)
{
m_stabilization->RollRateKd->setValue(m_stabilization->PitchRateKd->value());
}
}
if(m_stabilization->checkBox_8->checkState()==Qt::Checked)
{

View File

@ -28,12 +28,19 @@
#include "configtxpidwidget.h"
#include "txpidsettings.h"
#include "hwsettings.h"
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/generalsettings.h>
ConfigTxPIDWidget::ConfigTxPIDWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_txpid = new Ui_TxPIDWidget();
m_txpid->setupUi(this);
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
m_txpid->Apply->setVisible(false);
autoLoadWidgets();
addApplySaveButtons(m_txpid->Apply, m_txpid->Save);
// Cannot use addUAVObjectToWidgetRelation() for OptionaModules enum because

View File

@ -41,6 +41,9 @@
#include "systemsettings.h"
#include "mixersettings.h"
#include "actuatorsettings.h"
#include <extensionsystem/pluginmanager.h>
#include <coreplugin/generalsettings.h>
/**
Helper delegate for the custom mixer editor table.
@ -97,6 +100,11 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
{
m_aircraft = new Ui_AircraftWidget();
m_aircraft->setupUi(this);
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
if(!settings->useExpertMode())
m_aircraft->saveAircraftToRAM->setVisible(false);
addApplySaveButtons(m_aircraft->saveAircraftToRAM,m_aircraft->saveAircraftToSD);
@ -109,7 +117,7 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
//Generate lists of mixerTypeNames, mixerVectorNames, channelNames
channelNames << "None";
for (int i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) {
for (int i = 0; i < (int)ActuatorSettings::CHANNELADDR_NUMELEM; i++) {
mixerTypes << QString("Mixer%1Type").arg(i+1);
mixerVectors << QString("Mixer%1Vector").arg(i+1);
@ -164,14 +172,14 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("Mixer1Type"));
QStringList list = field->getOptions();
for (int i=0;i<8;i++) {
for (int i=0; i<(int)(VehicleConfig::CHANNEL_NUMELEM); i++) {
QComboBox* qb = new QComboBox(m_aircraft->customMixerTable);
qb->addItems(list);
m_aircraft->customMixerTable->setCellWidget(0,i,qb);
}
SpinBoxDelegate *sbd = new SpinBoxDelegate();
for (int i=1;i<8; i++) {
for (int i=1; i<(int)(VehicleConfig::CHANNEL_NUMELEM); i++) {
m_aircraft->customMixerTable->setItemDelegateForRow(i, sbd);
}
@ -193,9 +201,6 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
m_heli = m_aircraft->widget_3;
m_heli->setupUI(QString("HeliCP"));
// initialize the ui to show the mixersettings tab
//mdl m_aircraft->tabWidget->setCurrentIndex(0);
//Connect aircraft type selection dropbox to callback function
connect(m_aircraft->aircraftType, SIGNAL(currentIndexChanged(int)), this, SLOT(switchAirframeType(int)));
@ -205,25 +210,6 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
connect(m_aircraft->groundVehicleType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString)));
//mdl connect(m_heli->m_ccpm->ccpmType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString)));
//Connect throttle curve reset pushbuttons to reset functions
connect(m_aircraft->fwThrottleReset, SIGNAL(clicked()), this, SLOT(resetFwMixer()));
connect(m_aircraft->mrThrottleCurveReset, SIGNAL(clicked()), this, SLOT(resetMrMixer()));
connect(m_aircraft->gvThrottleCurve1Reset, SIGNAL(clicked()), this, SLOT(resetGvFrontMixer()));
connect(m_aircraft->gvThrottleCurve2Reset, SIGNAL(clicked()), this, SLOT(resetGvRearMixer()));
connect(m_aircraft->customReset1, SIGNAL(clicked()), this, SLOT(resetCt1Mixer()));
connect(m_aircraft->customReset2, SIGNAL(clicked()), this, SLOT(resetCt2Mixer()));
//Connect throttle curve manipulation points to output text
connect(m_aircraft->fixedWingThrottle, SIGNAL(curveUpdated(QList<double>,double)), this, SLOT(updateFwThrottleCurveValue(QList<double>,double)));
connect(m_aircraft->multiThrottleCurve, SIGNAL(curveUpdated(QList<double>,double)), this, SLOT(updateMrThrottleCurveValue(QList<double>,double)));
connect(m_aircraft->groundVehicleThrottle1, SIGNAL(curveUpdated(QList<double>,double)), this, SLOT(updateGvThrottle1CurveValue(QList<double>,double)));
connect(m_aircraft->groundVehicleThrottle2, SIGNAL(curveUpdated(QList<double>,double)), this, SLOT(updateGvThrottle2CurveValue(QList<double>,double)));
connect(m_aircraft->customThrottle1Curve, SIGNAL(curveUpdated(QList<double>,double)), this, SLOT(updateCustomThrottle1CurveValue(QList<double>,double)));
connect(m_aircraft->customThrottle2Curve, SIGNAL(curveUpdated(QList<double>,double)), this, SLOT(updateCustomThrottle2CurveValue(QList<double>,double)));
// connect(m_aircraft->fwAileron1Channel, SIGNAL(currentIndexChanged(int)), this, SLOT(toggleAileron2(int)));
// connect(m_aircraft->fwElevator1Channel, SIGNAL(currentIndexChanged(int)), this, SLOT(toggleElevator2(int)));
//Connect the three feed forward test checkboxes
connect(m_aircraft->ffTestBox1, SIGNAL(clicked(bool)), this, SLOT(enableFFTest()));
connect(m_aircraft->ffTestBox2, SIGNAL(clicked(bool)), this, SLOT(enableFFTest()));
@ -273,16 +259,14 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions()
case SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON:
case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL:
{
QPointer<ConfigFixedWingWidget> fixedwing = new ConfigFixedWingWidget();
channelDesc = fixedwing->getChannelDescriptions();
channelDesc = ConfigFixedWingWidget::getChannelDescriptions();
}
break;
// helicp
case SystemSettings::AIRFRAMETYPE_HELICP:
{
QPointer<ConfigCcpmWidget> heli = new ConfigCcpmWidget();
channelDesc = heli->getChannelDescriptions();
channelDesc = ConfigCcpmWidget::getChannelDescriptions();
}
break;
@ -299,8 +283,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions()
case SystemSettings::AIRFRAMETYPE_HEXACOAX:
case SystemSettings::AIRFRAMETYPE_HEXA:
{
QPointer<ConfigMultiRotorWidget> multi = new ConfigMultiRotorWidget();
channelDesc = multi->getChannelDescriptions();
channelDesc = ConfigMultiRotorWidget::getChannelDescriptions();
}
break;
@ -309,8 +292,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions()
case SystemSettings::AIRFRAMETYPE_GROUNDVEHICLEDIFFERENTIAL:
case SystemSettings::AIRFRAMETYPE_GROUNDVEHICLEMOTORCYCLE:
{
QPointer<ConfigGroundVehicleWidget> ground = new ConfigGroundVehicleWidget();
channelDesc = ground->getChannelDescriptions();
channelDesc = ConfigGroundVehicleWidget::getChannelDescriptions();
}
break;
@ -341,9 +323,9 @@ void ConfigVehicleTypeWidget::switchAirframeType(int index)
m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio);
if (m_aircraft->aircraftType->findText("Custom")) {
m_aircraft->customMixerTable->resizeColumnsToContents();
for (int i=0;i<8;i++) {
for (int i=0;i<(int)(VehicleConfig::CHANNEL_NUMELEM);i++) {
m_aircraft->customMixerTable->setColumnWidth(i,(m_aircraft->customMixerTable->width()-
m_aircraft->customMixerTable->verticalHeader()->width())/8);
m_aircraft->customMixerTable->verticalHeader()->width())/10);
}
}
}
@ -360,9 +342,9 @@ void ConfigVehicleTypeWidget::showEvent(QShowEvent *event)
// the result is usually a ahrsbargraph that is way too small.
m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio);
m_aircraft->customMixerTable->resizeColumnsToContents();
for (int i=0;i<8;i++) {
for (int i=0;i<(int)(VehicleConfig::CHANNEL_NUMELEM);i++) {
m_aircraft->customMixerTable->setColumnWidth(i,(m_aircraft->customMixerTable->width()-
m_aircraft->customMixerTable->verticalHeader()->width())/8);
m_aircraft->customMixerTable->verticalHeader()->width())/ 10);
}
}
@ -375,9 +357,9 @@ void ConfigVehicleTypeWidget::resizeEvent(QResizeEvent* event)
m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio);
// Make the custom table columns autostretch:
m_aircraft->customMixerTable->resizeColumnsToContents();
for (int i=0;i<8;i++) {
for (int i=0;i<(int)(VehicleConfig::CHANNEL_NUMELEM);i++) {
m_aircraft->customMixerTable->setColumnWidth(i,(m_aircraft->customMixerTable->width()-
m_aircraft->customMixerTable->verticalHeader()->width())/8);
m_aircraft->customMixerTable->verticalHeader()->width())/ 10);
}
}
@ -478,132 +460,6 @@ void ConfigVehicleTypeWidget::enableFFTest()
}
}
/**
Resets Fixed wing throttle mixer
*/
void ConfigVehicleTypeWidget::resetFwMixer()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("ThrottleCurve1"));
resetMixer(m_aircraft->fixedWingThrottle, field->getNumElements(),1);
}
/**
Resets Multirotor throttle mixer
*/
void ConfigVehicleTypeWidget::resetMrMixer()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("ThrottleCurve1"));
resetMixer(m_aircraft->multiThrottleCurve, field->getNumElements(),0.9);
}
/**
Resets Ground vehicle front throttle mixer
*/
void ConfigVehicleTypeWidget::resetGvFrontMixer()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("ThrottleCurve1"));
resetMixer(m_aircraft->groundVehicleThrottle1, field->getNumElements(),1);
}
/**
Resets Ground vehicle rear throttle mixer
*/
void ConfigVehicleTypeWidget::resetGvRearMixer()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("ThrottleCurve2"));
resetMixer(m_aircraft->groundVehicleThrottle2, field->getNumElements(),1);
}
/**
Resets Custom throttle 1 mixer
*/
void ConfigVehicleTypeWidget::resetCt1Mixer()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("ThrottleCurve1"));
resetMixer(m_aircraft->customThrottle1Curve, field->getNumElements(),1);
}
/**
Resets Custom throttle 2 mixer
*/
void ConfigVehicleTypeWidget::resetCt2Mixer()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
UAVObjectField* field = obj->getField(QString("ThrottleCurve2"));
resetMixer(m_aircraft->customThrottle2Curve, field->getNumElements(),1);
}
/**
Resets a mixer curve
*/
void ConfigVehicleTypeWidget::resetMixer(MixerCurveWidget *mixer, int numElements, double maxvalue)
{
// Setup all Throttle1 curves for all types of airframes
mixer->initLinearCurve((quint32)numElements,maxvalue);
}
/**
Updates the currently moved fixed wing throttle curve item value
*/
void ConfigVehicleTypeWidget::updateFwThrottleCurveValue(QList<double> list, double value)
{
Q_UNUSED(list);
m_aircraft->fwThrottleCurveItemValue->setText(QString().sprintf("Val: %.2f",value));
}
/**
Updates the currently moved multi-rotor throttle curve item value
*/
void ConfigVehicleTypeWidget::updateMrThrottleCurveValue(QList<double> list, double value)
{
Q_UNUSED(list);
m_aircraft->mrThrottleCurveItemValue->setText(QString().sprintf("Val: %.2f",value));
}
/**
Updates the moved ground vehicle front throttle curve item value
*/
void ConfigVehicleTypeWidget::updateGvThrottle1CurveValue(QList<double> list, double value)
{
Q_UNUSED(list);
m_aircraft->gvThrottleCurve1ItemValue->setText(QString().sprintf("Val: %.2f",value));
}
/**
Updates the moved ground vehicle rear throttle curve item value
*/
void ConfigVehicleTypeWidget::updateGvThrottle2CurveValue(QList<double> list, double value)
{
Q_UNUSED(list);
m_aircraft->gvThrottleCurve2ItemValue->setText(QString().sprintf("Val: %.2f",value));
}
/**
Updates the currently moved custom throttle curve item value (Custom throttle 1)
*/
void ConfigVehicleTypeWidget::updateCustomThrottle1CurveValue(QList<double> list, double value)
{
Q_UNUSED(list);
m_aircraft->customThrottleCurve1Value->setText(QString().sprintf("Val: %.2f",value));
}
/**
Updates the currently moved custom throttle curve item value (Custom throttle 2)
*/
void ConfigVehicleTypeWidget::updateCustomThrottle2CurveValue(QList<double> list, double value)
{
Q_UNUSED(list);
m_aircraft->customThrottleCurve2Value->setText(QString().sprintf("Val: %.2f",value));
}
/**************************
* Aircraft settings
**************************/
@ -763,30 +619,34 @@ void ConfigVehicleTypeWidget::updateCustomAirframeUI()
// is at least one of the curve values != 0?
if (vconfig->isValidThrottleCurve(&curveValues)) {
// yes, use the curve we just read from mixersettings
m_aircraft->customThrottle1Curve->setMin(vconfig->getCurveMin(&curveValues));
m_aircraft->customThrottle1Curve->setMax(vconfig->getCurveMax(&curveValues));
m_aircraft->customThrottle1Curve->initCurve(&curveValues);
}
else {
// no, init a straight curve
m_aircraft->customThrottle1Curve->initLinearCurve(curveValues.count(),(double)1);
m_aircraft->customThrottle1Curve->initLinearCurve(curveValues.count(), 1.0);
}
// Setup all Throttle2 curves for all types of airframes //AT THIS MOMENT, THAT MEANS ONLY GROUND VEHICLES
if (MixerSettings* mxr = qobject_cast<MixerSettings *>(mixer)) {
MixerSettings::DataFields mixerSettingsData = mxr->getData();
if (mixerSettingsData.Curve2Source == MixerSettings::CURVE2SOURCE_THROTTLE)
m_aircraft->customThrottle2Curve->setMixerType(MixerCurve::MIXERCURVE_THROTTLE);
else {
m_aircraft->customThrottle2Curve->setMixerType(MixerCurve::MIXERCURVE_PITCH);
}
}
// Setup all Throttle2 curves for all types of airframes
vconfig->getThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, &curveValues);
if (vconfig->isValidThrottleCurve(&curveValues)) {
m_aircraft->customThrottle2Curve->setMin(vconfig->getCurveMin(&curveValues));
m_aircraft->customThrottle2Curve->setMax(vconfig->getCurveMax(&curveValues));
m_aircraft->customThrottle2Curve->initCurve(&curveValues);
}
else {
m_aircraft->customThrottle2Curve->initLinearCurve(curveValues.count(),(double)1);
m_aircraft->customThrottle2Curve->initLinearCurve(curveValues.count(), 1.0, m_aircraft->customThrottle2Curve->getMin());
}
// Update the mixer table:
for (int channel=0; channel<8; channel++) {
for (int channel=0; channel<(int)(VehicleConfig::CHANNEL_NUMELEM); channel++) {
UAVObjectField* field = mixer->getField(mixerTypes.at(channel));
if (field)
{
@ -856,7 +716,7 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
vconfig->setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE2, m_aircraft->customThrottle2Curve->getCurve());
// Update the table:
for (int channel=0; channel<8; channel++) {
for (int channel=0; channel<(int)(VehicleConfig::CHANNEL_NUMELEM); channel++) {
QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,channel);
vconfig->setMixerType(mixer,channel,
@ -892,7 +752,7 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
void ConfigVehicleTypeWidget::openHelp()
{
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Airframe+configuration", QUrl::StrictMode) );
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/44Cf", QUrl::StrictMode) );
}
/**
@ -912,13 +772,13 @@ void ConfigVehicleTypeWidget::setComboCurrentIndex(QComboBox* box, int index)
void ConfigVehicleTypeWidget::addToDirtyMonitor()
{
addWidget(m_aircraft->customMixerTable);
addWidget(m_aircraft->customThrottle1Curve);
addWidget(m_aircraft->customThrottle2Curve);
addWidget(m_aircraft->multiThrottleCurve);
addWidget(m_aircraft->fixedWingThrottle);
addWidget(m_aircraft->customThrottle1Curve->getCurveWidget());
addWidget(m_aircraft->customThrottle2Curve->getCurveWidget());
addWidget(m_aircraft->multiThrottleCurve->getCurveWidget());
addWidget(m_aircraft->fixedWingThrottle->getCurveWidget());
addWidget(m_aircraft->fixedWingType);
addWidget(m_aircraft->groundVehicleThrottle1);
addWidget(m_aircraft->groundVehicleThrottle2);
addWidget(m_aircraft->groundVehicleThrottle1->getCurveWidget());
addWidget(m_aircraft->groundVehicleThrottle2->getCurveWidget());
addWidget(m_aircraft->groundVehicleType);
addWidget(m_aircraft->feedForwardSlider);
addWidget(m_aircraft->accelTime);
@ -976,15 +836,8 @@ void ConfigVehicleTypeWidget::addToDirtyMonitor()
addWidget(m_heli->m_ccpm->ccpmRollScaleBox);
addWidget(m_heli->m_ccpm->SwashLvlPositionSlider);
addWidget(m_heli->m_ccpm->SwashLvlPositionSpinBox);
addWidget(m_heli->m_ccpm->CurveType);
addWidget(m_heli->m_ccpm->NumCurvePoints);
addWidget(m_heli->m_ccpm->CurveValue1);
addWidget(m_heli->m_ccpm->CurveValue2);
addWidget(m_heli->m_ccpm->CurveValue3);
addWidget(m_heli->m_ccpm->CurveToGenerate);
addWidget(m_heli->m_ccpm->CurveSettings);
addWidget(m_heli->m_ccpm->ThrottleCurve);
addWidget(m_heli->m_ccpm->PitchCurve);
addWidget(m_heli->m_ccpm->ThrottleCurve->getCurveWidget());
addWidget(m_heli->m_ccpm->PitchCurve->getCurveWidget());
addWidget(m_heli->m_ccpm->ccpmAdvancedSettingsTable);
}

View File

@ -67,7 +67,6 @@ private:
void updateCustomAirframeUI();
void addToDirtyMonitor();
void resetField(UAVObjectField * field);
void resetMixer (MixerCurveWidget *mixer, int numElements, double maxvalue);
//void setMixerChannel(int channelNumber, bool channelIsMotor, QList<double> vector);
@ -93,18 +92,7 @@ private slots:
void toggleElevator2(int index);
void toggleRudder2(int index);
void switchAirframeType(int index);
void resetFwMixer();
void resetMrMixer();
void resetGvFrontMixer();
void resetGvRearMixer();
void resetCt1Mixer();
void resetCt2Mixer();
void updateFwThrottleCurveValue(QList<double> list, double value);
void updateMrThrottleCurveValue(QList<double> list, double value);
void updateGvThrottle1CurveValue(QList<double> list, double value);
void updateGvThrottle2CurveValue(QList<double> list, double value);
void updateCustomThrottle1CurveValue(QList<double> list, double value);
void updateCustomThrottle2CurveValue(QList<double> list, double value);
void enableFFTest();
void openHelp();

View File

@ -0,0 +1,86 @@
/**
******************************************************************************
*
* @file doublespindelegate.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief A double spinbox delegate
*****************************************************************************/
/*
* 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 "dblspindelegate.h"
/**
Helper delegate for the custom mixer editor table.
*/
DoubleSpinDelegate::DoubleSpinDelegate(QObject *parent)
: QItemDelegate(parent)
{
m_min = 0.0;
m_max = 1.0;
m_decimals = 2;
m_step = 0.01;
}
QWidget *DoubleSpinDelegate::createEditor(QWidget *parent,
const QStyleOptionViewItem &/* option */,
const QModelIndex &/* index */) const
{
QDoubleSpinBox *editor = new QDoubleSpinBox(parent);
editor->setMinimum(m_min);
editor->setMaximum(m_max);
editor->setDecimals(m_decimals);
editor->setSingleStep(m_step);
connect(editor,SIGNAL(valueChanged(double)), this, SLOT(valueChanged()));
return editor;
}
void DoubleSpinDelegate::setEditorData(QWidget *editor,
const QModelIndex &index) const
{
double value = index.model()->data(index, Qt::EditRole).toDouble();
QDoubleSpinBox *spinBox = static_cast<QDoubleSpinBox*>(editor);
spinBox->setValue(value);
}
void DoubleSpinDelegate::setModelData(QWidget *editor, QAbstractItemModel *model,
const QModelIndex &index) const
{
QDoubleSpinBox *spinBox = static_cast<QDoubleSpinBox*>(editor);
spinBox->interpretText();
double value = spinBox->value();
model->setData(index, value, Qt::EditRole);
}
void DoubleSpinDelegate::updateEditorGeometry(QWidget *editor,
const QStyleOptionViewItem &option, const QModelIndex &/* index */) const
{
editor->setGeometry(option.rect);
}
void DoubleSpinDelegate::valueChanged()
{
emit ValueChanged();
}

View File

@ -0,0 +1,73 @@
/**
******************************************************************************
*
* @file doublespindelegate.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief A double spinbox delegate
*****************************************************************************/
/*
* 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
*/
#ifndef DOUBLESPINDELEGATE_H
#define DOUBLESPINDELEGATE_H
#include <QDoubleSpinBox>
#include <QItemDelegate>
namespace Ui {
class DoubleSpinDelegate;
}
class DoubleSpinDelegate : public QItemDelegate
{
Q_OBJECT
public:
DoubleSpinDelegate(QObject *parent = 0);
QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &option,
const QModelIndex &index) const;
void setEditorData(QWidget *editor, const QModelIndex &index) const;
void setModelData(QWidget *editor, QAbstractItemModel *model,
const QModelIndex &index) const;
void updateEditorGeometry(QWidget *editor,
const QStyleOptionViewItem &option, const QModelIndex &index) const;
void setMin(double min) { m_min = min; }
void setMax(double max) { m_max = max; }
void setRange(double min, double max) { m_min = min; m_max = max; }
void setStep(double step) { m_step = step; }
void setDecimals(int decimals) { m_decimals = decimals; }
private:
double m_min;
double m_max;
double m_step;
int m_decimals;
signals:
void ValueChanged();
private slots:
void valueChanged();
};
#endif // DOUBLESPINDELEGATE_H

View File

@ -6,14 +6,14 @@
<rect>
<x>0</x>
<y>0</y>
<width>626</width>
<height>532</height>
<width>702</width>
<height>920</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QTabWidget" name="tabWidget">
<property name="currentIndex">
@ -23,177 +23,629 @@
<attribute name="title">
<string>RC Input</string>
</attribute>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QStackedWidget" name="stackedWidget">
<property name="currentIndex">
<number>0</number>
<layout class="QVBoxLayout" name="verticalLayout_11">
<property name="spacing">
<number>12</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="palette">
<palette>
<active>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<widget class="QWidget" name="advancedPage">
<layout class="QVBoxLayout" name="verticalLayout_4">
<item>
<layout class="QVBoxLayout" name="channelSettings"/>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>5</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QGridLayout" name="gridLayout_3">
<item row="0" column="0">
<widget class="QLabel" name="labelDeadband">
<property name="text">
<string>Roll/Pitch/Yaw stick deadband</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QDoubleSpinBox" name="deadband">
<property name="toolTip">
<string>Stick deadband in percents of full range (0-10), zero to disable</string>
</property>
<property name="decimals">
<number>1</number>
</property>
<property name="maximum">
<double>10.000000000000000</double>
</property>
<property name="singleStep">
<double>0.100000000000000</double>
</property>
</widget>
</item>
<item row="0" column="3">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_4">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>5</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="configurationWizard">
<property name="text">
<string>Start Configuration Wizard</string>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>672</width>
<height>783</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="1" column="0">
<widget class="QGroupBox" name="groupBox_5">
<property name="title">
<string/>
</property>
<layout class="QVBoxLayout" name="verticalLayout_6">
<item>
<widget class="QStackedWidget" name="stackedWidget">
<property name="currentIndex">
<number>0</number>
</property>
<widget class="QWidget" name="advancedPage">
<layout class="QVBoxLayout" name="verticalLayout_4">
<item>
<widget class="QPushButton" name="configurationWizard">
<property name="text">
<string>Start Configuration Wizard</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="runCalibration">
<property name="text">
<string>Run Calibration</string>
</property>
</widget>
</item>
<item>
<layout class="QGridLayout" name="gridLayout_8">
<property name="horizontalSpacing">
<number>0</number>
</property>
<item row="1" column="6">
<widget class="QLabel" name="legend4">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Neutral</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="10">
<widget class="QLabel" name="legend5_3">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>42</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Rev.</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="legend2">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Number</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QLabel" name="legend3">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>45</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="legend1">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>100</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Type</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="5">
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="7">
<widget class="QLabel" name="legend5">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>45</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLabel" name="legend0">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>80</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Function</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="9">
<widget class="QLabel" name="legend5_2">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>48</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Neut.</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="0">
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>2</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="channelSettings"/>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QGridLayout" name="gridLayout_3">
<item row="0" column="4">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="1">
<widget class="QLabel" name="labelDeadband">
<property name="text">
<string>Roll/Pitch/Yaw stick deadband</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QDoubleSpinBox" name="deadband">
<property name="toolTip">
<string>Stick deadband in percents of full range (0-10), zero to disable</string>
</property>
<property name="decimals">
<number>1</number>
</property>
<property name="maximum">
<double>10.000000000000000</double>
</property>
<property name="singleStep">
<double>0.100000000000000</double>
</property>
</widget>
</item>
<item row="0" column="0">
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>12</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
<widget class="QWidget" name="wizard">
<layout class="QVBoxLayout" name="verticalLayout_5">
<item>
<widget class="QLabel" name="wzText">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>90</height>
</size>
</property>
<property name="text">
<string>TextLabel</string>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_4">
<item>
<widget class="QGraphicsView" name="graphicsView"/>
</item>
<item>
<layout class="QVBoxLayout" name="checkBoxesLayout"/>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QPushButton" name="wzBack">
<property name="text">
<string>Back</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="wzNext">
<property name="text">
<string>Next</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="wzCancel">
<property name="text">
<string>Cancel</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QCheckBox" name="runCalibration">
<property name="text">
<string>Run Calibration</string>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
<widget class="QWidget" name="wizard">
<layout class="QVBoxLayout" name="verticalLayout_5">
<item>
<widget class="QLabel" name="wzText">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>90</height>
</size>
</property>
<property name="text">
<string>TextLabel</string>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_4">
<item>
<widget class="QGraphicsView" name="graphicsView"/>
</item>
<item>
<layout class="QVBoxLayout" name="checkBoxesLayout"/>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QPushButton" name="wzBack">
<property name="text">
<string>Back</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="wzNext">
<property name="text">
<string>Next</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="wzCancel">
<property name="text">
<string>Cancel</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</widget>
@ -204,442 +656,270 @@
<attribute name="title">
<string>Flight Mode Switch Settings</string>
</attribute>
<widget class="QGroupBox" name="groupBox">
<property name="geometry">
<rect>
<x>30</x>
<y>260</y>
<width>541</width>
<height>161</height>
</rect>
<layout class="QVBoxLayout" name="verticalLayout_8">
<property name="spacing">
<number>12</number>
</property>
<property name="styleSheet">
<string notr="true"/>
<property name="margin">
<number>0</number>
</property>
<property name="title">
<string>Configure each stabilization mode for each axis</string>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<item row="1" column="3">
<widget class="QLabel" name="label_10">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
<item>
<widget class="QScrollArea" name="scrollArea_3">
<property name="palette">
<palette>
<active>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_3">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>540</width>
<height>510</height>
</rect>
</property>
<property name="text">
<string>Yaw</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_14">
<property name="text">
<string>Stabilized1</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="fmsSsPos1Roll">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="fmsSsPos1Pitch">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QComboBox" name="fmsSsPos1Yaw">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_21">
<property name="text">
<string>Stabilized2</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="fmsSsPos2Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QComboBox" name="fmsSsPos2Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QComboBox" name="fmsSsPos2Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_22">
<property name="text">
<string>Stabilized3</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="fmsSsPos3Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QComboBox" name="fmsSsPos3Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="4" column="3">
<widget class="QComboBox" name="fmsSsPos3Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLabel" name="label_8">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="label_9">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
<widget class="QGroupBox" name="groupBox_2">
<property name="geometry">
<rect>
<x>30</x>
<y>20</y>
<width>541</width>
<height>211</height>
</rect>
</property>
<property name="title">
<string>FlightMode Switch Positions</string>
</property>
<widget class="QComboBox" name="fmsModePos5">
<property name="enabled">
<bool>false</bool>
</property>
<property name="geometry">
<rect>
<x>100</x>
<y>140</y>
<width>151</width>
<height>26</height>
</rect>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
<widget class="QComboBox" name="fmsModePos4">
<property name="enabled">
<bool>false</bool>
</property>
<property name="geometry">
<rect>
<x>100</x>
<y>110</y>
<width>151</width>
<height>26</height>
</rect>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select the stabilization mode on this position (manual/stabilized/auto)</string>
</property>
</widget>
<widget class="QLabel" name="label_pos4">
<property name="geometry">
<rect>
<x>10</x>
<y>115</y>
<width>62</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Pos. 4</string>
</property>
</widget>
<widget class="QComboBox" name="fmsModePos6">
<property name="enabled">
<bool>false</bool>
</property>
<property name="geometry">
<rect>
<x>100</x>
<y>170</y>
<width>151</width>
<height>26</height>
</rect>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
<widget class="QLabel" name="label_pos5">
<property name="geometry">
<rect>
<x>10</x>
<y>145</y>
<width>62</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Pos. 5</string>
</property>
</widget>
<widget class="QLabel" name="label_pos6">
<property name="geometry">
<rect>
<x>10</x>
<y>175</y>
<width>62</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Pos. 6</string>
</property>
</widget>
<widget class="QSlider" name="fmsSlider">
<property name="enabled">
<bool>false</bool>
</property>
<property name="geometry">
<rect>
<x>70</x>
<y>28</y>
<width>20</width>
<height>160</height>
</rect>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>This slider moves when you move the flight mode switch
<layout class="QGridLayout" name="gridLayout_7">
<item row="0" column="0">
<widget class="QGroupBox" name="groupBox_2">
<property name="title">
<string>FlightMode Switch Positions</string>
</property>
<layout class="QGridLayout" name="gridLayout_6">
<item row="0" column="0">
<layout class="QGridLayout" name="gridLayout_4">
<item row="0" column="0">
<layout class="QVBoxLayout" name="verticalLayout_9">
<item>
<widget class="QLabel" name="label_pos1">
<property name="text">
<string>Pos. 1</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_pos2">
<property name="text">
<string>Pos. 2</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_pos3">
<property name="text">
<string>Pos. 3</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_pos4">
<property name="text">
<string>Pos. 4</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_pos5">
<property name="text">
<string>Pos. 5</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_pos6">
<property name="text">
<string>Pos. 6</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="0" column="1">
<widget class="QSlider" name="fmsSlider">
<property name="enabled">
<bool>false</bool>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>This slider moves when you move the flight mode switch
on your remote. It shows currently active flight mode.
Setup the flight mode channel on the RC Input tab if you have not done so already.</string>
</property>
<property name="minimum">
<number>0</number>
</property>
<property name="maximum">
<number>5</number>
</property>
<property name="pageStep">
<number>10</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="sliderPosition">
<number>0</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="invertedAppearance">
<bool>true</bool>
</property>
<property name="tickPosition">
<enum>QSlider::TicksBelow</enum>
</property>
<property name="tickInterval">
<number>1</number>
</property>
</widget>
<widget class="QComboBox" name="fmsModePos2">
<property name="geometry">
<rect>
<x>100</x>
<y>50</y>
<width>151</width>
<height>26</height>
</rect>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
<widget class="QComboBox" name="fmsModePos3">
<property name="geometry">
<rect>
<x>100</x>
<y>80</y>
<width>151</width>
<height>26</height>
</rect>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
<widget class="QComboBox" name="fmsModePos1">
<property name="geometry">
<rect>
<x>100</x>
<y>20</y>
<width>151</width>
<height>26</height>
</rect>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select the stabilization mode on this position (manual/stabilized/auto)</string>
</property>
</widget>
<widget class="QLabel" name="label_pos2">
<property name="geometry">
<rect>
<x>11</x>
<y>55</y>
<width>62</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Pos. 2</string>
</property>
</widget>
<widget class="QLabel" name="label_pos1">
<property name="geometry">
<rect>
<x>11</x>
<y>25</y>
<width>62</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Pos. 1</string>
</property>
</widget>
<widget class="QLabel" name="label_pos3">
<property name="geometry">
<rect>
<x>11</x>
<y>85</y>
<width>62</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Pos. 3</string>
</property>
</widget>
<widget class="QSpinBox" name="fmsPosNum">
<property name="geometry">
<rect>
<x>458</x>
<y>20</y>
<width>61</width>
<height>20</height>
</rect>
</property>
<property name="toolTip">
<string>Number of positions your FlightMode switch has.
</property>
<property name="minimum">
<number>0</number>
</property>
<property name="maximum">
<number>5</number>
</property>
<property name="pageStep">
<number>10</number>
</property>
<property name="value">
<number>0</number>
</property>
<property name="sliderPosition">
<number>0</number>
</property>
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="invertedAppearance">
<bool>true</bool>
</property>
<property name="tickPosition">
<enum>QSlider::TicksBelow</enum>
</property>
<property name="tickInterval">
<number>1</number>
</property>
</widget>
</item>
<item row="0" column="2">
<layout class="QVBoxLayout" name="verticalLayout_10">
<item>
<widget class="QComboBox" name="fmsModePos1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select the stabilization mode on this position (manual/stabilized/auto)</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsModePos2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsModePos3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsModePos4">
<property name="enabled">
<bool>false</bool>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select the stabilization mode on this position (manual/stabilized/auto)</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsModePos5">
<property name="enabled">
<bool>false</bool>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsModePos6">
<property name="enabled">
<bool>false</bool>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
<item row="0" column="2">
<layout class="QGridLayout" name="gridLayout_5">
<item row="0" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_6">
<item>
<widget class="QLabel" name="label">
<property name="text">
<string>Number of flight modes:</string>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="fmsPosNum">
<property name="toolTip">
<string>Number of positions your FlightMode switch has.
Default is 3.
@ -647,239 +927,573 @@ It will be 2 or 3 for most of setups, but it also can be up to 6.
In that case you have to configure your radio mixers so the whole range
from min to max is split into N equal intervals, and you may set arbitrary
channel value for each flight mode.</string>
</property>
<property name="minimum">
<number>1</number>
</property>
<property name="maximum">
<number>6</number>
</property>
<property name="value">
<number>3</number>
</property>
</widget>
<widget class="QLabel" name="label">
<property name="geometry">
<rect>
<x>277</x>
<y>22</y>
<width>171</width>
<height>16</height>
</rect>
</property>
<property name="text">
<string>Number of flight modes:</string>
</property>
</widget>
<widget class="QLabel" name="label_15">
<property name="geometry">
<rect>
<x>310</x>
<y>120</y>
<width>191</width>
<height>30</height>
</rect>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Avoid &quot;Manual&quot; for multirotors!</string>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</widget>
<zorder>groupBox_2</zorder>
<zorder>groupBox</zorder>
</property>
<property name="minimum">
<number>1</number>
</property>
<property name="maximum">
<number>6</number>
</property>
<property name="value">
<number>3</number>
</property>
</widget>
</item>
</layout>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_15">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Avoid &quot;Manual&quot; for multirotors!</string>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item row="0" column="1">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item row="2" column="0">
<spacer name="verticalSpacer_5">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>100</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="0">
<widget class="QGroupBox" name="groupBox">
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="title">
<string>Configure each stabilization mode for each axis</string>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<property name="leftMargin">
<number>0</number>
</property>
<property name="horizontalSpacing">
<number>12</number>
</property>
<item row="3" column="0">
<widget class="QLabel" name="label_22">
<property name="text">
<string>Stabilized3</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_8">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Roll</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="fmsSsPos1Roll">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_9">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Pitch</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QComboBox" name="fmsSsPos3Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QComboBox" name="fmsSsPos3Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="fmsSsPos2Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_14">
<property name="text">
<string>Stabilized1</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="label_10">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Yaw</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="fmsSsPos3Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QComboBox" name="fmsSsPos1Yaw">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QComboBox" name="fmsSsPos2Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="fmsSsPos2Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_21">
<property name="text">
<string>Stabilized2</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QComboBox" name="fmsSsPos1Pitch">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="tab_4">
<attribute name="title">
<string>Arming Settings</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_2">
<layout class="QVBoxLayout" name="verticalLayout_12">
<property name="spacing">
<number>12</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="label_17">
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>Arm airframe using throttle off and:</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="armControl">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Indicate the control used for arming the airframe, in addition to setting the throttle to its minimum position. In other terms &quot;Throttle Off&quot;.</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<widget class="QLabel" name="label_18">
<property name="text">
<string>Arming timeout:</string>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="armTimeout">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>After the time indicated here, the frame go back to disarmed state.</string>
</property>
<property name="maximum">
<number>64</number>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_19">
<property name="text">
<string>seconds.</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="label_3">
<property name="text">
<string>Airframe disarm is done by throttle off and opposite of above combination.</string>
<widget class="QScrollArea" name="scrollArea_2">
<property name="palette">
<palette>
<active>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_2">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>529</width>
<height>165</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QGroupBox" name="groupBox_6">
<property name="title">
<string>Arming Settings</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_7">
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="label_17">
<property name="font">
<font>
<weight>50</weight>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>Arm airframe using throttle off and:</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="armControl">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Indicate the control used for arming the airframe, in addition to setting the throttle to its minimum position. In other terms &quot;Throttle Off&quot;.</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<widget class="QLabel" name="label_18">
<property name="text">
<string>Arming timeout:</string>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="armTimeout">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>After the time indicated here, the frame go back to disarmed state.</string>
</property>
<property name="maximum">
<number>64</number>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_19">
<property name="text">
<string>seconds.</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="label_3">
<property name="text">
<string>Airframe disarm is done by throttle off and opposite of above combination.</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>467</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<item>
<spacer name="horizontalSpacer_5">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="inputHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveRCInputToRAM">
<property name="toolTip">
<string>Send to OpenPilot but don't write in SD.
<widget class="QGroupBox" name="groupBox_3">
<property name="title">
<string/>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_5">
<property name="spacing">
<number>4</number>
</property>
<item>
<spacer name="horizontalSpacer_5">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="inputHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="toolTip">
<string>Takes you to the wiki page</string>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveRCInputToRAM">
<property name="minimumSize">
<size>
<width>60</width>
<height>28</height>
</size>
</property>
<property name="toolTip">
<string>Send to OpenPilot but don't write in SD.
Be sure to set the Neutral position on all sliders before sending!</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveRCInputToSD">
<property name="toolTip">
<string>Be sure to set the Neutral position on all sliders before sending!
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveRCInputToSD">
<property name="minimumSize">
<size>
<width>60</width>
<height>28</height>
</size>
</property>
<property name="toolTip">
<string>Be sure to set the Neutral position on all sliders before sending!
Applies and Saves all settings to SD</string>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
@ -896,8 +1510,6 @@ Applies and Saves all settings to SD</string>
<tabstop>fmsSsPos3Yaw</tabstop>
<tabstop>tabWidget</tabstop>
<tabstop>deadband</tabstop>
<tabstop>configurationWizard</tabstop>
<tabstop>runCalibration</tabstop>
<tabstop>graphicsView</tabstop>
<tabstop>wzBack</tabstop>
<tabstop>wzNext</tabstop>

View File

@ -10,22 +10,7 @@ inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) :
{
ui->setupUi(this);
//The first time through the loop, keep the legend. All other times, delete it.
if(!showlegend)
{
layout()->removeWidget(ui->legend0);
layout()->removeWidget(ui->legend1);
layout()->removeWidget(ui->legend2);
layout()->removeWidget(ui->legend3);
layout()->removeWidget(ui->legend4);
layout()->removeWidget(ui->legend5);
delete ui->legend0;
delete ui->legend1;
delete ui->legend2;
delete ui->legend3;
delete ui->legend4;
delete ui->legend5;
}
connect(ui->channelMin,SIGNAL(valueChanged(int)),this,SLOT(minMaxUpdated()));
connect(ui->channelMax,SIGNAL(valueChanged(int)),this,SLOT(minMaxUpdated()));

View File

@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>767</width>
<height>58</height>
<width>666</width>
<height>59</height>
</rect>
</property>
<property name="windowTitle">
@ -26,7 +26,7 @@
<property name="verticalSpacing">
<number>0</number>
</property>
<item row="2" column="1">
<item row="1" column="1">
<widget class="QLabel" name="channelName">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
@ -45,254 +45,7 @@
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="channelGroup">
<property name="sizePolicy">
<sizepolicy hsizetype="Maximum" vsizetype="Fixed">
<horstretch>6</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>25</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QSpinBox" name="channelMin">
<property name="minimumSize">
<size>
<width>0</width>
<height>25</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::NoButtons</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="value">
<number>1000</number>
</property>
</widget>
</item>
<item row="2" column="8">
<widget class="QSpinBox" name="channelMax">
<property name="minimumSize">
<size>
<width>0</width>
<height>25</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::NoButtons</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="value">
<number>1000</number>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="legend0">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Function</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="8">
<widget class="QLabel" name="legend5">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="legend3">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="6">
<widget class="QLabel" name="legend4">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Neutral</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="6">
<widget class="QSlider" name="channelNeutral">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>22</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="2" column="3">
<item row="1" column="3">
<widget class="QComboBox" name="channelNumberDropdown">
<property name="sizePolicy">
<sizepolicy hsizetype="Maximum" vsizetype="Fixed">
@ -320,20 +73,7 @@ font:bold;</string>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QSpinBox" name="channelNumber">
<property name="enabled">
<bool>true</bool>
</property>
<property name="maximumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
</widget>
</item>
<item row="2" column="10">
<item row="1" column="11">
<widget class="QCheckBox" name="channelRev">
<property name="enabled">
<bool>false</bool>
@ -345,11 +85,90 @@ font:bold;</string>
</size>
</property>
<property name="text">
<string>Rev</string>
<string/>
</property>
</widget>
</item>
<item row="2" column="9">
<item row="1" column="7">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="2">
<widget class="QComboBox" name="channelGroup">
<property name="sizePolicy">
<sizepolicy hsizetype="Maximum" vsizetype="Fixed">
<horstretch>6</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>25</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="8">
<widget class="QSpinBox" name="channelMax">
<property name="minimumSize">
<size>
<width>0</width>
<height>25</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::NoButtons</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="value">
<number>1000</number>
</property>
</widget>
</item>
<item row="1" column="5">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="9">
<widget class="QLabel" name="neutral">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
@ -374,84 +193,45 @@ font:bold;</string>
</property>
</widget>
</item>
<item row="2" column="5">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="7">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="2">
<widget class="QLabel" name="legend1">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>26</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Type</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="legend2">
<widget class="QSpinBox" name="channelNumber">
<property name="enabled">
<bool>true</bool>
</property>
<property name="maximumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QSpinBox" name="channelMin">
<property name="minimumSize">
<size>
<width>0</width>
<height>25</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::NoButtons</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="value">
<number>1000</number>
</property>
</widget>
</item>
<item row="1" column="6">
<widget class="QSlider" name="channelNeutral">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
@ -459,31 +239,49 @@ font:bold;</string>
<property name="minimumSize">
<size>
<width>0</width>
<height>26</height>
<height>22</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
margin:5px;
font:bold;</string>
</property>
<property name="text">
<string>Number</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="1" column="12">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="10">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>15</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
<tabstops>

View File

@ -0,0 +1,474 @@
/**
******************************************************************************
*
* @file mixercurve.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief A MixerCurve Gadget used to update settings in the firmware
*****************************************************************************/
/*
* 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 <QtGui/QWidget>
#include <QResizeEvent>
#include <math.h>
#include "mixercurve.h"
#include "dblspindelegate.h"
MixerCurve::MixerCurve(QWidget *parent) :
QFrame(parent),
m_mixerUI(new Ui::MixerCurve)
{
m_mixerUI->setupUi(this);
// setup some convienence pointers
m_curve = m_mixerUI->CurveWidget;
m_settings = m_mixerUI->CurveSettings;
m_mixerUI->SettingsGroup->hide();
m_curve->showCommands(false);
m_curve->showCommand("Reset", false);
m_curve->showCommand("Popup", false);
m_curve->showCommand("Commands", false);
// create our spin delegate
m_spinDelegate = new DoubleSpinDelegate();
// set the default mixer type
setMixerType(MixerCurve::MIXERCURVE_THROTTLE);
// setup and turn off advanced mode
CommandActivated();
// paint the ui
UpdateCurveUI();
// wire up our signals
connect(m_mixerUI->CurveType, SIGNAL(currentIndexChanged(int)), this, SLOT(CurveTypeChanged()));
connect(m_mixerUI->ResetCurve, SIGNAL(clicked()), this, SLOT(ResetCurve()));
connect(m_mixerUI->PopupCurve, SIGNAL(clicked()),this,SLOT(PopupCurve()));
connect(m_mixerUI->GenerateCurve, SIGNAL(clicked()), this, SLOT(GenerateCurve()));
connect(m_curve, SIGNAL(curveUpdated()), this, SLOT(UpdateSettingsTable()));
connect(m_curve, SIGNAL(commandActivated(Node*)),this, SLOT(CommandActivated(Node*)));
connect(m_settings, SIGNAL(cellChanged(int,int)), this, SLOT(SettingsTableChanged()));
connect(m_mixerUI->CurveMin, SIGNAL(valueChanged(double)), this, SLOT(CurveMinChanged(double)));
connect(m_mixerUI->CurveMax, SIGNAL(valueChanged(double)), this, SLOT(CurveMaxChanged(double)));
connect(m_mixerUI->CurveStep, SIGNAL(valueChanged(double)), this, SLOT(GenerateCurve()));
}
MixerCurve::~MixerCurve()
{
delete m_mixerUI;
delete m_spinDelegate;
}
void MixerCurve::setMixerType(MixerCurveType curveType)
{
m_curveType = curveType;
m_mixerUI->CurveMin->setMaximum(1.0);
m_mixerUI->CurveMax->setMaximum(1.0);
switch (m_curveType) {
case MixerCurve::MIXERCURVE_THROTTLE:
{
m_mixerUI->SettingsGroup->setTitle("Throttle Curve");
m_curve->setRange(0.0, 1.0);
m_mixerUI->CurveMin->setMinimum(0.0);
m_mixerUI->CurveMax->setMinimum(0.0);
break;
}
case MixerCurve::MIXERCURVE_PITCH:
{
m_mixerUI->SettingsGroup->setTitle("Pitch Curve");
m_curve->setRange(-1.0, 1.0);
m_curve->setPositiveColor("#0000aa", "#0000aa");
m_mixerUI->CurveMin->setMinimum(-1.0);
m_mixerUI->CurveMax->setMinimum(-1.0);
break;
}
}
m_spinDelegate->setRange(m_mixerUI->CurveMin->minimum(), m_mixerUI->CurveMax->maximum());
for (int i=0; i<MixerCurveWidget::NODE_NUMELEM; i++) {
m_settings->setItemDelegateForRow(i, m_spinDelegate);
}
ResetCurve();
}
void MixerCurve::ResetCurve()
{
m_mixerUI->CurveMin->setValue(m_mixerUI->CurveMin->minimum());
m_mixerUI->CurveMax->setValue(m_mixerUI->CurveMax->maximum());
m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Linear"));
initLinearCurve(MixerCurveWidget::NODE_NUMELEM, getCurveMax(), getCurveMin());
m_curve->activateCommand("Linear");
UpdateSettingsTable();
}
void MixerCurve::PopupCurve()
{
if (!m_curve->isCommandActive("Popup")) {
m_mixerUI->SettingsGroup->show();
m_mixerUI->PopupCurve->hide();
PopupWidget* popup = new PopupWidget();
popup->popUp(this);
m_mixerUI->SettingsGroup->hide();
m_mixerUI->PopupCurve->show();
m_curve->showCommands(false);
}
}
void MixerCurve::UpdateCurveUI()
{
//get the user settings
QString curveType = m_mixerUI->CurveType->currentText();
m_curve->activateCommand(curveType);
bool cmdsActive = m_curve->isCommandActive("Commands");
m_curve->showCommand("StepPlus", cmdsActive && curveType != "Linear");
m_curve->showCommand("StepMinus", cmdsActive && curveType != "Linear");
m_curve->showCommand("StepValue", cmdsActive && curveType != "Linear");
m_mixerUI->CurveStep->setMinimum(0.0);
m_mixerUI->CurveStep->setMaximum(100.0);
m_mixerUI->CurveStep->setSingleStep(1.00);
//set default visible
m_mixerUI->minLabel->setVisible(true);
m_mixerUI->CurveMin->setVisible(true);
m_mixerUI->maxLabel->setVisible(false);
m_mixerUI->CurveMax->setVisible(false);
m_mixerUI->stepLabel->setVisible(false);
m_mixerUI->CurveStep->setVisible(false);
if ( curveType.compare("Flat")==0)
{
m_mixerUI->minLabel->setVisible(false);
m_mixerUI->CurveMin->setVisible(false);
m_mixerUI->stepLabel->setVisible(true);
m_mixerUI->CurveStep->setVisible(true);
m_mixerUI->CurveStep->setMinimum(m_mixerUI->CurveMin->minimum());
m_mixerUI->CurveStep->setMaximum(m_mixerUI->CurveMax->maximum());
m_mixerUI->CurveStep->setSingleStep(0.01);
m_mixerUI->CurveStep->setValue(m_mixerUI->CurveMax->value() / 2);
}
if ( curveType.compare("Linear")==0)
{
m_mixerUI->maxLabel->setVisible(true);
m_mixerUI->CurveMax->setVisible(true);
}
if ( curveType.compare("Step")==0)
{
m_mixerUI->maxLabel->setVisible(true);
m_mixerUI->CurveMax->setVisible(true);
m_mixerUI->stepLabel->setText("Step at");
m_mixerUI->stepLabel->setVisible(true);
m_mixerUI->CurveStep->setVisible(true);
m_mixerUI->CurveStep->setMinimum(1.0);
}
if ( curveType.compare("Exp")==0)
{
m_mixerUI->maxLabel->setVisible(true);
m_mixerUI->CurveMax->setVisible(true);
m_mixerUI->stepLabel->setText("Power");
m_mixerUI->stepLabel->setVisible(true);
m_mixerUI->CurveStep->setVisible(true);
m_mixerUI->CurveStep->setMinimum(1.0);
}
if ( curveType.compare("Log")==0)
{
m_mixerUI->maxLabel->setVisible(true);
m_mixerUI->CurveMax->setVisible(true);
m_mixerUI->stepLabel->setText("Power");
m_mixerUI->stepLabel->setVisible(true);
m_mixerUI->CurveStep->setVisible(true);
m_mixerUI->CurveStep->setMinimum(1.0);
}
GenerateCurve();
}
void MixerCurve::GenerateCurve()
{
double scale;
double newValue;
//get the user settings
double value1 = getCurveMin();
double value2 = getCurveMax();
double value3 = getCurveStep();
m_curve->setCommandText("StepValue", QString("%0").arg(value3));
QString CurveType = m_mixerUI->CurveType->currentText();
QList<double> points;
for (int i=0; i<MixerCurveWidget::NODE_NUMELEM; i++)
{
scale =((double)i/(double)(MixerCurveWidget::NODE_NUMELEM - 1));
if ( CurveType.compare("Flat")==0)
{
points.append(value3);
}
if ( CurveType.compare("Linear")==0)
{
newValue =value1 +(scale*(value2-value1));
points.append(newValue);
}
if ( CurveType.compare("Step")==0)
{
if (scale*100<value3)
{
points.append(value1);
}
else
{
points.append(value2);
}
}
if ( CurveType.compare("Exp")==0)
{
newValue =value1 +(((exp(scale*(value3/10))-1))/(exp((value3/10))-1)*(value2-value1));
points.append(newValue);
}
if ( CurveType.compare("Log")==0)
{
newValue = value1 +(((log(scale*(value3*2)+1))/(log(1+(value3*2))))*(value2-value1));
points.append(newValue);
}
}
setCurve(&points);
}
/**
Wrappers for mixercurvewidget.
*/
void MixerCurve::initCurve (const QList<double>* points)
{
m_curve->setCurve(points);
UpdateSettingsTable();
}
QList<double> MixerCurve::getCurve()
{
return m_curve->getCurve();
}
void MixerCurve::initLinearCurve(int numPoints, double maxValue, double minValue)
{
setMin(minValue);
setMax(maxValue);
m_curve->initLinearCurve(numPoints, maxValue, minValue);
if (m_spinDelegate)
m_spinDelegate->setRange(minValue, maxValue);
}
void MixerCurve::setCurve(const QList<double>* points)
{
m_curve->setCurve(points);
UpdateSettingsTable();
}
void MixerCurve::setMin(double value)
{
//m_curve->setMin(value);
m_mixerUI->CurveMin->setMinimum(value);
}
double MixerCurve::getMin()
{
return m_curve->getMin();
}
void MixerCurve::setMax(double value)
{
//m_curve->setMax(value);
m_mixerUI->CurveMax->setMaximum(value);
}
double MixerCurve::getMax()
{
return m_curve->getMax();
}
double MixerCurve::setRange(double min, double max)
{
return m_curve->setRange(min, max);
}
double MixerCurve::getCurveMin()
{
return m_mixerUI->CurveMin->value();
}
double MixerCurve::getCurveMax()
{
return m_mixerUI->CurveMax->value();
}
double MixerCurve::getCurveStep()
{
return m_mixerUI->CurveStep->value();
}
void MixerCurve::UpdateSettingsTable()
{
QList<double> points = m_curve->getCurve();
int ptCnt = points.count();
for (int i=0; i<ptCnt; i++)
{
QTableWidgetItem* item = m_settings->item(i, 0);
if (item)
item->setText(QString().sprintf("%.2f",points.at( (ptCnt - 1) - i )));
}
}
void MixerCurve::SettingsTableChanged()
{
QList<double> points;
for (int i=0; i < m_settings->rowCount(); i++)
{
QTableWidgetItem* item = m_settings->item(i, 0);
if (item)
points.push_front(item->text().toDouble());
}
m_mixerUI->CurveMin->setValue(points.first());
m_mixerUI->CurveMax->setValue(points.last());
m_curve->setCurve(&points);
}
void MixerCurve::CommandActivated(Node* node)
{
QString name = (node) ? node->getName() : "Reset";
if (name == "Reset") {
ResetCurve();
m_curve->showCommands(false);
}
else if (name == "Commands") {
}
else if (name == "Popup" ) {
PopupCurve();
}
else if (name == "Linear") {
m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Linear"));
}
else if (name == "Log") {
m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Log"));
}
else if (name == "Exp") {
m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Exp"));
}
else if (name == "Flat") {
m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Flat"));
}
else if (name == "Step") {
m_mixerUI->CurveType->setCurrentIndex(m_mixerUI->CurveType->findText("Step"));
}
else if (name == "MinPlus") {
m_mixerUI->CurveMin->stepUp();
}
else if (name == "MinMinus") {
m_mixerUI->CurveMin->stepDown();
}
else if (name == "MaxPlus") {
m_mixerUI->CurveMax->stepUp();
}
else if (name == "MaxMinus"){
m_mixerUI->CurveMax->stepDown();
}
else if (name == "StepPlus") {
m_mixerUI->CurveStep->stepUp();
m_curve->setCommandText("StepValue", QString("%0").arg(getCurveStep()));
}
else if (name == "StepMinus") {
m_mixerUI->CurveStep->stepDown();
m_curve->setCommandText("StepValue", QString("%0").arg(getCurveStep()));
}
GenerateCurve();
}
void MixerCurve::CurveTypeChanged()
{
// setup the ui for this curvetype
UpdateCurveUI();
}
void MixerCurve::CurveMinChanged(double value)
{
QList<double> points = m_curve->getCurve();
points.removeFirst();
points.push_front(value);
setCurve(&points);
}
void MixerCurve::CurveMaxChanged(double value)
{
// the max changed so redraw the curve
// mixercurvewidget::setCurve will trim any points above max
QList<double> points = m_curve->getCurve();
points.removeLast();
points.append(value);
setCurve(&points);
}
void MixerCurve::showEvent(QShowEvent *event)
{
Q_UNUSED(event);
m_settings->resizeColumnsToContents();
m_settings->setColumnWidth(0,(m_settings->width()- m_settings->verticalHeader()->width()));
int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount();
for (int i=0; i<m_settings->rowCount(); i++)
m_settings->setRowHeight(i, h);
m_curve->showEvent(event);
}
void MixerCurve::resizeEvent(QResizeEvent* event)
{
m_settings->resizeColumnsToContents();
m_settings->setColumnWidth(0,(m_settings->width() - m_settings->verticalHeader()->width()));
int h = (m_settings->height() - m_settings->horizontalHeader()->height()) / m_settings->rowCount();
for (int i=0; i<m_settings->rowCount(); i++)
m_settings->setRowHeight(i, h);
m_curve->resizeEvent(event);
}

View File

@ -0,0 +1,103 @@
/**
******************************************************************************
*
* @file mixercurve.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief A MixerCurve Gadget used to update settings in the firmware
*****************************************************************************/
/*
* 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
*/
#ifndef MIXERCURVE_H
#define MIXERCURVE_H
#include <QFrame>
#include <QtGui/QWidget>
#include <QList>
#include <QTableWidget>
#include "ui_mixercurve.h"
#include "mixercurvewidget.h"
#include "dblspindelegate.h"
#include "uavobjectwidgetutils_global.h"
#include "uavobjectwidgetutils/popupwidget.h"
namespace Ui {
class MixerCurve;
}
class MixerCurve : public QFrame
{
Q_OBJECT
public:
explicit MixerCurve(QWidget *parent = 0);
~MixerCurve();
/* Enumeration options for ThrottleCurves */
typedef enum { MIXERCURVE_THROTTLE=0, MIXERCURVE_PITCH=1 } MixerCurveType;
void setMixerType(MixerCurveType curveType);
void initCurve (const QList<double>* points);
QList<double> getCurve();
void initLinearCurve(int numPoints, double maxValue = 1, double minValue = 0);
void setCurve(const QList<double>* points);
void setMin(double value);
double getMin();
void setMax(double value);
double getMax();
double getCurveMin();
double getCurveMax();
double getCurveStep();
double setRange(double min, double max);
MixerCurveWidget* getCurveWidget() { return m_curve; }
signals:
protected:
void showEvent(QShowEvent *event);
void resizeEvent(QResizeEvent *event);
public slots:
void ResetCurve();
void PopupCurve();
void GenerateCurve();
void UpdateSettingsTable();
private slots:
void CommandActivated(Node* node = 0);
void SettingsTableChanged();
void CurveTypeChanged();
void CurveMinChanged(double value);
void CurveMaxChanged(double value);
void UpdateCurveUI();
private:
Ui::MixerCurve* m_mixerUI;
MixerCurveWidget* m_curve;
QTableWidget* m_settings;
MixerCurveType m_curveType;
DoubleSpinDelegate* m_spinDelegate;
};
#endif // MIXERCURVE_H

View File

@ -0,0 +1,369 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>MixerCurve</class>
<widget class="QFrame" name="MixerCurve">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>543</width>
<height>467</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>1</horstretch>
<verstretch>1</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>441</width>
<height>321</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>1000</height>
</size>
</property>
<property name="baseSize">
<size>
<width>300</width>
<height>300</height>
</size>
</property>
<property name="windowTitle">
<string>MixerCurve</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0" rowspan="2">
<widget class="QGroupBox" name="SettingsGroup">
<property name="maximumSize">
<size>
<width>150</width>
<height>16777215</height>
</size>
</property>
<property name="title">
<string>Throttle Curve</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QTableWidget" name="CurveSettings">
<property name="maximumSize">
<size>
<width>100</width>
<height>200</height>
</size>
</property>
<property name="font">
<font>
<pointsize>8</pointsize>
</font>
</property>
<property name="verticalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</property>
<property name="horizontalScrollBarPolicy">
<enum>Qt::ScrollBarAlwaysOff</enum>
</property>
<property name="autoScroll">
<bool>false</bool>
</property>
<property name="alternatingRowColors">
<bool>true</bool>
</property>
<property name="rowCount">
<number>5</number>
</property>
<property name="columnCount">
<number>1</number>
</property>
<row>
<property name="text">
<string>Max</string>
</property>
</row>
<row>
<property name="text">
<string>4</string>
</property>
</row>
<row>
<property name="text">
<string>3</string>
</property>
</row>
<row>
<property name="text">
<string>2</string>
</property>
</row>
<row>
<property name="text">
<string>Min</string>
</property>
</row>
<column>
<property name="text">
<string>Value</string>
</property>
<property name="textAlignment">
<set>AlignJustify|AlignVCenter</set>
</property>
</column>
<item row="0" column="0">
<property name="text">
<string>1.0</string>
</property>
</item>
<item row="1" column="0">
<property name="text">
<string>.75</string>
</property>
</item>
<item row="2" column="0">
<property name="text">
<string>.50</string>
</property>
</item>
<item row="3" column="0">
<property name="text">
<string>.25</string>
</property>
</item>
<item row="4" column="0">
<property name="text">
<string>.00</string>
</property>
</item>
</widget>
</item>
<item>
<widget class="QComboBox" name="CurveType">
<item>
<property name="text">
<string>Linear</string>
</property>
</item>
<item>
<property name="text">
<string>Log</string>
</property>
</item>
<item>
<property name="text">
<string>Exp</string>
</property>
</item>
<item>
<property name="text">
<string>Flat</string>
</property>
</item>
<item>
<property name="text">
<string>Step</string>
</property>
</item>
</widget>
</item>
<item>
<widget class="QPushButton" name="GenerateCurve">
<property name="text">
<string>Generate</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="minLabel">
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="CurveMin">
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="correctionMode">
<enum>QAbstractSpinBox::CorrectToNearestValue</enum>
</property>
<property name="minimum">
<double>-1.000000000000000</double>
</property>
<property name="maximum">
<double>1.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
<property name="value">
<double>0.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="maxLabel">
<property name="text">
<string>Max</string>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="CurveMax">
<property name="correctionMode">
<enum>QAbstractSpinBox::CorrectToNearestValue</enum>
</property>
<property name="minimum">
<double>0.000000000000000</double>
</property>
<property name="maximum">
<double>1.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
<property name="value">
<double>1.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="stepLabel">
<property name="text">
<string>Step</string>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="CurveStep">
<property name="correctionMode">
<enum>QAbstractSpinBox::CorrectToNearestValue</enum>
</property>
<property name="value">
<double>50.000000000000000</double>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
<zorder>GenerateCurve</zorder>
<zorder>CurveSettings</zorder>
<zorder>CurveType</zorder>
<zorder>CurveMin</zorder>
<zorder>minLabel</zorder>
<zorder>CurveMax</zorder>
<zorder>maxLabel</zorder>
<zorder>CurveStep</zorder>
<zorder>stepLabel</zorder>
<zorder>verticalSpacer</zorder>
</widget>
</item>
<item row="0" column="1">
<widget class="MixerCurveWidget" name="CurveWidget" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>5</horstretch>
<verstretch>5</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>50</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>1000</width>
<height>1000</height>
</size>
</property>
<property name="sizeIncrement">
<size>
<width>10</width>
<height>10</height>
</size>
</property>
<property name="baseSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
<property name="font">
<font>
<pointsize>7</pointsize>
</font>
</property>
</widget>
</item>
<item row="1" column="1">
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="ResetCurve">
<property name="text">
<string>Reset</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="PopupCurve">
<property name="text">
<string>Advanced...</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<customwidgets>
<customwidget>
<class>MixerCurveWidget</class>
<extends>QWidget</extends>
<header location="global">uavobjectwidgetutils/mixercurvewidget.h</header>
<container>1</container>
</customwidget>
</customwidgets>
<resources/>
<connections/>
</ui>

View File

@ -6,48 +6,943 @@
<rect>
<x>0</x>
<y>0</y>
<width>659</width>
<height>523</height>
<width>811</width>
<height>937</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<layout class="QVBoxLayout" name="verticalLayout_5">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
<widget class="QTabWidget" name="tabWidget">
<property name="tabShape">
<enum>QTabWidget::Rounded</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
<property name="currentIndex">
<number>0</number>
</property>
<layout class="QGridLayout" name="gridLayout">
<property name="leftMargin">
<number>1</number>
</property>
<property name="topMargin">
<number>1</number>
</property>
<property name="rightMargin">
<number>1</number>
</property>
<property name="bottomMargin">
<number>3</number>
</property>
<property name="spacing">
<number>2</number>
</property>
<item row="0" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_6">
<property name="elideMode">
<enum>Qt::ElideMiddle</enum>
</property>
<widget class="QWidget" name="tab">
<attribute name="title">
<string>Output</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_4">
<property name="spacing">
<number>12</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="palette">
<palette>
<active>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>781</width>
<height>800</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QGroupBox" name="groupBox_2">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>78</height>
</size>
</property>
<property name="title">
<string/>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_9">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Channel:</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="chBank1">
<property name="text">
<string>-</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="chBank2">
<property name="text">
<string>-</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="chBank3">
<property name="text">
<string>-</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="5">
<widget class="QLabel" name="chBank4">
<property name="text">
<string>-</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="0">
<spacer name="horizontalSpacer_4">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="1">
<widget class="QLabel" name="label_3">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Update rate:</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QComboBox" name="cb_outputRate1">
<property name="enabled">
<bool>false</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="toolTip">
<string>Setup &quot;TurboPWM&quot; here: usual value is 400 Hz for multirotor airframes.
Leave at 50Hz for fixed wing.</string>
</property>
<item>
<property name="text">
<string>50</string>
</property>
</item>
<item>
<property name="text">
<string>60</string>
</property>
</item>
<item>
<property name="text">
<string>125</string>
</property>
</item>
<item>
<property name="text">
<string>165</string>
</property>
</item>
<item>
<property name="text">
<string>270</string>
</property>
</item>
<item>
<property name="text">
<string>330</string>
</property>
</item>
<item>
<property name="text">
<string>400</string>
</property>
</item>
</widget>
</item>
<item row="1" column="3">
<widget class="QComboBox" name="cb_outputRate2">
<property name="enabled">
<bool>false</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="toolTip">
<string>Setup &quot;TurboPWM&quot; here: usual value is 400 Hz for multirotor airframes.
Leave at 50Hz for fixed wing.</string>
</property>
<item>
<property name="text">
<string>50</string>
</property>
</item>
<item>
<property name="text">
<string>60</string>
</property>
</item>
<item>
<property name="text">
<string>125</string>
</property>
</item>
<item>
<property name="text">
<string>165</string>
</property>
</item>
<item>
<property name="text">
<string>270</string>
</property>
</item>
<item>
<property name="text">
<string>330</string>
</property>
</item>
<item>
<property name="text">
<string>400</string>
</property>
</item>
</widget>
</item>
<item row="1" column="4">
<widget class="QComboBox" name="cb_outputRate3">
<property name="enabled">
<bool>false</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="toolTip">
<string>Setup &quot;TurboPWM&quot; here: usual value is 400 Hz for multirotor airframes.
Leave at 50Hz for fixed wing.</string>
</property>
<item>
<property name="text">
<string>50</string>
</property>
</item>
<item>
<property name="text">
<string>60</string>
</property>
</item>
<item>
<property name="text">
<string>125</string>
</property>
</item>
<item>
<property name="text">
<string>165</string>
</property>
</item>
<item>
<property name="text">
<string>270</string>
</property>
</item>
<item>
<property name="text">
<string>330</string>
</property>
</item>
<item>
<property name="text">
<string>400</string>
</property>
</item>
</widget>
</item>
<item row="1" column="5">
<widget class="QComboBox" name="cb_outputRate4">
<property name="enabled">
<bool>false</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="toolTip">
<string>Setup &quot;TurboPWM&quot; here: usual value is 400 Hz for multirotor airframes.
Leave at 50Hz for fixed wing.</string>
</property>
<item>
<property name="text">
<string>50</string>
</property>
</item>
<item>
<property name="text">
<string>60</string>
</property>
</item>
<item>
<property name="text">
<string>125</string>
</property>
</item>
<item>
<property name="text">
<string>165</string>
</property>
</item>
<item>
<property name="text">
<string>270</string>
</property>
</item>
<item>
<property name="text">
<string>330</string>
</property>
</item>
<item>
<property name="text">
<string>400</string>
</property>
</item>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox_3">
<property name="title">
<string/>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>14</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="legend6">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>22</width>
<height>0</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="layoutDirection">
<enum>Qt::LeftToRight</enum>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>#</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="margin">
<number>0</number>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>1</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="legend0">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>104</width>
<height>0</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Assignment</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="legend1">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>61</width>
<height>0</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="legend2">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>45</width>
<height>0</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Neutral</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_5">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="legend3">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>50</width>
<height>0</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="legend4">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>40</width>
<height>0</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Rev.</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="legend5">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>40</width>
<height>0</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Link</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="channelLayout">
<property name="spacing">
<number>-1</number>
</property>
<property name="sizeConstraint">
<enum>QLayout::SetDefaultConstraint</enum>
</property>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<widget class="QCheckBox" name="spinningArmed">
<property name="minimumSize">
<size>
<width>519</width>
<height>0</height>
</size>
</property>
<property name="text">
<string>Motors spin at neutral output when armed and throttle below zero (be careful)</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>542</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox_4">
<property name="minimumSize">
<size>
<width>0</width>
<height>60</height>
</size>
</property>
<property name="title">
<string/>
</property>
<layout class="QVBoxLayout" name="verticalLayout_6">
<item>
<widget class="QCheckBox" name="channelOutTest">
<property name="enabled">
<bool>true</bool>
</property>
<property name="minimumSize">
<size>
<width>105</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Move the servos using the sliders. Two important things:
- Take extra care if the output is connected to an motor controller!
- Will only work if the RC receiver is working (failsafe)</string>
</property>
<property name="text">
<string>Test outputs</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>75</height>
</size>
</property>
<property name="title">
<string/>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>4</number>
</property>
<item>
<spacer name="horizontalSpacer_3">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
@ -57,429 +952,94 @@
</spacer>
</item>
<item>
<widget class="QLabel" name="label_9">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
<widget class="QPushButton" name="outputHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Channel:</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item row="1" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_7">
<item>
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<property name="minimumSize">
<size>
<width>40</width>
<height>20</height>
<width>32</width>
<height>32</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="label_3">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="toolTip">
<string>Takes you to the wiki page</string>
</property>
<property name="text">
<string>Update rate:</string>
<string/>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveRCOutputToRAM">
<property name="minimumSize">
<size>
<width>60</width>
<height>28</height>
</size>
</property>
<property name="toolTip">
<string>Send to OpenPilot but don't write in SD.
Be sure to set the Neutral position on all sliders before sending!</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveRCOutputToSD">
<property name="minimumSize">
<size>
<width>60</width>
<height>28</height>
</size>
</property>
<property name="toolTip">
<string>Be sure to set the Neutral position on all sliders before sending!
Applies and Saves all settings to SD</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="1" column="1">
<widget class="QComboBox" name="cb_outputRate1">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Setup &quot;TurboPWM&quot; here: usual value is 400 Hz for multirotor airframes.
Leave at 50Hz for fixed wing.</string>
</property>
<item>
<property name="text">
<string>50</string>
</property>
</item>
<item>
<property name="text">
<string>60</string>
</property>
</item>
<item>
<property name="text">
<string>125</string>
</property>
</item>
<item>
<property name="text">
<string>165</string>
</property>
</item>
<item>
<property name="text">
<string>270</string>
</property>
</item>
<item>
<property name="text">
<string>330</string>
</property>
</item>
<item>
<property name="text">
<string>400</string>
</property>
</item>
</widget>
</item>
<item row="1" column="2">
<widget class="QComboBox" name="cb_outputRate2">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Setup &quot;TurboPWM&quot; here: usual value is 400 Hz for multirotor airframes.
Leave at 50Hz for fixed wing.</string>
</property>
<item>
<property name="text">
<string>50</string>
</property>
</item>
<item>
<property name="text">
<string>60</string>
</property>
</item>
<item>
<property name="text">
<string>125</string>
</property>
</item>
<item>
<property name="text">
<string>165</string>
</property>
</item>
<item>
<property name="text">
<string>270</string>
</property>
</item>
<item>
<property name="text">
<string>330</string>
</property>
</item>
<item>
<property name="text">
<string>400</string>
</property>
</item>
</widget>
</item>
<item row="1" column="3">
<widget class="QComboBox" name="cb_outputRate3">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Setup &quot;TurboPWM&quot; here: usual value is 400 Hz for multirotor airframes.
Leave at 50Hz for fixed wing.</string>
</property>
<item>
<property name="text">
<string>50</string>
</property>
</item>
<item>
<property name="text">
<string>60</string>
</property>
</item>
<item>
<property name="text">
<string>125</string>
</property>
</item>
<item>
<property name="text">
<string>165</string>
</property>
</item>
<item>
<property name="text">
<string>270</string>
</property>
</item>
<item>
<property name="text">
<string>330</string>
</property>
</item>
<item>
<property name="text">
<string>400</string>
</property>
</item>
</widget>
</item>
<item row="1" column="4">
<widget class="QComboBox" name="cb_outputRate4">
<property name="enabled">
<bool>false</bool>
</property>
<property name="toolTip">
<string>Setup &quot;TurboPWM&quot; here: usual value is 400 Hz for multirotor airframes.
Leave at 50Hz for fixed wing.</string>
</property>
<item>
<property name="text">
<string>50</string>
</property>
</item>
<item>
<property name="text">
<string>60</string>
</property>
</item>
<item>
<property name="text">
<string>125</string>
</property>
</item>
<item>
<property name="text">
<string>165</string>
</property>
</item>
<item>
<property name="text">
<string>270</string>
</property>
</item>
<item>
<property name="text">
<string>330</string>
</property>
</item>
<item>
<property name="text">
<string>400</string>
</property>
</item>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="chBank1">
<property name="text">
<string>-</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="chBank2">
<property name="text">
<string>-</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="chBank3">
<property name="text">
<string>-</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="chBank4">
<property name="text">
<string>-</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<layout class="QVBoxLayout" name="channelLayout"/>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<widget class="QCheckBox" name="spinningArmed">
<property name="text">
<string>Motors spin at neutral output when armed and throttle below zero (be careful)</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QCheckBox" name="channelOutTest">
<property name="enabled">
<bool>true</bool>
</property>
<property name="toolTip">
<string>Move the servos using the sliders. Two important things:
- Take extra care if the output is connected to an motor controller!
- Will only work if the RC receiver is working (failsafe)</string>
</property>
<property name="text">
<string>Test outputs</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="outputHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveRCOutputToRAM">
<property name="toolTip">
<string>Send to OpenPilot but don't write in SD.
Be sure to set the Neutral position on all sliders before sending!</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveRCOutputToSD">
<property name="toolTip">
<string>Be sure to set the Neutral position on all sliders before sending!
Applies and Saves all settings to SD</string>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<tabstops>
<tabstop>channelOutTest</tabstop>
<tabstop>saveRCOutputToRAM</tabstop>
<tabstop>saveRCOutputToSD</tabstop>
</tabstops>

View File

@ -35,23 +35,6 @@ OutputChannelForm::OutputChannelForm(const int index, QWidget *parent, const boo
m_inChannelTest(false)
{
ui.setupUi(this);
if(!showLegend)
{
// Remove legend
QGridLayout *grid_layout = dynamic_cast<QGridLayout*>(layout());
Q_ASSERT(grid_layout);
for (int col = 0; col < grid_layout->columnCount(); col++)
{ // remove every item in first row
QLayoutItem *item = grid_layout->itemAtPosition(0, col);
if (!item) continue;
// get widget from layout item
QWidget *legend_widget = item->widget();
if (!legend_widget) continue;
// delete widget
grid_layout->removeWidget(legend_widget);
delete legend_widget;
}
}
// The convention for OP is Channel 1 to Channel 10.
ui.actuatorNumber->setText(QString("%1:").arg(m_index+1));

View File

@ -6,7 +6,7 @@
<rect>
<x>0</x>
<y>0</y>
<width>813</width>
<width>645</width>
<height>58</height>
</rect>
</property>
@ -20,53 +20,61 @@
<property name="bottomMargin">
<number>1</number>
</property>
<item row="1" column="5">
<widget class="QLabel" name="actuatorValue">
<item row="0" column="6">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="4">
<widget class="QSlider" name="actuatorNeutral">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="0" column="8">
<widget class="QSpinBox" name="actuatorMax">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Current value of slider.</string>
<string>Maximum PWM value, beware of not overdriving your servo.</string>
</property>
<property name="text">
<string>0000</string>
<property name="maximum">
<number>9999</number>
</property>
</widget>
</item>
<item row="0" column="10">
<widget class="QLabel" name="legend5">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Link</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="1">
<item row="0" column="1">
<widget class="QLabel" name="actuatorName">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
@ -89,42 +97,6 @@ margin:1px;</string>
</widget>
</item>
<item row="0" column="0">
<widget class="QLabel" name="legend6">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="layoutDirection">
<enum>Qt::LeftToRight</enum>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>#</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="margin">
<number>0</number>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="actuatorNumber">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
@ -152,7 +124,7 @@ margin:1px;</string>
</property>
</widget>
</item>
<item row="1" column="2">
<item row="0" column="2">
<widget class="QSpinBox" name="actuatorMin">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
@ -165,7 +137,7 @@ margin:1px;</string>
</property>
</widget>
</item>
<item row="1" column="9">
<item row="0" column="9">
<widget class="QCheckBox" name="actuatorRev">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
@ -187,67 +159,7 @@ margin:1px;</string>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="legend2">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Neutral (slowest for motor)</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="legend0">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Assignment</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="3">
<item row="0" column="3">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
@ -263,67 +175,7 @@ margin:1px;</string>
</property>
</spacer>
</item>
<item row="0" column="2">
<widget class="QLabel" name="legend1">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="8">
<widget class="QLabel" name="legend3">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="10">
<item row="0" column="10">
<widget class="QCheckBox" name="actuatorLink">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
@ -345,87 +197,19 @@ margin:1px;</string>
</property>
</widget>
</item>
<item row="1" column="6">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="9">
<widget class="QLabel" name="legend4">
<item row="0" column="5">
<widget class="QLabel" name="actuatorValue">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="font">
<font>
<weight>75</weight>
<italic>false</italic>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font:bold;
margin:1px;</string>
<property name="toolTip">
<string>Current value of slider.</string>
</property>
<property name="text">
<string>Rev.</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QSlider" name="actuatorNeutral">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="maximum">
<number>9999</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="1" column="8">
<widget class="QSpinBox" name="actuatorMax">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PWM value, beware of not overdriving your servo.</string>
</property>
<property name="maximum">
<number>9999</number>
<string>0000</string>
</property>
</widget>
</item>

View File

@ -86,6 +86,32 @@
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="pushButton">
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>button:help</string>
<string>url:http://wiki.openpilot.org/x/dACrAQ</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="Apply">
<property name="toolTip">
@ -1752,6 +1778,8 @@
<tabstop>Apply</tabstop>
<tabstop>Save</tabstop>
</tabstops>
<resources/>
<resources>
<include location="../coreplugin/core.qrc"/>
</resources>
<connections/>
</ui>

View File

@ -29,9 +29,9 @@
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt;&quot;&gt;Set the serial speed of your onboard telemetry modem here. It is the speed between the OpenPilot board and the onboard modem, and could be different from the radio link speed.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Sans'; font-size:10pt;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Sans'; font-size:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Sans'; font-size:10pt;&quot;&gt;Beware of not locking yourself out! You should only modify this setting when the OpenPilot board is connected through the USB port.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
@ -76,6 +76,9 @@ p, li { white-space: pre-wrap; }
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<property name="spacing">
<number>4</number>
</property>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">

File diff suppressed because it is too large Load Diff

View File

@ -6,39 +6,125 @@
<rect>
<x>0</x>
<y>0</y>
<width>720</width>
<height>567</height>
<width>708</width>
<height>880</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
<string>TxPID</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<widget class="QScrollArea" name="scrollArea">
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
<widget class="QTabWidget" name="tabWidget">
<property name="currentIndex">
<number>0</number>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_2">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>696</width>
<height>475</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<widget class="QWidget" name="tab">
<attribute name="title">
<string>Tx PID</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_4">
<property name="spacing">
<number>12</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QCheckBox" name="TxPIDEnable">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
<widget class="QScrollArea" name="scrollArea">
<property name="palette">
<palette>
<active>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</active>
<inactive>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="255">
<red>255</red>
<green>255</green>
<blue>255</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</inactive>
<disabled>
<colorrole role="Base">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
<colorrole role="Window">
<brush brushstyle="SolidPattern">
<color alpha="0">
<red>232</red>
<green>232</green>
<blue>232</blue>
</color>
</brush>
</colorrole>
</disabled>
</palette>
</property>
<property name="toolTip">
<string>This module will periodically update values of stabilization PID settings
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="widgetResizable">
<bool>true</bool>
</property>
<widget class="QWidget" name="scrollAreaWidgetContents_2">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>678</width>
<height>678</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QGroupBox" name="groupBox_2">
<property name="title">
<string/>
</property>
<layout class="QVBoxLayout" name="verticalLayout_5">
<item>
<widget class="QCheckBox" name="TxPIDEnable">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>This module will periodically update values of stabilization PID settings
depending on configured input control channels. New values of stabilization
settings are not saved to flash, but updated in RAM. It is expected that the
module will be enabled only for tuning. When desired values are found, they
@ -46,156 +132,152 @@ can be read via GCS and saved permanently. Then this module should be
disabled again.
Up to 3 separate PID options (or option pairs) can be selected and updated.</string>
</property>
<property name="text">
<string>Enable TxPID module</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>After enabling the module, you must power cycle before using and configuring.</string>
</property>
</widget>
</item>
<item>
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox_6">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="title">
<string>Module Settings</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="1" column="1">
<widget class="QLabel" name="label_51">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
</property>
<property name="text">
<string>Enable TxPID module</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>After enabling the module, you must power cycle before using and configuring.</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="groupBox_6">
<property name="enabled">
<bool>true</bool>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>100</height>
</size>
</property>
<property name="title">
<string>Module Settings</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="1" column="1">
<widget class="QLabel" name="label_51">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>PID option</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="label_50">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
</property>
<property name="text">
<string>PID option</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLabel" name="label_50">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Control Source</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="label_49">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
</property>
<property name="text">
<string>Control Source</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QLabel" name="label_49">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QLabel" name="label">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="4">
<widget class="QLabel" name="label">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_47">
<property name="text">
<string>Instance 1</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="PID1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select PID option or option pair to update.
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_47">
<property name="text">
<string>Instance 1</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QComboBox" name="PID1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select PID option or option pair to update.
Set to Disabled if not used.</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="Input1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select input used as a control source for this instance.
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QComboBox" name="Input1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select input used as a control source for this instance.
It can be one of Accessory channels or Throttle channel.
If Accessory channel is chosen then its range [0..1] will be mapped
@ -209,68 +291,68 @@ accordingly.
Note that it is possible to set PID Min &gt; Max. In that case increasing
control input value will decrease the PID option value. This can be
used, for instance, to decrease PID value when increasing Throttle.</string>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QDoubleSpinBox" name="MinPID1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PID value mapped to Accessory channel = 0 or
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QDoubleSpinBox" name="MinPID1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PID value mapped to Accessory channel = 0 or
Throttle channel lesser or equal to Throttle Min value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QDoubleSpinBox" name="MaxPID1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PID value mapped to Accessory channel = 1 or
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QDoubleSpinBox" name="MaxPID1">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PID value mapped to Accessory channel = 1 or
Throttle channel greater or equal to Throttle Max value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_48">
<property name="text">
<string>Instance 2</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="PID2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select PID option or option pair to update.
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_48">
<property name="text">
<string>Instance 2</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QComboBox" name="PID2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select PID option or option pair to update.
Set to Disabled if not used.</string>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QComboBox" name="Input2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select input used as a control source for this instance.
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QComboBox" name="Input2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select input used as a control source for this instance.
It can be one of Accessory channels or Throttle channel.
If Accessory channel is chosen then its range [0..1] will be mapped
@ -284,68 +366,68 @@ accordingly.
Note that it is possible to set PID Min &gt; Max. In that case increasing
control input value will decrease the PID option value. This can be
used, for instance, to decrease PID value when increasing Throttle.</string>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QDoubleSpinBox" name="MinPID2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PID value mapped to Accessory channel = 0 or
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QDoubleSpinBox" name="MinPID2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PID value mapped to Accessory channel = 0 or
Throttle channel lesser or equal to Throttle Min value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="3" column="4">
<widget class="QDoubleSpinBox" name="MaxPID2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PID value mapped to Accessory channel = 1 or
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="3" column="4">
<widget class="QDoubleSpinBox" name="MaxPID2">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PID value mapped to Accessory channel = 1 or
Throttle channel greater or equal to Throttle Max value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_52">
<property name="text">
<string>Instance 3</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="PID3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select PID option or option pair to update.
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="label_52">
<property name="text">
<string>Instance 3</string>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QComboBox" name="PID3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select PID option or option pair to update.
Set to Disabled if not used.</string>
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QComboBox" name="Input3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select input used as a control source for this instance.
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QComboBox" name="Input3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Select input used as a control source for this instance.
It can be one of Accessory channels or Throttle channel.
If Accessory channel is chosen then its range [0..1] will be mapped
@ -359,57 +441,57 @@ accordingly.
Note that it is possible to set PID Min &gt; Max. In that case increasing
control input value will decrease the PID option value. This can be
used, for instance, to decrease PID value when increasing Throttle.</string>
</property>
</widget>
</item>
<item row="4" column="3">
<widget class="QDoubleSpinBox" name="MinPID3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PID value mapped to Accessory channel = 0 or
</property>
</widget>
</item>
<item row="4" column="3">
<widget class="QDoubleSpinBox" name="MinPID3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Minimum PID value mapped to Accessory channel = 0 or
Throttle channel lesser or equal to Throttle Min value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="4" column="4">
<widget class="QDoubleSpinBox" name="MaxPID3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PID value mapped to Accessory channel = 1 or
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="4" column="4">
<widget class="QDoubleSpinBox" name="MaxPID3">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Maximum PID value mapped to Accessory channel = 1 or
Throttle channel greater or equal to Throttle Max value.</string>
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="8" column="0">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Update Mode</string>
</property>
</widget>
</item>
<item row="8" column="1">
<widget class="QComboBox" name="UpdateMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>PID values update mode which can be set to:
</property>
<property name="decimals">
<number>6</number>
</property>
<property name="singleStep">
<double>0.000100000000000</double>
</property>
</widget>
</item>
<item row="8" column="0">
<widget class="QLabel" name="label_2">
<property name="text">
<string>Update Mode</string>
</property>
</widget>
</item>
<item row="8" column="1">
<widget class="QComboBox" name="UpdateMode">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>PID values update mode which can be set to:
- Never: this disables PID updates (but module still will be run if enabled),
- When Armed: PID updated only when system is armed,
- Always: PID updated always regardless of arm state.
@ -419,183 +501,265 @@ tricky to change other PID values from the GUI if the module is enabled
and constantly updates stabilization settings object. As a workaround,
this option can be used to temporarily disable updates or enable them
only when system is armed without disabling the module.</string>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Throttle Range</string>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QDoubleSpinBox" name="ThrottleMin">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Throttle channel lower bound mapped to PID Min value</string>
</property>
<property name="maximum">
<double>1.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="7" column="2">
<widget class="QDoubleSpinBox" name="ThrottleMax">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Throttle channel upper bound mapped to PID Max value</string>
</property>
<property name="maximum">
<double>1.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QLabel" name="label_4">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QLabel" name="label_3">
<property name="text">
<string>Throttle Range</string>
</property>
</widget>
</item>
<item row="7" column="1">
<widget class="QDoubleSpinBox" name="ThrottleMin">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Throttle channel lower bound mapped to PID Min value</string>
</property>
<property name="maximum">
<double>1.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="7" column="2">
<widget class="QDoubleSpinBox" name="ThrottleMax">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Throttle channel upper bound mapped to PID Max value</string>
</property>
<property name="maximum">
<double>1.000000000000000</double>
</property>
<property name="singleStep">
<double>0.010000000000000</double>
</property>
</widget>
</item>
<item row="6" column="1">
<widget class="QLabel" name="label_4">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="6" column="2">
<widget class="QLabel" name="label_5">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
</property>
<property name="text">
<string>Min</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="6" column="2">
<widget class="QLabel" name="label_5">
<property name="styleSheet">
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
color: rgb(255, 255, 255);
border-radius: 5;
font: bold 12px;
margin:1px;</string>
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="5" column="1">
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</property>
<property name="text">
<string>Max</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="5" column="1">
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="message">
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="submitButtons">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="Apply">
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="Save">
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
<widget class="QGroupBox" name="groupBox_3">
<property name="title">
<string>Messages</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="message">
<property name="text">
<string/>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<widget class="QGroupBox" name="groupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>75</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>79</height>
</size>
</property>
<property name="title">
<string/>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<layout class="QHBoxLayout" name="submitButtons">
<property name="spacing">
<number>4</number>
</property>
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="pushButton">
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>button:help</string>
<string>url:http://wiki.openpilot.org/x/DACiAQ</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="Apply">
<property name="minimumSize">
<size>
<width>60</width>
<height>28</height>
</size>
</property>
<property name="toolTip">
<string>Send settings to the board but do not save to the non-volatile memory</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="Save">
<property name="minimumSize">
<size>
<width>60</width>
<height>28</height>
</size>
</property>
<property name="toolTip">
<string>Send settings to the board and save to the non-volatile memory</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Save</string>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
<tabstops>
<tabstop>TxPIDEnable</tabstop>
<tabstop>Apply</tabstop>
<tabstop>Save</tabstop>
<tabstop>scrollArea</tabstop>
@ -615,6 +779,8 @@ margin:1px;</string>
<tabstop>ThrottleMax</tabstop>
<tabstop>UpdateMode</tabstop>
</tabstops>
<resources/>
<resources>
<include location="../coreplugin/core.qrc"/>
</resources>
<connections/>
</ui>

View File

@ -2,21 +2,11 @@
<General>
<AutoConnect>true</AutoConnect>
<AutoSelect>true</AutoSelect>
<LastPreferenceCategory>LineardialGadget</LastPreferenceCategory>
<LastPreferencePage>Mainboard CPU</LastPreferencePage>
<ExpertMode>false</ExpertMode>
<OverrideLanguage>en_AU</OverrideLanguage>
<SaveSettingsOnExit>true</SaveSettingsOnExit>
<SettingsWindowHeight>476</SettingsWindowHeight>
<SettingsWindowWidth>697</SettingsWindowWidth>
<UDPMirror>false</UDPMirror>
</General>
<IPconnection>
<Current>
<arr_1>
<Port>1</Port>
<UseTCP>0</UseTCP>
</arr_1>
<size>1</size>
</Current>
</IPconnection>
<KeyBindings>
<size>0</size>
</KeyBindings>
@ -31,11 +21,9 @@
<Mode3>89</Mode3>
<Mode4>88</Mode4>
<Mode5>87</Mode5>
<Mode6>86</Mode6>
<Welcome>100</Welcome>
</ModePriorities>
<SerialConnection>
<speed>57600</speed>
</SerialConnection>
<UAVGadgetConfigurations>
<ConfigGadget>
<default>
@ -858,6 +846,7 @@
<channel5Reverse>false</channel5Reverse>
<channel6Reverse>false</channel6Reverse>
<channel7Reverse>false</channel7Reverse>
<controlPortUDP>0</controlPortUDP>
<controlsMode>2</controlsMode>
<pitchChannel>1</pitchChannel>
<rollChannel>0</rollChannel>
@ -2383,9 +2372,13 @@
<version>0.0.0</version>
</configInfo>
<data>
<CategorizedView>false</CategorizedView>
<ScientificView>false</ScientificView>
<manuallyChangedColor>#5baa56</manuallyChangedColor>
<onlyHilightChangedValues>false</onlyHilightChangedValues>
<recentlyUpdatedColor>#ff7957</recentlyUpdatedColor>
<recentlyUpdatedTimeout>500</recentlyUpdatedTimeout>
<showMetaData>false</showMetaData>
</data>
</default>
</UAVObjectBrowser>
@ -2418,45 +2411,45 @@
<side0>
<side0>
<side0>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Flight Time</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>GPS Sats</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Flight Time</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Flight mode</activeConfiguration>
<activeConfiguration>Arm Status</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Arm Status</activeConfiguration>
</gadget>
<type>uavGadget</type>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Flight mode</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>GPS Sats</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAoAAAAAIAAACk)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAmQAAAAIAAAFC)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAA1wAAAAIAAADt)</splitterSizes>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAmQAAAAIAAAHc)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
@ -2466,8 +2459,8 @@
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAkAAAAAIAAAJg)</splitterSizes>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAG4)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
@ -2479,224 +2472,48 @@
<type>uavGadget</type>
</side0>
<side1>
<side0>
<side0>
<classId>SystemHealthGadget</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Mainboard CPU</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAACB)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Telemetry RX Rate Horizontal</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Telemetry TX Rate Horizontal</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABJQAAAAIAAABA)</splitterSizes>
<type>splitter</type>
<classId>SystemHealthGadget</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABMAAAAAIAAAGx)</splitterSizes>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABIAAAAAIAAAFV)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABxQAAAAIAAAFH)</splitterSizes>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB7wAAAAIAAAEf)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>OPMapGadget</classId>
<gadget>
<activeConfiguration>Google Sat</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<side0>
<side0>
<side0>
<side0>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Groundspeed kph</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Barometer</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Attitude</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Compass</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAgwAAAAIAAACK)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Baro Altimeter</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>DialGadget</classId>
<gadget>
<activeConfiguration>Deluxe Climbrate</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABFQAAAAIAAACH)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Throttle</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Roll Desired</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Pitch Desired</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Yaw Desired</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAE3)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAF4)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAG5)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABuQAAAAIAAAED)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB7AAAAAIAAAEg)</splitterSizes>
<type>splitter</type>
<classId>OPMapGadget</classId>
<gadget>
<activeConfiguration>Google Sat</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAC4gAAAAIAAAK9)</splitterSizes>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACdgAAAAIAAAMp)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode1>
<Mode2>
<showToolbars>false</showToolbars>
<splitter>
<classId>ConfigGadget</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode2>
<Mode3>
<showToolbars>false</showToolbars>
<splitter>
<side0>
<side0>
<classId>ConfigGadget</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Telemetry RX Rate Horizontal</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Telemetry TX Rate Horizontal</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACNQAAAAIAAABC)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>UAVObjectBrowser</classId>
<gadget>
@ -2705,23 +2522,33 @@
<type>uavGadget</type>
</side0>
<side1>
<classId>GCSControlGadget</classId>
<gadget>
<activeConfiguration>MS Sidewinder</activeConfiguration>
</gadget>
<classId>DebugGadget</classId>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABqgAAAAIAAAFi)</splitterSizes>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<side0>
<classId>EmptyGadget</classId>
<type>uavGadget</type>
</side0>
<side1>
<classId>EmptyGadget</classId>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAC3gAAAAIAAAJ3)</splitterSizes>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAACJgAAAAIAAADo)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode2>
<Mode3>
</Mode3>
<Mode4>
<showToolbars>false</showToolbars>
<splitter>
<side0>
@ -2776,8 +2603,8 @@
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode3>
<Mode4>
</Mode4>
<Mode5>
<showToolbars>false</showToolbars>
<splitter>
<side0>
@ -2789,66 +2616,39 @@
<type>uavGadget</type>
</side0>
<side1>
<side0>
<classId>GCSControlGadget</classId>
<gadget>
<activeConfiguration>MS Sidewinder</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<side0>
<side0>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Pitch Desired</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>PitchActual</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>Pitch</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABFAAAAAIAAABA)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB6AAAAAIAAADC)</splitterSizes>
<type>splitter</type>
<classId>HITLv2</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABaQAAAAIAAAEO)</splitterSizes>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<type>splitter</type>
</side0>
<side1>
<classId>UAVObjectBrowser</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
<side0>
<classId>EmptyGadget</classId>
<type>uavGadget</type>
</side0>
<side1>
<classId>GCSControlGadget</classId>
<gadget>
<activeConfiguration>MS Sidewinder</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAAB6AAAAAIAAADC)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADDAAAAAIAAAJJ)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode4>
<Mode5>
</Mode5>
<Mode6>
<showToolbars>false</showToolbars>
<splitter>
<side0>
@ -2861,16 +2661,16 @@
<side1>
<side0>
<side0>
<classId>SystemHealthGadget</classId>
<classId>LineardialGadget</classId>
<gadget>
<activeConfiguration>default</activeConfiguration>
<activeConfiguration>Flight Time</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side0>
<side1>
<classId>PFDGadget</classId>
<classId>SystemHealthGadget</classId>
<gadget>
<activeConfiguration>raw</activeConfiguration>
<activeConfiguration>default</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
@ -2879,44 +2679,44 @@
<type>splitter</type>
</side0>
<side1>
<classId>ScopeGadget</classId>
<classId>PFDGadget</classId>
<gadget>
<activeConfiguration>Uptimes</activeConfiguration>
<activeConfiguration>raw</activeConfiguration>
</gadget>
<type>uavGadget</type>
</side1>
<splitterOrientation>2</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABEgAAAAIAAAH6)</splitterSizes>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAABLwAAAAIAAAHf)</splitterSizes>
<type>splitter</type>
</side1>
<splitterOrientation>1</splitterOrientation>
<splitterSizes>@Variant(AAAACQAAAAA=)</splitterSizes>
<splitterSizes>@Variant(AAAACQAAAAIAAAACAAADVQAAAAIAAAJK)</splitterSizes>
<type>splitter</type>
</splitter>
<version>UAVGadgetManagerV1</version>
</Mode5>
</Mode6>
</UAVGadgetManager>
<Workspace>
<AllowTabBarMovement>false</AllowTabBarMovement>
<Icon1>:\core\images\ah.png</Icon1>
<Icon10>:/core/images/openpilot_logo_64.png</Icon10>
<Icon2>:/core/images/config.png</Icon2>
<Icon3>:/core/images/scopes.png</Icon3>
<Icon4>:/core/images/joystick.png</Icon4>
<Icon5>:/core/images/cog.png</Icon5>
<Icon6>:/core/images/openpilot_logo_64.png</Icon6>
<Icon3>:/core/images/cpu.png</Icon3>
<Icon4>:/core/images/scopes.png</Icon4>
<Icon5>:/core/images/joystick.png</Icon5>
<Icon6>:/core/images/cog.png</Icon6>
<Icon7>:/core/images/openpilot_logo_64.png</Icon7>
<Icon8>:/core/images/openpilot_logo_64.png</Icon8>
<Icon9>:/core/images/openpilot_logo_64.png</Icon9>
<NumberOfWorkspaces>5</NumberOfWorkspaces>
<NumberOfWorkspaces>6</NumberOfWorkspaces>
<TabBarPlacementIndex>1</TabBarPlacementIndex>
<Workspace1>Flight data</Workspace1>
<Workspace10>Workspace10</Workspace10>
<Workspace2>Configuration</Workspace2>
<Workspace3>Scopes</Workspace3>
<Workspace4>HITL</Workspace4>
<Workspace5>Firmware</Workspace5>
<Workspace6>Workspace6</Workspace6>
<Workspace3>System</Workspace3>
<Workspace4>Scopes</Workspace4>
<Workspace5>HITL</Workspace5>
<Workspace6>Firmware</Workspace6>
<Workspace7>Workspace7</Workspace7>
<Workspace8>Workspace8</Workspace8>
<Workspace9>Workspace9</Workspace9>

View File

@ -81,7 +81,7 @@ ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow, QTabWidge
// modeStack->insertCornerWidget(modeStack->cornerWidgetCount()-1, this);
modeStack->setCornerWidget(this, Qt::TopRightCorner);
QObject::connect(m_connectBtn, SIGNAL(pressed()), this, SLOT(onConnectPressed()));
QObject::connect(m_connectBtn, SIGNAL(clicked()), this, SLOT(onConnectClicked()));
}
ConnectionManager::~ConnectionManager()
@ -224,9 +224,9 @@ void ConnectionManager::onConnectionDestroyed(QObject *obj) // Pip
}
/**
* Slot called when the user pressed the connect/disconnect button
* Slot called when the user clicks the connect/disconnect button
*/
void ConnectionManager::onConnectPressed()
void ConnectionManager::onConnectClicked()
{
// Check if we have a ioDev already created:
if (!m_ioDev)

View File

@ -93,7 +93,7 @@ private slots:
void objectAdded(QObject *obj);
void aboutToRemoveObject(QObject *obj);
void onConnectPressed();
void onConnectClicked();
void devChanged(IConnection *connection);
// void onConnectionClosed(QObject *obj);

View File

@ -61,5 +61,6 @@
<file>images/cog.png</file>
<file>OpenPilotGCS.xml</file>
<file>images/helpicon.svg</file>
<file>images/cpu.png</file>
</qresource>
</RCC>

View File

@ -47,7 +47,7 @@ const char * const GCS_VERSION_CODENAME = "Pascal";
const char * const GCS_VERSION_LONG = GCS_VERSION;
const char * const GCS_AUTHOR = "OpenPilot Project";
const char * const GCS_YEAR = "2011";
const char * const GCS_YEAR = "2012";
const char * const GCS_HELP = "http://wiki.openpilot.org";
#ifdef GCS_REVISION

View File

@ -29,7 +29,7 @@
#include "coreplugin.h"
#include "coreimpl.h"
#include "mainwindow.h"
#include <QtPlugin>
#include <extensionsystem/pluginmanager.h>
#include <QtCore/QtPlugin>
@ -78,4 +78,4 @@ void CorePlugin::shutdown()
m_mainWindow->shutdown();
}
Q_EXPORT_PLUGIN(CorePlugin)
Q_EXPORT_PLUGIN2(Core,CorePlugin)

View File

@ -39,6 +39,7 @@
#include <QtCore/QSettings>
#include "ui_generalsettings.h"
#include <QKeyEvent>
using namespace Utils;
using namespace Core::Internal;
@ -47,7 +48,9 @@ GeneralSettings::GeneralSettings():
m_saveSettingsOnExit(true),
m_dialog(0),
m_autoConnect(true),
m_autoSelect(true)
m_autoSelect(true),
m_useUDPMirror(false),
m_useExpertMode(false)
{
}
@ -107,18 +110,24 @@ void GeneralSettings::fillLanguageBox() const
}
}
QWidget *GeneralSettings::createPage(QWidget *parent)
{
m_page = new Ui::GeneralSettings();
QWidget *w = new QWidget(parent);
globalSettingsWidget *w = new globalSettingsWidget(parent);
connect(w,SIGNAL(showHidden()),this,SLOT(showHidden()));
m_page->setupUi(w);
m_page->labelUDP->setVisible(false);
m_page->cbUseUDPMirror->setVisible(false);
m_page->labelExpert->setVisible(false);
m_page->cbExpertMode->setVisible(false);
fillLanguageBox();
connect(m_page->checkAutoConnect,SIGNAL(stateChanged(int)),this,SLOT(slotAutoConnect(int)));
m_page->checkBoxSaveOnExit->setChecked(m_saveSettingsOnExit);
m_page->checkAutoConnect->setChecked(m_autoConnect);
m_page->checkAutoSelect->setChecked(m_autoSelect);
m_page->cbUseUDPMirror->setChecked(m_useUDPMirror);
m_page->cbExpertMode->setChecked(m_useExpertMode);
m_page->colorButton->setColor(StyleHelper::baseColor());
connect(m_page->resetButton, SIGNAL(clicked()),
@ -135,6 +144,8 @@ void GeneralSettings::apply()
StyleHelper::setBaseColor(m_page->colorButton->color());
m_saveSettingsOnExit = m_page->checkBoxSaveOnExit->isChecked();
m_useUDPMirror=m_page->cbUseUDPMirror->isChecked();
m_useExpertMode=m_page->cbExpertMode->isChecked();
m_autoConnect = m_page->checkAutoConnect->isChecked();
m_autoSelect = m_page->checkAutoSelect->isChecked();
}
@ -151,6 +162,8 @@ void GeneralSettings::readSettings(QSettings* qs)
m_saveSettingsOnExit = qs->value(QLatin1String("SaveSettingsOnExit"),m_saveSettingsOnExit).toBool();
m_autoConnect = qs->value(QLatin1String("AutoConnect"),m_autoConnect).toBool();
m_autoSelect = qs->value(QLatin1String("AutoSelect"),m_autoSelect).toBool();
m_useUDPMirror = qs->value(QLatin1String("UDPMirror"),m_useUDPMirror).toBool();
m_useExpertMode = qs->value(QLatin1String("ExpertMode"),m_useExpertMode).toBool();
qs->endGroup();
}
@ -166,6 +179,8 @@ void GeneralSettings::saveSettings(QSettings* qs)
qs->setValue(QLatin1String("SaveSettingsOnExit"), m_saveSettingsOnExit);
qs->setValue(QLatin1String("AutoConnect"), m_autoConnect);
qs->setValue(QLatin1String("AutoSelect"), m_autoSelect);
qs->setValue(QLatin1String("UDPMirror"), m_useUDPMirror);
qs->setValue(QLatin1String("ExpertMode"), m_useExpertMode);
qs->endGroup();
}
@ -231,6 +246,16 @@ bool GeneralSettings::autoSelect() const
return m_autoSelect;
}
bool GeneralSettings::useUDPMirror() const
{
return m_useUDPMirror;
}
bool GeneralSettings::useExpertMode() const
{
return m_useExpertMode;
}
void GeneralSettings::slotAutoConnect(int value)
{
if (value==Qt::Checked)
@ -238,3 +263,21 @@ void GeneralSettings::slotAutoConnect(int value)
else
m_page->checkAutoSelect->setEnabled(true);
}
void GeneralSettings::showHidden()
{
m_page->labelUDP->setVisible(true);
m_page->cbUseUDPMirror->setVisible(true);
m_page->labelExpert->setVisible(true);
m_page->cbExpertMode->setVisible(true);
}
globalSettingsWidget::globalSettingsWidget(QWidget *parent):QWidget(parent){}
void globalSettingsWidget::keyPressEvent(QKeyEvent *event)
{
if(event->key()==Qt::Key_F7)
{
emit showHidden();
}
}

View File

@ -41,7 +41,7 @@ namespace Ui {
class GeneralSettings;
}
class GeneralSettings : public IOptionsPage
class CORE_EXPORT GeneralSettings : public IOptionsPage
{
Q_OBJECT
@ -58,9 +58,10 @@ public:
bool saveSettingsOnExit() const;
bool autoConnect() const;
bool autoSelect() const;
bool useUDPMirror() const;
void readSettings(QSettings* qs);
void saveSettings(QSettings* qs);
bool useExpertMode() const;
signals:
private slots:
@ -68,6 +69,7 @@ private slots:
void resetLanguage();
void showHelpForExternalEditor();
void slotAutoConnect(int);
void showHidden();
private:
void fillLanguageBox() const;
@ -78,10 +80,22 @@ private:
bool m_saveSettingsOnExit;
bool m_autoConnect;
bool m_autoSelect;
bool m_useUDPMirror;
bool m_useExpertMode;
QPointer<QWidget> m_dialog;
QList<QTextCodec *> m_codecs;
};
class globalSettingsWidget:public QWidget
{
Q_OBJECT
public:
globalSettingsWidget(QWidget * parent);
protected:
void keyPressEvent(QKeyEvent *);
signals:
void showHidden();
};
} // namespace Internal
} // namespace Core

View File

@ -178,6 +178,34 @@
</property>
</widget>
</item>
<item row="12" column="1">
<widget class="QCheckBox" name="cbUseUDPMirror">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="12" column="0">
<widget class="QLabel" name="labelUDP">
<property name="text">
<string>Use UDP Mirror</string>
</property>
</widget>
</item>
<item row="13" column="0">
<widget class="QLabel" name="labelExpert">
<property name="text">
<string>Expert Mode</string>
</property>
</widget>
</item>
<item row="13" column="1">
<widget class="QCheckBox" name="cbExpertMode">
<property name="text">
<string/>
</property>
</widget>
</item>
</layout>
</widget>
</item>

Binary file not shown.

After

Width:  |  Height:  |  Size: 635 B

View File

@ -76,7 +76,7 @@ VersionDialog::VersionDialog(QWidget *parent)
"<br/>"
"%8"
"<br/>"
"Copyright 2008-%6 %7. All rights reserved.<br/>"
"Copyright 2010-%6 %7. All rights reserved.<br/>"
"<br/>"
"<small>This program is free software; you can redistribute it and/or modify<br/>"
"it under the terms of the GNU General Public License as published by<br/>"

View File

@ -38,13 +38,7 @@ const quint16 DBG_BUFFER_MAX_SIZE = 4096;
#define OBSOLETE_MIT_CHECKBOX (1 << 1)
#define OBSOLETE_MIT_SEPARATOR (1 << 7)
#if defined(Q_CC_MSVC)
#define PACK_STRUCT
#define MAX_PATH 260
#pragma pack (push, r1, 1)
#elif defined(Q_CC_GNU)
#define PACK_STRUCT __attribute__((packed))
#endif
struct simToPlugin
{
@ -207,9 +201,6 @@ struct pluginInit
const char *strOutputFolder;
} PACK_STRUCT ; // normal - 144, packed - 144 OK (3.81 & 3.83 & 3.90)
#ifdef Q_CC_MSVC
#pragma pack (pop, r1)
#endif
#undef PACK_STRUCT
#endif // AEROSIMRCDATASTRUCT_H

View File

@ -15,12 +15,6 @@ SIM_DIR = $$GCS_BUILD_TREE/../AeroSIM-RC
PLUGIN_DIR = $$SIM_DIR/Plugin/CopterControl
DLLDESTDIR = $$PLUGIN_DIR
# Don't depend on MSVRT*.dll
win32-msvc* {
QMAKE_CXXFLAGS_RELEASE -= -MD
QMAKE_CXXFLAGS_MT_DLL += -MT
}
HEADERS = \
aerosimrcdatastruct.h \
enums.h \
@ -57,14 +51,20 @@ equals(copydata, 1) {
# Qt DLLs
QT_DLLS = \
libgcc_s_dw2-1.dll \
mingwm10.dll \
QtCore4.dll \
QtNetwork4.dll
for(dll, QT_DLLS) {
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/$$dll\") $$targetPath(\"$$SIM_DIR/$$dll\") $$addNewline()
}
# MinGW DLLs
MINGW_DLLS = \
libgcc_s_dw2-1.dll \
mingwm10.dll
for(dll, MINGW_DLLS) {
data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/../../../../../mingw/bin/$$dll\") $$targetPath(\"$$SIM_DIR/$$dll\") $$addNewline()
}
data_copy.target = FORCE
QMAKE_EXTRA_TARGETS += data_copy
}

View File

@ -31,9 +31,6 @@
#include <QWidget>
#include <QUdpSocket>
#include <QTime>
#if defined(Q_CC_MSVC)
#define _USE_MATH_DEFINES
#endif
#include <qmath.h>
#include <QVector3D>
#include <QMatrix4x4>

View File

@ -1,512 +0,0 @@
/**
******************************************************************************
*
* @file notifypluginoptionspage.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Notify Plugin options page
* @see The GNU Public License (GPL) Version 3
* @defgroup notifyplugin
* @{
*
*****************************************************************************/
/*
* 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 "notifypluginoptionspage.h"
#include <coreplugin/icore.h>
#include "notificationitem.h"
#include "ui_notifypluginoptionspage.h"
#include "extensionsystem/pluginmanager.h"
#include "utils/pathutils.h"
#include <QFileDialog>
#include <QtAlgorithms>
#include <QStringList>
#include <QtCore/QSettings>
#include <QTableWidget>
#include <QPalette>
#include <QBuffer>
#include "notifyplugin.h"
#include "notifyitemdelegate.h"
#include "notifytablemodel.h"
#include "notifylogging.h"
NotifyPluginOptionsPage::NotifyPluginOptionsPage(/*NotificationItem *config,*/ QObject *parent)
: IOptionsPage(parent)
, objManager(*ExtensionSystem::PluginManager::instance()->getObject<UAVObjectManager>())
, owner(qobject_cast<SoundNotifyPlugin*>(parent))
, currentCollectionPath("")
{
}
NotifyPluginOptionsPage::~NotifyPluginOptionsPage()
{
}
//creates options page widget (uses the UI file)
QWidget *NotifyPluginOptionsPage::createPage(QWidget *parent)
{
options_page.reset(new Ui::NotifyPluginOptionsPage());
//main widget
QWidget *optionsPageWidget = new QWidget;
//main layout
options_page->setupUi(optionsPageWidget);
listSoundFiles.clear();
options_page->SoundDirectoryPathChooser->setExpectedKind(Utils::PathChooser::Directory);
options_page->SoundDirectoryPathChooser->setPromptDialogTitle(tr("Choose sound collection directory"));
// Fills the combo boxes for the UAVObjects
QList< QList<UAVDataObject*> > objList = objManager.getDataObjects();
foreach (QList<UAVDataObject*> list, objList) {
foreach (UAVDataObject* obj, list) {
options_page->UAVObject->addItem(obj->getName());
}
}
<<<<<<< Updated upstream
connect(options_page->SoundDirectoryPathChooser, SIGNAL(changed(const QString&)), this, SLOT(on_buttonSoundFolder_clicked(const QString&)));
connect(options_page->SoundCollectionList, SIGNAL(currentIndexChanged (int)), this, SLOT(on_soundLanguage_indexChanged(int)));
connect(options_page->UAVObject, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_UAVObject_indexChanged(QString)));
=======
options_page = new Ui::NotifyPluginOptionsPage();
//main widget
QWidget *optionsPageWidget = new QWidget;
//main layout
options_page->setupUi(optionsPageWidget);
delegateItems.clear();
listSoundFiles.clear();
options_page->horizontalLayout_3->addWidget(new QPushButton("testtt"));
delegateItems << "Repeat Once"
<< "Repeat Instantly"
<< "Repeat 10 seconds"
<< "Repeat 30 seconds"
<< "Repeat 1 minute";
options_page->chkEnableSound->setChecked(owner->getEnableSound());
options_page->SoundDirectoryPathChooser->setExpectedKind(Utils::PathChooser::Directory);
options_page->SoundDirectoryPathChooser->setPromptDialogTitle(tr("Choose sound collection directory"));
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
objManager = pm->getObject<UAVObjectManager>();
// Fills the combo boxes for the UAVObjects
QList< QList<UAVDataObject*> > objList = objManager->getDataObjects();
foreach (QList<UAVDataObject*> list, objList) {
foreach (UAVDataObject* obj, list) {
options_page->UAVObject->addItem(obj->getName());
}
}
connect(options_page->SoundDirectoryPathChooser, SIGNAL(changed(const QString&)), this, SLOT(on_buttonSoundFolder_clicked(const QString&)));
connect(options_page->SoundCollectionList, SIGNAL(currentIndexChanged (int)), this, SLOT(on_soundLanguage_indexChanged(int)));
connect(options_page->buttonAdd, SIGNAL(pressed()), this, SLOT(on_buttonAddNotification_clicked()));
connect(options_page->buttonDelete, SIGNAL(pressed()), this, SLOT(on_buttonDeleteNotification_clicked()));
connect(options_page->buttonModify, SIGNAL(pressed()), this, SLOT(on_buttonModifyNotification_clicked()));
// connect(options_page->buttonTestSound1, SIGNAL(clicked()), this, SLOT(on_buttonTestSound1_clicked()));
// connect(options_page->buttonTestSound2, SIGNAL(clicked()), this, SLOT(on_buttonTestSound2_clicked()));
connect(options_page->buttonPlayNotification, SIGNAL(clicked()), this, SLOT(on_buttonTestSoundNotification_clicked()));
connect(options_page->chkEnableSound, SIGNAL(toggled(bool)), this, SLOT(on_chkEnableSound_toggled(bool)));
connect(options_page->UAVObject, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_UAVObject_indexChanged(QString)));
connect(this, SIGNAL(updateNotifications(QList<NotifyPluginConfiguration*>)),
owner, SLOT(updateNotificationList(QList<NotifyPluginConfiguration*>)));
connect(this, SIGNAL(resetNotification()),owner, SLOT(resetNotification()));
//emit resetNotification();
privListNotifications.clear();
for (int i = 0; i < owner->getListNotifications().size(); ++i) {
NotifyPluginConfiguration* notification = new NotifyPluginConfiguration();
owner->getListNotifications().at(i)->copyTo(notification);
privListNotifications.append(notification);
}
updateConfigView(owner->getCurrentNotification());
options_page->chkEnableSound->setChecked(owner->getEnableSound());
QStringList headerStrings;
headerStrings << "Name" << "Repeats" << "Lifetime,sec";
>>>>>>> Stashed changes
connect(this, SIGNAL(updateNotifications(QList<NotificationItem*>)),
owner, SLOT(updateNotificationList(QList<NotificationItem*>)));
//connect(this, SIGNAL(resetNotification()),owner, SLOT(resetNotification()));
// privListNotifications = ((qobject_cast<SoundNotifyPlugin*>(parent))->getListNotifications());
privListNotifications = owner->getListNotifications();
updateConfigView(owner->getCurrentNotification());
initRulesTable();
initButtons();
initPhononPlayer();
return optionsPageWidget;
}
void NotifyPluginOptionsPage::initButtons()
{
options_page->chkEnableSound->setChecked(owner->getEnableSound());
connect(options_page->chkEnableSound, SIGNAL(toggled(bool)), this, SLOT(on_chkEnableSound_toggled(bool)));
options_page->buttonModify->setEnabled(false);
options_page->buttonDelete->setEnabled(false);
options_page->buttonPlayNotification->setEnabled(false);
connect(options_page->buttonAdd, SIGNAL(pressed()), this, SLOT(on_buttonAddNotification_clicked()));
connect(options_page->buttonDelete, SIGNAL(pressed()), this, SLOT(on_buttonDeleteNotification_clicked()));
connect(options_page->buttonModify, SIGNAL(pressed()), this, SLOT(on_buttonModifyNotification_clicked()));
connect(options_page->buttonPlayNotification, SIGNAL(clicked()), this, SLOT(on_buttonTestSoundNotification_clicked()));
}
void NotifyPluginOptionsPage::initPhononPlayer()
{
notifySound.reset(Phonon::createPlayer(Phonon::NotificationCategory));
connect(notifySound.data(),SIGNAL(stateChanged(Phonon::State,Phonon::State)),
this,SLOT(changeButtonText(Phonon::State,Phonon::State)));
connect(notifySound.data(), SIGNAL(finished(void)), this, SLOT(onFinishedPlaying(void)));
}
void NotifyPluginOptionsPage::initRulesTable()
{
qNotifyDebug_if(_notifyRulesModel.isNull()) << "_notifyRulesModel.isNull())";
qNotifyDebug_if(!_notifyRulesSelection) << "_notifyRulesSelection.isNull())";
//QItemSelectionModel* selection = _notifyRulesSelection.take();
_notifyRulesModel.reset(new NotifyTableModel(privListNotifications));
_notifyRulesSelection = new QItemSelectionModel(_notifyRulesModel.data());
connect(_notifyRulesSelection, SIGNAL(selectionChanged ( const QItemSelection &, const QItemSelection & )),
this, SLOT(on_tableNotification_changeSelection( const QItemSelection & , const QItemSelection & )));
connect(this, SIGNAL(entryUpdated(int)),
_notifyRulesModel.data(), SLOT(entryUpdated(int)));
connect(this, SIGNAL(entryAdded(int)),
_notifyRulesModel.data(), SLOT(entryAdded(int)));
options_page->notifyRulesView->setModel(_notifyRulesModel.data());
options_page->notifyRulesView->setSelectionModel(_notifyRulesSelection);
options_page->notifyRulesView->setItemDelegate(new NotifyItemDelegate(this));
options_page->notifyRulesView->resizeRowsToContents();
options_page->notifyRulesView->setColumnWidth(eMESSAGE_NAME,200);
options_page->notifyRulesView->setColumnWidth(eREPEAT_VALUE,120);
options_page->notifyRulesView->setColumnWidth(eEXPIRE_TIME,100);
options_page->notifyRulesView->setColumnWidth(eENABLE_NOTIFICATION,60);
options_page->notifyRulesView->setDragEnabled(true);
options_page->notifyRulesView->setAcceptDrops(true);
options_page->notifyRulesView->setDropIndicatorShown(true);
options_page->notifyRulesView->setDragDropMode(QAbstractItemView::InternalMove);
}
void NotifyPluginOptionsPage::getOptionsPageValues(NotificationItem* notification)
{
notification->setSoundCollectionPath(options_page->SoundDirectoryPathChooser->path());
notification->setCurrentLanguage(options_page->SoundCollectionList->currentText());
notification->setDataObject(options_page->UAVObject->currentText());
notification->setObjectField(options_page->UAVObjectField->currentText());
notification->setSound1(options_page->Sound1->currentText());
notification->setSound2(options_page->Sound2->currentText());
notification->setSound3(options_page->Sound3->currentText());
notification->setSayOrder(options_page->SayOrder->currentText());
notification->setValue(options_page->Value->currentText());
notification->setSpinBoxValue(options_page->ValueSpinBox->value());
}
/*!
* Called when the user presses apply or OK.
* Saves the current values
*/
void NotifyPluginOptionsPage::apply()
{
getOptionsPageValues(owner->getCurrentNotification());
owner->setEnableSound(options_page->chkEnableSound->isChecked());
emit updateNotifications(privListNotifications);
}
void NotifyPluginOptionsPage::finish()
{
disconnect(notifySound.data(),SIGNAL(stateChanged(Phonon::State,Phonon::State)),
this,SLOT(changeButtonText(Phonon::State,Phonon::State)));
if (notifySound) {
notifySound->stop();
notifySound->clear();
}
}
//////////////////////////////////////////////////////////////////////////////
// Fills in the <Field> combo box when value is changed in the
// <Object> combo box
//////////////////////////////////////////////////////////////////////////////
void NotifyPluginOptionsPage::on_UAVObject_indexChanged(QString val) {
options_page->UAVObjectField->clear();
ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager* objManager = pm->getObject<UAVObjectManager>();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>( objManager->getObject(val) );
QList<UAVObjectField*> fieldList = obj->getFields();
foreach (UAVObjectField* field, fieldList) {
options_page->UAVObjectField->addItem(field->getName());
}
}
// locate collection folder on disk
void NotifyPluginOptionsPage::on_buttonSoundFolder_clicked(const QString& path)
{
QDir dirPath(path);
listDirCollections = dirPath.entryList(QDir::AllDirs | QDir::NoDotAndDotDot);
options_page->SoundCollectionList->clear();
options_page->SoundCollectionList->addItems(listDirCollections);
}
void NotifyPluginOptionsPage::on_soundLanguage_indexChanged(int index)
{
options_page->SoundCollectionList->setCurrentIndex(index);
currentCollectionPath = options_page->SoundDirectoryPathChooser->path()
+ QDir::toNativeSeparators("/" + options_page->SoundCollectionList->currentText());
QDir dirPath(currentCollectionPath);
QStringList filters;
filters << "*.mp3" << "*.wav";
dirPath.setNameFilters(filters);
listSoundFiles = dirPath.entryList(filters);
listSoundFiles.replaceInStrings(QRegExp(".mp3|.wav"), "");
options_page->Sound1->clear();
options_page->Sound2->clear();
options_page->Sound3->clear();
options_page->Sound1->addItems(listSoundFiles);
options_page->Sound2->addItem("");
options_page->Sound2->addItems(listSoundFiles);
options_page->Sound3->addItem("");
options_page->Sound3->addItems(listSoundFiles);
}
void NotifyPluginOptionsPage::changeButtonText(Phonon::State newstate, Phonon::State oldstate)
{
//Q_ASSERT(Phonon::ErrorState != newstate);
if (newstate == Phonon::PausedState || newstate == Phonon::StoppedState) {
options_page->buttonPlayNotification->setText("Play");
options_page->buttonPlayNotification->setIcon(QPixmap(":/notify/images/play.png"));
} else {
if (newstate == Phonon::PlayingState) {
options_page->buttonPlayNotification->setText("Stop");
options_page->buttonPlayNotification->setIcon(QPixmap(":/notify/images/stop.png"));
}
}
}
void NotifyPluginOptionsPage::onFinishedPlaying()
{
notifySound->clear();
}
void NotifyPluginOptionsPage::on_buttonTestSoundNotification_clicked()
{
NotificationItem* notification = NULL;
if (-1 == _notifyRulesSelection->currentIndex().row())
return;
notifySound->clearQueue();
notification = privListNotifications.at(_notifyRulesSelection->currentIndex().row());
notification->parseNotifyMessage();
QStringList sequence = notification->getMessageSequence();
Q_ASSERT(!!sequence.size());
foreach(QString item, sequence)
notifySound->enqueue(Phonon::MediaSource(item));
notifySound->play();
}
void NotifyPluginOptionsPage::on_chkEnableSound_toggled(bool state)
{
bool state1 = 1^state;
QList<Phonon::Path> listOutputs = notifySound->outputPaths();
Phonon::AudioOutput * audioOutput = (Phonon::AudioOutput*)listOutputs.last().sink();
audioOutput->setMuted(state1);
}
void NotifyPluginOptionsPage::updateConfigView(NotificationItem* notification)
{
QString path = notification->getSoundCollectionPath();
if (path == "") {
//QDir dir = QDir::currentPath();
//path = QDir::currentPath().left(QDir::currentPath().indexOf("OpenPilot",0,Qt::CaseSensitive))+"../share/sounds";
path = Utils::PathUtils().InsertDataPath("%%DATAPATH%%sounds");
}
options_page->SoundDirectoryPathChooser->setPath(path);
if (-1 != options_page->SoundCollectionList->findText(notification->getCurrentLanguage())){
options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText(notification->getCurrentLanguage()));
} else {
options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default"));
}
if (options_page->UAVObject->findText(notification->getDataObject())!=-1){
options_page->UAVObject->setCurrentIndex(options_page->UAVObject->findText(notification->getDataObject()));
}
// Now load the object field values:
options_page->UAVObjectField->clear();
QString uavDataObject = notification->getDataObject();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(objManager.getObject(uavDataObject));
if (obj != NULL ) {
QList<UAVObjectField*> fieldList = obj->getFields();
foreach (UAVObjectField* field, fieldList) {
options_page->UAVObjectField->addItem(field->getName());
}
}
if (-1 != options_page->UAVObjectField->findText(notification->getObjectField())) {
options_page->UAVObjectField->setCurrentIndex(options_page->UAVObjectField->findText(notification->getObjectField()));
}
if (-1 != options_page->Sound1->findText(notification->getSound1())) {
options_page->Sound1->setCurrentIndex(options_page->Sound1->findText(notification->getSound1()));
} else {
// show item from default location
options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default"));
options_page->Sound1->setCurrentIndex(options_page->Sound1->findText(notification->getSound1()));
// don't show item if it wasn't find in stored location
//options_page->Sound1->setCurrentIndex(-1);
}
if (-1 != options_page->Sound2->findText(notification->getSound2())) {
options_page->Sound2->setCurrentIndex(options_page->Sound2->findText(notification->getSound2()));
} else {
// show item from default location
options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default"));
options_page->Sound2->setCurrentIndex(options_page->Sound2->findText(notification->getSound2()));
// don't show item if it wasn't find in stored location
//options_page->Sound2->setCurrentIndex(-1);
}
if (-1 != options_page->Sound3->findText(notification->getSound3())) {
options_page->Sound3->setCurrentIndex(options_page->Sound3->findText(notification->getSound3()));
} else {
// show item from default location
options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default"));
options_page->Sound3->setCurrentIndex(options_page->Sound3->findText(notification->getSound3()));
}
if (-1 != options_page->Value->findText(notification->getValue())) {
options_page->Value->setCurrentIndex(options_page->Value->findText(notification->getValue()));
}
if (-1 != options_page->SayOrder->findText(notification->getSayOrder())) {
options_page->SayOrder->setCurrentIndex(options_page->SayOrder->findText(notification->getSayOrder()));
}
options_page->ValueSpinBox->setValue(notification->getSpinBoxValue());
}
void NotifyPluginOptionsPage::on_tableNotification_changeSelection( const QItemSelection & selected, const QItemSelection & deselected )
{
bool select = false;
notifySound->stop();
if (selected.indexes().size()) {
select = true;
updateConfigView(privListNotifications.at(selected.indexes().at(0).row()));
}
options_page->buttonModify->setEnabled(select);
options_page->buttonDelete->setEnabled(select);
options_page->buttonPlayNotification->setEnabled(select);
}
void NotifyPluginOptionsPage::on_buttonAddNotification_clicked()
{
NotificationItem* notification = new NotificationItem;
if (options_page->SoundDirectoryPathChooser->path()=="") {
QPalette textPalette=options_page->SoundDirectoryPathChooser->palette();
textPalette.setColor(QPalette::Normal,QPalette::Text, Qt::red);
options_page->SoundDirectoryPathChooser->setPalette(textPalette);
options_page->SoundDirectoryPathChooser->setPath("please select sound collection folder");
return;
}
notification->setSoundCollectionPath(options_page->SoundDirectoryPathChooser->path());
notification->setCurrentLanguage(options_page->SoundCollectionList->currentText());
notification->setDataObject(options_page->UAVObject->currentText());
notification->setObjectField(options_page->UAVObjectField->currentText());
notification->setValue(options_page->Value->currentText());
notification->setSpinBoxValue(options_page->ValueSpinBox->value());
if (options_page->Sound1->currentText().size() > 0)
notification->setSound1(options_page->Sound1->currentText());
notification->setSound2(options_page->Sound2->currentText());
notification->setSound3(options_page->Sound3->currentText());
if ( ((!options_page->Sound2->currentText().size()) && (options_page->SayOrder->currentText()=="After second"))
|| ((!options_page->Sound3->currentText().size()) && (options_page->SayOrder->currentText()=="After third")) ) {
return;
} else {
notification->setSayOrder(options_page->SayOrder->currentText());
}
privListNotifications.append(notification);
emit entryAdded(privListNotifications.size() - 1);
_notifyRulesSelection->setCurrentIndex(_notifyRulesModel->index(privListNotifications.size()-1,0,QModelIndex()),
QItemSelectionModel::ClearAndSelect | QItemSelectionModel::Rows);
}
void NotifyPluginOptionsPage::on_buttonDeleteNotification_clicked()
{
_notifyRulesModel->removeRow(_notifyRulesSelection->currentIndex().row());
if (!_notifyRulesModel->rowCount()
&& (_notifyRulesSelection->currentIndex().row() > 0
&& _notifyRulesSelection->currentIndex().row() < _notifyRulesModel->rowCount()) )
{
options_page->buttonDelete->setEnabled(false);
options_page->buttonModify->setEnabled(false);
options_page->buttonPlayNotification->setEnabled(false);
}
}
void NotifyPluginOptionsPage::on_buttonModifyNotification_clicked()
{
NotificationItem* notification = new NotificationItem;
getOptionsPageValues(notification);
notification->setRetryString(privListNotifications.at(_notifyRulesSelection->currentIndex().row())->retryString());
notification->setLifetime(privListNotifications.at(_notifyRulesSelection->currentIndex().row())->lifetime());
notification->setMute(privListNotifications.at(_notifyRulesSelection->currentIndex().row())->mute());
privListNotifications.replace(_notifyRulesSelection->currentIndex().row(),notification);
entryUpdated(_notifyRulesSelection->currentIndex().row());
}

View File

@ -48,6 +48,7 @@
#include "positionactual.h"
#include "homelocation.h"
#include "gpsposition.h"
#define allow_manual_home_location_move
@ -662,15 +663,17 @@ void OPMapGadgetWidget::updatePosition()
uav_pos = internals::PointLatLng(uav_latitude, uav_longitude);
// *************
// get the current GPS details
// get current GPS position
ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager* objManager = pm->getObject<UAVObjectManager>();
// get current GPS position
if (!getGPSPosition(gps_latitude, gps_longitude, gps_altitude))
return;
GPSPosition *gpsPositionData = GPSPosition::GetInstance(objManager);
// get current GPS heading
// gps_heading = getGPS_Heading();
gps_heading = 0;
gps_heading = gpsPositionData->getData().Heading;
gps_latitude = gpsPositionData->getData().Latitude;
gps_longitude = gpsPositionData->getData().Longitude;
gps_altitude = gpsPositionData->getData().Altitude;
gps_pos = internals::PointLatLng(gps_latitude, gps_longitude);
@ -698,7 +701,7 @@ void OPMapGadgetWidget::updatePosition()
m_map->GPS->SetUAVPos(gps_pos, gps_altitude); // set the maps GPS position
m_map->GPS->SetUAVHeading(gps_heading); // set the maps GPS heading
// *************
// *************
}
/**
@ -2387,25 +2390,8 @@ double OPMapGadgetWidget::getUAV_Yaw()
return yaw;
}
bool OPMapGadgetWidget::getGPSPosition(double &latitude, double &longitude, double &altitude)
{
double LLA[3];
if (!obum)
return false;
if (obum->getGPSPosition(LLA) < 0)
return false; // error
latitude = LLA[0];
longitude = LLA[1];
altitude = LLA[2];
return true;
}
// *************************************************************************************
void OPMapGadgetWidget::setMapFollowingMode()
{
if (!m_widget || !m_map)

View File

@ -350,7 +350,6 @@ private:
internals::PointLatLng destPoint(internals::PointLatLng source, double bear, double dist);
bool getUAVPosition(double &latitude, double &longitude, double &altitude);
bool getGPSPosition(double &latitude, double &longitude, double &altitude);
double getUAV_Yaw();
void setMapFollowingMode();

View File

@ -3,31 +3,39 @@ TARGET = PfdQml
QT += svg
QT += opengl
QT += declarative
#DEFINES += USE_OSG
include(../../openpilotgcsplugin.pri)
include(../../plugins/coreplugin/coreplugin.pri)
include(pfdqml_dependencies.pri)
contains(DEFINES,USE_OSG){
LIBS += -losg -losgUtil -losgViewer -losgQt -losgDB -lOpenThreads -losgGA
LIBS += -losgEarth -losgEarthFeatures -losgEarthUtil
}
HEADERS += \
pfdqmlplugin.h \
pfdqmlgadget.h \
pfdqmlgadgetwidget.h \
pfdqmlgadgetfactory.h \
pfdqmlgadgetconfiguration.h \
pfdqmlgadgetoptionspage.h \
pfdqmlgadgetoptionspage.h
contains(DEFINES,USE_OSG){
\
osgearth.h
}
SOURCES += \
pfdqmlplugin.cpp \
pfdqmlgadget.cpp \
pfdqmlgadgetfactory.cpp \
pfdqmlgadgetwidget.cpp \
pfdqmlgadgetconfiguration.cpp \
pfdqmlgadgetoptionspage.cpp \
pfdqmlgadgetoptionspage.cpp
contains(DEFINES,USE_OSG){
\
osgearth.cpp
}
OTHER_FILES += PfdQml.pluginspec

View File

@ -52,6 +52,7 @@ void PfdQmlGadget::loadConfiguration(IUAVGadgetConfiguration* config)
qputenv("OSGEARTH_CACHE_ONLY", "true");
} else {
//how portable it is?
unsetenv("OSGEARTH_CACHE_ONLY");
//unsetenv("OSGEARTH_CACHE_ONLY");
qputenv("OSGEARTH_CACHE_ONLY", "false");
}
}

View File

@ -19,8 +19,9 @@
#include "uavobjectmanager.h"
#include "uavobject.h"
#include "utils/svgimageprovider.h"
#ifdef USE_OSG
#include "osgearth.h"
#endif
#include <QDebug>
#include <QSvgRenderer>
#include <QtOpenGL/QGLWidget>
@ -66,8 +67,9 @@ PfdQmlGadgetWidget::PfdQmlGadgetWidget(QWidget *parent) :
//to expose settings values
engine()->rootContext()->setContextProperty("qmlWidget", this);
#ifdef USE_OSG
qmlRegisterType<OsgEarthItem>("org.OpenPilot", 1, 0, "OsgEarth");
#endif
}
PfdQmlGadgetWidget::~PfdQmlGadgetWidget()

View File

@ -48,8 +48,6 @@
#define QINT32MAX std::numeric_limits<qint32>::max()
#define QUINT32MAX std::numeric_limits<qint32>::max()
//#define USE_SCIENTIFIC_NOTATION
class FieldTreeItem : public TreeItem
{
Q_OBJECT
@ -214,10 +212,10 @@ class FloatFieldTreeItem : public FieldTreeItem
{
Q_OBJECT
public:
FloatFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_field(field) { }
FloatFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_field(field) { }
FloatFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data, bool scientific = false, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_field(field), m_useScientificNotation(scientific){}
FloatFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, bool scientific = false, TreeItem *parent = 0) :
FieldTreeItem(index, data, parent), m_field(field), m_useScientificNotation(scientific) { }
void setData(QVariant value, int column) {
setChanged(m_field->getValue(m_index) != value);
TreeItem::setData(value, column);
@ -233,39 +231,49 @@ public:
setHighlight(true);
}
}
QWidget *createEditor(QWidget *parent) {
#ifdef USE_SCIENTIFIC_NOTATION
QScienceSpinBox *editor = new QScienceSpinBox(parent);
editor->setDecimals(6);
#else
if(m_useScientificNotation) {
QScienceSpinBox *editor = new QScienceSpinBox(parent);
editor->setDecimals(6);
editor->setMinimum(-std::numeric_limits<float>::max());
editor->setMaximum(std::numeric_limits<float>::max());
return editor;
} else {
QDoubleSpinBox *editor = new QDoubleSpinBox(parent);
editor->setDecimals(8);
#endif
editor->setMinimum(-std::numeric_limits<float>::max());
editor->setMaximum(std::numeric_limits<float>::max());
return editor;
editor->setMinimum(-std::numeric_limits<float>::max());
editor->setMaximum(std::numeric_limits<float>::max());
return editor;
}
}
QVariant getEditorValue(QWidget *editor) {
#ifdef USE_SCIENTIFIC_NOTATION
QScienceSpinBox *spinBox = static_cast<QScienceSpinBox*>(editor);
#else
QDoubleSpinBox *spinBox = static_cast<QDoubleSpinBox*>(editor);
#endif
spinBox->interpretText();
return spinBox->value();
if(m_useScientificNotation) {
QScienceSpinBox *spinBox = static_cast<QScienceSpinBox*>(editor);
spinBox->interpretText();
return spinBox->value();
} else {
QDoubleSpinBox *spinBox = static_cast<QDoubleSpinBox*>(editor);
spinBox->interpretText();
return spinBox->value();
}
}
void setEditorValue(QWidget *editor, QVariant value) {
#ifdef USE_SCIENTIFIC_NOTATION
QScienceSpinBox *spinBox = static_cast<QScienceSpinBox*>(editor);
#else
QDoubleSpinBox *spinBox = static_cast<QDoubleSpinBox*>(editor);
#endif
spinBox->setValue(value.toDouble());
if(m_useScientificNotation) {
QScienceSpinBox *spinBox = static_cast<QScienceSpinBox*>(editor);
spinBox->setValue(value.toDouble());
} else {
QDoubleSpinBox *spinBox = static_cast<QDoubleSpinBox*>(editor);
spinBox->setValue(value.toDouble());
}
}
private:
UAVObjectField *m_field;
bool m_useScientificNotation;
};
#endif // FIELDTREEITEM_H

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.7 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.2 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.2 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.5 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.5 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 3.6 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.2 KiB

View File

@ -165,10 +165,9 @@ private:
bool m_changed;
QTime m_highlightExpires;
HighLightManager* m_highlightManager;
static int m_highlightTimeMs;
public:
static const int dataColumn = 1;
private:
static int m_highlightTimeMs;
};
class DataObjectTreeItem;

View File

@ -26,12 +26,13 @@
*/
#include "uavobjectbrowser.h"
#include "uavobjectbrowserwidget.h"
#include "uavobjectbrowserconfiguration.h"
UAVObjectBrowser::UAVObjectBrowser(QString classId, UAVObjectBrowserWidget *widget, QWidget *parent) :
IUAVGadget(classId, parent),
m_widget(widget)
m_widget(widget),
m_config(NULL)
{
connect(m_widget,SIGNAL(viewOptionsChanged(bool,bool,bool)),this,SLOT(viewOptionsChangedSlot(bool,bool,bool)));
}
UAVObjectBrowser::~UAVObjectBrowser()
@ -42,9 +43,21 @@ UAVObjectBrowser::~UAVObjectBrowser()
void UAVObjectBrowser::loadConfiguration(IUAVGadgetConfiguration* config)
{
UAVObjectBrowserConfiguration *m = qobject_cast<UAVObjectBrowserConfiguration*>(config);
m_config=m;
m_widget->setRecentlyUpdatedColor(m->recentlyUpdatedColor());
m_widget->setManuallyChangedColor(m->manuallyChangedColor());
m_widget->setRecentlyUpdatedTimeout(m->recentlyUpdatedTimeout());
m_widget->setOnlyHilightChangedValues(m->onlyHighlightChangedValues());
m_widget->setViewOptions(m->categorizedView(),m->scientificView(),m->showMetaData());
}
void UAVObjectBrowser::viewOptionsChangedSlot(bool categorized, bool scientific, bool metadata)
{
if(m_config)
{
m_config->setCategorizedView(categorized);
m_config->setScientificView(scientific);
m_config->setShowMetaData(metadata);
}
}

View File

@ -30,6 +30,7 @@
#include <coreplugin/iuavgadget.h>
#include "uavobjectbrowserwidget.h"
#include "uavobjectbrowserconfiguration.h"
class IUAVGadget;
class QWidget;
@ -47,9 +48,11 @@ public:
QWidget *widget() { return m_widget; }
void loadConfiguration(IUAVGadgetConfiguration* config);
private slots:
void viewOptionsChangedSlot(bool categorized,bool scientific,bool metadata);
private:
UAVObjectBrowserWidget *m_widget;
UAVObjectBrowserConfiguration *m_config;
};

View File

@ -24,4 +24,8 @@ SOURCES += browserplugin.cpp \
fieldtreeitem.cpp
OTHER_FILES += UAVObjectBrowser.pluginspec
FORMS += uavobjectbrowser.ui \
uavobjectbrowseroptionspage.ui
uavobjectbrowseroptionspage.ui \
viewoptions.ui
RESOURCES += \
uavobjectbrowser.qrc

View File

@ -0,0 +1,10 @@
<RCC>
<qresource prefix="/uavobjectbrowser">
<file>images/down_alt.png</file>
<file>images/install.png</file>
<file>images/remove.png</file>
<file>images/up_alt.png</file>
<file>images/trash.png</file>
<file>images/1343241276_eye.png</file>
</qresource>
</RCC>

View File

@ -17,12 +17,48 @@
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QPushButton" name="requestButton">
<widget class="QToolButton" name="requestButton">
<property name="toolTip">
<string>Request update</string>
<string>Request</string>
</property>
<property name="text">
<string>Request</string>
<string>...</string>
</property>
<property name="icon">
<iconset resource="uavobjectbrowser.qrc">
<normaloff>:/uavobjectbrowser/images/down_alt.png</normaloff>:/uavobjectbrowser/images/down_alt.png</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="checkable">
<bool>false</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QToolButton" name="sendButton">
<property name="toolTip">
<string>Send</string>
</property>
<property name="text">
<string>...</string>
</property>
<property name="icon">
<iconset resource="uavobjectbrowser.qrc">
<normaloff>:/uavobjectbrowser/images/up_alt.png</normaloff>:/uavobjectbrowser/images/up_alt.png</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
</widget>
</item>
@ -42,32 +78,6 @@
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="sendButton">
<property name="toolTip">
<string>Send update</string>
</property>
<property name="text">
<string>Send</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="Line" name="line">
<property name="orientation">
@ -76,28 +86,62 @@
</widget>
</item>
<item>
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="saveSDButton">
<widget class="QToolButton" name="saveSDButton">
<property name="toolTip">
<string>Save to SD Card</string>
<string>Save</string>
</property>
<property name="text">
<string>Save</string>
<string>...</string>
</property>
<property name="icon">
<iconset resource="uavobjectbrowser.qrc">
<normaloff>:/uavobjectbrowser/images/remove.png</normaloff>:/uavobjectbrowser/images/remove.png</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QToolButton" name="readSDButton">
<property name="toolTip">
<string>Load</string>
</property>
<property name="text">
<string>...</string>
</property>
<property name="icon">
<iconset resource="uavobjectbrowser.qrc">
<normaloff>:/uavobjectbrowser/images/install.png</normaloff>:/uavobjectbrowser/images/install.png</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
</widget>
</item>
<item>
<widget class="QToolButton" name="eraseSDButton">
<property name="toolTip">
<string>Erase</string>
</property>
<property name="text">
<string>...</string>
</property>
<property name="icon">
<iconset resource="uavobjectbrowser.qrc">
<normaloff>:/uavobjectbrowser/images/trash.png</normaloff>:/uavobjectbrowser/images/trash.png</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
</widget>
</item>
@ -117,58 +161,6 @@
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="readSDButton">
<property name="toolTip">
<string>Load from SD Card</string>
</property>
<property name="text">
<string>Load</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="eraseSDButton">
<property name="toolTip">
<string>Erase from SD card</string>
</property>
<property name="text">
<string>Erase</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Preferred</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="Line" name="line_2">
<property name="orientation">
@ -193,25 +185,22 @@
</spacer>
</item>
<item>
<widget class="QCheckBox" name="metaCheckBox">
<widget class="QToolButton" name="tbView">
<property name="toolTip">
<string>Show Meta Data</string>
<string>View Options</string>
</property>
<property name="text">
<string>Show Meta Data</string>
<string>...</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="categorizeCheckbox">
<property name="toolTip">
<string>Select to sort objects in to categories.</string>
<property name="icon">
<iconset resource="uavobjectbrowser.qrc">
<normaloff>:/uavobjectbrowser/images/1343241276_eye.png</normaloff>:/uavobjectbrowser/images/1343241276_eye.png</iconset>
</property>
<property name="text">
<string>Categorize Objects</string>
</property>
<property name="checked">
<bool>true</bool>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
</widget>
</item>
@ -235,6 +224,8 @@
</item>
</layout>
</widget>
<resources/>
<resources>
<include location="uavobjectbrowser.qrc"/>
</resources>
<connections/>
</ui>

View File

@ -31,8 +31,11 @@ UAVObjectBrowserConfiguration::UAVObjectBrowserConfiguration(QString classId, QS
IUAVGadgetConfiguration(classId, parent),
m_recentlyUpdatedColor(QColor(255, 230, 230)),
m_manuallyChangedColor(QColor(230, 230, 255)),
m_onlyHilightChangedValues(false),
m_recentlyUpdatedTimeout(500),
m_onlyHilightChangedValues(false)
m_useCategorizedView(false),
m_useScientificView(false),
m_showMetaData(false)
{
//if a saved configuration exists load it
if(qSettings != 0) {
@ -41,6 +44,9 @@ UAVObjectBrowserConfiguration::UAVObjectBrowserConfiguration(QString classId, QS
int timeout = qSettings->value("recentlyUpdatedTimeout").toInt();
bool hilight = qSettings->value("onlyHilightChangedValues").toBool();
m_useCategorizedView = qSettings->value("CategorizedView").toBool();
m_useScientificView = qSettings->value("ScientificView").toBool();
m_showMetaData = qSettings->value("showMetaData").toBool();
m_recentlyUpdatedColor = recent;
m_manuallyChangedColor = manual;
m_recentlyUpdatedTimeout = timeout;
@ -55,6 +61,9 @@ IUAVGadgetConfiguration *UAVObjectBrowserConfiguration::clone()
m->m_manuallyChangedColor = m_manuallyChangedColor;
m->m_recentlyUpdatedTimeout = m_recentlyUpdatedTimeout;
m->m_onlyHilightChangedValues = m_onlyHilightChangedValues;
m->m_useCategorizedView = m_useCategorizedView;
m->m_useScientificView = m_useScientificView;
m->m_showMetaData = m_showMetaData;
return m;
}
@ -67,4 +76,7 @@ void UAVObjectBrowserConfiguration::saveConfig(QSettings* qSettings) const {
qSettings->setValue("manuallyChangedColor", m_manuallyChangedColor);
qSettings->setValue("recentlyUpdatedTimeout", m_recentlyUpdatedTimeout);
qSettings->setValue("onlyHilightChangedValues", m_onlyHilightChangedValues);
qSettings->setValue("CategorizedView", m_useCategorizedView);
qSettings->setValue("ScientificView", m_useScientificView);
qSettings->setValue("showMetaData", m_showMetaData);
}

View File

@ -40,6 +40,9 @@ Q_PROPERTY(QColor m_recentlyUpdatedColor READ recentlyUpdatedColor WRITE setRece
Q_PROPERTY(QColor m_manuallyChangedColor READ manuallyChangedColor WRITE setManuallyChangedColor)
Q_PROPERTY(int m_recentlyUpdatedTimeout READ recentlyUpdatedTimeout WRITE setRecentlyUpdatedTimeout)
Q_PROPERTY(bool m_onlyHilightChangedValues READ onlyHighlightChangedValues WRITE setOnlyHighlightChangedValues)
Q_PROPERTY(bool m_useCategorizedView READ categorizedView WRITE setCategorizedView)
Q_PROPERTY(bool m_useScientificView READ scientificView WRITE setScientificView)
Q_PROPERTY(bool m_showMetaData READ showMetaData WRITE setShowMetaData)
public:
explicit UAVObjectBrowserConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0);
@ -50,6 +53,9 @@ public:
QColor manuallyChangedColor() const { return m_manuallyChangedColor; }
int recentlyUpdatedTimeout() const { return m_recentlyUpdatedTimeout; }
bool onlyHighlightChangedValues() const {return m_onlyHilightChangedValues;}
bool categorizedView() const { return m_useCategorizedView; }
bool scientificView() const { return m_useScientificView; }
bool showMetaData() const { return m_showMetaData; }
signals:
@ -58,12 +64,18 @@ public slots:
void setManuallyChangedColor(QColor color) { m_manuallyChangedColor = color; }
void setRecentlyUpdatedTimeout(int timeout) { m_recentlyUpdatedTimeout = timeout; }
void setOnlyHighlightChangedValues(bool hilight) { m_onlyHilightChangedValues = hilight; }
void setCategorizedView(bool value) { m_useCategorizedView = value; }
void setScientificView(bool value) { m_useScientificView = value; }
void setShowMetaData(bool value) { m_showMetaData = value; }
private:
QColor m_recentlyUpdatedColor;
QColor m_manuallyChangedColor;
int m_recentlyUpdatedTimeout;
bool m_onlyHilightChangedValues;
bool m_useCategorizedView;
bool m_useScientificView;
bool m_showMetaData;
};
#endif // UAVOBJECTBROWSERCONFIGURATION_H

View File

@ -29,6 +29,7 @@
#include "browseritemdelegate.h"
#include "treeitem.h"
#include "ui_uavobjectbrowser.h"
#include "ui_viewoptions.h"
#include "uavobjectmanager.h"
#include <QStringList>
#include <QtGui/QHBoxLayout>
@ -42,6 +43,9 @@
UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent)
{
m_browser = new Ui_UAVObjectBrowser();
m_viewoptions = new Ui_viewoptions();
m_viewoptionsDialog = new QDialog(this);
m_viewoptions->setupUi(m_viewoptionsDialog);
m_browser->setupUi(this);
m_model = new UAVObjectTreeModel();
m_browser->treeView->setModel(m_model);
@ -51,21 +55,33 @@ UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent
m_browser->treeView->setItemDelegate(m_delegate);
m_browser->treeView->setEditTriggers(QAbstractItemView::AllEditTriggers);
m_browser->treeView->setSelectionBehavior(QAbstractItemView::SelectItems);
showMetaData(m_browser->metaCheckBox->isChecked());
showMetaData(m_viewoptions->cbMetaData->isChecked());
connect(m_browser->treeView->selectionModel(), SIGNAL(currentChanged(QModelIndex,QModelIndex)), this, SLOT(currentChanged(QModelIndex,QModelIndex)));
connect(m_browser->metaCheckBox, SIGNAL(toggled(bool)), this, SLOT(showMetaData(bool)));
connect(m_browser->categorizeCheckbox, SIGNAL(toggled(bool)), this, SLOT(categorize(bool)));
connect(m_viewoptions->cbMetaData, SIGNAL(toggled(bool)), this, SLOT(showMetaData(bool)));
connect(m_viewoptions->cbCategorized, SIGNAL(toggled(bool)), this, SLOT(categorize(bool)));
connect(m_browser->saveSDButton, SIGNAL(clicked()), this, SLOT(saveObject()));
connect(m_browser->readSDButton, SIGNAL(clicked()), this, SLOT(loadObject()));
connect(m_browser->eraseSDButton, SIGNAL(clicked()), this, SLOT(eraseObject()));
connect(m_browser->sendButton, SIGNAL(clicked()), this, SLOT(sendUpdate()));
connect(m_browser->requestButton, SIGNAL(clicked()), this, SLOT(requestUpdate()));
connect(m_browser->tbView,SIGNAL(clicked()),this,SLOT(viewSlot()));
connect(m_viewoptions->cbScientific, SIGNAL(toggled(bool)), this, SLOT(useScientificNotation(bool)));
connect(m_viewoptions->cbScientific, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot()));
connect(m_viewoptions->cbMetaData, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot()));
connect(m_viewoptions->cbCategorized, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot()));
enableSendRequest(false);
}
UAVObjectBrowserWidget::~UAVObjectBrowserWidget()
{
delete m_browser;
delete m_browser;
}
void UAVObjectBrowserWidget::setViewOptions(bool categorized, bool scientific, bool metadata)
{
m_viewoptions->cbCategorized->setChecked(categorized);
m_viewoptions->cbMetaData->setChecked(metadata);
m_viewoptions->cbScientific->setChecked(scientific);
}
void UAVObjectBrowserWidget::showMetaData(bool show)
@ -85,13 +101,31 @@ void UAVObjectBrowserWidget::categorize(bool categorize)
Q_ASSERT(objManager);
UAVObjectTreeModel* tmpModel = m_model;
m_model = new UAVObjectTreeModel(0, categorize);
m_model = new UAVObjectTreeModel(0, categorize,m_viewoptions->cbScientific->isChecked());
m_model->setRecentlyUpdatedColor(m_recentlyUpdatedColor);
m_model->setManuallyChangedColor(m_manuallyChangedColor);
m_model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout);
m_model->setOnlyHilightChangedValues(m_onlyHilightChangedValues);
m_browser->treeView->setModel(m_model);
showMetaData(m_browser->metaCheckBox->isChecked());
showMetaData(m_viewoptions->cbMetaData->isChecked());
delete tmpModel;
}
void UAVObjectBrowserWidget::useScientificNotation(bool scientific)
{
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
Q_ASSERT(pm);
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
Q_ASSERT(objManager);
UAVObjectTreeModel* tmpModel = m_model;
m_model = new UAVObjectTreeModel(0, m_viewoptions->cbCategorized,scientific);
m_model->setRecentlyUpdatedColor(m_recentlyUpdatedColor);
m_model->setManuallyChangedColor(m_manuallyChangedColor);
m_model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout);
m_browser->treeView->setModel(m_model);
showMetaData(m_viewoptions->cbMetaData->isChecked());
delete tmpModel;
}
@ -194,6 +228,24 @@ void UAVObjectBrowserWidget::currentChanged(const QModelIndex &current, const QM
enableSendRequest(enable);
}
void UAVObjectBrowserWidget::viewSlot()
{
if(m_viewoptionsDialog->isVisible())
m_viewoptionsDialog->setVisible(false);
else
{
QPoint pos=QCursor::pos();
pos.setX(pos.x()-m_viewoptionsDialog->width());
m_viewoptionsDialog->move(pos);
m_viewoptionsDialog->show();
}
}
void UAVObjectBrowserWidget::viewOptionsChangedSlot()
{
emit viewOptionsChanged(m_viewoptions->cbCategorized->isChecked(),m_viewoptions->cbScientific->isChecked(),m_viewoptions->cbMetaData->isChecked());
}
void UAVObjectBrowserWidget::enableSendRequest(bool enable)
{
m_browser->sendButton->setEnabled(enable);

View File

@ -36,7 +36,7 @@
class QPushButton;
class ObjectTreeItem;
class Ui_UAVObjectBrowser;
class Ui_viewoptions;
class UAVObjectBrowserWidget : public QWidget
{
@ -49,11 +49,11 @@ public:
void setManuallyChangedColor(QColor color) { m_manuallyChangedColor = color; m_model->setManuallyChangedColor(color); }
void setRecentlyUpdatedTimeout(int timeout) { m_recentlyUpdatedTimeout = timeout; m_model->setRecentlyUpdatedTimeout(timeout); }
void setOnlyHilightChangedValues(bool hilight) { m_onlyHilightChangedValues = hilight; m_model->setOnlyHilightChangedValues(hilight); }
void setViewOptions(bool categorized,bool scientific,bool metadata);
public slots:
void showMetaData(bool show);
void categorize(bool categorize);
void useScientificNotation(bool scientific);
private slots:
void sendUpdate();
@ -62,11 +62,16 @@ private slots:
void loadObject();
void eraseObject();
void currentChanged(const QModelIndex &current, const QModelIndex &previous);
void viewSlot();
void viewOptionsChangedSlot();
signals:
void viewOptionsChanged(bool categorized,bool scientific,bool metadata);
private:
QPushButton *m_requestUpdate;
QPushButton *m_sendUpdate;
Ui_UAVObjectBrowser *m_browser;
Ui_viewoptions *m_viewoptions;
QDialog *m_viewoptionsDialog;
UAVObjectTreeModel *m_model;
int m_recentlyUpdatedTimeout;

View File

@ -38,8 +38,9 @@
#include <QtCore/QSignalMapper>
#include <QtCore/QDebug>
UAVObjectTreeModel::UAVObjectTreeModel(QObject *parent, bool categorize) :
UAVObjectTreeModel::UAVObjectTreeModel(QObject *parent, bool categorize, bool useScientificNotation) :
QAbstractItemModel(parent),
m_useScientificFloatNotation(useScientificNotation),
m_recentlyUpdatedTimeout(500), // ms
m_recentlyUpdatedColor(QColor(255, 230, 230)),
m_manuallyChangedColor(QColor(230, 230, 255))
@ -227,7 +228,7 @@ void UAVObjectTreeModel::addSingleField(int index, UAVObjectField *field, TreeIt
case UAVObjectField::FLOAT32:
data.append(field->getValue(index));
data.append(field->getUnits());
item = new FloatFieldTreeItem(field, index, data);
item = new FloatFieldTreeItem(field, index, data, m_useScientificFloatNotation);
break;
default:
Q_ASSERT(false);

View File

@ -49,7 +49,7 @@ class UAVObjectTreeModel : public QAbstractItemModel
{
Q_OBJECT
public:
explicit UAVObjectTreeModel(QObject *parent = 0, bool categorize=true);
explicit UAVObjectTreeModel(QObject *parent = 0, bool categorize=true, bool useScientificNotation=false);
~UAVObjectTreeModel();
QVariant data(const QModelIndex &index, int role) const;
@ -105,6 +105,7 @@ private:
QColor m_recentlyUpdatedColor;
QColor m_manuallyChangedColor;
bool m_onlyHilightChangedValues;
bool m_useScientificFloatNotation;
// Highlight manager to handle highlighting of tree items.
HighLightManager *m_highlightManager;

View File

@ -0,0 +1,42 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>viewoptions</class>
<widget class="QDialog" name="viewoptions">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>169</width>
<height>96</height>
</rect>
</property>
<property name="windowTitle">
<string>View Options</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QCheckBox" name="cbMetaData">
<property name="text">
<string>Show MetaData</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="cbCategorized">
<property name="text">
<string>Show Categorized</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="cbScientific">
<property name="text">
<string>Show Scientific</string>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>

View File

@ -247,14 +247,6 @@ FirmwareIAPObj::DataFields UAVObjectUtilManager::getFirmwareIap()
if (!firmwareIap)
return dummy;
// The code below will ask for the object update and wait for the updated to be received,
// or the timeout of the timer, set to 1 second.
QEventLoop loop;
connect(firmwareIap, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit()));
QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout
firmwareIap->requestUpdate();
loop.exec();
return firmwareIap->getData();
}

View File

@ -784,6 +784,9 @@ void ConfigTaskWidget::defaultButtonClicked()
*/
void ConfigTaskWidget::reloadButtonClicked()
{
QPushButton * button=qobject_cast<QPushButton*>(sender());
if(button)
button->setEnabled(false);
int group=sender()->property("group").toInt();
QList<objectToWidget*> * list=defaultReloadGroups.value(group,NULL);
if(!list)
@ -793,10 +796,19 @@ void ConfigTaskWidget::reloadButtonClicked()
QEventLoop * eventLoop=new QEventLoop(this);
connect(timeOut, SIGNAL(timeout()),eventLoop,SLOT(quit()));
connect(objper, SIGNAL(objectUpdated(UAVObject*)), eventLoop, SLOT(quit()));
QList<temphelper> temp;
foreach(objectToWidget * oTw,*list)
{
if (oTw->object != NULL)
{
temphelper value;
value.objid=oTw->object->getObjID();
value.objinstid=oTw->object->getInstID();
if(temp.contains(value))
continue;
else
temp.append(value);
ObjectPersistence::DataFields data;
data.Operation = ObjectPersistence::OPERATION_LOAD;
data.Selection = ObjectPersistence::SELECTION_SINGLEOBJECT;
@ -824,6 +836,8 @@ void ConfigTaskWidget::reloadButtonClicked()
delete timeOut;
timeOut=NULL;
}
if(button)
button->setEnabled(true);
}
/**
@ -843,7 +857,7 @@ void ConfigTaskWidget::connectWidgetUpdatesToSlot(QWidget * widget,const char* f
}
else if(MixerCurveWidget * cb=qobject_cast<MixerCurveWidget *>(widget))
{
connect(cb,SIGNAL(curveUpdated(QList<double>,double)),this,function);
connect(cb,SIGNAL(curveUpdated()),this,function);
}
else if(QTableWidget * cb=qobject_cast<QTableWidget *>(widget))
{
@ -886,7 +900,7 @@ void ConfigTaskWidget::disconnectWidgetUpdatesToSlot(QWidget * widget,const char
}
else if(MixerCurveWidget * cb=qobject_cast<MixerCurveWidget *>(widget))
{
disconnect(cb,SIGNAL(curveUpdated(QList<double>,double)),this,function);
disconnect(cb,SIGNAL(curveUpdated()),this,function);
}
else if(QTableWidget * cb=qobject_cast<QTableWidget *>(widget))
{

View File

@ -70,6 +70,16 @@ public:
QList<shadow *> shadowsList;
};
struct temphelper
{
quint32 objid;
quint32 objinstid;
bool operator==(const temphelper& lhs)
{
return (lhs.objid==this->objid && lhs.objinstid==this->objinstid);
}
};
enum buttonTypeEnum {none,save_button,apply_button,reload_button,default_button,help_button};
struct uiRelationAutomation
{

View File

@ -83,7 +83,7 @@ void Edge::adjust()
prepareGeometryChange();
if (length > qreal(20.)) {
QPointF edgeOffset((line.dx() * 10) / length, (line.dy() * 10) / length);
QPointF edgeOffset((line.dx() * 13) / length, (line.dy() * 13) / length);
sourcePoint = line.p1() + edgeOffset;
destPoint = line.p2() - edgeOffset;
} else {

View File

@ -29,6 +29,7 @@
#include <QGraphicsSceneMouseEvent>
#include <QPainter>
#include <QStyleOption>
#include <QColor>
#include <QDebug>
#include "mixercurveline.h"
@ -42,7 +43,18 @@ Node::Node(MixerCurveWidget *graphWidget)
setFlag(ItemSendsGeometryChanges);
setCacheMode(DeviceCoordinateCache);
setZValue(-1);
cmdActive = false;
vertical = false;
cmdNode = false;
cmdToggle = true;
drawNode = true;
drawText = true;
posColor0 = "#1c870b"; //greenish?
posColor1 = "#116703"; //greenish?
negColor0 = "#aa0000"; //red
negColor1 = "#aa0000"; //red
}
void Node::addEdge(Edge *edge)
@ -59,48 +71,74 @@ QList<Edge *> Node::edges() const
QRectF Node::boundingRect() const
{
qreal adjust = 2;
return QRectF(-12 - adjust, -12 - adjust,
28 + adjust, 28 + adjust);
return cmdNode ? QRectF(-4, -4, 15, 10) : QRectF(-13, -13, 26, 26);
}
QPainterPath Node::shape() const
{
QPainterPath path;
path.addEllipse(-12, -12, 25, 25);
path.addEllipse(boundingRect());
return path;
}
void Node::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *)
{
/*
painter->setPen(Qt::NoPen);
painter->setBrush(Qt::darkGray);
painter->drawEllipse(-7, -7, 20, 20);
*/
QString text = cmdNode ? cmdText : QString().sprintf("%.2f", value());
QRadialGradient gradient(-3, -3, 10);
if (option->state & QStyle::State_Sunken) {
gradient.setCenter(3, 3);
gradient.setFocalPoint(3, 3);
gradient.setColorAt(1, QColor("#1c870b").light(120));
gradient.setColorAt(0, QColor("#116703").light(120));
} else {
gradient.setColorAt(0, "#1c870b");
gradient.setColorAt(1, "#116703");
if (drawNode) {
QRadialGradient gradient(-3, -3, 10);
if (option->state & QStyle::State_Sunken) {
gradient.setCenter(3, 3);
gradient.setFocalPoint(3, 3);
gradient.setColorAt(1, Qt::darkBlue);
gradient.setColorAt(0, Qt::darkBlue);
} else {
if (cmdNode) {
gradient.setColorAt(0, cmdActive ? posColor0 : negColor0);
gradient.setColorAt(1, cmdActive ? posColor1 : negColor1);
}
else {
if (value() < 0) {
gradient.setColorAt(0, negColor0);
gradient.setColorAt(1, negColor1);
}
else {
gradient.setColorAt(0, posColor0);
gradient.setColorAt(1, posColor1);
}
}
}
painter->setBrush(gradient);
painter->setPen(QPen(Qt::black, 0));
painter->drawEllipse(boundingRect());
if (!image.isNull())
painter->drawImage(boundingRect().adjusted(1,1,-1,-1), image);
}
painter->setBrush(gradient);
painter->setPen(QPen(Qt::black, 0));
painter->drawEllipse(-12, -12, 25, 25);
painter->setPen(QPen(Qt::white, 0));
painter->drawText(-10, 3, QString().sprintf("%.2f", value()));
if (drawText) {
painter->setPen(QPen(drawNode ? Qt::white : Qt::black, 0));
if (cmdNode) {
painter->drawText(0,4,text);
}
else {
painter->drawText( (value() < 0) ? -13 : -11, 4, text);
}
}
}
void Node::verticalMove(bool flag){
vertical = flag;
}
void Node::commandNode(bool enable){
cmdNode = enable;
}
void Node::commandText(QString text){
cmdText = text;
}
double Node::value() {
double h = graph->sceneRect().height();
double ratio = (h - pos().y()) / h;
@ -149,6 +187,10 @@ QVariant Node::itemChange(GraphicsItemChange change, const QVariant &val)
void Node::mousePressEvent(QGraphicsSceneMouseEvent *event)
{
if (cmdNode) {
graph->cmdActivated(this);
//return;
}
update();
QGraphicsItem::mousePressEvent(event);
}

Some files were not shown because too many files have changed in this diff Show More