1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-18 08:54:15 +01:00

Merge branch 'thread/OP-1154_Cruise_Control_automatically_increase_copter_throttle_per' into next

This commit is contained in:
Fredrik Arvidsson 2014-01-17 21:41:07 +01:00
commit 4cc453efb1
10 changed files with 2115 additions and 707 deletions

View File

@ -105,7 +105,14 @@ float sin_lookup_deg(float angle)
return 0;
}
int i_ang = ((int32_t)angle) % 360;
// <bug, was> int i_ang = ((int32_t)angle) % 360;
// 1073741760 is a multiple of 360 that is close to 0x3fffffff
// so angle can be a very large number of positive or negative rotations
// this is the fastest fix (no tests, one integer addition)
// and has the largest range since float mantissas are 23-4 bit
// we could halve the lookup table size
// we could interpolate for greater accuracy
int i_ang = ((int32_t)(angle + 0.5f) + (int32_t)1073741760) % 360;
if (i_ang >= 180) { // for 180 to 360 deg
return -sin_table[i_ang - 180];
} else { // for 0 to 179 deg

View File

@ -96,7 +96,7 @@ static void updateStabilizationDesired(ManualControlCommandData *cmd, ManualCont
static void updateLandDesired(ManualControlCommandData *cmd, bool changed);
static void altitudeHoldDesired(ManualControlCommandData *cmd, bool changed);
static void updatePathDesired(ManualControlCommandData *cmd, bool changed, bool home);
static void processFlightMode(ManualControlSettingsData *settings, float flightMode);
static void processFlightMode(ManualControlSettingsData *settings, float flightMode, ManualControlCommandData *cmd);
static void processArm(ManualControlCommandData *cmd, ManualControlSettingsData *settings, int8_t armSwitch);
static void setArmedIfChanged(uint8_t val);
static void configurationUpdatedCb(UAVObjEvent *ev);
@ -358,6 +358,7 @@ static void manualControlTask(__attribute__((unused)) void *parameters)
AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING);
}
}
cmd.FlightModeSwitchPosition = (uint8_t) 255;
} else if (valid_input_detected) {
AlarmsClear(SYSTEMALARMS_ALARM_MANUALCONTROL);
@ -446,7 +447,7 @@ static void manualControlTask(__attribute__((unused)) void *parameters)
}
}
processFlightMode(&settings, flightMode);
processFlightMode(&settings, flightMode, &cmd);
}
// Process arming outside conditional so system will disarm when disconnected
@ -1198,7 +1199,7 @@ static void processArm(ManualControlCommandData *cmd, ManualControlSettingsData
* @param[in] settings The settings which indicate which position is which mode
* @param[in] flightMode the value of the switch position
*/
static void processFlightMode(ManualControlSettingsData *settings, float flightMode)
static void processFlightMode(ManualControlSettingsData *settings, float flightMode, ManualControlCommandData *cmd)
{
FlightStatusData flightStatus;
@ -1210,6 +1211,8 @@ static void processFlightMode(ManualControlSettingsData *settings, float flightM
pos = settings->FlightModeNumber - 1;
}
cmd->FlightModeSwitchPosition = pos;
uint8_t newMode = settings->FlightModePosition[pos];
if (flightStatus.FlightMode != newMode) {

View File

@ -48,6 +48,7 @@
#include "airspeedstate.h"
#include "gyrostate.h"
#include "flightstatus.h"
#include "manualcontrolsettings.h"
#include "manualcontrol.h" // Just to get a macro
#include "taskinfo.h"
@ -75,6 +76,9 @@
#define TASK_PRIORITY (tskIDLE_PRIORITY + 4)
#define FAILSAFE_TIMEOUT_MS 30
// number of flight mode switch positions
#define NUM_FMS_POSITIONS 6
// The PID_RATE_ROLL set is used by Rate mode and the rate portion of Attitude mode
// The PID_RATE set is used by the attitude portion of Attitude mode
// The PID_RATEA_ROLL set is used by Rattitude mode because it needs to maintain
@ -98,9 +102,17 @@ bool lowThrottleZeroAxis[MAX_AXES];
float vbar_decay = 0.991f;
struct pid pids[PID_MAX];
int flight_mode = -1;
int cur_flight_mode = -1;
static uint8_t rattitude_anti_windup;
static float cruise_control_min_throttle;
static float cruise_control_max_throttle;
static uint8_t cruise_control_max_angle;
static float cruise_control_max_power_factor;
static float cruise_control_power_trim;
static int8_t cruise_control_inverted_power_switch;
static float cruise_control_neutral_thrust;
static uint8_t cruise_control_flight_mode_switch_pos_enable[NUM_FMS_POSITIONS];
// Private functions
static void stabilizationTask(void *parameters);
@ -150,6 +162,9 @@ int32_t StabilizationStart()
*/
int32_t StabilizationInitialize()
{
// stop the compile if the number of switch positions changes, but has not been changed here
PIOS_STATIC_ASSERT(NUM_FMS_POSITIONS == sizeof(((ManualControlSettingsData *)0)->FlightModePosition) / sizeof((((ManualControlSettingsData *)0)->FlightModePosition)[0]) );
// Initialize variables
StabilizationSettingsInitialize();
StabilizationBankInitialize();
@ -223,9 +238,11 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
#ifdef DIAG_RATEDESIRED
RateDesiredGet(&rateDesired);
#endif
uint8_t flight_mode_switch_position;
ManualControlCommandFlightModeSwitchPositionGet(&flight_mode_switch_position);
if (flight_mode != flightStatus.FlightMode) {
flight_mode = flightStatus.FlightMode;
if (cur_flight_mode != flight_mode_switch_position) {
cur_flight_mode = flight_mode_switch_position;
SettingsBankUpdatedCb(NULL);
}
@ -588,6 +605,64 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
}
}
// modify throttle according to 1/cos(bank angle)
// to maintain same altitdue with changing bank angle
// but without manually adjusting throttle
// do it here and all the various flight modes (e.g. Altitude Hold) can use it
if (flight_mode_switch_position < NUM_FMS_POSITIONS
&& cruise_control_flight_mode_switch_pos_enable[flight_mode_switch_position] != (uint8_t) 0
&& cruise_control_max_power_factor > 0.0001f) {
static uint8_t toggle;
static float factor;
float angle;
// get attitude state and calculate angle
// do it every 8th iteration to save CPU
if ((toggle++ & 7) == 0) {
// spherical right triangle
// 0 <= acosf() <= Pi
angle = RAD2DEG(acosf(cos_lookup_deg(attitudeState.Roll) * cos_lookup_deg(attitudeState.Pitch)));
// if past the cutoff angle (60 to 180 (180 means never))
if (angle > cruise_control_max_angle) {
// -1 reversed collective, 0 zero power, or 1 normal power
// these are all unboosted
factor = cruise_control_inverted_power_switch;
} else {
// avoid singularity
if (angle > 89.999f && angle < 90.001f) {
factor = cruise_control_max_power_factor;
} else {
factor = 1.0f / fabsf(cos_lookup_deg(angle));
if (factor > cruise_control_max_power_factor) {
factor = cruise_control_max_power_factor;
}
}
// factor in the power trim, no effect at 1.0, linear effect increases with factor
factor = (factor - 1.0f) * cruise_control_power_trim + 1.0f;
// if inverted and they want negative boost
if (angle > 90.0f && cruise_control_inverted_power_switch == (int8_t) -1) {
factor = -factor;
// as long as throttle is getting reversed
// we may as well do pitch and yaw for a complete "invert switch"
actuatorDesired.Pitch = -actuatorDesired.Pitch;
actuatorDesired.Yaw = -actuatorDesired.Yaw;
}
}
}
// also don't adjust throttle if <= 0, leaves neg alone and zero throttle stops motors
if (actuatorDesired.Throttle > cruise_control_min_throttle)
{
// quad example factor of 2 at hover power of 40%: (0.4 - 0.0) * 2.0 + 0.0 = 0.8
// CP heli example factor of 2 at hover stick of 60%: (0.6 - 0.5) * 2.0 + 0.5 = 0.7
actuatorDesired.Throttle = (actuatorDesired.Throttle - cruise_control_neutral_thrust) * factor + cruise_control_neutral_thrust;
if (actuatorDesired.Throttle > cruise_control_max_throttle) {
actuatorDesired.Throttle = cruise_control_max_throttle;
} else if (actuatorDesired.Throttle < cruise_control_min_throttle) {
actuatorDesired.Throttle = cruise_control_min_throttle;
}
}
}
if (PARSE_FLIGHT_MODE(flightStatus.FlightMode) != FLIGHTMODE_MANUAL) {
ActuatorDesiredSet(&actuatorDesired);
} else {
@ -638,9 +713,9 @@ static void ZeroPids(void)
static float bound(float val, float range)
{
if (val < -range) {
val = -range;
return -range;
} else if (val > range) {
val = range;
return range;
}
return val;
}
@ -687,11 +762,11 @@ static void SettingsBankUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
StabilizationBankGet(&oldBank);
if (flight_mode < 0) {
if (cur_flight_mode < 0 || cur_flight_mode >= NUM_FMS_POSITIONS) {
return;
}
switch (cast_struct_to_array(settings.FlightModeMap, settings.FlightModeMap.Stabilized1)[flight_mode]) {
switch (settings.FlightModeMap[cur_flight_mode]) {
case 0:
StabilizationSettingsBank1Get((StabilizationSettingsBank1Data *)&bank);
break;
@ -856,10 +931,23 @@ static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
vbar_decay = expf(-fakeDt / settings.VbarTau);
// force flight mode update
flight_mode = -1;
cur_flight_mode = -1;
// Rattitude flight mode anti-windup factor
rattitude_anti_windup = settings.RattitudeAntiWindup;
cruise_control_min_throttle = (float) settings.CruiseControlMinThrottle / 100.0f;
cruise_control_max_throttle = (float) settings.CruiseControlMaxThrottle / 100.0f;
cruise_control_max_angle = settings.CruiseControlMaxAngle;
cruise_control_max_power_factor = settings.CruiseControlMaxPowerFactor;
cruise_control_power_trim = settings.CruiseControlPowerTrim / 100.0f;
cruise_control_inverted_power_switch = settings.CruiseControlInvertedPowerSwitch;
cruise_control_neutral_thrust = (float) settings.CruiseControlNeutralThrust / 100.0f;
memcpy(
cruise_control_flight_mode_switch_pos_enable,
settings.CruiseControlFlightModeSwitchPosEnable,
sizeof(cruise_control_flight_mode_switch_pos_enable));
}
/**

View File

@ -144,10 +144,6 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
addWidgetBinding("ManualControlSettings", "Stabilization2Settings", ui->fmsSsPos2Yaw, "Yaw", 1, true);
addWidgetBinding("ManualControlSettings", "Stabilization3Settings", ui->fmsSsPos3Yaw, "Yaw", 1, true);
addWidgetBinding("StabilizationSettings", "FlightModeMap", ui->pidBankSs1, "Stabilized1", 1, true);
addWidgetBinding("StabilizationSettings", "FlightModeMap", ui->pidBankSs2, "Stabilized2", 1, true);
addWidgetBinding("StabilizationSettings", "FlightModeMap", ui->pidBankSs3, "Stabilized3", 1, true);
addWidgetBinding("ManualControlSettings", "Arming", ui->armControl);
addWidgetBinding("ManualControlSettings", "ArmedTimeout", ui->armTimeout, 0, 1000);
connect(ManualControlCommand::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(moveFMSlider()));
@ -156,6 +152,8 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
addWidget(ui->configurationWizard);
addWidget(ui->runCalibration);
autoLoadWidgets();
populateWidgets();
refreshWidgetsValues();
// Connect the help button
@ -1314,21 +1312,33 @@ void ConfigInputWidget::updatePositionSlider()
default:
case 6:
ui->fmsModePos6->setEnabled(true);
ui->cc_box_5->setEnabled(true);
ui->pidBankSs1_5->setEnabled(true);
// pass through
case 5:
ui->fmsModePos5->setEnabled(true);
ui->cc_box_4->setEnabled(true);
ui->pidBankSs1_4->setEnabled(true);
// pass through
case 4:
ui->fmsModePos4->setEnabled(true);
ui->cc_box_3->setEnabled(true);
ui->pidBankSs1_3->setEnabled(true);
// pass through
case 3:
ui->fmsModePos3->setEnabled(true);
ui->cc_box_2->setEnabled(true);
ui->pidBankSs1_2->setEnabled(true);
// pass through
case 2:
ui->fmsModePos2->setEnabled(true);
ui->cc_box_1->setEnabled(true);
ui->pidBankSs1_1->setEnabled(true);
// pass through
case 1:
ui->fmsModePos1->setEnabled(true);
ui->cc_box_0->setEnabled(true);
ui->pidBankSs1_0->setEnabled(true);
// pass through
case 0:
break;
@ -1337,21 +1347,33 @@ void ConfigInputWidget::updatePositionSlider()
switch (manualSettingsDataPriv.FlightModeNumber) {
case 0:
ui->fmsModePos1->setEnabled(false);
ui->cc_box_0->setEnabled(false);
ui->pidBankSs1_0->setEnabled(false);
// pass through
case 1:
ui->fmsModePos2->setEnabled(false);
ui->cc_box_1->setEnabled(false);
ui->pidBankSs1_1->setEnabled(false);
// pass through
case 2:
ui->fmsModePos3->setEnabled(false);
ui->cc_box_2->setEnabled(false);
ui->pidBankSs1_2->setEnabled(false);
// pass through
case 3:
ui->fmsModePos4->setEnabled(false);
ui->cc_box_3->setEnabled(false);
ui->pidBankSs1_3->setEnabled(false);
// pass through
case 4:
ui->fmsModePos5->setEnabled(false);
ui->cc_box_4->setEnabled(false);
ui->pidBankSs1_4->setEnabled(false);
// pass through
case 5:
ui->fmsModePos6->setEnabled(false);
ui->cc_box_5->setEnabled(false);
ui->pidBankSs1_5->setEnabled(false);
// pass through
case 6:
default:

View File

@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>880</width>
<height>672</height>
<width>796</width>
<height>828</height>
</rect>
</property>
<property name="windowTitle">
@ -128,8 +128,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>850</width>
<height>589</height>
<width>768</width>
<height>742</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout">
@ -277,6 +277,13 @@
</property>
</spacer>
</item>
<item>
<widget class="Line" name="line_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
</layout>
</widget>
<widget class="QWidget" name="wizard">
@ -552,11 +559,11 @@
<rect>
<x>0</x>
<y>0</y>
<width>850</width>
<height>589</height>
<width>768</width>
<height>742</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout_7" rowstretch="1,0,0">
<layout class="QGridLayout" name="gridLayout_7" rowstretch="1,0,0,0">
<property name="leftMargin">
<number>12</number>
</property>
@ -569,420 +576,21 @@
<property name="bottomMargin">
<number>12</number>
</property>
<item row="0" column="0">
<widget class="QGroupBox" name="groupBox_2">
<property name="minimumSize">
<item row="3" column="0">
<spacer name="verticalSpacer_5">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Expanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>0</width>
<height>230</height>
<width>20</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>230</height>
</size>
</property>
<property name="title">
<string>FlightMode Switch Positions</string>
</property>
<layout class="QGridLayout" name="gridLayout_4" rowstretch="0,0,0" columnstretch="0,0,1,0,1,0">
<property name="leftMargin">
<number>12</number>
</property>
<property name="topMargin">
<number>12</number>
</property>
<property name="rightMargin">
<number>12</number>
</property>
<property name="bottomMargin">
<number>12</number>
</property>
<item row="0" column="0" rowspan="3">
<layout class="QVBoxLayout" name="verticalLayout_9" stretch="0,0,0,0,0,0">
<item>
<widget class="QLabel" name="label_pos1">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Pos. 1</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_pos2">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>16</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Pos. 2</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_pos3">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Pos. 3</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_pos4">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Pos. 4</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_pos5">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Pos. 5</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_pos6">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>16</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Pos. 6</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="1" column="1">
<widget class="QSlider" name="fmsSlider">
<property name="enabled">
<bool>false</bool>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>160</height>
</size>
</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>
</item>
<item row="0" column="2" rowspan="3">
<layout class="QVBoxLayout" name="verticalLayout_10">
<property name="spacing">
<number>3</number>
</property>
<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>
<item row="1" column="3">
<spacer name="horizontalSpacer_4">
<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 row="0" column="4" rowspan="3">
<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.
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>
</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="2" column="1">
<spacer name="verticalSpacer_4">
<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>0</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="1">
<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>0</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="5">
<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>
</widget>
</spacer>
</item>
<item row="1" column="0">
<widget class="QGroupBox" name="groupBox">
@ -992,34 +600,50 @@ channel value for each flight mode.</string>
<property name="title">
<string>Stabilization Modes Configuration</string>
</property>
<layout class="QGridLayout" name="gridLayout_2" columnstretch="0,0,0,0,0,0,0,0,0,0">
<layout class="QGridLayout" name="gridLayout_2" columnstretch="0,0,0,0,0,0,0,0,0,0,0">
<property name="leftMargin">
<number>9</number>
</property>
<property name="horizontalSpacing">
<number>12</number>
<number>6</number>
</property>
<item row="2" column="1">
<spacer name="horizontalSpacer_11">
<item row="1" column="4">
<spacer name="horizontalSpacer_12">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Minimum</enum>
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="6">
<item row="1" column="8">
<spacer name="horizontalSpacer_13">
<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="9">
<widget class="QLabel" name="label_10">
<property name="minimumSize">
<size>
<width>0</width>
<width>120</width>
<height>20</height>
</size>
</property>
@ -1044,120 +668,11 @@ margin:1px;</string>
</property>
</widget>
</item>
<item row="2" column="3">
<spacer name="horizontalSpacer_12">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="3" column="2">
<widget class="QComboBox" name="fmsSsPos3Roll">
<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>Stabilized 1</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="2" column="5">
<spacer name="horizontalSpacer_13">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_21">
<property name="text">
<string>Stabilized 2</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="3" column="4">
<widget class="QComboBox" name="fmsSsPos3Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="3" column="6">
<widget class="QComboBox" name="fmsSsPos3Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="2" column="6">
<widget class="QComboBox" name="fmsSsPos2Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_8">
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</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>
<item row="0" column="4">
<item row="0" column="7">
<widget class="QLabel" name="label_9">
<property name="minimumSize">
<size>
<width>0</width>
<width>120</width>
<height>20</height>
</size>
</property>
@ -1182,113 +697,315 @@ margin:1px;</string>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QComboBox" name="fmsSsPos2Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="6">
<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="2">
<widget class="QComboBox" name="fmsSsPos2Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item row="1" column="2">
<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="3" column="0">
<widget class="QLabel" name="label_22">
<property name="text">
<string>Stabilized 3</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="1" column="4">
<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="3" column="8">
<widget class="QComboBox" name="pidBankSs3">
<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="8">
<widget class="QComboBox" name="pidBankSs2">
<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="9">
<spacer name="horizontalSpacer_14">
<item row="1" column="10">
<spacer name="horizontalSpacer_11">
<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>
<width>170</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="8">
<item row="0" column="3">
<widget class="QLabel" name="label_8">
<property name="minimumSize">
<size>
<width>120</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</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>
<item row="1" column="1">
<widget class="QFrame" name="frame_3">
<property name="minimumSize">
<size>
<width>106</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>105</width>
<height>16777215</height>
</size>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QVBoxLayout" name="verticalLayout_13">
<item>
<widget class="QLabel" name="label_14">
<property name="text">
<string>Stabilized 1</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_21">
<property name="text">
<string>Stabilized 2</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_22">
<property name="text">
<string>Stabilized 3</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item row="1" column="3">
<widget class="QFrame" name="frame_2">
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QVBoxLayout" name="verticalLayout_10">
<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>1</number>
</property>
<item>
<widget class="QComboBox" name="fmsSsPos1Roll">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos2Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos3Roll">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item row="1" column="7">
<widget class="QFrame" name="frame_5">
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QVBoxLayout" name="verticalLayout_14">
<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>1</number>
</property>
<item>
<widget class="QComboBox" name="fmsSsPos1Pitch">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos2Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos3Pitch">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item row="1" column="9">
<widget class="QFrame" name="frame_6">
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QVBoxLayout" name="verticalLayout_15">
<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>1</number>
</property>
<item>
<widget class="QComboBox" name="fmsSsPos1Yaw">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos2Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="fmsSsPos3Yaw">
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item row="1" column="2">
<spacer name="horizontalSpacer_14">
<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>
</layout>
</widget>
</item>
<item row="0" column="0">
<widget class="QGroupBox" name="groupBox_2">
<property name="minimumSize">
<size>
<width>0</width>
<height>230</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>230</height>
</size>
</property>
<property name="title">
<string>Flight Mode Switch Positions</string>
</property>
<layout class="QGridLayout" name="gridLayout_4">
<property name="leftMargin">
<number>9</number>
</property>
<property name="topMargin">
<number>9</number>
</property>
<property name="rightMargin">
<number>9</number>
</property>
<property name="bottomMargin">
<number>9</number>
</property>
<property name="horizontalSpacing">
<number>6</number>
</property>
<item row="0" column="6">
<widget class="QLabel" name="label_11">
<property name="minimumSize">
<size>
<width>0</width>
<width>80</width>
<height>20</height>
</size>
</property>
@ -1313,54 +1030,1059 @@ margin:1px;</string>
</property>
</widget>
</item>
<item row="1" column="8">
<widget class="QComboBox" name="pidBankSs1">
<item row="0" column="10">
<widget class="QLabel" name="label_16">
<property name="minimumSize">
<size>
<width>102</width>
<height>0</height>
<width>132</width>
<height>20</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</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>Flight Mode Count</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="7">
<spacer name="horizontalSpacer_15">
<item row="1" column="10">
<widget class="QSpinBox" name="fmsPosNum">
<property name="maximumSize">
<size>
<width>151</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Number of positions your FlightMode switch has.
Default is 3.
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>
</item>
<item row="2" column="10">
<widget class="QLabel" name="label_15">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" 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>Avoid &quot;Manual&quot; for multirotors!</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="3">
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="5">
<spacer name="horizontalSpacer_15">
<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="7">
<spacer name="horizontalSpacer_16">
<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="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>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="4">
<widget class="QLabel" name="label_12">
<property name="minimumSize">
<size>
<width>105</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</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>Cruise Control</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="8" rowspan="3">
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_13">
<property name="minimumSize">
<size>
<width>138</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</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>Flight Mode</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="4" rowspan="2">
<widget class="QFrame" name="frame_4">
<property name="minimumSize">
<size>
<width>30</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<layout class="QVBoxLayout" name="verticalLayout_4">
<property name="spacing">
<number>6</number>
</property>
<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>1</number>
</property>
<item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="cc_box_0">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Minimum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #1.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string/>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlFlightModeSwitchPosEnable</string>
<string>index:0</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="cc_box_1">
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #2.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string/>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlFlightModeSwitchPosEnable</string>
<string>index:1</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="cc_box_2">
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #3.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string/>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlFlightModeSwitchPosEnable</string>
<string>index:2</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="cc_box_3">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #4.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string/>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlFlightModeSwitchPosEnable</string>
<string>index:3</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="cc_box_4">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #5.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string/>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlFlightModeSwitchPosEnable</string>
<string>index:4</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item alignment="Qt::AlignHCenter">
<widget class="QCheckBox" name="cc_box_5">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>20</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Enabling this checkbox will enable Cruise Control for Flight Mode Switch position #6.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="layoutDirection">
<enum>Qt::RightToLeft</enum>
</property>
<property name="text">
<string/>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlFlightModeSwitchPosEnable</string>
<string>index:5</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item row="1" column="0" rowspan="2">
<widget class="QFrame" name="frame">
<property name="minimumSize">
<size>
<width>90</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>90</width>
<height>16777215</height>
</size>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QGridLayout" name="gridLayout_8">
<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>1</number>
</property>
<property name="horizontalSpacing">
<number>10</number>
</property>
<item row="4" column="1">
<widget class="QLabel" name="label_pos5">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Pos. 5</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLabel" name="label_pos3">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Pos. 3</string>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QLabel" name="label_pos4">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Pos. 4</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_pos1">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Pos. 1</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLabel" name="label_pos2">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>16</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Pos. 2</string>
</property>
</widget>
</item>
<item row="5" column="1">
<widget class="QLabel" name="label_pos6">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Maximum">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>20</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>Pos. 6</string>
</property>
</widget>
</item>
<item row="0" column="0" rowspan="6">
<widget class="QSlider" name="fmsSlider">
<property name="enabled">
<bool>false</bool>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>150</height>
</size>
</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>
</item>
</layout>
</widget>
</item>
<item row="1" column="2" rowspan="2">
<widget class="QFrame" name="frame">
<property name="minimumSize">
<size>
<width>120</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<layout class="QGridLayout" name="gridLayout_6">
<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>1</number>
</property>
<item row="5" column="1">
<widget class="QComboBox" name="fmsModePos6">
<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 row="0" column="1">
<widget class="QComboBox" name="fmsModePos1">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</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 row="4" column="1">
<widget class="QComboBox" name="fmsModePos5">
<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 row="2" column="1">
<widget class="QComboBox" name="fmsModePos3">
<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 row="3" column="1">
<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 row="1" column="1">
<widget class="QComboBox" name="fmsModePos2">
<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>
</layout>
</widget>
</item>
<item row="1" column="6" rowspan="2">
<widget class="QFrame" name="frame_7">
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<layout class="QVBoxLayout" name="verticalLayout_9">
<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>1</number>
</property>
<item>
<widget class="QComboBox" name="pidBankSs1_0">
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Select which set of roll rates / max bank angles / PIDs you want active on this switch position.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:FlightModeMap</string>
<string>index:0</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="pidBankSs1_1">
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Select which set of roll rates / max bank angles / PIDs you want active on this switch position.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:FlightModeMap</string>
<string>index:1</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="pidBankSs1_2">
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Select which set of roll rates / max bank angles / PIDs you want active on this switch position.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:FlightModeMap</string>
<string>index:2</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="pidBankSs1_3">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Select which set of roll rates / max bank angles / PIDs you want active on this switch position.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:FlightModeMap</string>
<string>index:3</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="pidBankSs1_4">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Select which set of roll rates / max bank angles / PIDs you want active on this switch position.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:FlightModeMap</string>
<string>index:4</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="pidBankSs1_5">
<property name="enabled">
<bool>false</bool>
</property>
<property name="minimumSize">
<size>
<width>75</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Select which set of roll rates / max bank angles / PIDs you want active on this switch position.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:FlightModeMap</string>
<string>index:5</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
</item>
<item row="2" column="0">
<spacer name="verticalSpacer_5">
<property name="orientation">
<enum>Qt::Vertical</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>
</widget>
@ -1461,8 +2183,8 @@ margin:1px;</string>
<rect>
<x>0</x>
<y>0</y>
<width>850</width>
<height>589</height>
<width>504</width>
<height>156</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
@ -1722,15 +2444,6 @@ Applies and Saves all settings to SD</string>
</layout>
</widget>
<tabstops>
<tabstop>fmsSsPos1Roll</tabstop>
<tabstop>fmsSsPos1Pitch</tabstop>
<tabstop>fmsSsPos1Yaw</tabstop>
<tabstop>fmsSsPos2Roll</tabstop>
<tabstop>fmsSsPos2Pitch</tabstop>
<tabstop>fmsSsPos2Yaw</tabstop>
<tabstop>fmsSsPos3Roll</tabstop>
<tabstop>fmsSsPos3Pitch</tabstop>
<tabstop>fmsSsPos3Yaw</tabstop>
<tabstop>tabWidget</tabstop>
<tabstop>deadband</tabstop>
<tabstop>graphicsView</tabstop>

View File

@ -26972,7 +26972,7 @@ border-radius: 5;</string>
</spacer>
</item>
<item row="1" column="1">
<widget class="QDoubleSpinBox" name="HorizonAntiWindup">
<widget class="QDoubleSpinBox" name="RattitudeAntiWindup">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
@ -27000,6 +27000,9 @@ border-radius: 5;</string>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="decimals">
<number>0</number>
</property>
@ -27081,6 +27084,566 @@ border-radius: 5;</string>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer_12">
<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="QGroupBox" name="gridGroupBox">
<property name="title">
<string>Cruise Control</string>
</property>
<layout class="QGridLayout" name="gridLayout_23">
<property name="leftMargin">
<number>9</number>
</property>
<property name="topMargin">
<number>9</number>
</property>
<property name="rightMargin">
<number>9</number>
</property>
<property name="bottomMargin">
<number>9</number>
</property>
<item row="1" column="0" colspan="2">
<widget class="QGroupBox" name="gridGroupBox">
<layout class="QGridLayout" name="gridLayout_25">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>9</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item row="1" column="4">
<widget class="QDoubleSpinBox" name="doubleSpinBox_6">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;-1, 0, or 1. Cruise Control multiplies the throttle stick by this value if the bank angle is past MaxAngle. The default is 0 which says to turn the motors off (actually set them to MinThrottle) when inverted. 1 says to use the unboosted throttle stick value. -1 (DON'T USE, INCOMPLETE, UNTESTED, for use by CP helis using idle up) says to reverse the throttle stick when inverted.
&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="minimum">
<double>-1.000000000000000</double>
</property>
<property name="maximum">
<double>1.000000000000000</double>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlInvertedPowerSwitch</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="1" column="5">
<spacer name="horizontalSpacer_59">
<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="2">
<widget class="QDoubleSpinBox" name="doubleSpinBox_3">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This is the bank angle that CruiseControl goes into inverted / power disabled mode. The power for inverted mode is controlled by CruiseControlInvertedPowerSwitch&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="maximum">
<double>180.000000000000000</double>
</property>
<property name="value">
<double>105.000000000000000</double>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlMaxAngle</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QDoubleSpinBox" name="doubleSpinBox">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Really just a safety limit. 4.0 means it will not use more than 4 times the power the throttle stick is requesting.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="decimals">
<number>2</number>
</property>
<property name="minimum">
<double>0.000000000000000</double>
</property>
<property name="maximum">
<double>50.000000000000000</double>
</property>
<property name="singleStep">
<double>0.250000000000000</double>
</property>
<property name="value">
<double>3.000000000000000</double>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlMaxPowerFactor</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLabel" name="label_6">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<height>16</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<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;</string>
</property>
<property name="text">
<string>PowerTrim</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="4">
<widget class="QDoubleSpinBox" name="doubleSpinBox_7">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This needs to be 0 for all copters except CP helis that are using idle up.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlNeutralThrust</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QDoubleSpinBox" name="doubleSpinBox_2">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;If you find that banging the stick around a lot makes the copter climb a bit, adjust this number down a little.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="decimals">
<number>2</number>
</property>
<property name="minimum">
<double>80.000000000000000</double>
</property>
<property name="maximum">
<double>120.000000000000000</double>
</property>
<property name="singleStep">
<double>0.250000000000000</double>
</property>
<property name="value">
<double>100.000000000000000</double>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlPowerTrim</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_4">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<height>16</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<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;</string>
</property>
<property name="text">
<string>MaxPowerFactor</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLabel" name="label_7">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<height>16</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<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;</string>
</property>
<property name="text">
<string>MaxAngle</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="label_8">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<height>16</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<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;</string>
</property>
<property name="text">
<string>MinThrottle</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="3">
<widget class="QDoubleSpinBox" name="doubleSpinBox_4">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Throttle stick below this disables Cruise Control. Also, by default Cruise Control forces the use of this value for throttle when the copter is inverted. For safety, never set this so low that the trimmed throttle stick cannot get below it.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="value">
<double>5.000000000000000</double>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlMinThrottle</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="2" column="4">
<widget class="QLabel" name="label_11">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<height>16</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<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;</string>
</property>
<property name="text">
<string>NeutralThrust</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="3">
<widget class="QDoubleSpinBox" name="doubleSpinBox_5">
<property name="toolTip">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Multi-copters should probably use 90% to 95% to leave some headroom for stabilization. CP helis can set this to 100%.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="value">
<double>90.000000000000000</double>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>fieldname:CruiseControlMaxThrottle</string>
<string>haslimits:no</string>
<string>scale:1</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="2" column="3">
<widget class="QLabel" name="label_9">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<height>16</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<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;</string>
</property>
<property name="text">
<string>MaxThrottle</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLabel" name="label_10">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>140</width>
<height>16</height>
</size>
</property>
<property name="font">
<font>
<weight>75</weight>
<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;</string>
</property>
<property name="text">
<string>InvertedPower</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="1" column="0">
<spacer name="horizontalSpacer_60">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::Fixed</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>90</width>
<height>11</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</item>
<item row="0" column="1">
<widget class="QPushButton" name="pushButton_11">
<property name="text">
<string>Default</string>
</property>
<property name="objrelation" stdset="0">
<stringlist>
<string>objname:StabilizationSettings</string>
<string>button:default</string>
<string>buttongroup:16</string>
</stringlist>
</property>
</widget>
</item>
<item row="0" column="0">
<spacer name="horizontalSpacer_58">
<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>
</item>
<item>
<spacer name="verticalSpacer_11">
<property name="orientation">

View File

@ -276,12 +276,6 @@ void ConfigTaskWidget::onAutopilotConnect()
}
invalidateObjects();
m_isConnected = true;
foreach(WidgetBinding * binding, m_widgetBindingsPerObject) {
if (!binding->isEnabled()) {
continue;
}
loadWidgetLimits(binding->widget(), binding->field(), binding->index(), binding->isLimited(), binding->scale());
}
setDirty(false);
enableControls(true);
refreshWidgetsValues();
@ -556,7 +550,7 @@ bool ConfigTaskWidget::addShadowWidgetBinding(QString objectName, QString fieldN
if (defaultReloadGroups) {
addWidgetToReloadGroups(widget, defaultReloadGroups);
}
if (!binding->isEnabled()) {
if (binding->isEnabled()) {
loadWidgetLimits(widget, binding->field(), binding->index(), isLimited, scale);
}
return true;
@ -575,20 +569,23 @@ void ConfigTaskWidget::autoLoadWidgets()
if (info.isValid()) {
bindingStruct uiRelation;
uiRelation.buttonType = none;
uiRelation.buttonType = none;
uiRelation.scale = 1;
uiRelation.element = QString();
uiRelation.haslimits = false;
uiRelation.index = -1;
uiRelation.elementName = QString();
uiRelation.haslimits = false;
foreach(QString str, info.toStringList()) {
QString prop = str.split(":").at(0);
QString value = str.split(":").at(1);
if (prop == "objname") {
uiRelation.objname = value;
uiRelation.objectName = value;
} else if (prop == "fieldname") {
uiRelation.fieldname = value;
uiRelation.fieldName = value;
} else if (prop == "element") {
uiRelation.element = value;
uiRelation.elementName = value;
} else if (prop == "index") {
uiRelation.index = value.toInt();
} else if (prop == "scale") {
if (value == "null") {
uiRelation.scale = 1;
@ -661,7 +658,11 @@ void ConfigTaskWidget::autoLoadWidgets()
} else {
QWidget *wid = qobject_cast<QWidget *>(widget);
if (wid) {
addWidgetBinding(uiRelation.objname, uiRelation.fieldname, wid, uiRelation.element, uiRelation.scale, uiRelation.haslimits, &uiRelation.buttonGroup);
if (uiRelation.index != -1) {
addWidgetBinding(uiRelation.objectName, uiRelation.fieldName, wid, uiRelation.index, uiRelation.scale, uiRelation.haslimits, &uiRelation.buttonGroup);
} else {
addWidgetBinding(uiRelation.objectName, uiRelation.fieldName, wid, uiRelation.elementName, uiRelation.scale, uiRelation.haslimits, &uiRelation.buttonGroup);
}
}
}
}

View File

@ -191,9 +191,10 @@ private:
enum buttonTypeEnum { none, save_button, apply_button, reload_button, default_button, help_button };
struct bindingStruct {
QString objname;
QString fieldname;
QString element;
QString objectName;
QString fieldName;
QString elementName;
int index;
QString url;
buttonTypeEnum buttonType;
QList<int> buttonGroup;

View File

@ -8,6 +8,7 @@
<field name="Yaw" units="%" type="float" elements="1"/>
<field name="Collective" units="%" type="float" elements="1"/>
<field name="Channel" units="us" type="uint16" elements="9"/>
<field name="FlightModeSwitchPosition" units="" type="uint8" elements="1"/>
<access gcs="readwrite" flight="readwrite"/>
<telemetrygcs acked="false" updatemode="manual" period="0"/>
<telemetryflight acked="false" updatemode="periodic" period="2000"/>

View File

@ -3,11 +3,11 @@
<object name="StabilizationSettings" singleinstance="true" settings="true" category="Control">
<description>PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired</description>
<!-- Note: The number of elements here must match the number of available flight modes -->
<field name="FlightModeMap" units="" type="enum"
options="Bank1,Bank2,Bank3"
elementnames="Manual,Stabilized1,Stabilized2,Stabilized3,Autotune,AltitudeHold,AltitudeVario,VelocityControl,PositionHold,ReturnToBase,Land,PathPlanner,POI"
defaultvalue="Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1,Bank1"/>
<!-- Note: The number of elements here must match the number of available flight mode switch positions -->
<field name="FlightModeMap" units="" type="enum"
options="Bank1,Bank2,Bank3"
elements="6"
defaultvalue="Bank1,Bank1,Bank1,Bank1,Bank1,Bank1"/>
<field name="VbarSensitivity" units="frac" type="float" elementnames="Roll,Pitch,Yaw" defaultvalue="0.5,0.5,0.5"/>
<field name="VbarRollPI" units="1/(deg/s)" type="float" elementnames="Kp,Ki" defaultvalue="0.005,0.002"/>
@ -30,6 +30,15 @@
<field name="RattitudeAntiWindup" units="" type="uint8" elements="1" defaultvalue="10"/>
<field name="CruiseControlMinThrottle" units="%" type="uint8" elements="1" defaultvalue="5"/>
<field name="CruiseControlMaxThrottle" units="%" type="uint8" elements="1" defaultvalue="90"/>
<field name="CruiseControlMaxAngle" units="deg" type="uint8" elements="1" defaultvalue="105"/>
<field name="CruiseControlMaxPowerFactor" units="x" type="float" elements="1" defaultvalue="3.0"/>
<field name="CruiseControlPowerTrim" units="%" type="float" elements="1" defaultvalue="100.0"/>
<field name="CruiseControlInvertedPowerSwitch" units="" type="int8" elements="1" defaultvalue="0"/>
<field name="CruiseControlNeutralThrust" units="%" type="uint8" elements="1" defaultvalue="0"/>
<field name="CruiseControlFlightModeSwitchPosEnable" units="" type="enum" elements="6" options="FALSE,TRUE" defaultvalue="FALSE"/>
<field name="LowThrottleZeroIntegral" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="TRUE"/>
<field name="LowThrottleZeroAxis" units="" type="enum" elementnames="Roll,Pitch,Yaw" options="FALSE,TRUE" defaultvalue="FALSE,FALSE,FALSE"/>