mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-03-21 13:28:58 +01:00
Merge remote-tracking branch 'origin/rel-14.01' into laurent/OP-1187_allow_french_translations_in_future_releases
This commit is contained in:
commit
8795b1aebd
10
WHATSNEW.txt
10
WHATSNEW.txt
@ -1,5 +1,6 @@
|
||||
--- RELEASE-14.01-RC1 --- Cruising Ratt ---
|
||||
This is the RC1 for the first 2014 software release.
|
||||
|
||||
--- RELEASE-14.01-RC2 --- Cruising Ratt ---
|
||||
This is the RC2 for the first 2014 software release.
|
||||
This version still supports the CopterControl and CC3D.
|
||||
It includes some major "under the hood" changes like migration
|
||||
to Qt5.1 and QtQuick2 widgets, an overhaul of UAVTalk to improve
|
||||
@ -15,6 +16,11 @@ in this release is accessible here:
|
||||
|
||||
http://progress.openpilot.org/browse/OP/fixforversion/10220
|
||||
|
||||
Issues fixes since RC1 release
|
||||
http://progress.openpilot.org/issues/?jql=labels%20%3D%20%2214.01-rc1%22
|
||||
OP-1166 OP-1168 OP-1169 OP-1176 OP-1177 OP-1178 OP-1179 OP-1180
|
||||
OP-1182 OP-1183 OP-1184 OP-1187 OP-1188 OP-1192
|
||||
|
||||
--- RELEASE-13.06.04 ---
|
||||
This maintenance release includes the following fixes missing in (previously not released to public) RELEASE-13.06.03.
|
||||
- Fixed issues with Google Maps;
|
||||
|
@ -55,7 +55,7 @@
|
||||
#define STACK_SIZE_BYTES 1312
|
||||
#endif
|
||||
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 4)
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 4) // device driver
|
||||
#define FAILSAFE_TIMEOUT_MS 100
|
||||
#define MAX_MIX_ACTUATORS ACTUATORCOMMAND_CHANNEL_NUMELEM
|
||||
|
||||
|
@ -72,10 +72,16 @@
|
||||
#define UPDATE_RATE 25.0f
|
||||
#define GYRO_NEUTRAL 1665
|
||||
|
||||
#define UPDATE_EXPECTED (1.0f / 666.0f)
|
||||
#define UPDATE_MIN 1.0e-6f
|
||||
#define UPDATE_MAX 1.0f
|
||||
#define UPDATE_ALPHA 1.0e-2f
|
||||
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static xTaskHandle taskHandle;
|
||||
static PiOSDeltatimeConfig dtconfig;
|
||||
|
||||
// Private functions
|
||||
static void AttitudeTask(void *parameters);
|
||||
@ -214,6 +220,8 @@ static void AttitudeTask(__attribute__((unused)) void *parameters)
|
||||
// Force settings update to make sure rotation loaded
|
||||
settingsUpdatedCb(AttitudeSettingsHandle());
|
||||
|
||||
PIOS_DELTATIME_Init(&dtconfig, UPDATE_EXPECTED, UPDATE_MIN, UPDATE_MAX, UPDATE_ALPHA);
|
||||
|
||||
// Main task loop
|
||||
while (1) {
|
||||
FlightStatusData flightStatus;
|
||||
@ -473,12 +481,7 @@ static inline void apply_accel_filter(const float *raw, float *filtered)
|
||||
|
||||
static void updateAttitude(AccelStateData *accelStateData, GyroStateData *gyrosData)
|
||||
{
|
||||
float dT;
|
||||
portTickType thisSysTime = xTaskGetTickCount();
|
||||
static portTickType lastSysTime = 0;
|
||||
|
||||
dT = (thisSysTime == lastSysTime) ? 0.001f : (thisSysTime - lastSysTime) * portTICK_RATE_MS * 0.001f;
|
||||
lastSysTime = thisSysTime;
|
||||
float dT = PIOS_DELTATIME_GetAverageSeconds(&dtconfig);
|
||||
|
||||
// Bad practice to assume structure order, but saves memory
|
||||
float *gyros = &gyrosData->x;
|
||||
|
@ -64,7 +64,7 @@
|
||||
#define STACK_SIZE_BYTES 1152
|
||||
#endif
|
||||
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 4)
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3) // 3 = flight control
|
||||
#define UPDATE_PERIOD_MS 20
|
||||
#define THROTTLE_FAILSAFE -0.1f
|
||||
#define ARMED_THRESHOLD 0.50f
|
||||
|
@ -65,6 +65,11 @@
|
||||
#include "relay_tuning.h"
|
||||
|
||||
// Private constants
|
||||
#define UPDATE_EXPECTED (1.0f / 666.0f)
|
||||
#define UPDATE_MIN 1.0e-6f
|
||||
#define UPDATE_MAX 1.0f
|
||||
#define UPDATE_ALPHA 1.0e-2f
|
||||
|
||||
#define MAX_QUEUE_SIZE 1
|
||||
|
||||
#if defined(PIOS_STABILIZATION_STACK_SIZE)
|
||||
@ -73,7 +78,7 @@
|
||||
#define STACK_SIZE_BYTES 840
|
||||
#endif
|
||||
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 4)
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 3) // FLIGHT CONTROL priority
|
||||
#define FAILSAFE_TIMEOUT_MS 30
|
||||
|
||||
// number of flight mode switch positions
|
||||
@ -194,7 +199,9 @@ MODULE_INITCALL(StabilizationInitialize, StabilizationStart);
|
||||
static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
UAVObjEvent ev;
|
||||
uint32_t timeval = PIOS_DELAY_GetRaw();
|
||||
PiOSDeltatimeConfig timeval;
|
||||
|
||||
PIOS_DELTATIME_Init(&timeval, UPDATE_EXPECTED, UPDATE_MIN, UPDATE_MAX, UPDATE_ALPHA);
|
||||
|
||||
ActuatorDesiredData actuatorDesired;
|
||||
StabilizationDesiredData stabDesired;
|
||||
@ -226,9 +233,7 @@ static void stabilizationTask(__attribute__((unused)) void *parameters)
|
||||
continue;
|
||||
}
|
||||
|
||||
dT = PIOS_DELAY_DiffuS(timeval) * 1.0e-6f;
|
||||
timeval = PIOS_DELAY_GetRaw();
|
||||
|
||||
dT = PIOS_DELTATIME_GetAverageSeconds(&timeval);
|
||||
FlightStatusGet(&flightStatus);
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
AttitudeStateGet(&attitudeState);
|
||||
|
@ -40,20 +40,22 @@
|
||||
|
||||
#define STACK_REQUIRED 128
|
||||
|
||||
#define DT_ALPHA 1e-3f
|
||||
#define DT_ALPHA 1e-2f
|
||||
#define DT_MIN 1e-6f
|
||||
#define DT_MAX 1.0f
|
||||
#define DT_AVERAGE 1e-3f
|
||||
|
||||
// Private types
|
||||
struct data {
|
||||
float state[4]; // state = altitude,velocity,accel_offset,accel
|
||||
float pos[3]; // position updates from other filters
|
||||
float vel[3]; // position updates from other filters
|
||||
float dTA;
|
||||
float dTA2;
|
||||
int32_t lastTime;
|
||||
float accelLast;
|
||||
float baroLast;
|
||||
int32_t baroLastTime;
|
||||
bool first_run;
|
||||
float state[4]; // state = altitude,velocity,accel_offset,accel
|
||||
float pos[3]; // position updates from other filters
|
||||
float vel[3]; // position updates from other filters
|
||||
|
||||
PiOSDeltatimeConfig dt1config;
|
||||
PiOSDeltatimeConfig dt2config;
|
||||
float accelLast;
|
||||
float baroLast;
|
||||
bool first_run;
|
||||
AltitudeFilterSettingsData settings;
|
||||
};
|
||||
|
||||
@ -89,8 +91,8 @@ static int32_t init(stateFilter *self)
|
||||
this->vel[0] = 0.0f;
|
||||
this->vel[1] = 0.0f;
|
||||
this->vel[2] = 0.0f;
|
||||
this->dTA = -1.0f;
|
||||
this->dTA2 = -1.0f;
|
||||
PIOS_DELTATIME_Init(&this->dt1config, DT_AVERAGE, DT_MIN, DT_MAX, DT_ALPHA);
|
||||
PIOS_DELTATIME_Init(&this->dt2config, DT_AVERAGE, DT_MIN, DT_MAX, DT_ALPHA);
|
||||
this->baroLast = 0.0f;
|
||||
this->accelLast = 0.0f;
|
||||
this->first_run = 1;
|
||||
@ -104,12 +106,8 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
|
||||
if (this->first_run) {
|
||||
// Initialize to current altitude reading at initial location
|
||||
if (IS_SET(state->updated, SENSORUPDATES_accel)) {
|
||||
this->lastTime = PIOS_DELAY_GetRaw();
|
||||
}
|
||||
if (IS_SET(state->updated, SENSORUPDATES_baro)) {
|
||||
this->first_run = 0;
|
||||
this->baroLastTime = PIOS_DELAY_GetRaw();
|
||||
this->first_run = 0;
|
||||
}
|
||||
} else {
|
||||
// save existing position and velocity updates so GPS will still work
|
||||
@ -141,22 +139,14 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
|
||||
// correct velocity and position state (integration)
|
||||
// low pass for average dT, compensate timing jitter from scheduler
|
||||
float dT = PIOS_DELAY_DiffuS(this->lastTime) / 1.0e6f;
|
||||
this->lastTime = PIOS_DELAY_GetRaw();
|
||||
if (dT < 0.001f) {
|
||||
dT = 0.001f;
|
||||
}
|
||||
if (this->dTA < 0) {
|
||||
this->dTA = dT;
|
||||
} else {
|
||||
this->dTA = this->dTA * (1.0f - DT_ALPHA) + dT * DT_ALPHA;
|
||||
}
|
||||
//
|
||||
float dT = PIOS_DELTATIME_GetAverageSeconds(&this->dt1config);
|
||||
float speedLast = this->state[1];
|
||||
|
||||
this->state[1] += 0.5f * (this->accelLast + (this->state[3] - this->state[2])) * this->dTA;
|
||||
this->state[1] += 0.5f * (this->accelLast + (this->state[3] - this->state[2])) * dT;
|
||||
this->accelLast = this->state[3] - this->state[2];
|
||||
|
||||
this->state[0] += 0.5f * (speedLast + this->state[1]) * this->dTA;
|
||||
this->state[0] += 0.5f * (speedLast + this->state[1]) * dT;
|
||||
|
||||
|
||||
state->pos[0] = this->pos[0];
|
||||
@ -175,17 +165,8 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
|
||||
// correct the velocity state (low pass differentiation)
|
||||
// low pass for average dT, compensate timing jitter from scheduler
|
||||
float dT = PIOS_DELAY_DiffuS(this->baroLastTime) / 1.0e6f;
|
||||
this->baroLastTime = PIOS_DELAY_GetRaw();
|
||||
if (dT < 0.001f) {
|
||||
dT = 0.001f;
|
||||
}
|
||||
if (this->dTA2 < 0) {
|
||||
this->dTA2 = dT;
|
||||
} else {
|
||||
this->dTA2 = this->dTA2 * (1.0f - DT_ALPHA) + dT * DT_ALPHA;
|
||||
}
|
||||
this->state[1] = (1.0f - (this->settings.BaroKp * this->settings.BaroKp)) * this->state[1] + (this->settings.BaroKp * this->settings.BaroKp) * (state->baro[0] - this->baroLast) / this->dTA2;
|
||||
float dT = PIOS_DELTATIME_GetAverageSeconds(&this->dt2config);
|
||||
this->state[1] = (1.0f - (this->settings.BaroKp * this->settings.BaroKp)) * this->state[1] + (this->settings.BaroKp * this->settings.BaroKp) * (state->baro[0] - this->baroLast) / dT;
|
||||
this->baroLast = state->baro[0];
|
||||
|
||||
state->pos[0] = this->pos[0];
|
||||
|
@ -45,6 +45,8 @@
|
||||
|
||||
#define STACK_REQUIRED 2048
|
||||
#define DT_ALPHA 1e-3f
|
||||
#define DT_MIN 1e-6f
|
||||
#define DT_MAX 1.0f
|
||||
#define DT_INIT (1.0f / 666.0f) // initialize with 666 Hz (default sensor update rate on revo)
|
||||
|
||||
#define IMPORT_SENSOR_IF_UPDATED(shortname, num) \
|
||||
@ -66,10 +68,9 @@ struct data {
|
||||
|
||||
stateEstimation work;
|
||||
|
||||
uint32_t ins_last_time;
|
||||
bool inited;
|
||||
bool inited;
|
||||
|
||||
float dTa;
|
||||
PiOSDeltatimeConfig dtconfig;
|
||||
};
|
||||
|
||||
// Private variables
|
||||
@ -154,11 +155,10 @@ static int32_t maininit(stateFilter *self)
|
||||
{
|
||||
struct data *this = (struct data *)self->localdata;
|
||||
|
||||
this->inited = false;
|
||||
this->init_stage = 0;
|
||||
this->work.updated = 0;
|
||||
this->ins_last_time = PIOS_DELAY_GetRaw();
|
||||
this->dTa = DT_INIT;
|
||||
this->inited = false;
|
||||
this->init_stage = 0;
|
||||
this->work.updated = 0;
|
||||
PIOS_DELTATIME_Init(&this->dtconfig, DT_INIT, DT_MIN, DT_MAX, DT_ALPHA);
|
||||
|
||||
EKFConfigurationGet(&this->ekfConfiguration);
|
||||
int t;
|
||||
@ -224,17 +224,7 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
return 0;
|
||||
}
|
||||
|
||||
dT = PIOS_DELAY_DiffuS(this->ins_last_time) / 1.0e6f;
|
||||
this->ins_last_time = PIOS_DELAY_GetRaw();
|
||||
|
||||
// This should only happen at start up or at mode switches
|
||||
if (dT > 0.01f) {
|
||||
dT = 0.01f;
|
||||
} else if (dT <= 0.001f) {
|
||||
dT = 0.001f;
|
||||
}
|
||||
|
||||
this->dTa = this->dTa * (1.0f - DT_ALPHA) + dT * DT_ALPHA; // low pass for average dT, compensate timing jitter from scheduler
|
||||
dT = PIOS_DELTATIME_GetAverageSeconds(&this->dtconfig);
|
||||
|
||||
if (!this->inited && IS_SET(this->work.updated, SENSORUPDATES_mag) && IS_SET(this->work.updated, SENSORUPDATES_baro) && IS_SET(this->work.updated, SENSORUPDATES_pos)) {
|
||||
// Don't initialize until all sensors are read
|
||||
@ -300,7 +290,7 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
// Run prediction a bit before any corrections
|
||||
|
||||
float gyros[3] = { DEG2RAD(this->work.gyro[0]), DEG2RAD(this->work.gyro[1]), DEG2RAD(this->work.gyro[2]) };
|
||||
INSStatePrediction(gyros, this->work.accel, this->dTa);
|
||||
INSStatePrediction(gyros, this->work.accel, dT);
|
||||
|
||||
// Copy the attitude into the state
|
||||
// NOTE: updating gyr correctly is valid, because this code is reached only when SENSORUPDATES_gyro is already true
|
||||
@ -335,7 +325,7 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
float gyros[3] = { DEG2RAD(this->work.gyro[0]), DEG2RAD(this->work.gyro[1]), DEG2RAD(this->work.gyro[2]) };
|
||||
|
||||
// Advance the state estimate
|
||||
INSStatePrediction(gyros, this->work.accel, this->dTa);
|
||||
INSStatePrediction(gyros, this->work.accel, dT);
|
||||
|
||||
// Copy the attitude into the state
|
||||
// NOTE: updating gyr correctly is valid, because this code is reached only when SENSORUPDATES_gyro is already true
|
||||
@ -355,7 +345,7 @@ static int32_t filter(stateFilter *self, stateEstimation *state)
|
||||
state->updated |= SENSORUPDATES_attitude | SENSORUPDATES_pos | SENSORUPDATES_vel;
|
||||
|
||||
// Advance the covariance estimate
|
||||
INSCovariancePrediction(this->dTa);
|
||||
INSCovariancePrediction(dT);
|
||||
|
||||
if (IS_SET(this->work.updated, SENSORUPDATES_mag)) {
|
||||
sensors |= MAG_SENSORS;
|
||||
|
64
flight/pios/common/pios_deltatime.c
Normal file
64
flight/pios/common/pios_deltatime.c
Normal file
@ -0,0 +1,64 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_DELTATIME time measurement Functions
|
||||
* @brief PiOS Delay functionality
|
||||
* @{
|
||||
*
|
||||
* @file pios_deltatime.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Settings functions header
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 <pios.h>
|
||||
|
||||
|
||||
void PIOS_DELTATIME_Init(PiOSDeltatimeConfig *config, float average, float min, float max, float alpha)
|
||||
{
|
||||
PIOS_Assert(config);
|
||||
config->average = average;
|
||||
config->min = min;
|
||||
config->max = max;
|
||||
config->alpha = alpha;
|
||||
config->last = PIOS_DELAY_GetRaw();
|
||||
};
|
||||
|
||||
|
||||
float PIOS_DELTATIME_GetAverageSeconds(PiOSDeltatimeConfig *config)
|
||||
{
|
||||
PIOS_Assert(config);
|
||||
float dT = PIOS_DELAY_DiffuS(config->last) * 1.0e-6f;
|
||||
config->last = PIOS_DELAY_GetRaw();
|
||||
if (dT < config->min) {
|
||||
dT = config->min;
|
||||
}
|
||||
if (dT > config->max) {
|
||||
dT = config->max;
|
||||
}
|
||||
config->average = config->average * (1.0f - config->alpha) + dT * config->alpha;
|
||||
return config->average;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -64,7 +64,7 @@
|
||||
|
||||
/* Local Defines */
|
||||
#define STACK_SIZE_BYTES 200
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 2)
|
||||
#define TASK_PRIORITY (tskIDLE_PRIORITY + 4) // flight control relevant device driver (ppm link)
|
||||
#define ISR_TIMEOUT 1 // ms
|
||||
#define EVENT_QUEUE_SIZE 5
|
||||
#define RFM22B_DEFAULT_RX_DATARATE RFM22_datarate_9600
|
||||
|
53
flight/pios/inc/pios_deltatime.h
Normal file
53
flight/pios/inc/pios_deltatime.h
Normal file
@ -0,0 +1,53 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_DELTATIME time measurement Functions
|
||||
* @brief PiOS Delay functionality
|
||||
* @{
|
||||
*
|
||||
* @file pios_deltatime.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Settings functions header
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 PIOS_DELTATIME_H
|
||||
#define PIOS_DELTATIME_H
|
||||
|
||||
struct PiOSDeltatimeConfigStruct {
|
||||
uint32_t last;
|
||||
float average;
|
||||
float min;
|
||||
float max;
|
||||
float alpha;
|
||||
};
|
||||
typedef struct PiOSDeltatimeConfigStruct PiOSDeltatimeConfig;
|
||||
|
||||
/* Public Functions */
|
||||
void PIOS_DELTATIME_Init(PiOSDeltatimeConfig *config, float average, float min, float max, float alpha);
|
||||
|
||||
float PIOS_DELTATIME_GetAverageSeconds(PiOSDeltatimeConfig *config);
|
||||
|
||||
#endif /* PIOS_DELTATIME_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -102,6 +102,7 @@
|
||||
/* PIOS system functions */
|
||||
#ifdef PIOS_INCLUDE_DELAY
|
||||
#include <pios_delay.h>
|
||||
#include <pios_deltatime.h>
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_INITCALL
|
||||
|
@ -79,6 +79,7 @@ extern void PIOS_LED_Init(void);
|
||||
#include <pios_wdg.h>
|
||||
#include <pios_debug.h>
|
||||
#include <pios_debuglog.h>
|
||||
#include <pios_deltatime.h>
|
||||
#include <pios_crc.h>
|
||||
#include <pios_rcvr.h>
|
||||
#include <pios_flash.h>
|
||||
|
@ -101,6 +101,7 @@ SRC += $(MATHLIB)/pid.c
|
||||
SRC += $(PIOSCORECOMMON)/pios_task_monitor.c
|
||||
SRC += $(PIOSCORECOMMON)/pios_dosfs_logfs.c
|
||||
SRC += $(PIOSCORECOMMON)/pios_debuglog.c
|
||||
SRC += $(PIOSCORECOMMON)/pios_deltatime.c
|
||||
|
||||
## PIOS Hardware
|
||||
include $(PIOS)/posix/library.mk
|
||||
|
@ -2285,7 +2285,7 @@
|
||||
<configurationStreamVersion>1000</configurationStreamVersion>
|
||||
<dataSize>240</dataSize>
|
||||
<plotCurve0>
|
||||
<color>4294945280</color>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-System</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
@ -2297,37 +2297,17 @@
|
||||
<plotCurve1>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Actuator</uavField>
|
||||
<uavField>StackRemaining-CallbackScheduler0</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve1>
|
||||
<plotCurve10>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Guidance</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve10>
|
||||
<plotCurve11>
|
||||
<color>4294945280</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Watchdog</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve11>
|
||||
<plotCurve2>
|
||||
<color>4294945280</color>
|
||||
<color>4278190335</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTx</uavField>
|
||||
<uavField>StackRemaining-CallbackScheduler1</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2335,9 +2315,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve2>
|
||||
<plotCurve3>
|
||||
<color>4294945280</color>
|
||||
<color>4294967040</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryTxPri</uavField>
|
||||
<uavField>StackRemaining-ManualControl</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2345,9 +2325,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve3>
|
||||
<plotCurve4>
|
||||
<color>4294945280</color>
|
||||
<color>4278255615</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
<uavField>StackRemaining-Stabilization</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2355,9 +2335,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve4>
|
||||
<plotCurve5>
|
||||
<color>4294945280</color>
|
||||
<color>4294923775</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-GPS</uavField>
|
||||
<uavField>StackRemaining-Actuator</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2365,9 +2345,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve5>
|
||||
<plotCurve6>
|
||||
<color>4294945280</color>
|
||||
<color>4289331327</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-ManualControl</uavField>
|
||||
<uavField>StackRemaining-Sensors</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2385,9 +2365,9 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve7>
|
||||
<plotCurve8>
|
||||
<color>4294945280</color>
|
||||
<color>4283760767</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-AHRSComms</uavField>
|
||||
<uavField>StackRemaining-TelemetryTx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
@ -2395,15 +2375,35 @@
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve8>
|
||||
<plotCurve9>
|
||||
<color>4294945280</color>
|
||||
<color>4289331327</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-Stabilization</uavField>
|
||||
<uavField>StackRemaining-TelemetryTxPri</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve9>
|
||||
<plotCurve10>
|
||||
<color>4294901760</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-TelemetryRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve10>
|
||||
<plotCurve11>
|
||||
<color>4283782527</color>
|
||||
<mathFunction>None</mathFunction>
|
||||
<uavField>StackRemaining-RadioRx</uavField>
|
||||
<uavObject>TaskInfo</uavObject>
|
||||
<yMaximum>0</yMaximum>
|
||||
<yMeanSamples>1</yMeanSamples>
|
||||
<yMinimum>0</yMinimum>
|
||||
<yScalePower>0</yScalePower>
|
||||
</plotCurve11>
|
||||
<plotCurveCount>12</plotCurveCount>
|
||||
<plotType>1</plotType>
|
||||
<refreshInterval>1000</refreshInterval>
|
||||
|
@ -1,19 +1,5 @@
|
||||
/* Linux styles */
|
||||
|
||||
QGroupBox {
|
||||
border: 1px solid gray;
|
||||
border-radius: 5px;
|
||||
margin-top: 1ex;
|
||||
font-size: 11px;
|
||||
font-weight: bold;
|
||||
}
|
||||
|
||||
QGroupBox::title {
|
||||
subcontrol-origin: margin;
|
||||
subcontrol-position: top left;
|
||||
padding: 0 3px;
|
||||
}
|
||||
|
||||
MixerCurveWidget {
|
||||
font-size: 12px;
|
||||
}
|
||||
QToolTip {
|
||||
color: black;
|
||||
}
|
||||
|
@ -1,22 +1,2 @@
|
||||
/* MacOS styles */
|
||||
|
||||
QGroupBox {
|
||||
border: 1px solid gray;
|
||||
border-radius: 5px;
|
||||
margin-top: 1ex;
|
||||
font-size: 11px;
|
||||
font-weight: bold;
|
||||
}
|
||||
|
||||
QGroupBox::title {
|
||||
subcontrol-origin: margin;
|
||||
subcontrol-position: top left;
|
||||
padding: 0 3px;
|
||||
}
|
||||
|
||||
QTabWidget::pane {
|
||||
margin: 1px, 1px, 1px, 1px;
|
||||
border: 2px solid rgb(196, 196, 196);
|
||||
border-radius: 5px;
|
||||
padding: 0px;
|
||||
}
|
||||
|
@ -14,521 +14,695 @@
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_10">
|
||||
<property name="margin">
|
||||
<number>12</number>
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="vehicleTypeGroupBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string/>
|
||||
</property>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<property name="margin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<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="aircraftType">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<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="sizeType">
|
||||
<enum>QSizePolicy::Expanding</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>2</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<widget class="QTabBar" name="aircraftType" native="true"/>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QTabWidget" name="tabWidget">
|
||||
<property name="currentIndex">
|
||||
<number>0</number>
|
||||
<widget class="QFrame" name="vehicleTypeFrame">
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<widget class="QWidget" name="mixerSettingsPage">
|
||||
<property name="autoFillBackground">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<attribute name="title">
|
||||
<string>Mixer Settings</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<property name="margin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QScrollArea" name="airframesScrollArea">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<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">
|
||||
<property name="autoFillBackground">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">#vehicleTypeFrame{
|
||||
color: rgb(180, 180, 180);
|
||||
margin-top: -1px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<widget class="QTabWidget" name="tabWidget">
|
||||
<property name="currentIndex">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<widget class="QWidget" name="mixerSettingsPage">
|
||||
<property name="autoFillBackground">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<widget class="QWidget" name="scrollAreaWidgetContents">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>832</width>
|
||||
<height>461</height>
|
||||
</rect>
|
||||
<attribute name="title">
|
||||
<string>Mixer Settings</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<property name="leftMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<property name="margin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QStackedWidget" name="airframesWidget">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="currentIndex">
|
||||
<number>-1</number>
|
||||
<property name="topMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QScrollArea" name="airframesScrollArea">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<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>820</width>
|
||||
<height>478</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QStackedWidget" name="airframesWidget">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="currentIndex">
|
||||
<number>-1</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<widget class="QWidget" name="feedForwardPage">
|
||||
<property name="autoFillBackground">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<attribute name="title">
|
||||
<string>Feed Forward</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_25">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<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">
|
||||
<widget class="QWidget" name="feedForwardPage">
|
||||
<property name="autoFillBackground">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<widget class="QWidget" name="scrollAreaWidgetContents_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>223</width>
|
||||
<height>269</height>
|
||||
</rect>
|
||||
<attribute name="title">
|
||||
<string>Feed Forward</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_25">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_18">
|
||||
<property name="margin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_12">
|
||||
<property name="title">
|
||||
<string>Feed Forward Configuration</string>
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<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>271</width>
|
||||
<height>307</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_8">
|
||||
<property name="margin">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_18">
|
||||
<property name="leftMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item row="2" column="0" colspan="3">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_10">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_22">
|
||||
<property name="text">
|
||||
<string>Decel Time Constant</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<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 name="topMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_12">
|
||||
<property name="title">
|
||||
<string>Feed Forward Configuration</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_8">
|
||||
<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="2" column="0" colspan="3">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_10">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_22">
|
||||
<property name="text">
|
||||
<string>Decel Time Constant</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<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>
|
||||
<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>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="1" column="0" colspan="3">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_9">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_21">
|
||||
<property name="text">
|
||||
<string>Accel Time Constant</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<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.
|
||||
</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>
|
||||
<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>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="1" column="0" colspan="3">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_9">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_21">
|
||||
<property name="text">
|
||||
<string>Accel Time Constant</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<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>
|
||||
<spacer name="horizontalSpacer_13">
|
||||
<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="1">
|
||||
<widget class="QLabel" name="maxAccelSliderValue">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>1000</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QSlider" name="feedForwardSlider">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</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="2">
|
||||
<widget class="QSlider" name="maxAccelSlider">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Limits how much the engines can accelerate or decelerate.
|
||||
</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>
|
||||
<spacer name="horizontalSpacer_13">
|
||||
<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="1">
|
||||
<widget class="QLabel" name="maxAccelSliderValue">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>1000</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QSlider" name="feedForwardSlider">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</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="2">
|
||||
<widget class="QSlider" name="maxAccelSlider">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>32</height>
|
||||
</size>
|
||||
</property>
|
||||
<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>
|
||||
<property name="invertedAppearance">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="invertedControls">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</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>
|
||||
<property name="invertedAppearance">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="invertedControls">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_37">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<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>16777215</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>MaxAccel</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="feedForwardSliderValue">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>30</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>000</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label_20">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>FeedForward </string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_37">
|
||||
<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>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_13">
|
||||
<property name="title">
|
||||
<string/>
|
||||
</property>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_5">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_8">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>267</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><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html></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><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html></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><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html></string>
|
||||
</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>267</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QTextBrowser" name="textBrowser">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
@ -536,202 +710,53 @@ In 'units per second', a sound default is 1000.</string>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>MaxAccel</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="feedForwardSliderValue">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>30</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>000</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label_20">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>FeedForward </string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</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>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_13">
|
||||
<property name="title">
|
||||
<string/>
|
||||
</property>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_5">
|
||||
<property name="margin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_8">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>267</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">
|
||||
<property name="html">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html></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><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html></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><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">Beware! Check </span><span style=" font-family:'Sans'; font-size:10pt; font-weight:600;">all three</span><span style=" font-family:'Sans'; font-size:10pt;"> checkboxes to test Feed Forward.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Sans'; font-size:10pt;">It will run only if your airframe armed.</span></p></body></html></string>
|
||||
</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>267</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</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><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
</style></head><body style=" font-family:'Sans Serif'; font-size:9pt; font-weight:400; font-style:normal;">
|
||||
<table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;">
|
||||
<tr>
|
||||
<td style="border: none;">
|
||||
<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD REQUIRES CAUTION</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;"><br /></span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;"><br /></span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</span></p>
|
||||
<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">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.</span></p></td></tr></table></body></html></string>
|
||||
</property>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</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>20</width>
|
||||
<height>9</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="bottomLayout">
|
||||
<property name="spacing">
|
||||
@ -809,6 +834,14 @@ p, li { white-space: pre-wrap; }
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<customwidgets>
|
||||
<customwidget>
|
||||
<class>QTabBar</class>
|
||||
<extends>QWidget</extends>
|
||||
<header>qtabbar.h</header>
|
||||
<container>1</container>
|
||||
</customwidget>
|
||||
</customwidgets>
|
||||
<resources>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
</resources>
|
||||
|
@ -42,7 +42,16 @@
|
||||
<string>Camera Stabilization</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -64,15 +73,24 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>762</width>
|
||||
<height>658</height>
|
||||
<width>750</width>
|
||||
<height>729</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<property name="spacing">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<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>
|
||||
@ -1358,6 +1376,37 @@ The same value is used for all axes.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_4">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>50</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Messages</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<item>
|
||||
<widget class="QLabel" name="message">
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
@ -1379,37 +1428,6 @@ The same value is used for all axes.</string>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_4">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>50</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Messages</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<item>
|
||||
<widget class="QLabel" name="message">
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<property name="horizontalSpacing">
|
||||
|
@ -14,9 +14,6 @@
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<property name="margin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QTabWidget" name="tabWidget">
|
||||
<property name="currentIndex">
|
||||
@ -27,7 +24,16 @@
|
||||
<string>HW settings</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -110,12 +116,21 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>616</width>
|
||||
<height>513</height>
|
||||
<width>624</width>
|
||||
<height>516</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<property name="margin">
|
||||
<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="6" column="0" colspan="3">
|
||||
@ -627,7 +642,6 @@ Beware of not locking yourself out!</string>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="configgadget.qrc"/>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
|
@ -14,9 +14,6 @@
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||
<property name="margin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QTabWidget" name="tabWidget">
|
||||
<property name="currentIndex">
|
||||
@ -27,7 +24,16 @@
|
||||
<string>Attitude</string>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -110,12 +116,21 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>750</width>
|
||||
<height>483</height>
|
||||
<width>758</width>
|
||||
<height>486</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<property name="margin">
|
||||
<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>
|
||||
|
@ -250,7 +250,7 @@ void ConfigGadgetWidget::tabAboutToChange(int i, bool *proceed)
|
||||
}
|
||||
if (wid->isDirty()) {
|
||||
int ans = QMessageBox::warning(this, tr("Unsaved changes"), tr("The tab you are leaving has unsaved changes,"
|
||||
"if you proceed they will be lost."
|
||||
"if you proceed they will be lost.\n"
|
||||
"Do you still want to proceed?"), QMessageBox::Yes, QMessageBox::No);
|
||||
if (ans == QMessageBox::No) {
|
||||
*proceed = false;
|
||||
|
@ -82,12 +82,13 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) :
|
||||
InputChannelForm *inpForm = new InputChannelForm(this, index == 0);
|
||||
ui->channelSettings->layout()->addWidget(inpForm); // Add the row to the UI
|
||||
inpForm->setName(name);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelGroups", inpForm->ui->channelGroup, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelNumber", inpForm->ui->channelNumber, index);
|
||||
|
||||
// The order of the following three binding calls is important. Since the values will be populated
|
||||
// The order of the following binding calls is important. Since the values will be populated
|
||||
// in reverse order of the binding order otherwise the 'Reversed' logic will floor the neutral value
|
||||
// to the max value ( which is smaller than the neutral value when reversed )
|
||||
// to the max value ( which is smaller than the neutral value when reversed ) and the channel number
|
||||
// will not be set correctly.
|
||||
addWidgetBinding("ManualControlSettings", "ChannelNumber", inpForm->ui->channelNumber, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelGroups", inpForm->ui->channelGroup, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelNeutral", inpForm->ui->channelNeutral, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelNeutral", inpForm->ui->neutralValue, index);
|
||||
addWidgetBinding("ManualControlSettings", "ChannelMin", inpForm->ui->channelMin, index);
|
||||
|
@ -30,6 +30,7 @@
|
||||
#include <coreplugin/generalsettings.h>
|
||||
#include <oplinksettings.h>
|
||||
#include <oplinkstatus.h>
|
||||
#include <QMessageBox>
|
||||
|
||||
ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget(parent)
|
||||
{
|
||||
@ -40,19 +41,14 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
|
||||
oplinkStatusObj = dynamic_cast<UAVDataObject *>(objManager->getObject("OPLinkStatus"));
|
||||
if (oplinkStatusObj != NULL) {
|
||||
connect(oplinkStatusObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateStatus(UAVObject *)));
|
||||
} else {
|
||||
qDebug() << "Error: Object is unknown (OPLinkStatus).";
|
||||
}
|
||||
Q_ASSERT(oplinkStatusObj);
|
||||
connect(oplinkStatusObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateStatus(UAVObject *)));
|
||||
|
||||
// Connect to the OPLinkSettings object updates
|
||||
oplinkSettingsObj = dynamic_cast<OPLinkSettings *>(objManager->getObject("OPLinkSettings"));
|
||||
if (oplinkSettingsObj != NULL) {
|
||||
connect(oplinkSettingsObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateSettings(UAVObject *)));
|
||||
} else {
|
||||
qDebug() << "Error: Object is unknown (OPLinkSettings).";
|
||||
}
|
||||
Q_ASSERT(oplinkSettingsObj);
|
||||
connect(oplinkSettingsObj, SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateSettings(UAVObject *)));
|
||||
|
||||
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if (!settings->useExpertMode()) {
|
||||
m_oplink->Apply->setVisible(false);
|
||||
@ -62,7 +58,6 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
|
||||
addWidgetBinding("OPLinkSettings", "MainPort", m_oplink->MainPort);
|
||||
addWidgetBinding("OPLinkSettings", "FlexiPort", m_oplink->FlexiPort);
|
||||
addWidgetBinding("OPLinkSettings", "VCPPort", m_oplink->VCPPort);
|
||||
addWidgetBinding("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed);
|
||||
addWidgetBinding("OPLinkSettings", "MaxRFPower", m_oplink->MaxRFTxPower);
|
||||
addWidgetBinding("OPLinkSettings", "MinChannel", m_oplink->MinimumChannel);
|
||||
addWidgetBinding("OPLinkSettings", "MaxChannel", m_oplink->MaximumChannel);
|
||||
@ -72,6 +67,7 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
|
||||
addWidgetBinding("OPLinkSettings", "OneWay", m_oplink->OneWayLink);
|
||||
addWidgetBinding("OPLinkSettings", "PPMOnly", m_oplink->PPMOnly);
|
||||
addWidgetBinding("OPLinkSettings", "PPM", m_oplink->PPM);
|
||||
addWidgetBinding("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed);
|
||||
|
||||
addWidgetBinding("OPLinkStatus", "DeviceID", m_oplink->DeviceID);
|
||||
addWidgetBinding("OPLinkStatus", "RxGood", m_oplink->Good);
|
||||
@ -94,27 +90,19 @@ ConfigPipXtremeWidget::ConfigPipXtremeWidget(QWidget *parent) : ConfigTaskWidget
|
||||
addWidgetBinding("OPLinkStatus", "TXRate", m_oplink->TXRate);
|
||||
|
||||
// Connect the bind buttons
|
||||
connect(m_oplink->Bind1, SIGNAL(clicked()), this, SLOT(bind1()));
|
||||
connect(m_oplink->Bind2, SIGNAL(clicked()), this, SLOT(bind2()));
|
||||
connect(m_oplink->Bind3, SIGNAL(clicked()), this, SLOT(bind3()));
|
||||
connect(m_oplink->Bind4, SIGNAL(clicked()), this, SLOT(bind3()));
|
||||
connect(m_oplink->Bind1, SIGNAL(clicked()), this, SLOT(bind()));
|
||||
connect(m_oplink->Bind2, SIGNAL(clicked()), this, SLOT(bind()));
|
||||
connect(m_oplink->Bind3, SIGNAL(clicked()), this, SLOT(bind()));
|
||||
connect(m_oplink->Bind4, SIGNAL(clicked()), this, SLOT(bind()));
|
||||
|
||||
// Connect the selection changed signals.
|
||||
connect(m_oplink->PPMOnly, SIGNAL(toggled(bool)), this, SLOT(ppmOnlyToggled(bool)));
|
||||
connect(m_oplink->ComSpeed, SIGNAL(currentIndexChanged(int)), this, SLOT(comSpeedChanged(int)));
|
||||
|
||||
ppmOnlyToggled(m_oplink->PPMOnly->isChecked());
|
||||
|
||||
// Add scroll bar when necessary
|
||||
QScrollArea *scroll = new QScrollArea;
|
||||
scroll->setWidget(m_oplink->frame_3);
|
||||
scroll->setWidgetResizable(true);
|
||||
m_oplink->verticalLayout_3->addWidget(scroll);
|
||||
connect(m_oplink->PPMOnly, SIGNAL(toggled(bool)), this, SLOT(ppmOnlyChanged()));
|
||||
|
||||
// Request and update of the setting object.
|
||||
settingsUpdated = false;
|
||||
autoLoadWidgets();
|
||||
disableMouseWheelEvents();
|
||||
updateEnableControls();
|
||||
}
|
||||
|
||||
ConfigPipXtremeWidget::~ConfigPipXtremeWidget()
|
||||
@ -130,101 +118,102 @@ void ConfigPipXtremeWidget::updateStatus(UAVObject *object)
|
||||
oplinkSettingsObj->requestUpdate();
|
||||
}
|
||||
|
||||
// Update the link state
|
||||
UAVObjectField *linkField = object->getField("LinkState");
|
||||
m_oplink->LinkState->setText(linkField->getValue().toString());
|
||||
bool linkConnected = (linkField->getValue() == linkField->getOptions().at(OPLinkStatus::LINKSTATE_CONNECTED));
|
||||
bool modemEnabled = linkConnected || (linkField->getValue() == linkField->getOptions().at(OPLinkStatus::LINKSTATE_DISCONNECTED)) ||
|
||||
(linkField->getValue() == linkField->getOptions().at(OPLinkStatus::LINKSTATE_ENABLED));
|
||||
|
||||
UAVObjectField *pairRssiField = object->getField("PairSignalStrengths");
|
||||
|
||||
bool bound;
|
||||
bool ok;
|
||||
quint32 boundPairId = m_oplink->CoordID->text().toUInt(&ok, 16);
|
||||
|
||||
// Update the detected devices.
|
||||
UAVObjectField *pairIdField = object->getField("PairIDs");
|
||||
if (pairIdField) {
|
||||
quint32 pairid1 = pairIdField->getValue(0).toUInt();
|
||||
m_oplink->PairID1->setText(QString::number(pairid1, 16).toUpper());
|
||||
m_oplink->PairID1->setEnabled(false);
|
||||
m_oplink->Bind1->setEnabled(pairid1);
|
||||
quint32 pairid2 = pairIdField->getValue(1).toUInt();
|
||||
m_oplink->PairID2->setText(QString::number(pairIdField->getValue(1).toUInt(), 16).toUpper());
|
||||
m_oplink->PairID2->setEnabled(false);
|
||||
m_oplink->Bind2->setEnabled(pairid2);
|
||||
quint32 pairid3 = pairIdField->getValue(2).toUInt();
|
||||
m_oplink->PairID3->setText(QString::number(pairIdField->getValue(2).toUInt(), 16).toUpper());
|
||||
m_oplink->PairID3->setEnabled(false);
|
||||
m_oplink->Bind3->setEnabled(pairid3);
|
||||
quint32 pairid4 = pairIdField->getValue(3).toUInt();
|
||||
m_oplink->PairID4->setText(QString::number(pairIdField->getValue(3).toUInt(), 16).toUpper());
|
||||
m_oplink->PairID4->setEnabled(false);
|
||||
m_oplink->Bind4->setEnabled(pairid4);
|
||||
} else {
|
||||
qDebug() << "ConfigPipXtremeWidget: Count not read PairID field.";
|
||||
}
|
||||
UAVObjectField *pairRssiField = object->getField("PairSignalStrengths");
|
||||
if (pairRssiField) {
|
||||
m_oplink->PairSignalStrengthBar1->setValue(pairRssiField->getValue(0).toInt());
|
||||
m_oplink->PairSignalStrengthBar2->setValue(pairRssiField->getValue(1).toInt());
|
||||
m_oplink->PairSignalStrengthBar3->setValue(pairRssiField->getValue(2).toInt());
|
||||
m_oplink->PairSignalStrengthBar4->setValue(pairRssiField->getValue(3).toInt());
|
||||
m_oplink->PairSignalStrengthLabel1->setText(QString("%1dB").arg(pairRssiField->getValue(0).toInt()));
|
||||
m_oplink->PairSignalStrengthLabel2->setText(QString("%1dB").arg(pairRssiField->getValue(1).toInt()));
|
||||
m_oplink->PairSignalStrengthLabel3->setText(QString("%1dB").arg(pairRssiField->getValue(2).toInt()));
|
||||
m_oplink->PairSignalStrengthLabel4->setText(QString("%1dB").arg(pairRssiField->getValue(3).toInt()));
|
||||
} else {
|
||||
qDebug() << "ConfigPipXtremeWidget: Count not read PairID field.";
|
||||
}
|
||||
quint32 pairid = pairIdField->getValue(0).toUInt();
|
||||
bound = (pairid == boundPairId);
|
||||
m_oplink->PairID1->setText(QString::number(pairid, 16).toUpper());
|
||||
m_oplink->PairID1->setEnabled(false);
|
||||
m_oplink->Bind1->setText(bound ? tr("Unbind") : tr("Bind"));
|
||||
m_oplink->Bind1->setEnabled(pairid && modemEnabled);
|
||||
m_oplink->PairSignalStrengthBar1->setValue(((bound && !linkConnected) || !modemEnabled) ? -127 : pairRssiField->getValue(0).toInt());
|
||||
m_oplink->PairSignalStrengthLabel1->setText(QString("%1dB").arg(m_oplink->PairSignalStrengthBar1->value()));
|
||||
|
||||
pairid = pairIdField->getValue(1).toUInt();
|
||||
bound = (pairid == boundPairId);
|
||||
m_oplink->PairID2->setText(QString::number(pairid, 16).toUpper());
|
||||
m_oplink->PairID2->setEnabled(false);
|
||||
m_oplink->Bind2->setText(bound ? tr("Unbind") : tr("Bind"));
|
||||
m_oplink->Bind2->setEnabled(pairid && modemEnabled);
|
||||
m_oplink->PairSignalStrengthBar2->setValue(((bound && !linkConnected) || !modemEnabled) ? -127 : pairRssiField->getValue(1).toInt());
|
||||
m_oplink->PairSignalStrengthLabel2->setText(QString("%1dB").arg(m_oplink->PairSignalStrengthBar2->value()));
|
||||
|
||||
pairid = pairIdField->getValue(2).toUInt();
|
||||
bound = (pairid == boundPairId);
|
||||
m_oplink->PairID3->setText(QString::number(pairid, 16).toUpper());
|
||||
m_oplink->PairID3->setEnabled(false);
|
||||
m_oplink->Bind3->setText(bound ? tr("Unbind") : tr("Bind"));
|
||||
m_oplink->Bind3->setEnabled(pairid && modemEnabled);
|
||||
m_oplink->PairSignalStrengthBar3->setValue(((bound && !linkConnected) || !modemEnabled) ? -127 : pairRssiField->getValue(2).toInt());
|
||||
m_oplink->PairSignalStrengthLabel3->setText(QString("%1dB").arg(m_oplink->PairSignalStrengthBar3->value()));
|
||||
|
||||
pairid = pairIdField->getValue(3).toUInt();
|
||||
bound = (pairid == boundPairId);
|
||||
m_oplink->PairID4->setText(QString::number(pairid, 16).toUpper());
|
||||
m_oplink->PairID4->setEnabled(false);
|
||||
m_oplink->Bind4->setText(bound ? tr("Unbind") : tr("Bind"));
|
||||
m_oplink->Bind4->setEnabled(pairid && modemEnabled);
|
||||
m_oplink->PairSignalStrengthBar4->setValue(((bound && !linkConnected) || !modemEnabled) ? -127 : pairRssiField->getValue(3).toInt());
|
||||
m_oplink->PairSignalStrengthLabel4->setText(QString("%1dB").arg(m_oplink->PairSignalStrengthBar4->value()));
|
||||
|
||||
// Update the Description field
|
||||
// TODO use UAVObjectUtilManager::descriptionToStructure()
|
||||
UAVObjectField *descField = object->getField("Description");
|
||||
if (descField) {
|
||||
if (descField->getValue(0) != QChar(255)) {
|
||||
/*
|
||||
* This looks like a binary with a description at the end:
|
||||
* 4 bytes: header: "OpFw".
|
||||
* 4 bytes: GIT commit tag (short version of SHA1).
|
||||
* 4 bytes: Unix timestamp of compile time.
|
||||
* 2 bytes: target platform. Should follow same rule as BOARD_TYPE and BOARD_REVISION in board define files.
|
||||
* 26 bytes: commit tag if it is there, otherwise branch name. '-dirty' may be added if needed. Zero-padded.
|
||||
* 20 bytes: SHA1 sum of the firmware.
|
||||
* 20 bytes: SHA1 sum of the uavo definitions.
|
||||
* 20 bytes: free for now.
|
||||
*/
|
||||
char buf[OPLinkStatus::DESCRIPTION_NUMELEM];
|
||||
for (unsigned int i = 0; i < 26; ++i) {
|
||||
buf[i] = descField->getValue(i + 14).toChar().toLatin1();
|
||||
}
|
||||
buf[26] = '\0';
|
||||
QString descstr(buf);
|
||||
quint32 gitDate = descField->getValue(11).toChar().toLatin1() & 0xFF;
|
||||
for (int i = 1; i < 4; i++) {
|
||||
gitDate = gitDate << 8;
|
||||
gitDate += descField->getValue(11 - i).toChar().toLatin1() & 0xFF;
|
||||
}
|
||||
QString date = QDateTime::fromTime_t(gitDate).toUTC().toString("yyyy-MM-dd HH:mm");
|
||||
m_oplink->FirmwareVersion->setText(descstr + " " + date);
|
||||
} else {
|
||||
m_oplink->FirmwareVersion->setText(tr("Unknown"));
|
||||
if (descField->getValue(0) != QChar(255)) {
|
||||
/*
|
||||
* This looks like a binary with a description at the end:
|
||||
* 4 bytes: header: "OpFw".
|
||||
* 4 bytes: GIT commit tag (short version of SHA1).
|
||||
* 4 bytes: Unix timestamp of compile time.
|
||||
* 2 bytes: target platform. Should follow same rule as BOARD_TYPE and BOARD_REVISION in board define files.
|
||||
* 26 bytes: commit tag if it is there, otherwise branch name. '-dirty' may be added if needed. Zero-padded.
|
||||
* 20 bytes: SHA1 sum of the firmware.
|
||||
* 20 bytes: SHA1 sum of the uavo definitions.
|
||||
* 20 bytes: free for now.
|
||||
*/
|
||||
char buf[OPLinkStatus::DESCRIPTION_NUMELEM];
|
||||
for (unsigned int i = 0; i < 26; ++i) {
|
||||
buf[i] = descField->getValue(i + 14).toChar().toLatin1();
|
||||
}
|
||||
buf[26] = '\0';
|
||||
QString descstr(buf);
|
||||
quint32 gitDate = descField->getValue(11).toChar().toLatin1() & 0xFF;
|
||||
for (int i = 1; i < 4; i++) {
|
||||
gitDate = gitDate << 8;
|
||||
gitDate += descField->getValue(11 - i).toChar().toLatin1() & 0xFF;
|
||||
}
|
||||
QString date = QDateTime::fromTime_t(gitDate).toUTC().toString("yyyy-MM-dd HH:mm");
|
||||
m_oplink->FirmwareVersion->setText(descstr + " " + date);
|
||||
} else {
|
||||
qDebug() << "ConfigPipXtremeWidget: Failed to read Description field.";
|
||||
m_oplink->FirmwareVersion->setText(tr("Unknown"));
|
||||
}
|
||||
|
||||
// Update the serial number field
|
||||
UAVObjectField *serialField = object->getField("CPUSerial");
|
||||
if (serialField) {
|
||||
char buf[OPLinkStatus::CPUSERIAL_NUMELEM * 2 + 1];
|
||||
for (unsigned int i = 0; i < OPLinkStatus::CPUSERIAL_NUMELEM; ++i) {
|
||||
unsigned char val = serialField->getValue(i).toUInt() >> 4;
|
||||
buf[i * 2] = ((val < 10) ? '0' : '7') + val;
|
||||
val = serialField->getValue(i).toUInt() & 0xf;
|
||||
buf[i * 2 + 1] = ((val < 10) ? '0' : '7') + val;
|
||||
}
|
||||
buf[OPLinkStatus::CPUSERIAL_NUMELEM * 2] = '\0';
|
||||
m_oplink->SerialNumber->setText(buf);
|
||||
} else {
|
||||
qDebug() << "ConfigPipXtremeWidget: Failed to read CPUSerial field.";
|
||||
char buf[OPLinkStatus::CPUSERIAL_NUMELEM * 2 + 1];
|
||||
for (unsigned int i = 0; i < OPLinkStatus::CPUSERIAL_NUMELEM; ++i) {
|
||||
unsigned char val = serialField->getValue(i).toUInt() >> 4;
|
||||
buf[i * 2] = ((val < 10) ? '0' : '7') + val;
|
||||
val = serialField->getValue(i).toUInt() & 0xf;
|
||||
buf[i * 2 + 1] = ((val < 10) ? '0' : '7') + val;
|
||||
}
|
||||
buf[OPLinkStatus::CPUSERIAL_NUMELEM * 2] = '\0';
|
||||
m_oplink->SerialNumber->setText(buf);
|
||||
|
||||
// Update the link state
|
||||
UAVObjectField *linkField = object->getField("LinkState");
|
||||
if (linkField) {
|
||||
m_oplink->LinkState->setText(linkField->getValue().toString());
|
||||
} else {
|
||||
qDebug() << "ConfigPipXtremeWidget: Failed to read LinkState field.";
|
||||
}
|
||||
updateEnableControls();
|
||||
}
|
||||
|
||||
/*!
|
||||
@ -239,124 +228,94 @@ void ConfigPipXtremeWidget::updateSettings(UAVObject *object)
|
||||
|
||||
// Enable components based on the board type connected.
|
||||
UAVObjectField *board_type_field = oplinkStatusObj->getField("BoardType");
|
||||
if (board_type_field) {
|
||||
switch (board_type_field->getValue().toInt()) {
|
||||
case 0x09: // Revolution
|
||||
m_oplink->MainPort->setVisible(false);
|
||||
m_oplink->MainPortLabel->setVisible(false);
|
||||
m_oplink->FlexiPort->setVisible(false);
|
||||
m_oplink->FlexiPortLabel->setVisible(false);
|
||||
m_oplink->VCPPort->setVisible(false);
|
||||
m_oplink->VCPPortLabel->setVisible(false);
|
||||
m_oplink->FlexiIOPort->setVisible(false);
|
||||
m_oplink->FlexiIOPortLabel->setVisible(false);
|
||||
m_oplink->PPM->setVisible(true);
|
||||
break;
|
||||
case 0x03: // OPLinkMini
|
||||
m_oplink->MainPort->setVisible(true);
|
||||
m_oplink->MainPortLabel->setVisible(true);
|
||||
m_oplink->FlexiPort->setVisible(true);
|
||||
m_oplink->FlexiPortLabel->setVisible(true);
|
||||
m_oplink->VCPPort->setVisible(true);
|
||||
m_oplink->VCPPortLabel->setVisible(true);
|
||||
m_oplink->FlexiIOPort->setVisible(false);
|
||||
m_oplink->FlexiIOPortLabel->setVisible(false);
|
||||
m_oplink->PPM->setVisible(false);
|
||||
break;
|
||||
case 0x0A:
|
||||
m_oplink->MainPort->setVisible(true);
|
||||
m_oplink->MainPortLabel->setVisible(true);
|
||||
m_oplink->FlexiPort->setVisible(true);
|
||||
m_oplink->FlexiPortLabel->setVisible(true);
|
||||
m_oplink->VCPPort->setVisible(true);
|
||||
m_oplink->VCPPortLabel->setVisible(true);
|
||||
m_oplink->FlexiIOPort->setVisible(true);
|
||||
m_oplink->FlexiIOPortLabel->setVisible(true);
|
||||
m_oplink->PPM->setVisible(false);
|
||||
break;
|
||||
default:
|
||||
// This shouldn't happen.
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
qDebug() << "BoardType not found.";
|
||||
switch (board_type_field->getValue().toInt()) {
|
||||
case 0x09: // Revolution
|
||||
m_oplink->MainPort->setVisible(false);
|
||||
m_oplink->MainPortLabel->setVisible(false);
|
||||
m_oplink->FlexiPort->setVisible(false);
|
||||
m_oplink->FlexiPortLabel->setVisible(false);
|
||||
m_oplink->VCPPort->setVisible(false);
|
||||
m_oplink->VCPPortLabel->setVisible(false);
|
||||
m_oplink->FlexiIOPort->setVisible(false);
|
||||
m_oplink->FlexiIOPortLabel->setVisible(false);
|
||||
m_oplink->PPM->setVisible(true);
|
||||
break;
|
||||
case 0x03: // OPLinkMini
|
||||
m_oplink->MainPort->setVisible(true);
|
||||
m_oplink->MainPortLabel->setVisible(true);
|
||||
m_oplink->FlexiPort->setVisible(true);
|
||||
m_oplink->FlexiPortLabel->setVisible(true);
|
||||
m_oplink->VCPPort->setVisible(true);
|
||||
m_oplink->VCPPortLabel->setVisible(true);
|
||||
m_oplink->FlexiIOPort->setVisible(false);
|
||||
m_oplink->FlexiIOPortLabel->setVisible(false);
|
||||
m_oplink->PPM->setVisible(false);
|
||||
break;
|
||||
case 0x0A: // OPLink?
|
||||
m_oplink->MainPort->setVisible(true);
|
||||
m_oplink->MainPortLabel->setVisible(true);
|
||||
m_oplink->FlexiPort->setVisible(true);
|
||||
m_oplink->FlexiPortLabel->setVisible(true);
|
||||
m_oplink->VCPPort->setVisible(true);
|
||||
m_oplink->VCPPortLabel->setVisible(true);
|
||||
m_oplink->FlexiIOPort->setVisible(true);
|
||||
m_oplink->FlexiIOPortLabel->setVisible(true);
|
||||
m_oplink->PPM->setVisible(false);
|
||||
break;
|
||||
default:
|
||||
// This shouldn't happen.
|
||||
break;
|
||||
}
|
||||
|
||||
// Enable the push buttons.
|
||||
enableControls(true);
|
||||
updateEnableControls();
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::updateEnableControls()
|
||||
{
|
||||
enableControls(true);
|
||||
ppmOnlyChanged();
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::disconnected()
|
||||
{
|
||||
if (settingsUpdated) {
|
||||
settingsUpdated = false;
|
||||
|
||||
// Enable the push buttons.
|
||||
enableControls(false);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::SetPairID(QLineEdit *pairIdWidget)
|
||||
void ConfigPipXtremeWidget::bind()
|
||||
{
|
||||
// Get the pair ID out of the selection widget
|
||||
quint32 pairID = 0;
|
||||
bool okay;
|
||||
QPushButton *bindButton = qobject_cast<QPushButton *>(sender());
|
||||
|
||||
pairID = pairIdWidget->text().toUInt(&okay, 16);
|
||||
|
||||
// Store the ID in the coord ID field.
|
||||
m_oplink->CoordID->setText(QString::number(pairID, 16).toUpper());
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::bind1()
|
||||
{
|
||||
SetPairID(m_oplink->PairID1);
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::bind2()
|
||||
{
|
||||
SetPairID(m_oplink->PairID1);
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::bind3()
|
||||
{
|
||||
SetPairID(m_oplink->PairID1);
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::bind4()
|
||||
{
|
||||
SetPairID(m_oplink->PairID1);
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::ppmOnlyToggled(bool on)
|
||||
{
|
||||
if (on) {
|
||||
m_oplink->PPM->setEnabled(false);
|
||||
m_oplink->OneWayLink->setEnabled(false);
|
||||
m_oplink->ComSpeed->setEnabled(false);
|
||||
} else {
|
||||
m_oplink->PPM->setEnabled(true);
|
||||
m_oplink->OneWayLink->setEnabled(true);
|
||||
m_oplink->ComSpeed->setEnabled(true);
|
||||
// Change the comspeed from 4800 of PPM only is turned off.
|
||||
if (m_oplink->ComSpeed->currentIndex() == OPLinkSettings::COMSPEED_4800) {
|
||||
m_oplink->ComSpeed->setCurrentIndex(OPLinkSettings::COMSPEED_9600);
|
||||
if (bindButton) {
|
||||
QLineEdit *editField = NULL;
|
||||
if (bindButton == m_oplink->Bind1) {
|
||||
editField = m_oplink->PairID1;
|
||||
} else if (bindButton == m_oplink->Bind2) {
|
||||
editField = m_oplink->PairID2;
|
||||
} else if (bindButton == m_oplink->Bind3) {
|
||||
editField = m_oplink->PairID3;
|
||||
} else if (bindButton == m_oplink->Bind4) {
|
||||
editField = m_oplink->PairID4;
|
||||
}
|
||||
Q_ASSERT(editField);
|
||||
bool ok;
|
||||
quint32 pairid = editField->text().toUInt(&ok, 16);
|
||||
if (ok) {
|
||||
quint32 boundPairId = m_oplink->CoordID->text().toUInt(&ok, 16);
|
||||
(pairid != boundPairId) ? m_oplink->CoordID->setText(QString::number(pairid, 16).toUpper()) : m_oplink->CoordID->setText("0");
|
||||
}
|
||||
QMessageBox::information(this, tr("Information"), tr("To apply the changes when binding/unbinding the board must be rebooted or power cycled."), QMessageBox::Ok);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigPipXtremeWidget::comSpeedChanged(int index)
|
||||
void ConfigPipXtremeWidget::ppmOnlyChanged()
|
||||
{
|
||||
qDebug() << "comSpeedChanged: " << index;
|
||||
switch (index) {
|
||||
case OPLinkSettings::COMSPEED_4800:
|
||||
m_oplink->PPMOnly->setChecked(true);
|
||||
break;
|
||||
default:
|
||||
m_oplink->PPMOnly->setChecked(false);
|
||||
break;
|
||||
}
|
||||
bool is_ppm_only = m_oplink->PPMOnly->isChecked();
|
||||
|
||||
m_oplink->PPM->setEnabled(!is_ppm_only);
|
||||
m_oplink->OneWayLink->setEnabled(!is_ppm_only);
|
||||
m_oplink->ComSpeed->setEnabled(!is_ppm_only);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -55,16 +55,13 @@ private:
|
||||
// Are the settings current?
|
||||
bool settingsUpdated;
|
||||
|
||||
void SetPairID(QLineEdit *pairIdWidget);
|
||||
protected:
|
||||
void updateEnableControls();
|
||||
|
||||
private slots:
|
||||
void disconnected();
|
||||
void bind1();
|
||||
void bind2();
|
||||
void bind3();
|
||||
void bind4();
|
||||
void ppmOnlyToggled(bool toggled);
|
||||
void comSpeedChanged(int index);
|
||||
void bind();
|
||||
void ppmOnlyChanged();
|
||||
};
|
||||
|
||||
#endif // CONFIGTXPIDWIDGET_H
|
||||
|
@ -117,9 +117,11 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
|
||||
addWidget(ui->pushButton_23);
|
||||
|
||||
addWidget(ui->basicResponsivenessGroupBox);
|
||||
connect(ui->basicResponsivenessGroupBox, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
|
||||
addWidget(ui->basicResponsivenessCheckBox);
|
||||
connect(ui->basicResponsivenessCheckBox, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
|
||||
addWidget(ui->advancedResponsivenessGroupBox);
|
||||
connect(ui->advancedResponsivenessGroupBox, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
|
||||
addWidget(ui->advancedResponsivenessCheckBox);
|
||||
connect(ui->advancedResponsivenessCheckBox, SIGNAL(toggled(bool)), this, SLOT(linkCheckBoxes(bool)));
|
||||
|
||||
connect(this, SIGNAL(widgetContentsChanged(QWidget *)), this, SLOT(processLinkedWidgets(QWidget *)));
|
||||
|
||||
@ -138,7 +140,7 @@ void ConfigStabilizationWidget::refreshWidgetsValues(UAVObject *o)
|
||||
{
|
||||
ConfigTaskWidget::refreshWidgetsValues(o);
|
||||
|
||||
ui->basicResponsivenessGroupBox->setChecked(ui->rateRollKp_3->value() == ui->ratePitchKp_4->value() &&
|
||||
ui->basicResponsivenessCheckBox->setChecked(ui->rateRollKp_3->value() == ui->ratePitchKp_4->value() &&
|
||||
ui->rateRollKi_3->value() == ui->ratePitchKi_4->value());
|
||||
}
|
||||
|
||||
@ -169,14 +171,18 @@ void ConfigStabilizationWidget::linkCheckBoxes(bool value)
|
||||
ui->checkBox_2->setChecked(value);
|
||||
} else if (sender() == ui->checkBox_2) {
|
||||
ui->checkBox_8->setChecked(value);
|
||||
} else if (sender() == ui->basicResponsivenessGroupBox) {
|
||||
ui->advancedResponsivenessGroupBox->setChecked(!value);
|
||||
} else if (sender() == ui->basicResponsivenessCheckBox) {
|
||||
ui->advancedResponsivenessCheckBox->setChecked(!value);
|
||||
ui->basicResponsivenessControls->setEnabled(value);
|
||||
ui->advancedResponsivenessControls->setEnabled(!value);
|
||||
if (value) {
|
||||
processLinkedWidgets(ui->AttitudeResponsivenessSlider);
|
||||
processLinkedWidgets(ui->RateResponsivenessSlider);
|
||||
}
|
||||
} else if (sender() == ui->advancedResponsivenessGroupBox) {
|
||||
ui->basicResponsivenessGroupBox->setChecked(!value);
|
||||
} else if (sender() == ui->advancedResponsivenessCheckBox) {
|
||||
ui->basicResponsivenessCheckBox->setChecked(!value);
|
||||
ui->basicResponsivenessControls->setEnabled(!value);
|
||||
ui->advancedResponsivenessControls->setEnabled(value);
|
||||
}
|
||||
}
|
||||
|
||||
@ -218,7 +224,7 @@ void ConfigStabilizationWidget::processLinkedWidgets(QWidget *widget)
|
||||
}
|
||||
}
|
||||
|
||||
if (ui->basicResponsivenessGroupBox->isChecked()) {
|
||||
if (ui->basicResponsivenessCheckBox->isChecked()) {
|
||||
if (widget == ui->AttitudeResponsivenessSlider) {
|
||||
ui->ratePitchKp_4->setValue(ui->AttitudeResponsivenessSlider->value());
|
||||
} else if (widget == ui->RateResponsivenessSlider) {
|
||||
|
@ -122,18 +122,18 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
|
||||
addUAVObject("MixerSettings");
|
||||
addUAVObject("ActuatorSettings");
|
||||
|
||||
ffTuningInProgress = false;
|
||||
ffTuningPhase = false;
|
||||
m_ffTuningInProgress = false;
|
||||
m_ffTuningPhase = false;
|
||||
|
||||
QStringList airframeTypes;
|
||||
airframeTypes << "Fixed Wing" << "Multirotor" << "Helicopter" << "Ground" << "Custom";
|
||||
m_aircraft->aircraftType->addItems(airframeTypes);
|
||||
|
||||
// Set default vehicle to MultiRotor
|
||||
// m_aircraft->aircraftType->setCurrentIndex(3);
|
||||
// The order of the tabs is important since they correspond with the AirframCategory enum
|
||||
m_aircraft->aircraftType->addTab(tr("Multirotor"));
|
||||
m_aircraft->aircraftType->addTab(tr("Fixed Wing"));
|
||||
m_aircraft->aircraftType->addTab(tr("Helicopter"));
|
||||
m_aircraft->aircraftType->addTab(tr("Ground"));
|
||||
m_aircraft->aircraftType->addTab(tr("Custom"));
|
||||
|
||||
// Connect aircraft type selection dropbox to callback function
|
||||
connect(m_aircraft->aircraftType, SIGNAL(currentIndexChanged(int)), this, SLOT(switchAirframeType(int)));
|
||||
connect(m_aircraft->aircraftType, SIGNAL(currentChanged(int)), this, SLOT(switchAirframeType(int)));
|
||||
|
||||
// Connect the three feed forward test checkboxes
|
||||
connect(m_aircraft->ffTestBox1, SIGNAL(clicked(bool)), this, SLOT(enableFFTest()));
|
||||
@ -145,9 +145,6 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi
|
||||
|
||||
refreshWidgetsValues();
|
||||
|
||||
// register widgets for dirty state management
|
||||
addWidget(m_aircraft->aircraftType);
|
||||
|
||||
// register FF widgets for dirty state management
|
||||
addWidget(m_aircraft->feedForwardSlider);
|
||||
addWidget(m_aircraft->accelTime);
|
||||
@ -171,10 +168,7 @@ ConfigVehicleTypeWidget::~ConfigVehicleTypeWidget()
|
||||
|
||||
void ConfigVehicleTypeWidget::switchAirframeType(int index)
|
||||
{
|
||||
// TODO not safe w/r to translation!!!
|
||||
QString frameCategory = m_aircraft->aircraftType->currentText();
|
||||
|
||||
m_aircraft->airframesWidget->setCurrentWidget(getVehicleConfigWidget(frameCategory));
|
||||
m_aircraft->airframesWidget->setCurrentWidget(getVehicleConfigWidget(index));
|
||||
}
|
||||
|
||||
/**
|
||||
@ -202,10 +196,9 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *o)
|
||||
// At this stage, we will need to have some hardcoded settings in this code, this
|
||||
// is not ideal, but there you go.
|
||||
QString frameType = field->getValue().toString();
|
||||
qDebug() << "ConfigVehicleTypeWidget::refreshWidgetsValues - frame type:" << frameType;
|
||||
|
||||
QString category = frameCategory(frameType);
|
||||
setComboCurrentIndex(m_aircraft->aircraftType, m_aircraft->aircraftType->findText(category));
|
||||
int category = frameCategory(frameType);
|
||||
m_aircraft->aircraftType->setCurrentIndex(category);
|
||||
|
||||
VehicleConfig *vehicleConfig = getVehicleConfigWidget(category);
|
||||
if (vehicleConfig) {
|
||||
@ -215,8 +208,6 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *o)
|
||||
updateFeedForwardUI();
|
||||
|
||||
setDirty(dirty);
|
||||
|
||||
qDebug() << "ConfigVehicleTypeWidget::refreshWidgetsValues - end";
|
||||
}
|
||||
|
||||
/**
|
||||
@ -264,63 +255,61 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
|
||||
updateFeedForwardUI();
|
||||
}
|
||||
|
||||
QString ConfigVehicleTypeWidget::frameCategory(QString frameType)
|
||||
int ConfigVehicleTypeWidget::frameCategory(QString frameType)
|
||||
{
|
||||
QString category;
|
||||
|
||||
if (frameType == "FixedWing" || frameType == "Elevator aileron rudder" || frameType == "FixedWingElevon"
|
||||
|| frameType == "Elevon" || frameType == "FixedWingVtail" || frameType == "Vtail") {
|
||||
category = "Fixed Wing";
|
||||
return ConfigVehicleTypeWidget::FIXED_WING;
|
||||
} else if (frameType == "Tri" || frameType == "Tricopter Y" || frameType == "QuadX" || frameType == "Quad X"
|
||||
|| frameType == "QuadP" || frameType == "Quad +" || frameType == "Hexa" || frameType == "Hexacopter"
|
||||
|| frameType == "HexaX" || frameType == "Hexacopter X" || frameType == "HexaCoax"
|
||||
|| frameType == "Hexacopter Y6" || frameType == "Octo" || frameType == "Octocopter" || frameType == "OctoV"
|
||||
|| frameType == "Octocopter V" || frameType == "OctoCoaxP" || frameType == "Octo Coax +"
|
||||
|| frameType == "OctoCoaxX" || frameType == "Octo Coax X") {
|
||||
category = "Multirotor";
|
||||
return ConfigVehicleTypeWidget::MULTIROTOR;
|
||||
} else if (frameType == "HeliCP") {
|
||||
category = "Helicopter";
|
||||
return ConfigVehicleTypeWidget::HELICOPTER;
|
||||
} else if (frameType == "GroundVehicleCar" || frameType == "Turnable (car)"
|
||||
|| frameType == "GroundVehicleDifferential" || frameType == "Differential (tank)"
|
||||
|| frameType == "GroundVehicleMotorcyle" || frameType == "Motorcycle") {
|
||||
category = "Ground";
|
||||
return ConfigVehicleTypeWidget::GROUND;
|
||||
} else {
|
||||
category = "Custom";
|
||||
return ConfigVehicleTypeWidget::CUSTOM;
|
||||
}
|
||||
return category;
|
||||
}
|
||||
|
||||
VehicleConfig *ConfigVehicleTypeWidget::getVehicleConfigWidget(QString frameCategory)
|
||||
VehicleConfig *ConfigVehicleTypeWidget::getVehicleConfigWidget(int frameCategory)
|
||||
{
|
||||
VehicleConfig *vehiculeConfig;
|
||||
|
||||
if (!vehicleIndexMap.contains(frameCategory)) {
|
||||
if (!m_vehicleIndexMap.contains(frameCategory)) {
|
||||
// create config widget
|
||||
vehiculeConfig = createVehicleConfigWidget(frameCategory);
|
||||
// bind config widget "field" to this ConfigTaskWodget
|
||||
// this is necessary to get "dirty" state management
|
||||
vehiculeConfig->registerWidgets(*this);
|
||||
|
||||
// add config widget to UI
|
||||
int index = m_aircraft->airframesWidget->insertWidget(m_aircraft->airframesWidget->count(), vehiculeConfig);
|
||||
vehicleIndexMap[frameCategory] = index;
|
||||
m_vehicleIndexMap[frameCategory] = index;
|
||||
updateEnableControls();
|
||||
}
|
||||
int index = vehicleIndexMap.value(frameCategory);
|
||||
int index = m_vehicleIndexMap.value(frameCategory);
|
||||
vehiculeConfig = (VehicleConfig *)m_aircraft->airframesWidget->widget(index);
|
||||
return vehiculeConfig;
|
||||
}
|
||||
|
||||
VehicleConfig *ConfigVehicleTypeWidget::createVehicleConfigWidget(QString frameCategory)
|
||||
VehicleConfig *ConfigVehicleTypeWidget::createVehicleConfigWidget(int frameCategory)
|
||||
{
|
||||
qDebug() << "ConfigVehicleTypeWidget::createVehicleConfigWidget - creating" << frameCategory;
|
||||
if (frameCategory == "Fixed Wing") {
|
||||
if (frameCategory == ConfigVehicleTypeWidget::FIXED_WING) {
|
||||
return new ConfigFixedWingWidget();
|
||||
} else if (frameCategory == "Multirotor") {
|
||||
} else if (frameCategory == ConfigVehicleTypeWidget::MULTIROTOR) {
|
||||
return new ConfigMultiRotorWidget();
|
||||
} else if (frameCategory == "Helicopter") {
|
||||
} else if (frameCategory == ConfigVehicleTypeWidget::HELICOPTER) {
|
||||
return new ConfigCcpmWidget();
|
||||
} else if (frameCategory == "Ground") {
|
||||
} else if (frameCategory == ConfigVehicleTypeWidget::GROUND) {
|
||||
return new ConfigGroundVehicleWidget();
|
||||
} else if (frameCategory == "Custom") {
|
||||
} else if (frameCategory == ConfigVehicleTypeWidget::CUSTOM) {
|
||||
return new ConfigCustomWidget();
|
||||
}
|
||||
return NULL;
|
||||
@ -337,17 +326,17 @@ void ConfigVehicleTypeWidget::enableFFTest()
|
||||
// - Every other time event: send FF settings to flight FW
|
||||
if (m_aircraft->ffTestBox1->isChecked() && m_aircraft->ffTestBox2->isChecked()
|
||||
&& m_aircraft->ffTestBox3->isChecked()) {
|
||||
if (!ffTuningInProgress) {
|
||||
if (!m_ffTuningInProgress) {
|
||||
// Initiate tuning:
|
||||
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(getObjectManager()->getObject(
|
||||
QString("ManualControlCommand")));
|
||||
UAVObject::Metadata mdata = obj->getMetadata();
|
||||
accInitialData = mdata;
|
||||
m_accInitialData = mdata;
|
||||
UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READONLY);
|
||||
obj->setMetadata(mdata);
|
||||
}
|
||||
// Depending on phase, either move actuator or send FF settings:
|
||||
if (ffTuningPhase) {
|
||||
if (m_ffTuningPhase) {
|
||||
// Send FF settings to the board
|
||||
UAVDataObject *mixer = dynamic_cast<UAVDataObject *>(getObjectManager()->getObject(QString("MixerSettings")));
|
||||
Q_ASSERT(mixer);
|
||||
@ -369,18 +358,18 @@ void ConfigVehicleTypeWidget::enableFFTest()
|
||||
obj->getField("Throttle")->setValue(target);
|
||||
obj->updated();
|
||||
}
|
||||
ffTuningPhase = !ffTuningPhase;
|
||||
ffTuningInProgress = true;
|
||||
m_ffTuningPhase = !m_ffTuningPhase;
|
||||
m_ffTuningInProgress = true;
|
||||
QTimer::singleShot(1000, this, SLOT(enableFFTest()));
|
||||
} else {
|
||||
// - If no: disarm timer, restore actuatorcommand metadata
|
||||
// Disarm!
|
||||
if (ffTuningInProgress) {
|
||||
ffTuningInProgress = false;
|
||||
if (m_ffTuningInProgress) {
|
||||
m_ffTuningInProgress = false;
|
||||
UAVDataObject *obj = dynamic_cast<UAVDataObject *>(getObjectManager()->getObject(
|
||||
QString("ManualControlCommand")));
|
||||
UAVObject::Metadata mdata = obj->getMetadata();
|
||||
mdata = accInitialData; // Restore metadata
|
||||
mdata = m_accInitialData; // Restore metadata
|
||||
obj->setMetadata(mdata);
|
||||
}
|
||||
}
|
||||
@ -413,15 +402,3 @@ void ConfigVehicleTypeWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl(QUrl("http://wiki.openpilot.org/x/44Cf", QUrl::StrictMode));
|
||||
}
|
||||
|
||||
/**
|
||||
Helper function:
|
||||
Sets the current index on supplied combobox to index
|
||||
if it is within bounds 0 <= index < combobox.count()
|
||||
*/
|
||||
void ConfigVehicleTypeWidget::setComboCurrentIndex(QComboBox *box, int index)
|
||||
{
|
||||
if (index >= 0 && index < box->count()) {
|
||||
box->setCurrentIndex(index);
|
||||
}
|
||||
}
|
||||
|
@ -64,7 +64,6 @@ class ConfigVehicleTypeWidget : public ConfigTaskWidget {
|
||||
|
||||
public:
|
||||
static QStringList getChannelDescriptions();
|
||||
static void setComboCurrentIndex(QComboBox *box, int index);
|
||||
|
||||
ConfigVehicleTypeWidget(QWidget *parent = 0);
|
||||
~ConfigVehicleTypeWidget();
|
||||
@ -76,20 +75,23 @@ protected slots:
|
||||
private:
|
||||
Ui_AircraftWidget *m_aircraft;
|
||||
|
||||
static enum { MULTIROTOR = 0, FIXED_WING, HELICOPTER, GROUND, CUSTOM } AirframeCategory;
|
||||
|
||||
// Maps a frame category to its index in the m_aircraft->airframesWidget QStackedWidget
|
||||
QMap<QString, int> vehicleIndexMap;
|
||||
QMap<int, int> m_vehicleIndexMap;
|
||||
|
||||
QString frameCategory(QString frameType);
|
||||
|
||||
VehicleConfig *getVehicleConfigWidget(QString frameCategory);
|
||||
VehicleConfig *createVehicleConfigWidget(QString frameCategory);
|
||||
int frameCategory(QString frameType);
|
||||
|
||||
VehicleConfig *getVehicleConfigWidget(int frameCategory);
|
||||
VehicleConfig *createVehicleConfigWidget(int frameCategory);
|
||||
|
||||
// Feed Forward
|
||||
void updateFeedForwardUI();
|
||||
|
||||
bool ffTuningInProgress;
|
||||
bool ffTuningPhase;
|
||||
UAVObject::Metadata accInitialData;
|
||||
bool m_ffTuningInProgress;
|
||||
bool m_ffTuningPhase;
|
||||
UAVObject::Metadata m_accInitialData;
|
||||
|
||||
private slots:
|
||||
void switchAirframeType(int index);
|
||||
|
@ -14,18 +14,6 @@
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<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>
|
||||
<widget class="QTabWidget" name="tabWidget">
|
||||
<property name="currentIndex">
|
||||
@ -128,8 +116,8 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>766</width>
|
||||
<height>745</height>
|
||||
<width>774</width>
|
||||
<height>748</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
@ -558,8 +546,8 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>766</width>
|
||||
<height>745</height>
|
||||
<width>768</width>
|
||||
<height>742</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_7" rowstretch="1,0,0,0">
|
||||
@ -1313,7 +1301,6 @@ margin:1px;</string>
|
||||
<string>index:0</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:16</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
@ -1354,7 +1341,6 @@ margin:1px;</string>
|
||||
<string>index:1</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:16</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
@ -1395,7 +1381,6 @@ margin:1px;</string>
|
||||
<string>index:2</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:16</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
@ -1439,7 +1424,6 @@ margin:1px;</string>
|
||||
<string>index:3</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:16</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
@ -1483,7 +1467,6 @@ margin:1px;</string>
|
||||
<string>index:4</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:16</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
@ -1527,7 +1510,6 @@ margin:1px;</string>
|
||||
<string>index:5</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:16</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
@ -2182,8 +2164,8 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>766</width>
|
||||
<height>745</height>
|
||||
<width>768</width>
|
||||
<height>742</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
|
@ -14,9 +14,6 @@
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<property name="margin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QTabWidget" name="tabWidget">
|
||||
<property name="tabShape">
|
||||
@ -36,7 +33,16 @@
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -116,15 +122,24 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>668</width>
|
||||
<height>671</height>
|
||||
<width>676</width>
|
||||
<height>674</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<property name="spacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<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>
|
||||
@ -145,12 +160,6 @@
|
||||
<string>Output Update Speed</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<property name="margin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<property name="horizontalSpacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<item row="0" column="6">
|
||||
<widget class="QLabel" name="chBank5">
|
||||
<property name="text">
|
||||
@ -173,12 +182,6 @@
|
||||
</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>
|
||||
@ -391,12 +394,6 @@ Leave at 50Hz for fixed wing.</string>
|
||||
<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>
|
||||
@ -653,12 +650,9 @@ Leave at 50Hz for fixed wing.</string>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_3">
|
||||
<property name="title">
|
||||
<string/>
|
||||
<string>Output Channel Configuration</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<property name="margin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="channelLayout">
|
||||
<property name="sizeConstraint">
|
||||
@ -668,15 +662,12 @@ Leave at 50Hz for fixed wing.</string>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<property name="margin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QCheckBox" name="spinningArmed">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>519</width>
|
||||
<height>0</height>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
@ -707,7 +698,7 @@ Leave at 50Hz for fixed wing.</string>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>542</height>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
@ -724,12 +715,9 @@ Leave at 50Hz for fixed wing.</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string/>
|
||||
<string>Live Testing</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_6">
|
||||
<property name="margin">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QCheckBox" name="channelOutTest">
|
||||
<property name="enabled">
|
||||
@ -738,7 +726,7 @@ Leave at 50Hz for fixed wing.</string>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>105</width>
|
||||
<height>0</height>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
|
@ -23,29 +23,7 @@
|
||||
<property name="horizontalSpacing">
|
||||
<number>12</number>
|
||||
</property>
|
||||
<item row="1" 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="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Current value of slider.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="10">
|
||||
<item row="0" column="11">
|
||||
<widget class="QLabel" name="legend5">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
|
||||
@ -55,7 +33,7 @@
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<width>45</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
@ -81,22 +59,55 @@ margin:1px;</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QLabel" name="actuatorName">
|
||||
<item row="1" column="8">
|
||||
<widget class="QSpinBox" name="actuatorMax">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<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>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4" colspan="2">
|
||||
<widget class="QLabel" name="legend2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>110</width>
|
||||
<height>25</height>
|
||||
<width>0</width>
|
||||
<height>20</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>TextLabel</string>
|
||||
<string>Neutral (slowest for motor)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
@ -145,110 +156,21 @@ margin:1px;</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="actuatorNumber">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
<item row="1" column="6">
|
||||
<spacer name="horizontalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Minimum</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Channel Number</string>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>TextLabel</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QSpinBox" name="actuatorMin">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Minimum PWM value, beware of not overdriving your servo.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="9">
|
||||
<widget class="QCheckBox" name="actuatorRev">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>45</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Check to invert the channel.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="legend2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<width>5</width>
|
||||
<height>20</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 (slowest for motor)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="legend0">
|
||||
@ -286,26 +208,29 @@ margin:1px;</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="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">
|
||||
<item row="1" column="2">
|
||||
<widget class="QSpinBox" name="actuatorMin">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>5</width>
|
||||
<height>20</height>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Minimum PWM value, beware of not overdriving your servo.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="legend1">
|
||||
<item row="1" column="4">
|
||||
<widget class="QSlider" name="actuatorNeutral">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
@ -313,28 +238,17 @@ margin:1px;</string>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
<height>25</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;
|
||||
font:bold;
|
||||
margin:1px;</string>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Min</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
@ -374,30 +288,33 @@ margin:1px;</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="10">
|
||||
<widget class="QCheckBox" name="actuatorLink">
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="actuatorNumber">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>45</width>
|
||||
<width>20</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Output mode</string>
|
||||
<string>Channel Number</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>TextLabel</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="6">
|
||||
<spacer name="horizontalSpacer_2">
|
||||
<item row="1" column="3">
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
@ -412,6 +329,28 @@ margin:1px;</string>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QLabel" name="actuatorName">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>110</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>TextLabel</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="9">
|
||||
<widget class="QLabel" name="legend4">
|
||||
<property name="sizePolicy">
|
||||
@ -441,17 +380,17 @@ font:bold;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Rev</string>
|
||||
<string>Reversed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<widget class="QSlider" name="actuatorNeutral">
|
||||
<item row="1" column="5">
|
||||
<widget class="QLabel" name="actuatorValue">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
@ -462,34 +401,152 @@ margin:1px;</string>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
<property name="toolTip">
|
||||
<string>Current value of slider.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>9999</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
<property name="text">
|
||||
<string>0000</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="8">
|
||||
<widget class="QSpinBox" name="actuatorMax">
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="legend1">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<italic>false</italic>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Maximum PWM value, beware of not overdriving your servo.</string>
|
||||
<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="maximum">
|
||||
<number>9999</number>
|
||||
<property name="text">
|
||||
<string>Min</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="9">
|
||||
<widget class="QFrame" name="frame">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>75</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<widget class="QCheckBox" name="actuatorRev">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" 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="toolTip">
|
||||
<string>Check to invert the channel.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="11">
|
||||
<widget class="QFrame" name="frame">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>45</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="0" column="0" alignment="Qt::AlignHCenter">
|
||||
<widget class="QCheckBox" name="actuatorLink">
|
||||
<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="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Output mode</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
@ -498,8 +555,6 @@ margin:1px;</string>
|
||||
<tabstop>actuatorMin</tabstop>
|
||||
<tabstop>actuatorNeutral</tabstop>
|
||||
<tabstop>actuatorMax</tabstop>
|
||||
<tabstop>actuatorRev</tabstop>
|
||||
<tabstop>actuatorLink</tabstop>
|
||||
</tabstops>
|
||||
<resources/>
|
||||
<connections/>
|
||||
|
@ -15,1724 +15,1822 @@
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
<item>
|
||||
<widget class="QFrame" name="frame_3">
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<item row="6" column="0" colspan="2">
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QLabel" name="message">
|
||||
<property name="text">
|
||||
<string/>
|
||||
<widget class="QTabWidget" name="tabWidget_3">
|
||||
<widget class="QWidget" name="tabWidget_3Page1">
|
||||
<attribute name="title">
|
||||
<string>OPLink configuration</string>
|
||||
</attribute>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="0" column="0" colspan="2">
|
||||
<widget class="QScrollArea" name="scrollArea">
|
||||
<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>812</width>
|
||||
<height>692</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_5">
|
||||
<item row="0" column="1">
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Configuration</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="4" column="3">
|
||||
<widget class="QComboBox" name="ComSpeed">
|
||||
<property name="statusTip">
|
||||
<string>Com speed in bps.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="2">
|
||||
<widget class="QLabel" name="ComSpeedLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Com Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="2">
|
||||
<widget class="QLabel" name="VCPPortLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>VCP Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="3">
|
||||
<widget class="QComboBox" name="FlexiPort">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the function for the flexi port</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="2">
|
||||
<widget class="QLabel" name="MainPortLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Main Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="3">
|
||||
<widget class="QComboBox" name="MainPort">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the function for the main port</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<widget class="QComboBox" name="MaxRFTxPower">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the maximum TX output power the modem will use (mW)</string>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="modelColumn">
|
||||
<number>0</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="MaxRFTxPowerLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Max Power</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="3">
|
||||
<widget class="QComboBox" name="VCPPort">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the function for the USB virtual com port</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="2">
|
||||
<widget class="QLabel" name="FlexiIOPortLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>FlexiIO Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="3">
|
||||
<widget class="QComboBox" name="FlexiIOPort"/>
|
||||
</item>
|
||||
<item row="7" column="2">
|
||||
<widget class="QLabel" name="FlexiPortLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Flexi Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="MaximumChannelLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Max Chan</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QSpinBox" name="MaximumChannel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Channel 0 is 430 MHz, channel 249 is 440 MHz, and the channel spacing is 40 KHz.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>249</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="0">
|
||||
<widget class="QLabel" name="MinimumChannelLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Min Chan</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="1">
|
||||
<widget class="QSpinBox" name="MinimumChannel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Channel 0 is 430 MHz, channel 249 is 440 MHz, and the channel spacing is 40 KHz.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>249</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="ChannelSetLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Channel Set</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="1">
|
||||
<widget class="QSpinBox" name="ChannelSet">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Sets the random sequence of channels to use for frequency hopping.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>249</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QCheckBox" name="PPMOnly">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="statusTip">
|
||||
<string>Only PPM packets will be transmitted.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>PPM Only</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QCheckBox" name="OneWayLink">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="statusTip">
|
||||
<string>If selected, data will only be transmitted from the coordinator to the Rx modem.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>One-Way</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QCheckBox" name="PPM">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="statusTip">
|
||||
<string>PPM packets will be received by this modem. Must be selected if Coordinator modem is configured for PPM.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>PPM</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0" colspan="2">
|
||||
<widget class="QCheckBox" name="Coordinator">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="statusTip">
|
||||
<string>This modem will be a coordinator and other modems will bind to it.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Coordinator</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QGroupBox" name="PairingGroupBox">
|
||||
<property name="title">
|
||||
<string>Remote modems</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<item row="5" column="3">
|
||||
<widget class="QLabel" name="PairSignalStrengthLabel4">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-100dB</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="2">
|
||||
<widget class="QProgressBar" name="PairSignalStrengthBar4">
|
||||
<property name="minimum">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string>%v dBm</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QLabel" name="PairSignalStrengthLabel2">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-100dB</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QLineEdit" name="PairID2">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QProgressBar" name="PairSignalStrengthBar2">
|
||||
<property name="minimum">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string>%v dBm</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QLineEdit" name="PairID4">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QProgressBar" name="PairSignalStrengthBar1">
|
||||
<property name="minimum">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string>%v dBm</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QLabel" name="PairSignalStrengthLabel1">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-100dB</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="2">
|
||||
<widget class="QProgressBar" name="PairSignalStrengthBar3">
|
||||
<property name="minimum">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string>%v dBm</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="3">
|
||||
<widget class="QLabel" name="PairSignalStrengthLabel3">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>-100dB</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<widget class="QLineEdit" name="PairID3">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QLineEdit" name="PairID1">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="placeholderText">
|
||||
<string>12345678</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QPushButton" name="Bind2">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Bind</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QPushButton" name="Bind1">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Bind</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QPushButton" name="Bind4">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Bind</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QPushButton" name="Bind3">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Bind</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="CoordIDLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Coordinator ID</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QLineEdit" name="CoordID">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This is the coordinator id we currently are bound to.</p><p>To manually bind to a specific coordinator, just type</p><p>or paste its device id in this box and save.</p><p>The device must be rebooted for the binding to take place.</p></body></html></string>
|
||||
</property>
|
||||
<property name="maxLength">
|
||||
<number>8</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0" colspan="2">
|
||||
<widget class="QGroupBox" name="groupBox_3">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>430</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Status</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_4">
|
||||
<item row="0" column="5">
|
||||
<widget class="QLineEdit" name="DeviceID">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="placeholderText">
|
||||
<string>12345678</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="6">
|
||||
<widget class="QLabel" name="label_11">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Link State</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="7">
|
||||
<widget class="QLineEdit" name="LinkState">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The modems current state</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="placeholderText">
|
||||
<string>Disconnected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label_9">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Firmware Ver.</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1" colspan="3">
|
||||
<widget class="QLineEdit" name="FirmwareVersion">
|
||||
<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="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="7">
|
||||
<widget class="QLineEdit" name="RSSI">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Serial Number</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1" colspan="3">
|
||||
<widget class="QLineEdit" name="SerialNumber">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<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>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<italic>false</italic>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="acceptDrops">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The modems serial number</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="DeviceIDLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Device ID</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<widget class="QLabel" name="LinkQualityLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Link Quality</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="5">
|
||||
<widget class="QLineEdit" name="LinkQuality">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="6">
|
||||
<widget class="QLabel" name="RSSILabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>RSSI</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QLineEdit" name="Resent">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The number of packets that were unable to be transmitted</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<widget class="QLabel" name="TXSeqLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>TX Seq. No.</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="5">
|
||||
<widget class="QLineEdit" name="TXSeq">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="6">
|
||||
<widget class="QLabel" name="TXRateLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>TX Rate (B/s)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="7">
|
||||
<widget class="QLineEdit" name="TXRate">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QLabel" name="RXSeqLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>RX Seq. No.</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="5">
|
||||
<widget class="QLineEdit" name="RXSeq">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="6">
|
||||
<widget class="QLabel" name="RXRateLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>RX Rate (B/s)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="7">
|
||||
<widget class="QLineEdit" name="RXRate">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="GoodLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>RX Good</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QLineEdit" name="Good">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that were corrected with error correction</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="CorrectedLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>RX Corrected</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QLineEdit" name="Corrected">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that were corrected with error correction</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="ErrorsLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>RX Errors</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QLineEdit" name="Errors">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that could not be corrected with error correction</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="MissedPacketsLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>RX Missed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QLineEdit" name="Missed">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that were not received at all</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QLabel" name="DroppedLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>TX Dropped</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QLineEdit" name="Dropped">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The number of packets that were unable to be transmitted</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QLabel" name="ResentLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>TX Resent</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="2">
|
||||
<widget class="QLabel" name="TxFailureLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Tx Failure</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="3">
|
||||
<widget class="QLineEdit" name="TxFailure">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="4">
|
||||
<widget class="QLabel" name="FreeHeapLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Free Heap</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="5">
|
||||
<widget class="QLineEdit" name="FreeHeap">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="6">
|
||||
<widget class="QLabel" name="UAVTalkErrorsLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>UAVTalk Errors</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="7">
|
||||
<widget class="QLineEdit" name="UAVTalkErrors">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="7">
|
||||
<widget class="QLineEdit" name="Resets">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="6">
|
||||
<widget class="QLabel" name="ResetsLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Resets</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="5">
|
||||
<widget class="QLineEdit" name="Timeouts">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="4">
|
||||
<widget class="QLabel" name="TimeoutsLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Timeouts</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="2">
|
||||
<widget class="QLabel" name="RxFailureLabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>RX Failure</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="3">
|
||||
<widget class="QLineEdit" name="RxFailure">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that were not received at all</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0" colspan="2">
|
||||
<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>
|
||||
</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>5</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/dACrAQ</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</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>
|
||||
</item>
|
||||
<item row="5" column="0" colspan="2">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_12">
|
||||
<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>
|
||||
</item>
|
||||
<item row="3" column="0" colspan="2">
|
||||
<widget class="QFrame" name="frame_4">
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::StyledPanel</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<widget class="QGroupBox" name="groupBox_3">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>430</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Status</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_4">
|
||||
<item row="0" column="5">
|
||||
<widget class="QLineEdit" name="DeviceID">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="placeholderText">
|
||||
<string>12345678</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="6">
|
||||
<widget class="QLabel" name="label_11">
|
||||
<property name="text">
|
||||
<string>Link State</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="7">
|
||||
<widget class="QLineEdit" name="LinkState">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The modems current state</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 3px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="placeholderText">
|
||||
<string>Disconnected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label_9">
|
||||
<property name="text">
|
||||
<string>Firmware Ver.</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1" colspan="3">
|
||||
<widget class="QLineEdit" name="FirmwareVersion">
|
||||
<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="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="7">
|
||||
<widget class="QLineEdit" name="RSSI">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="text">
|
||||
<string>Serial Number</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1" colspan="3">
|
||||
<widget class="QLineEdit" name="SerialNumber">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<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>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<italic>false</italic>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="acceptDrops">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The modems serial number</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="DeviceIDLabel">
|
||||
<property name="text">
|
||||
<string>Device ID</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<widget class="QLabel" name="LinkQualityLabel">
|
||||
<property name="text">
|
||||
<string>Link Quality</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="5">
|
||||
<widget class="QLineEdit" name="LinkQuality">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="6">
|
||||
<widget class="QLabel" name="RSSILabel">
|
||||
<property name="text">
|
||||
<string>RSSI</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QLineEdit" name="Resent">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The number of packets that were unable to be transmitted</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<widget class="QLabel" name="TXSeqLabel">
|
||||
<property name="text">
|
||||
<string>TX Seq. No.</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="5">
|
||||
<widget class="QLineEdit" name="TXSeq">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="6">
|
||||
<widget class="QLabel" name="TXRateLabel">
|
||||
<property name="text">
|
||||
<string>TX Rate (B/s)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="7">
|
||||
<widget class="QLineEdit" name="TXRate">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QLabel" name="RXSeqLabel">
|
||||
<property name="text">
|
||||
<string>RX Seq. No.</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="5">
|
||||
<widget class="QLineEdit" name="RXSeq">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="6">
|
||||
<widget class="QLabel" name="RXRateLabel">
|
||||
<property name="text">
|
||||
<string>RX Rate (B/s)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="7">
|
||||
<widget class="QLineEdit" name="RXRate">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="GoodLabel">
|
||||
<property name="text">
|
||||
<string>RX Good</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QLineEdit" name="Good">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that were corrected with error correction</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="CorrectedLabel">
|
||||
<property name="text">
|
||||
<string>RX Corrected</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QLineEdit" name="Corrected">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that were corrected with error correction</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="ErrorsLabel">
|
||||
<property name="text">
|
||||
<string>RX Errors</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QLineEdit" name="Errors">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that could not be corrected with error correction</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="MissedPacketsLabel">
|
||||
<property name="text">
|
||||
<string>RX Missed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QLineEdit" name="Missed">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that were not received at all</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QLabel" name="DroppedLabel">
|
||||
<property name="text">
|
||||
<string>TX Dropped</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QLineEdit" name="Dropped">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The number of packets that were unable to be transmitted</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QLabel" name="ResentLabel">
|
||||
<property name="text">
|
||||
<string>TX Resent</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="2">
|
||||
<widget class="QLabel" name="TxFailureLabel">
|
||||
<property name="text">
|
||||
<string>Tx Failure</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="3">
|
||||
<widget class="QLineEdit" name="TxFailure">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="4">
|
||||
<widget class="QLabel" name="FreeHeapLabel">
|
||||
<property name="text">
|
||||
<string>Free Heap</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="5">
|
||||
<widget class="QLineEdit" name="FreeHeap">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="6">
|
||||
<widget class="QLabel" name="UAVTalkErrorsLabel">
|
||||
<property name="text">
|
||||
<string>UAVTalk Errors</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="7">
|
||||
<widget class="QLineEdit" name="UAVTalkErrors">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="7">
|
||||
<widget class="QLineEdit" name="Resets">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="6">
|
||||
<widget class="QLabel" name="ResetsLabel">
|
||||
<property name="text">
|
||||
<string>Resets</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="5">
|
||||
<widget class="QLineEdit" name="Timeouts">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="frame">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="4">
|
||||
<widget class="QLabel" name="TimeoutsLabel">
|
||||
<property name="text">
|
||||
<string>Timeouts</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="2">
|
||||
<widget class="QLabel" name="RxFailureLabel">
|
||||
<property name="text">
|
||||
<string>RX Failure</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="3">
|
||||
<widget class="QLineEdit" name="RxFailure">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<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>101</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>The percentage of packets that were not received at all</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QLineEdit {
|
||||
border: none;
|
||||
border-radius: 1px;
|
||||
padding: 0 4px;
|
||||
background: rgba(0, 0, 0, 16);
|
||||
/* background: transparent; */
|
||||
/* selection-background-color: darkgray;*/
|
||||
}</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QGroupBox" name="groupBox_2">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Remote Modems</string>
|
||||
</property>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<item>
|
||||
<widget class="QFrame" name="PairingFrame">
|
||||
<layout class="QGridLayout" name="gridLayout_3">
|
||||
<item row="5" column="3">
|
||||
<widget class="QLabel" name="PairSignalStrengthLabel4">
|
||||
<property name="text">
|
||||
<string>-100dB</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="2">
|
||||
<widget class="QProgressBar" name="PairSignalStrengthBar4">
|
||||
<property name="minimum">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string>%v dBm</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QLabel" name="PairSignalStrengthLabel2">
|
||||
<property name="text">
|
||||
<string>-100dB</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QLineEdit" name="PairID2">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QProgressBar" name="PairSignalStrengthBar2">
|
||||
<property name="minimum">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string>%v dBm</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QLineEdit" name="PairID4">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QProgressBar" name="PairSignalStrengthBar1">
|
||||
<property name="minimum">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string>%v dBm</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QLabel" name="PairSignalStrengthLabel1">
|
||||
<property name="text">
|
||||
<string>-100dB</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="2">
|
||||
<widget class="QProgressBar" name="PairSignalStrengthBar3">
|
||||
<property name="minimum">
|
||||
<number>-127</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string>%v dBm</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="3">
|
||||
<widget class="QLabel" name="PairSignalStrengthLabel3">
|
||||
<property name="text">
|
||||
<string>-100dB</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<widget class="QLineEdit" name="PairID3">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QLineEdit" name="PairID1">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="placeholderText">
|
||||
<string>12345678</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QPushButton" name="Bind2">
|
||||
<property name="text">
|
||||
<string>Bind</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QPushButton" name="Bind1">
|
||||
<property name="text">
|
||||
<string>Bind</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QPushButton" name="Bind4">
|
||||
<property name="text">
|
||||
<string>Bind</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QPushButton" name="Bind3">
|
||||
<property name="text">
|
||||
<string>Bind</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="CoordIDLabel">
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Coord ID</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QLineEdit" name="CoordID">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maxLength">
|
||||
<number>8</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="2">
|
||||
<widget class="QCheckBox" name="Coordinator">
|
||||
<property name="statusTip">
|
||||
<string>This modem will be a coordinator and other modems will bind to it.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Coordinator</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QGroupBox" name="groupBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Configuration</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<item row="4" column="3">
|
||||
<widget class="QComboBox" name="ComSpeed">
|
||||
<property name="statusTip">
|
||||
<string>Com speed in bps.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="2">
|
||||
<widget class="QLabel" name="ComSpeedLabel">
|
||||
<property name="text">
|
||||
<string>Com Speed</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="2">
|
||||
<widget class="QLabel" name="VCPPortLabel">
|
||||
<property name="text">
|
||||
<string>VCP Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="3">
|
||||
<widget class="QComboBox" name="FlexiPort">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the function for the flexi port</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="2">
|
||||
<widget class="QLabel" name="MainPortLabel">
|
||||
<property name="text">
|
||||
<string>Main Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="3">
|
||||
<widget class="QComboBox" name="MainPort">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the function for the main port</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="3">
|
||||
<widget class="QComboBox" name="MaxRFTxPower">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Set the maximum TX output power the modem will use (mW)</string>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="modelColumn">
|
||||
<number>0</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="MaxRFTxPowerLabel">
|
||||
<property name="text">
|
||||
<string>Max Power</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="3">
|
||||
<widget class="QComboBox" name="VCPPort">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Choose the function for the USB virtual com port</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="2">
|
||||
<widget class="QLabel" name="FlexiIOPortLabel">
|
||||
<property name="text">
|
||||
<string>FlexiIO Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="3">
|
||||
<widget class="QComboBox" name="FlexiIOPort"/>
|
||||
</item>
|
||||
<item row="7" column="2">
|
||||
<widget class="QLabel" name="FlexiPortLabel">
|
||||
<property name="text">
|
||||
<string>Flexi Port</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QCheckBox" name="OneWayLink">
|
||||
<property name="statusTip">
|
||||
<string>If selected, data will only be transmitted from the coordinator to the Rx modem.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>One-Way Link</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QCheckBox" name="PPMOnly">
|
||||
<property name="statusTip">
|
||||
<string>Only PPM packets will be transmitted.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>PPM Only</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="MaximumChannelLabel">
|
||||
<property name="text">
|
||||
<string>Max Chan</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QSpinBox" name="MaximumChannel">
|
||||
<property name="toolTip">
|
||||
<string>Channel 0 is 430 MHz, channel 249 is 440 MHz, and the channel spacing is 40 KHz.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>249</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="0">
|
||||
<widget class="QLabel" name="MinimumChannelLabel">
|
||||
<property name="text">
|
||||
<string>Min Chan</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="7" column="1">
|
||||
<widget class="QSpinBox" name="MinimumChannel">
|
||||
<property name="toolTip">
|
||||
<string>Channel 0 is 430 MHz, channel 249 is 440 MHz, and the channel spacing is 40 KHz.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>249</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="0">
|
||||
<widget class="QLabel" name="ChannelSetLabel">
|
||||
<property name="text">
|
||||
<string>Channel Set</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="1">
|
||||
<widget class="QSpinBox" name="ChannelSet">
|
||||
<property name="toolTip">
|
||||
<string>Sets the random sequence of channels to use for frequency hopping.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>249</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="0">
|
||||
<widget class="QCheckBox" name="PPM">
|
||||
<property name="statusTip">
|
||||
<string>PPM packets will be received by this modem. Must be selected if Coordinator modem is configured for PPM.</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>PPM</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="submitButtons">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>5</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="pushButton">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>25</width>
|
||||
<height>25</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>25</width>
|
||||
<height>25</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">
|
||||
<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>
|
||||
<tabstops>
|
||||
|
@ -6,7 +6,7 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>649</width>
|
||||
<width>808</width>
|
||||
<height>510</height>
|
||||
</rect>
|
||||
</property>
|
||||
@ -20,7 +20,7 @@
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="currentIndex">
|
||||
<number>1</number>
|
||||
<number>0</number>
|
||||
</property>
|
||||
<widget class="QWidget" name="tab_2">
|
||||
<property name="autoFillBackground">
|
||||
@ -41,7 +41,16 @@
|
||||
<enum>QFrame::Sunken</enum>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_9">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -127,7 +136,16 @@
|
||||
<enum>QFrame::Sunken</enum>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_10">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -230,7 +248,16 @@ Hint: run this with engines at cruising speed.</string>
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>3</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -308,7 +335,7 @@ Hint: run this with engines at cruising speed.</string>
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
</style></head><body style=" font-family:'Sans Serif'; font-size:9pt; font-weight:400; font-style:normal;">
|
||||
<table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;">
|
||||
<tr>
|
||||
<td style="border: none;">
|
||||
@ -338,7 +365,16 @@ p, li { white-space: pre-wrap; }
|
||||
<layout class="QVBoxLayout" name="verticalLayout_6">
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout_4">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<item row="1" column="1">
|
||||
@ -838,8 +874,8 @@ A setting of 0.00 disables the filter.</string>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>32</width>
|
||||
<height>32</height>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
|
@ -22,421 +22,6 @@
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>240</red>
|
||||
<green>240</green>
|
||||
<blue>240</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>247</red>
|
||||
<green>247</green>
|
||||
<blue>247</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>120</red>
|
||||
<green>120</green>
|
||||
<blue>120</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>160</red>
|
||||
<green>160</green>
|
||||
<blue>160</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<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="255">
|
||||
<red>240</red>
|
||||
<green>240</green>
|
||||
<blue>240</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>247</red>
|
||||
<green>247</green>
|
||||
<blue>247</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>240</red>
|
||||
<green>240</green>
|
||||
<blue>240</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>247</red>
|
||||
<green>247</green>
|
||||
<blue>247</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>120</red>
|
||||
<green>120</green>
|
||||
<blue>120</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>160</red>
|
||||
<green>160</green>
|
||||
<blue>160</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<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="255">
|
||||
<red>240</red>
|
||||
<green>240</green>
|
||||
<blue>240</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>247</red>
|
||||
<green>247</green>
|
||||
<blue>247</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>120</red>
|
||||
<green>120</green>
|
||||
<blue>120</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>240</red>
|
||||
<green>240</green>
|
||||
<blue>240</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>247</red>
|
||||
<green>247</green>
|
||||
<blue>247</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>120</red>
|
||||
<green>120</green>
|
||||
<blue>120</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>160</red>
|
||||
<green>160</green>
|
||||
<blue>160</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>120</red>
|
||||
<green>120</green>
|
||||
<blue>120</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>120</red>
|
||||
<green>120</green>
|
||||
<blue>120</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>240</red>
|
||||
<green>240</green>
|
||||
<blue>240</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>240</red>
|
||||
<green>240</green>
|
||||
<blue>240</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>240</red>
|
||||
<green>240</green>
|
||||
<blue>240</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Stabilization</string>
|
||||
</property>
|
||||
@ -551,8 +136,8 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>796</width>
|
||||
<height>708</height>
|
||||
<width>798</width>
|
||||
<height>705</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
@ -582,9 +167,6 @@ margin-top: -1px;
|
||||
<layout class="QVBoxLayout" name="verticalLayout_6">
|
||||
<item>
|
||||
<widget class="QGroupBox" name="basicResponsivenessGroupBox">
|
||||
<property name="toolTip">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
@ -598,9 +180,9 @@ margin-top: -1px;
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_7" rowstretch="0,0">
|
||||
<layout class="QGridLayout" name="gridLayout_7" rowstretch="0,0,0">
|
||||
<property name="leftMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
@ -613,7 +195,7 @@ margin-top: -1px;
|
||||
<property name="bottomMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item row="0" column="4">
|
||||
<item row="1" column="4">
|
||||
<widget class="QPushButton" name="pushButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
@ -636,21 +218,8 @@ margin-top: -1px;
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0" colspan="4">
|
||||
<spacer name="horizontalSpacer_37">
|
||||
<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="0" colspan="5">
|
||||
<widget class="QGroupBox" name="groupBox_7">
|
||||
<item row="2" column="0" colspan="5">
|
||||
<widget class="QGroupBox" name="basicResponsivenessControls">
|
||||
<property name="styleSheet">
|
||||
<string>QGroupBox{border: 0px;}</string>
|
||||
</property>
|
||||
@ -2617,6 +2186,29 @@ border-radius: 5;</string>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1" colspan="3">
|
||||
<spacer name="horizontalSpacer_37">
|
||||
<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="0">
|
||||
<widget class="QCheckBox" name="basicResponsivenessCheckBox">
|
||||
<property name="text">
|
||||
<string>Use Basic Configuration</string>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
@ -3114,7 +2706,7 @@ border-radius: 5;</string>
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_11" columnstretch="0,1,0,1,0,1,0">
|
||||
<layout class="QGridLayout" name="gridLayout_11" columnstretch="0,0,0,0,0,0,0">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
@ -3124,19 +2716,6 @@ border-radius: 5;</string>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="0" column="2">
|
||||
<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>
|
||||
<item row="0" column="0">
|
||||
<spacer name="horizontalSpacer_44">
|
||||
<property name="orientation">
|
||||
@ -3163,6 +2742,760 @@ border-radius: 5;</string>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="3" column="6">
|
||||
<widget class="QSpinBox" name="spinBox_10">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>As a rule of thumb, you can set the Integral at roughly the same
|
||||
value as the Kp.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>200</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>200</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:YawRatePID</string>
|
||||
<string>element:Ki</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="5">
|
||||
<widget class="QSlider" name="horizontalSlider_81">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This adjusts how much stability your vehicle will have when flying tilted (ie forward flight) in Rate mode. A good starting point for Integral is the same as Proportional</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:YawRatePID</string>
|
||||
<string>element:Ki</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QSlider" name="horizontalSlider_80">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This adjusts how much stability your vehicle will have when flying tilted (ie forward flight) in Rate mode. A good starting point for Integral is the same as Proportional</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:PitchRatePID</string>
|
||||
<string>element:Ki</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QSpinBox" name="spinBox_9">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>As a rule of thumb, you can set the Integral at roughly the same
|
||||
value as the Kp.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>200</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>200</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:PitchRatePID</string>
|
||||
<string>element:Ki</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="label_138">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>58</red>
|
||||
<green>58</green>
|
||||
<blue>58</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>48</red>
|
||||
<green>48</green>
|
||||
<blue>48</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>58</red>
|
||||
<green>58</green>
|
||||
<blue>58</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>48</red>
|
||||
<green>48</green>
|
||||
<blue>48</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>58</red>
|
||||
<green>58</green>
|
||||
<blue>58</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>48</red>
|
||||
<green>48</green>
|
||||
<blue>48</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>39</red>
|
||||
<green>39</green>
|
||||
<blue>39</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<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;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="6">
|
||||
<spacer name="horizontalSpacer_45">
|
||||
<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="2">
|
||||
<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>
|
||||
<item row="0" column="5">
|
||||
<widget class="QLabel" name="label_140">
|
||||
<property name="sizePolicy">
|
||||
@ -4316,170 +4649,6 @@ border-radius: 5;</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QSpinBox" name="spinBox_7">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Slowly raise Proportional until you start seeing clear oscillations when you fly.
|
||||
Then lower the value by 5 or so.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>200</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>200</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:RollRatePID</string>
|
||||
<string>element:Kp</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_141">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>78</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Proportional</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="5">
|
||||
<widget class="QSlider" name="horizontalSlider_78">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This adjusts how much leveling stability is set into Rate mode (inner loop). Too much will make your vehicle oscillate in Rate mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:YawRatePID</string>
|
||||
<string>element:Kp</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QSlider" name="PitchPSlider">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This adjusts how much leveling stability is set into Rate mode (inner loop). Too much will make your vehicle oscillate in Rate mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:PitchRatePID</string>
|
||||
<string>element:Kp</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<widget class="QSpinBox" name="spinBox_PitchRateP">
|
||||
<property name="minimumSize">
|
||||
@ -4666,8 +4835,8 @@ value as the Kp.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="6">
|
||||
<widget class="QSpinBox" name="spinBox_10">
|
||||
<item row="2" column="2">
|
||||
<widget class="QSpinBox" name="spinBox_7">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
@ -4684,8 +4853,8 @@ value as the Kp.</string>
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>As a rule of thumb, you can set the Integral at roughly the same
|
||||
value as the Kp.</string>
|
||||
<string>Slowly raise Proportional until you start seeing clear oscillations when you fly.
|
||||
Then lower the value by 5 or so.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>200</number>
|
||||
@ -4696,8 +4865,8 @@ value as the Kp.</string>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:YawRatePID</string>
|
||||
<string>element:Ki</string>
|
||||
<string>fieldname:RollRatePID</string>
|
||||
<string>element:Kp</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
@ -4705,707 +4874,130 @@ value as the Kp.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="5">
|
||||
<widget class="QSlider" name="horizontalSlider_81">
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_141">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This adjusts how much stability your vehicle will have when flying tilted (ie forward flight) in Rate mode. A good starting point for Integral is the same as Proportional</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:YawRatePID</string>
|
||||
<string>element:Ki</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="3">
|
||||
<widget class="QSlider" name="horizontalSlider_80">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This adjusts how much stability your vehicle will have when flying tilted (ie forward flight) in Rate mode. A good starting point for Integral is the same as Proportional</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:PitchRatePID</string>
|
||||
<string>element:Ki</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QSpinBox" name="spinBox_9">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>As a rule of thumb, you can set the Integral at roughly the same
|
||||
value as the Kp.</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>200</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>200</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:PitchRatePID</string>
|
||||
<string>element:Ki</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QLabel" name="label_138">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<width>78</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>58</red>
|
||||
<green>58</green>
|
||||
<blue>58</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>48</red>
|
||||
<green>48</green>
|
||||
<blue>48</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>58</red>
|
||||
<green>58</green>
|
||||
<blue>58</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>48</red>
|
||||
<green>48</green>
|
||||
<blue>48</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>58</red>
|
||||
<green>58</green>
|
||||
<blue>58</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>48</red>
|
||||
<green>48</green>
|
||||
<blue>48</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.000000000000000" endx="0.507000000000000" endy="0.772000000000000" type="LinearGradient" spread="ReflectSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.208955000000000">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>39</red>
|
||||
<green>39</green>
|
||||
<blue>39</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<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;</string>
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
<string>Proportional</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="6">
|
||||
<spacer name="horizontalSpacer_45">
|
||||
<item row="2" column="5">
|
||||
<widget class="QSlider" name="horizontalSlider_78">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This adjusts how much leveling stability is set into Rate mode (inner loop). Too much will make your vehicle oscillate in Rate mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:YawRatePID</string>
|
||||
<string>element:Kp</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<widget class="QSlider" name="PitchPSlider">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
<width>0</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This adjusts how much leveling stability is set into Rate mode (inner loop). Too much will make your vehicle oscillate in Rate mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>25</number>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:PitchRatePID</string>
|
||||
<string>element:Kp</string>
|
||||
<string>haslimits:yes</string>
|
||||
<string>scale:0.0001</string>
|
||||
<string>buttongroup:1,10</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
@ -5511,520 +5103,6 @@ border-radius: 5;</string>
|
||||
<height>195</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>248</red>
|
||||
<green>248</green>
|
||||
<blue>248</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
@ -8759,8 +7837,8 @@ border-radius: 5;</string>
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>796</width>
|
||||
<height>708</height>
|
||||
<width>784</width>
|
||||
<height>733</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_29">
|
||||
@ -8805,520 +7883,6 @@ border-radius: 5;</string>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>248</red>
|
||||
<green>248</green>
|
||||
<blue>248</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Responsiveness</string>
|
||||
</property>
|
||||
@ -9326,7 +7890,7 @@ border-radius: 5;</string>
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>false</bool>
|
||||
@ -9347,62 +7911,11 @@ border-radius: 5;</string>
|
||||
<property name="horizontalSpacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<spacer name="horizontalSpacer_14">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
<item row="2" column="0" colspan="3">
|
||||
<widget class="QGroupBox" name="advancedResponsivenessControls">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Expanding</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>632</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QPushButton" name="pushButton_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<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>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Reset all values to GCS defaults</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Default</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettings</string>
|
||||
<string>button:default</string>
|
||||
<string>buttongroup:6</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0" colspan="2">
|
||||
<widget class="QGroupBox" name="RateStabilizationGroup_7">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
@ -12143,596 +10656,21 @@ border-radius: 5;</string>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="RateStabilizationGroup_8">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<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>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>248</red>
|
||||
<green>248</green>
|
||||
<blue>248</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Rate Stabilization (Inner Loop)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_16">
|
||||
<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="1">
|
||||
<spacer name="horizontalSpacer_6">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>497</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QCheckBox" name="checkBox_3">
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>Link roll &amp; pitch values together, thus giving the same value for each when setting up a symetrical vehicle that requires both to be the same.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
<item row="1" column="0">
|
||||
<widget class="QCheckBox" name="advancedResponsivenessCheckBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Link Roll and Pitch</string>
|
||||
<string>Use Advanced Configuration</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QPushButton" name="pushButton_4">
|
||||
<item row="1" column="2">
|
||||
<widget class="QPushButton" name="pushButton_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
@ -12764,11 +10702,72 @@ border-radius: 5;</string>
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettings</string>
|
||||
<string>button:default</string>
|
||||
<string>buttongroup:4</string>
|
||||
<string>buttongroup:6</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<spacer name="horizontalSpacer_14">
|
||||
<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>
|
||||
<widget class="QGroupBox" name="RateStabilizationGroup_8">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<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>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Rate Stabilization (Inner Loop)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_16">
|
||||
<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="1" column="0" colspan="3">
|
||||
<widget class="QGroupBox" name="RateStabilizationGroup_9">
|
||||
<property name="sizePolicy">
|
||||
@ -15476,6 +13475,70 @@ border-radius: 5;</string>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<spacer name="horizontalSpacer_6">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>497</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QCheckBox" name="checkBox_3">
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>Link roll &amp; pitch values together, thus giving the same value for each when setting up a symetrical vehicle that requires both to be the same.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Link Roll and Pitch</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QPushButton" name="pushButton_4">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<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>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Reset all values to GCS defaults</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Default</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettings</string>
|
||||
<string>button:default</string>
|
||||
<string>buttongroup:4</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
@ -15499,520 +13562,6 @@ border-radius: 5;</string>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>248</red>
|
||||
<green>248</green>
|
||||
<blue>248</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
@ -18750,8 +16299,8 @@ border-radius: 5;</string>
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>796</width>
|
||||
<height>708</height>
|
||||
<width>798</width>
|
||||
<height>705</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_9">
|
||||
@ -23865,520 +21414,6 @@ border-radius: 5;</string>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="RateStabilizationGroup_23">
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>248</red>
|
||||
<green>248</green>
|
||||
<blue>248</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
@ -26881,8 +23916,8 @@ border-radius: 5;</string>
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>796</width>
|
||||
<height>708</height>
|
||||
<width>798</width>
|
||||
<height>705</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_19">
|
||||
@ -27727,8 +24762,8 @@ border-radius: 5;</string>
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>796</width>
|
||||
<height>708</height>
|
||||
<width>798</width>
|
||||
<height>705</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_18">
|
||||
@ -27752,520 +24787,6 @@ border-radius: 5;</string>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>248</red>
|
||||
<green>248</green>
|
||||
<blue>248</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Tuning</string>
|
||||
</property>
|
||||
@ -28870,6 +25391,9 @@ border-radius: 5;</string>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QSlider" name="AltKpSlider">
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>How fast the vehicle should climb or descent to compensate a certain altitude difference. higher values could result in more accurate altitude hold but also more violent control actions, lower values are safer and ensure smoother flight. The default value should be fine for the majority of crafts.</p></body></html></string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
@ -28896,6 +25420,9 @@ border-radius: 5;</string>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QSlider" name="AltKiSlider">
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>How much the vehicle should throttle up or down to compensate or achieve a certain vertical speed. Higher values lead to more aggressive throttle changes and could lead to oscillations. This is the most likely candidate to change depending on the crafts engine thrust. Heavy craft with weak engines might require higher values.</p></body></html></string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
@ -28922,6 +25449,9 @@ border-radius: 5;</string>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QSlider" name="AltKdSlider">
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>How fast the vehicle should adjust its neutral throttle estimation. Altitude assumes that when engaged the throttle is in the range required to hover. If the throttle is a lot higher or lower, it needs to adjust this &quot;throttle trim&quot; Higher values make it do this adjustment faster, but this could lead to ugly oscillations. Leave at default unless you know what you are doing.</p></body></html></string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>1000</number>
|
||||
</property>
|
||||
@ -29679,520 +26209,6 @@ border-radius: 5;</string>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</inactive>
|
||||
<disabled>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Button">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Light">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>251</red>
|
||||
<green>251</green>
|
||||
<blue>251</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>165</red>
|
||||
<green>165</green>
|
||||
<blue>165</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>124</red>
|
||||
<green>124</green>
|
||||
<blue>124</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Base">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="LinearGradientPattern">
|
||||
<gradient startx="0.507000000000000" starty="0.869318000000000" endx="0.507000000000000" endy="0.096590900000000" type="LinearGradient" spread="PadSpread" coordinatemode="ObjectBoundingMode">
|
||||
<gradientstop position="0.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>243</red>
|
||||
<green>243</green>
|
||||
<blue>243</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="1.000000000000000">
|
||||
<color alpha="255">
|
||||
<red>250</red>
|
||||
<green>250</green>
|
||||
<blue>250</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
</gradient>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Shadow">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>248</red>
|
||||
<green>248</green>
|
||||
<blue>248</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
</disabled>
|
||||
</palette>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Vario Altitude</string>
|
||||
</property>
|
||||
|
@ -17,18 +17,6 @@
|
||||
<property name="spacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<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>
|
||||
<widget class="QTabWidget" name="tabWidget">
|
||||
<property name="currentIndex">
|
||||
@ -131,8 +119,8 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>742</width>
|
||||
<height>450</height>
|
||||
<width>753</width>
|
||||
<height>475</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
|
@ -60,8 +60,7 @@ ConnectionManager::ConnectionManager(Internal::MainWindow *mainWindow) :
|
||||
// put everything together
|
||||
QHBoxLayout *layout = new QHBoxLayout;
|
||||
layout->setSpacing(6);
|
||||
// cheat a bit with the margin to "nicely" center things vertically
|
||||
layout->setContentsMargins(6, 0, 4, 2);
|
||||
layout->setContentsMargins(5, 2, 5, 2);
|
||||
setLayout(layout);
|
||||
|
||||
layout->addWidget(new QLabel(tr("Connections:")), 0, Qt::AlignVCenter);
|
||||
|
@ -50,7 +50,9 @@
|
||||
#include "ioutputpane.h"
|
||||
#include "icorelistener.h"
|
||||
#include "iconfigurableplugin.h"
|
||||
#include "manhattanstyle.h"
|
||||
|
||||
#include <qstylefactory.h>
|
||||
|
||||
#include "rightpane.h"
|
||||
#include "settingsdialog.h"
|
||||
#include "threadmanager.h"
|
||||
@ -140,20 +142,7 @@ MainWindow::MainWindow() :
|
||||
QCoreApplication::setOrganizationName(QLatin1String("OpenPilot"));
|
||||
QCoreApplication::setOrganizationDomain(QLatin1String("openpilot.org"));
|
||||
QSettings::setDefaultFormat(XmlConfig::XmlSettingsFormat);
|
||||
QString baseName = qApp->style()->objectName();
|
||||
#ifdef Q_WS_X11
|
||||
if (baseName == QLatin1String("windows")) {
|
||||
// Sometimes we get the standard windows 95 style as a fallback
|
||||
// e.g. if we are running on a KDE4 desktop
|
||||
QByteArray desktopEnvironment = qgetenv("DESKTOP_SESSION");
|
||||
if (desktopEnvironment == "kde") {
|
||||
baseName = QLatin1String("plastique");
|
||||
} else {
|
||||
baseName = QLatin1String("cleanlooks");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
qApp->setStyle(new ManhattanStyle(baseName));
|
||||
qApp->setStyle(QStyleFactory::create("Fusion"));
|
||||
|
||||
setDockNestingEnabled(true);
|
||||
|
||||
|
@ -104,7 +104,7 @@ UAVGadgetView::UAVGadgetView(Core::UAVGadgetManager *uavGadgetManager, IUAVGadge
|
||||
++index;
|
||||
}
|
||||
|
||||
m_defaultToolBar->setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
|
||||
m_defaultToolBar->setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::Minimum);
|
||||
m_activeToolBar = m_defaultToolBar;
|
||||
|
||||
QHBoxLayout *toolBarLayout = new QHBoxLayout(m_toolBar);
|
||||
@ -115,7 +115,7 @@ UAVGadgetView::UAVGadgetView(Core::UAVGadgetManager *uavGadgetManager, IUAVGadge
|
||||
m_toolBar->setSizePolicy(QSizePolicy::Maximum, QSizePolicy::MinimumExpanding);
|
||||
|
||||
QWidget *spacerWidget = new QWidget(this);
|
||||
spacerWidget->setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
|
||||
spacerWidget->setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::Minimum);
|
||||
|
||||
m_activeLabel->setTextFormat(Qt::RichText);
|
||||
m_activeLabel->setText("<font color=red><b>" + tr("Active") + "</b></font>");
|
||||
@ -124,9 +124,10 @@ UAVGadgetView::UAVGadgetView(Core::UAVGadgetManager *uavGadgetManager, IUAVGadge
|
||||
m_closeButton->setIcon(QIcon(":/core/images/closebutton.png"));
|
||||
|
||||
m_top = new Utils::StyledBar(this);
|
||||
m_top->setMaximumHeight(35);
|
||||
QHBoxLayout *toplayout = new QHBoxLayout(m_top);
|
||||
toplayout->setSpacing(0);
|
||||
toplayout->setMargin(0);
|
||||
toplayout->setSpacing(4);
|
||||
toplayout->setMargin(4);
|
||||
toplayout->addWidget(m_uavGadgetList);
|
||||
toplayout->addWidget(m_toolBar); // Custom toolbar stretches
|
||||
toplayout->addWidget(spacerWidget);
|
||||
|
@ -51,18 +51,23 @@
|
||||
class FieldTreeItem : public TreeItem {
|
||||
Q_OBJECT
|
||||
public:
|
||||
|
||||
FieldTreeItem(int index, const QList<QVariant> &data, TreeItem *parent = 0) :
|
||||
TreeItem(data, parent), m_index(index) {}
|
||||
|
||||
FieldTreeItem(int index, const QVariant &data, TreeItem *parent = 0) :
|
||||
TreeItem(data, parent), m_index(index) {}
|
||||
|
||||
bool isEditable()
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
virtual QWidget *createEditor(QWidget *parent) = 0;
|
||||
virtual QVariant getEditorValue(QWidget *editor) = 0;
|
||||
virtual void setEditorValue(QWidget *editor, QVariant value) = 0;
|
||||
virtual void apply() {}
|
||||
|
||||
protected:
|
||||
int m_index;
|
||||
};
|
||||
@ -70,12 +75,12 @@ protected:
|
||||
class EnumFieldTreeItem : public FieldTreeItem {
|
||||
Q_OBJECT
|
||||
public:
|
||||
EnumFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data,
|
||||
TreeItem *parent = 0) :
|
||||
EnumFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data, TreeItem *parent = 0) :
|
||||
FieldTreeItem(index, data, parent), m_enumOptions(field->getOptions()), m_field(field) {}
|
||||
EnumFieldTreeItem(UAVObjectField *field, int index, const QVariant &data,
|
||||
TreeItem *parent = 0) :
|
||||
|
||||
EnumFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, TreeItem *parent = 0) :
|
||||
FieldTreeItem(index, data, parent), m_enumOptions(field->getOptions()), m_field(field) {}
|
||||
|
||||
void setData(QVariant value, int column)
|
||||
{
|
||||
QStringList options = m_field->getOptions();
|
||||
@ -85,6 +90,7 @@ public:
|
||||
setChanged(tmpValIndex != value);
|
||||
TreeItem::setData(value, column);
|
||||
}
|
||||
|
||||
QString enumOptions(int index)
|
||||
{
|
||||
if ((index < 0) || (index >= m_enumOptions.length())) {
|
||||
@ -92,14 +98,16 @@ public:
|
||||
}
|
||||
return m_enumOptions.at(index);
|
||||
}
|
||||
|
||||
void apply()
|
||||
{
|
||||
int value = data(dataColumn).toInt();
|
||||
int value = data().toInt();
|
||||
QStringList options = m_field->getOptions();
|
||||
|
||||
m_field->setValue(options[value], m_index);
|
||||
setChanged(false);
|
||||
}
|
||||
|
||||
void update()
|
||||
{
|
||||
QStringList options = m_field->getOptions();
|
||||
@ -111,14 +119,16 @@ public:
|
||||
setHighlight(true);
|
||||
}
|
||||
}
|
||||
|
||||
QWidget *createEditor(QWidget *parent)
|
||||
{
|
||||
QComboBox *editor = new QComboBox(parent);
|
||||
|
||||
// Setting ClickFocus lets the ComboBox stay open on Mac OSX.
|
||||
editor->setFocusPolicy(Qt::ClickFocus);
|
||||
foreach(QString option, m_enumOptions)
|
||||
editor->addItem(option);
|
||||
foreach(QString option, m_enumOptions) {
|
||||
editor->addItem(option);
|
||||
}
|
||||
return editor;
|
||||
}
|
||||
|
||||
@ -135,6 +145,7 @@ public:
|
||||
|
||||
comboBox->setCurrentIndex(value.toInt());
|
||||
}
|
||||
|
||||
private:
|
||||
QStringList m_enumOptions;
|
||||
UAVObjectField *m_field;
|
||||
@ -148,6 +159,7 @@ public:
|
||||
{
|
||||
setMinMaxValues();
|
||||
}
|
||||
|
||||
IntFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, TreeItem *parent = 0) :
|
||||
FieldTreeItem(index, data, parent), m_field(field)
|
||||
{
|
||||
@ -210,16 +222,19 @@ public:
|
||||
|
||||
spinBox->setValue(value.toInt());
|
||||
}
|
||||
|
||||
void setData(QVariant value, int column)
|
||||
{
|
||||
setChanged(m_field->getValue(m_index) != value);
|
||||
TreeItem::setData(value, column);
|
||||
}
|
||||
|
||||
void apply()
|
||||
{
|
||||
m_field->setValue(data(dataColumn).toInt(), m_index);
|
||||
m_field->setValue(data().toInt(), m_index);
|
||||
setChanged(false);
|
||||
}
|
||||
|
||||
void update()
|
||||
{
|
||||
int value = m_field->getValue(m_index).toInt();
|
||||
@ -241,18 +256,22 @@ class FloatFieldTreeItem : public FieldTreeItem {
|
||||
public:
|
||||
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);
|
||||
}
|
||||
|
||||
void apply()
|
||||
{
|
||||
m_field->setValue(data(dataColumn).toDouble(), m_index);
|
||||
m_field->setValue(data().toDouble(), m_index);
|
||||
setChanged(false);
|
||||
}
|
||||
|
||||
void update()
|
||||
{
|
||||
double value = m_field->getValue(m_index).toDouble();
|
||||
@ -303,9 +322,115 @@ public:
|
||||
spinBox->setValue(value.toDouble());
|
||||
}
|
||||
}
|
||||
|
||||
private:
|
||||
UAVObjectField *m_field;
|
||||
bool m_useScientificNotation;
|
||||
};
|
||||
|
||||
class HexFieldTreeItem : public FieldTreeItem {
|
||||
Q_OBJECT
|
||||
public:
|
||||
HexFieldTreeItem(UAVObjectField *field, int index, const QList<QVariant> &data, TreeItem *parent = 0) :
|
||||
FieldTreeItem(index, data, parent), m_field(field)
|
||||
{}
|
||||
|
||||
HexFieldTreeItem(UAVObjectField *field, int index, const QVariant &data, TreeItem *parent = 0) :
|
||||
FieldTreeItem(index, data, parent), m_field(field)
|
||||
{}
|
||||
|
||||
QWidget *createEditor(QWidget *parent)
|
||||
{
|
||||
QLineEdit *lineEdit = new QLineEdit(parent);
|
||||
|
||||
lineEdit->setInputMask(QString(maxLength(), 'H'));
|
||||
|
||||
return lineEdit;
|
||||
}
|
||||
|
||||
QVariant getEditorValue(QWidget *editor)
|
||||
{
|
||||
QLineEdit *lineEdit = static_cast<QLineEdit *>(editor);
|
||||
|
||||
return lineEdit->text();
|
||||
}
|
||||
|
||||
void setEditorValue(QWidget *editor, QVariant value)
|
||||
{
|
||||
QLineEdit *lineEdit = static_cast<QLineEdit *>(editor);
|
||||
|
||||
lineEdit->setText(value.toString());
|
||||
}
|
||||
|
||||
void setData(QVariant value, int column)
|
||||
{
|
||||
setChanged(m_field->getValue(m_index) != toUInt(value));
|
||||
TreeItem::setData(value, column);
|
||||
}
|
||||
|
||||
void apply()
|
||||
{
|
||||
m_field->setValue(toUInt(data()), m_index);
|
||||
setChanged(false);
|
||||
}
|
||||
|
||||
void update()
|
||||
{
|
||||
QVariant value = toHexString(m_field->getValue(m_index));
|
||||
|
||||
if (data() != value || changed()) {
|
||||
TreeItem::setData(value);
|
||||
setHighlight(true);
|
||||
}
|
||||
}
|
||||
|
||||
private:
|
||||
UAVObjectField *m_field;
|
||||
|
||||
QVariant toHexString(QVariant value)
|
||||
{
|
||||
QString str;
|
||||
bool ok;
|
||||
|
||||
return str.setNum(value.toUInt(&ok), 16).toUpper();
|
||||
}
|
||||
|
||||
QVariant toUInt(QVariant str)
|
||||
{
|
||||
bool ok;
|
||||
|
||||
return str.toString().toUInt(&ok, 16);
|
||||
}
|
||||
|
||||
int maxLength()
|
||||
{
|
||||
int maxLength = 0;
|
||||
|
||||
switch (m_field->getType()) {
|
||||
case UAVObjectField::INT8:
|
||||
maxLength = 2;
|
||||
break;
|
||||
case UAVObjectField::INT16:
|
||||
maxLength = 4;
|
||||
break;
|
||||
case UAVObjectField::INT32:
|
||||
maxLength = 8;
|
||||
break;
|
||||
case UAVObjectField::UINT8:
|
||||
maxLength = 2;
|
||||
break;
|
||||
case UAVObjectField::UINT16:
|
||||
maxLength = 4;
|
||||
break;
|
||||
case UAVObjectField::UINT32:
|
||||
maxLength = 8;
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(false);
|
||||
break;
|
||||
}
|
||||
return maxLength;
|
||||
}
|
||||
};
|
||||
|
||||
#endif // FIELDTREEITEM_H
|
||||
|
@ -228,7 +228,11 @@ void UAVObjectTreeModel::addSingleField(int index, UAVObjectField *field, TreeIt
|
||||
case UAVObjectField::UINT32:
|
||||
data.append(field->getValue(index));
|
||||
data.append(field->getUnits());
|
||||
item = new IntFieldTreeItem(field, index, data);
|
||||
if (field->getUnits().toLower() == "hex") {
|
||||
item = new HexFieldTreeItem(field, index, data);
|
||||
} else {
|
||||
item = new IntFieldTreeItem(field, index, data);
|
||||
}
|
||||
break;
|
||||
case UAVObjectField::FLOAT32:
|
||||
data.append(field->getValue(index));
|
||||
@ -351,9 +355,6 @@ QVariant UAVObjectTreeModel::data(const QModelIndex &index, int role) const
|
||||
return item->data(index.column());
|
||||
}
|
||||
|
||||
// if (role == Qt::DecorationRole)
|
||||
// return QIcon(":/core/images/openpilot_logo_128.png");
|
||||
|
||||
if (role == Qt::ToolTipRole) {
|
||||
TreeItem *item = static_cast<TreeItem *>(index.internalPointer());
|
||||
return item->description();
|
||||
|
@ -82,6 +82,7 @@ SRC += $(PIOSCOMMON)/pios_crc.c
|
||||
SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c
|
||||
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
|
||||
SRC += $(PIOSCOMMON)/pios_debuglog.c
|
||||
SRC += $(PIOSCOMMON)/pios_deltatime.c
|
||||
SRC += $(PIOSCOMMON)/pios_rcvr.c
|
||||
SRC += $(PIOSCOMMON)/pios_rfm22b.c
|
||||
SRC += $(PIOSCOMMON)/pios_rfm22b_com.c
|
||||
|
@ -3,72 +3,70 @@
|
||||
<description>Task information</description>
|
||||
<field name="StackRemaining" units="bytes" type="uint16">
|
||||
<elementnames>
|
||||
<!-- system -->
|
||||
<elementname>System</elementname>
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<elementname>RadioRx</elementname>
|
||||
<elementname>GPS</elementname>
|
||||
<elementname>ManualControl</elementname>
|
||||
<elementname>Altitude</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>AltitudeHold</elementname>
|
||||
<elementname>PathPlanner</elementname>
|
||||
<elementname>PathFollower</elementname>
|
||||
<elementname>FlightPlan</elementname>
|
||||
<elementname>Com2UsbBridge</elementname>
|
||||
<elementname>Usb2ComBridge</elementname>
|
||||
<elementname>OveroSync</elementname>
|
||||
<elementname>ModemRx</elementname>
|
||||
<elementname>ModemTx</elementname>
|
||||
<elementname>ModemStat</elementname>
|
||||
<elementname>Autotune</elementname>
|
||||
<elementname>EventDispatcher</elementname>
|
||||
<elementname>MagBaro</elementname>
|
||||
<elementname>OSDGen</elementname>
|
||||
<elementname>CallbackScheduler0</elementname>
|
||||
<elementname>CallbackScheduler1</elementname>
|
||||
<elementname>CallbackScheduler2</elementname>
|
||||
<elementname>CallbackScheduler3</elementname>
|
||||
<!-- fligth -->
|
||||
<elementname>ManualControl</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Altitude</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>MagBaro</elementname>
|
||||
<!-- navigation -->
|
||||
<elementname>PathFollower</elementname>
|
||||
<elementname>FlightPlan</elementname>
|
||||
<!-- telemetry -->
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<!-- com -->
|
||||
<elementname>RadioRx</elementname>
|
||||
<elementname>Com2UsbBridge</elementname>
|
||||
<elementname>Usb2ComBridge</elementname>
|
||||
<!-- optional -->
|
||||
<elementname>GPS</elementname>
|
||||
<elementname>OSDGen</elementname>
|
||||
<elementname>Autotune</elementname>
|
||||
</elementnames>
|
||||
</field>
|
||||
<field name="Running" units="bool" type="enum">
|
||||
<elementnames>
|
||||
<!-- system -->
|
||||
<elementname>System</elementname>
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<elementname>RadioRx</elementname>
|
||||
<elementname>GPS</elementname>
|
||||
<elementname>ManualControl</elementname>
|
||||
<elementname>Altitude</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>AltitudeHold</elementname>
|
||||
<elementname>PathPlanner</elementname>
|
||||
<elementname>PathFollower</elementname>
|
||||
<elementname>FlightPlan</elementname>
|
||||
<elementname>Com2UsbBridge</elementname>
|
||||
<elementname>Usb2ComBridge</elementname>
|
||||
<elementname>OveroSync</elementname>
|
||||
<elementname>ModemRx</elementname>
|
||||
<elementname>ModemTx</elementname>
|
||||
<elementname>ModemStat</elementname>
|
||||
<elementname>Autotune</elementname>
|
||||
<elementname>EventDispatcher</elementname>
|
||||
<elementname>MagBaro</elementname>
|
||||
<elementname>OSDGen</elementname>
|
||||
<elementname>CallbackScheduler0</elementname>
|
||||
<elementname>CallbackScheduler1</elementname>
|
||||
<elementname>CallbackScheduler2</elementname>
|
||||
<elementname>CallbackScheduler3</elementname>
|
||||
<!-- fligth -->
|
||||
<elementname>ManualControl</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Altitude</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>MagBaro</elementname>
|
||||
<!-- navigation -->
|
||||
<elementname>PathFollower</elementname>
|
||||
<elementname>FlightPlan</elementname>
|
||||
<!-- telemetry -->
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<!-- com -->
|
||||
<elementname>RadioRx</elementname>
|
||||
<elementname>Com2UsbBridge</elementname>
|
||||
<elementname>Usb2ComBridge</elementname>
|
||||
<!-- optional -->
|
||||
<elementname>GPS</elementname>
|
||||
<elementname>OSDGen</elementname>
|
||||
<elementname>Autotune</elementname>
|
||||
</elementnames>
|
||||
<options>
|
||||
<option>False</option>
|
||||
@ -77,40 +75,39 @@
|
||||
</field>
|
||||
<field name="RunningTime" units="%" type="uint8">
|
||||
<elementnames>
|
||||
<!-- system -->
|
||||
<elementname>System</elementname>
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<elementname>RadioRx</elementname>
|
||||
<elementname>GPS</elementname>
|
||||
<elementname>ManualControl</elementname>
|
||||
<elementname>Altitude</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>AltitudeHold</elementname>
|
||||
<elementname>PathPlanner</elementname>
|
||||
<elementname>PathFollower</elementname>
|
||||
<elementname>FlightPlan</elementname>
|
||||
<elementname>Com2UsbBridge</elementname>
|
||||
<elementname>Usb2ComBridge</elementname>
|
||||
<elementname>OveroSync</elementname>
|
||||
<elementname>ModemRx</elementname>
|
||||
<elementname>ModemTx</elementname>
|
||||
<elementname>ModemStat</elementname>
|
||||
<elementname>Autotune</elementname>
|
||||
<elementname>EventDispatcher</elementname>
|
||||
<elementname>MagBaro</elementname>
|
||||
<elementname>OSDGen</elementname>
|
||||
<elementname>CallbackScheduler0</elementname>
|
||||
<elementname>CallbackScheduler1</elementname>
|
||||
<elementname>CallbackScheduler2</elementname>
|
||||
<elementname>CallbackScheduler3</elementname>
|
||||
<!-- fligth -->
|
||||
<elementname>ManualControl</elementname>
|
||||
<elementname>Stabilization</elementname>
|
||||
<elementname>Actuator</elementname>
|
||||
<elementname>Sensors</elementname>
|
||||
<elementname>Attitude</elementname>
|
||||
<elementname>Altitude</elementname>
|
||||
<elementname>Airspeed</elementname>
|
||||
<elementname>MagBaro</elementname>
|
||||
<!-- navigation -->
|
||||
<elementname>PathFollower</elementname>
|
||||
<elementname>FlightPlan</elementname>
|
||||
<!-- telemetry -->
|
||||
<elementname>TelemetryTx</elementname>
|
||||
<elementname>TelemetryTxPri</elementname>
|
||||
<elementname>TelemetryRx</elementname>
|
||||
<!-- com -->
|
||||
<elementname>RadioRx</elementname>
|
||||
<elementname>Com2UsbBridge</elementname>
|
||||
<elementname>Usb2ComBridge</elementname>
|
||||
<!-- optional -->
|
||||
<elementname>GPS</elementname>
|
||||
<elementname>OSDGen</elementname>
|
||||
<elementname>Autotune</elementname>
|
||||
</elementnames>
|
||||
</field>
|
||||
<access gcs="readwrite" flight="readwrite"/>
|
||||
<access gcs="readonly" flight="readwrite"/>
|
||||
<telemetrygcs acked="true" updatemode="onchange" period="0"/>
|
||||
<telemetryflight acked="true" updatemode="periodic" period="10000"/>
|
||||
<logging updatemode="manual" period="0"/>
|
||||
|
Loading…
x
Reference in New Issue
Block a user