Merge remote-tracking branch 'origin/next' into laurent/OP-1337_French_translations_updates
2
Makefile
@ -638,7 +638,7 @@ uavo-collections_clean:
|
||||
#
|
||||
##############################
|
||||
|
||||
ALL_UNITTESTS := logfs math
|
||||
ALL_UNITTESTS := logfs math lednotification
|
||||
|
||||
# Build the directory for the unit tests
|
||||
UT_OUT_DIR := $(BUILD_DIR)/unit_tests
|
||||
|
33
flight/libraries/inc/lednotification.h
Normal file
@ -0,0 +1,33 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file lednotification.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief led notification library
|
||||
* --
|
||||
* @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 LEDNOTIFICATION_H_
|
||||
#define LEDNOTIFICATION_H_
|
||||
#include <optypes.h>
|
||||
|
||||
void LedNotificationExtLedsRun();
|
||||
|
||||
|
||||
#endif /* LEDNOTIFICATION_H_ */
|
@ -27,7 +27,7 @@
|
||||
#define NOTIFICATION_H
|
||||
|
||||
// period of each blink phase
|
||||
#define LED_BLINK_PERIOD_MS 200
|
||||
#define LED_BLINK_PERIOD_MS 50
|
||||
|
||||
// update the status snapshot used by notifcations
|
||||
void NotificationUpdateStatus();
|
||||
|
64
flight/libraries/inc/optypes.h
Normal file
@ -0,0 +1,64 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file optypes.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief OP Generic data type library
|
||||
* --
|
||||
* @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 UTIL_H
|
||||
#define UTIL_H
|
||||
#include <stdint.h>
|
||||
typedef struct {
|
||||
uint8_t R;
|
||||
uint8_t G;
|
||||
uint8_t B;
|
||||
} Color_t;
|
||||
|
||||
extern const Color_t Color_Off;
|
||||
extern const Color_t Color_Black;
|
||||
extern const Color_t Color_Red;
|
||||
extern const Color_t Color_Lime;
|
||||
extern const Color_t Color_Blue;
|
||||
extern const Color_t Color_Yellow;
|
||||
extern const Color_t Color_Cian;
|
||||
extern const Color_t Color_Magenta;
|
||||
extern const Color_t Color_Navy;
|
||||
extern const Color_t Color_Green;
|
||||
extern const Color_t Color_Purple;
|
||||
extern const Color_t Color_Teal;
|
||||
extern const Color_t Color_Orange;
|
||||
extern const Color_t Color_White;
|
||||
|
||||
#define COLOR_BLACK { .R = 0x00, .G = 0x00, .B = 0x00 }
|
||||
#define COLOR_OFF COLOR_BLACK
|
||||
#define COLOR_RED { .R = 0xFF, .G = 0x00, .B = 0x00 }
|
||||
#define COLOR_LIME { .R = 0x00, .G = 0xFF, .B = 0x00 }
|
||||
#define COLOR_BLUE { .R = 0x00, .G = 0x00, .B = 0xFF }
|
||||
#define COLOR_YELLOW { .R = 0xFF, .G = 0xFF, .B = 0x00 }
|
||||
#define COLOR_CIAN { .R = 0x00, .G = 0xFF, .B = 0xFF }
|
||||
#define COLOR_MAGENTA { .R = 0xFF, .G = 0x00, .B = 0xFF }
|
||||
#define COLOR_NAVY { .R = 0x00, .G = 0x00, .B = 0x80 }
|
||||
#define COLOR_GREEN { .R = 0x00, .G = 0x80, .B = 0x00 }
|
||||
#define COLOR_PURPLE { .R = 0x80, .G = 0x00, .B = 0x80 }
|
||||
#define COLOR_TEAL { .R = 0x00, .G = 0x80, .B = 0x80 }
|
||||
#define COLOR_ORANGE { .R = 0xFF, .G = 0xA5, .B = 0x00 }
|
||||
#define COLOR_WHITE { .R = 0xAA, .G = 0xAA, .B = 0xAA }
|
||||
#endif /* UTIL_H */
|
259
flight/libraries/lednotification.c
Normal file
@ -0,0 +1,259 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file lednotification.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief led notification library.
|
||||
* --
|
||||
* @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 "inc/lednotification.h"
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <FreeRTOS.h>
|
||||
#include <pios.h>
|
||||
#include <pios_notify.h>
|
||||
#include <pios_ws2811.h>
|
||||
|
||||
// Private defines
|
||||
|
||||
// Maximum number of notifications enqueued when a higher priority notification is added
|
||||
#define MAX_BACKGROUND_NOTIFICATIONS 6
|
||||
#define MAX_HANDLED_LED 1
|
||||
|
||||
#define BACKGROUND_SEQUENCE 0
|
||||
#define RESET_STEP -1
|
||||
#define GET_CURRENT_MILLIS (xTaskGetTickCount() * portTICK_RATE_MS)
|
||||
|
||||
// Private data types definition
|
||||
// this is the status for a single notification led set
|
||||
typedef struct {
|
||||
int8_t queued_priorities[MAX_BACKGROUND_NOTIFICATIONS]; // slot 0 is reserved for background
|
||||
LedSequence_t queued_sequences[MAX_BACKGROUND_NOTIFICATIONS]; // slot 0 is reserved for background
|
||||
uint32_t next_run_time;
|
||||
uint32_t sequence_starting_time;
|
||||
|
||||
int8_t active_sequence_num; // active queued sequence or BACKGROUND_SEQUENCE
|
||||
bool running; // is this led running?
|
||||
bool step_phase_on; // true = step on phase, false = step off phase
|
||||
uint8_t next_sequence_step; // (step number to be executed) << 1 || (0x00 = on phase, 0x01 = off phase)
|
||||
uint8_t next_step_rep; // next repetition number for next step (valid if step.repeats >1)
|
||||
uint8_t next_sequence_rep; // next sequence repetition counter (valid if sequence.repeats > 1)
|
||||
uint8_t led_set_start; // first target led for this set
|
||||
uint8_t led_set_end; // last target led for this set
|
||||
} NotifierLedStatus_t;
|
||||
|
||||
static bool led_status_initialized = false;
|
||||
|
||||
NotifierLedStatus_t led_status[MAX_HANDLED_LED];
|
||||
|
||||
static void InitExtLed()
|
||||
{
|
||||
memset(led_status, 0, sizeof(NotifierLedStatus_t) * MAX_HANDLED_LED);
|
||||
const uint32_t now = GET_CURRENT_MILLIS;
|
||||
for (uint8_t l = 0; l < MAX_HANDLED_LED; l++) {
|
||||
led_status[l].led_set_start = 0;
|
||||
led_status[l].led_set_end = PIOS_WS2811_NUMLEDS - 1;
|
||||
led_status[l].next_run_time = now + 500; // start within half a second
|
||||
for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) {
|
||||
led_status[l].queued_priorities[i] = NOTIFY_PRIORITY_BACKGROUND;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* restart current sequence
|
||||
*/
|
||||
static void restart_sequence(NotifierLedStatus_t *status, bool immediate)
|
||||
{
|
||||
status->next_sequence_step = 0;
|
||||
status->next_step_rep = 0;
|
||||
status->step_phase_on = true;
|
||||
status->running = true;
|
||||
if (immediate) {
|
||||
uint32_t currentTime = GET_CURRENT_MILLIS;
|
||||
status->next_run_time = currentTime;
|
||||
}
|
||||
status->sequence_starting_time = status->next_run_time;
|
||||
}
|
||||
|
||||
/**
|
||||
* modify background sequence or enqueue a new sequence to play
|
||||
*/
|
||||
static void push_queued_sequence(ExtLedNotification_t *new_notification, NotifierLedStatus_t *status)
|
||||
{
|
||||
int8_t updated_sequence;
|
||||
|
||||
int8_t lowest_priority_index = -1;
|
||||
int8_t lowest_priority = new_notification->priority;
|
||||
|
||||
if (new_notification->priority == NOTIFY_PRIORITY_BACKGROUND) {
|
||||
lowest_priority_index = BACKGROUND_SEQUENCE;
|
||||
} else {
|
||||
// slot 0 is reserved for Background sequence
|
||||
for (int8_t i = 1; i < MAX_BACKGROUND_NOTIFICATIONS; i++) {
|
||||
if (status->queued_priorities[i] < lowest_priority) {
|
||||
lowest_priority_index = i;
|
||||
lowest_priority = status->queued_priorities[i];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// no items with priority lower than the one we are trying to enqueue. skip
|
||||
if (lowest_priority_index < 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
status->queued_priorities[lowest_priority_index] = new_notification->priority;
|
||||
status->queued_sequences[lowest_priority_index] = new_notification->sequence;
|
||||
updated_sequence = lowest_priority_index;;
|
||||
|
||||
|
||||
// check whether we should preempt the current notification and play this new one
|
||||
if (status->queued_priorities[status->active_sequence_num] < new_notification->priority) {
|
||||
status->active_sequence_num = updated_sequence;
|
||||
}
|
||||
|
||||
if (status->active_sequence_num == updated_sequence) {
|
||||
restart_sequence(status, true);
|
||||
}
|
||||
}
|
||||
|
||||
static bool pop_queued_sequence(NotifierLedStatus_t *status)
|
||||
{
|
||||
if (status->active_sequence_num > BACKGROUND_SEQUENCE) {
|
||||
// set the last active slot as empty
|
||||
status->queued_priorities[status->active_sequence_num] = NOTIFY_PRIORITY_BACKGROUND;
|
||||
|
||||
// search the highest priority item
|
||||
int8_t highest_priority_index = BACKGROUND_SEQUENCE;
|
||||
int8_t highest_priority = NOTIFY_PRIORITY_BACKGROUND;
|
||||
|
||||
for (int8_t i = 1; i < MAX_BACKGROUND_NOTIFICATIONS; i++) {
|
||||
if (status->queued_priorities[i] > highest_priority) {
|
||||
highest_priority_index = i;
|
||||
highest_priority = status->queued_priorities[i];
|
||||
}
|
||||
}
|
||||
// set the next sequence to activate (or BACKGROUND_SEQUENCE when all slots are empty)
|
||||
status->active_sequence_num = highest_priority_index;
|
||||
return highest_priority_index != BACKGROUND_SEQUENCE;
|
||||
}
|
||||
// background sequence was completed
|
||||
return false;
|
||||
}
|
||||
|
||||
/**
|
||||
* advance current sequence pointers for next step
|
||||
*/
|
||||
static void advance_sequence(NotifierLedStatus_t *status)
|
||||
{
|
||||
LedSequence_t *activeSequence = &status->queued_sequences[status->active_sequence_num];
|
||||
|
||||
uint8_t step = status->next_sequence_step;
|
||||
LedStep_t *currentStep = &activeSequence->steps[step];
|
||||
|
||||
// Next step will be the OFF phase, so just update the time and
|
||||
if (status->step_phase_on) {
|
||||
// next will be the off phase
|
||||
status->next_run_time += currentStep->time_on;
|
||||
status->step_phase_on = false;
|
||||
// check if off phase should be skipped
|
||||
if (currentStep->time_off != 0) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// next step is ON phase. check whether to repeat current step or move to next one
|
||||
status->next_run_time += currentStep->time_off;
|
||||
status->step_phase_on = true;
|
||||
|
||||
if (status->next_step_rep + 1 < currentStep->repeats) {
|
||||
// setup next repetition
|
||||
status->next_step_rep++;
|
||||
return;
|
||||
}
|
||||
|
||||
// move to next step
|
||||
LedStep_t *nextStep = (step + 1 < NOTIFY_SEQUENCE_MAX_STEPS) ? &activeSequence->steps[step + 1] : 0;
|
||||
|
||||
// next step is null, check whether sequence must be repeated or it must move to lower priority queued or background sequences
|
||||
if (NOTIFY_IS_NULL_STEP(nextStep)) {
|
||||
if (activeSequence->repeats == -1 || status->next_sequence_rep + 1 < activeSequence->repeats) {
|
||||
status->next_sequence_rep++;
|
||||
// restart the sequence
|
||||
restart_sequence(status, false);
|
||||
return;
|
||||
}
|
||||
if (status->active_sequence_num != BACKGROUND_SEQUENCE) {
|
||||
// no repeat, pop enqueued or background sequences
|
||||
pop_queued_sequence(status);
|
||||
restart_sequence(status, false);
|
||||
status->next_sequence_rep = 0;
|
||||
} else {
|
||||
status->running = false;
|
||||
}
|
||||
} else {
|
||||
status->next_step_rep = 0;
|
||||
status->next_sequence_step++;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* run a led set
|
||||
*/
|
||||
static void run_led(NotifierLedStatus_t *status)
|
||||
{
|
||||
const uint32_t currentTime = GET_CURRENT_MILLIS;
|
||||
|
||||
if (!status->running || currentTime < status->next_run_time) {
|
||||
return;
|
||||
}
|
||||
status->next_run_time = currentTime;
|
||||
uint8_t step = status->next_sequence_step;
|
||||
|
||||
LedSequence_t *activeSequence = &status->queued_sequences[status->active_sequence_num];
|
||||
const Color_t color = status->step_phase_on ? activeSequence->steps[step].color : Color_Off;
|
||||
|
||||
for (uint8_t i = status->led_set_start; i <= status->led_set_end; i++) {
|
||||
PIOS_WS2811_setColorRGB(color, i, false);
|
||||
}
|
||||
PIOS_WS2811_Update();
|
||||
advance_sequence(status);
|
||||
}
|
||||
|
||||
void LedNotificationExtLedsRun()
|
||||
{
|
||||
// handle incoming sequences
|
||||
if (!led_status_initialized) {
|
||||
InitExtLed();
|
||||
led_status_initialized = true;
|
||||
}
|
||||
static ExtLedNotification_t *newNotification;
|
||||
newNotification = PIOS_NOTIFY_GetNewExtLedSequence(true);
|
||||
if (newNotification) {
|
||||
push_queued_sequence(newNotification, &led_status[0]);
|
||||
}
|
||||
|
||||
// Run Leds
|
||||
for (uint8_t i = 0; i < MAX_HANDLED_LED; i++) {
|
||||
run_led(&led_status[i]);
|
||||
}
|
||||
}
|
@ -28,6 +28,11 @@
|
||||
#include <systemalarms.h>
|
||||
#include <flightstatus.h>
|
||||
#include <pios_notify.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
|
||||
#define GET_CURRENT_MILLIS (xTaskGetTickCount() * portTICK_RATE_MS)
|
||||
// Private data types definition
|
||||
|
||||
#ifdef PIOS_LED_ALARM
|
||||
#define ALARM_LED_ON() PIOS_LED_On(PIOS_LED_ALARM)
|
||||
@ -136,6 +141,8 @@ static bool handleAlarms(uint16_t *r_pattern, uint16_t *b_pattern);
|
||||
static bool handleNotifications(pios_notify_notification runningNotification, uint16_t *r_pattern, uint16_t *b_pattern);
|
||||
static void handleFlightMode(uint16_t *r_pattern, uint16_t *b_pattern);
|
||||
static void handleHeartbeat(uint16_t *r_pattern, uint16_t *b_pattern);
|
||||
|
||||
|
||||
void NotificationUpdateStatus()
|
||||
{
|
||||
started = true;
|
||||
@ -149,7 +156,7 @@ void NotificationUpdateStatus()
|
||||
|
||||
void NotificationOnboardLedsRun()
|
||||
{
|
||||
static portTickType lastRunTimestamp;
|
||||
static uint32_t lastRunTimestamp;
|
||||
static uint16_t r_pattern;
|
||||
static uint16_t b_pattern;
|
||||
static uint8_t cycleCount; // count the number of cycles
|
||||
@ -163,11 +170,13 @@ void NotificationOnboardLedsRun()
|
||||
STATUS_LENGHT
|
||||
} status;
|
||||
|
||||
if (!started || (xTaskGetTickCount() - lastRunTimestamp) < (LED_BLINK_PERIOD_MS * portTICK_RATE_MS / 4)) {
|
||||
const uint32_t current_timestamp = GET_CURRENT_MILLIS;
|
||||
|
||||
if (!started || (current_timestamp - lastRunTimestamp) < LED_BLINK_PERIOD_MS) {
|
||||
return;
|
||||
}
|
||||
|
||||
lastRunTimestamp = xTaskGetTickCount();
|
||||
lastRunTimestamp = current_timestamp;
|
||||
// the led will show various status information, subdivided in three phases
|
||||
// - Notification
|
||||
// - Alarm
|
||||
|
42
flight/libraries/optypes.c
Normal file
@ -0,0 +1,42 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file optypes.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief OP Generic data type library
|
||||
* --
|
||||
* @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 <optypes.h>
|
||||
|
||||
const Color_t Color_Off = COLOR_OFF;
|
||||
const Color_t Color_Black = COLOR_BLACK;
|
||||
const Color_t Color_Red = COLOR_RED;
|
||||
const Color_t Color_Lime = COLOR_LIME;
|
||||
const Color_t Color_Blue = COLOR_BLUE;
|
||||
const Color_t Color_Yellow = COLOR_YELLOW;
|
||||
const Color_t Color_Cian = COLOR_CIAN;
|
||||
const Color_t Color_Magenta = COLOR_MAGENTA;
|
||||
const Color_t Color_Navy = COLOR_NAVY;
|
||||
const Color_t Color_Green = COLOR_GREEN;
|
||||
const Color_t Color_Purple = COLOR_PURPLE;
|
||||
const Color_t Color_Teal = COLOR_TEAL;
|
||||
const Color_t Color_Orange = COLOR_ORANGE;
|
||||
const Color_t Color_White = COLOR_WHITE;
|
@ -262,6 +262,7 @@ FrameType_t GetCurrentFrameType()
|
||||
switch ((SystemSettingsAirframeTypeOptions)airframe_type) {
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_QUADX:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_QUADH:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO:
|
||||
case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOX:
|
||||
|
@ -245,7 +245,9 @@ static void gpsTask(__attribute__((unused)) void *parameters)
|
||||
if (gpsSettings.DataProtocol == GPSSETTINGS_DATAPROTOCOL_UBX) {
|
||||
char *buffer = 0;
|
||||
uint16_t count = 0;
|
||||
ubx_autoconfig_run(&buffer, &count);
|
||||
uint8_t status;
|
||||
GPSPositionSensorStatusGet(&status);
|
||||
ubx_autoconfig_run(&buffer, &count, status != GPSPOSITIONSENSOR_STATUS_NOGPS);
|
||||
// Something to send?
|
||||
if (count) {
|
||||
PIOS_COM_SendBuffer(gpsPort, (uint8_t *)buffer, count);
|
||||
@ -266,11 +268,17 @@ static void gpsTask(__attribute__((unused)) void *parameters)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_GPS_UBX_PARSER) && !defined(PIOS_GPS_MINIMAL)
|
||||
int32_t ac_status = ubx_autoconfig_get_status();
|
||||
static uint8_t lastStatus = 0;
|
||||
|
||||
gpspositionsensor.AutoConfigStatus =
|
||||
ac_status == UBX_AUTOCONFIG_STATUS_DISABLED ? GPSPOSITIONSENSOR_AUTOCONFIGSTATUS_DISABLED :
|
||||
ac_status == UBX_AUTOCONFIG_STATUS_DONE ? GPSPOSITIONSENSOR_AUTOCONFIGSTATUS_DONE :
|
||||
ac_status == UBX_AUTOCONFIG_STATUS_ERROR ? GPSPOSITIONSENSOR_AUTOCONFIGSTATUS_ERROR :
|
||||
GPSPOSITIONSENSOR_AUTOCONFIGSTATUS_RUNNING;
|
||||
if (gpspositionsensor.AutoConfigStatus != lastStatus) {
|
||||
GPSPositionSensorAutoConfigStatusSet(&gpspositionsensor.AutoConfigStatus);
|
||||
lastStatus = gpspositionsensor.AutoConfigStatus;
|
||||
}
|
||||
#endif
|
||||
res = parse_ubx_stream(c, gps_rx_buffer, &gpspositionsensor, &gpsRxStats);
|
||||
}
|
||||
@ -290,7 +298,8 @@ static void gpsTask(__attribute__((unused)) void *parameters)
|
||||
|
||||
// Check for GPS timeout
|
||||
timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS;
|
||||
if ((timeNowMs - timeOfLastUpdateMs) >= GPS_TIMEOUT_MS) {
|
||||
if ((timeNowMs - timeOfLastUpdateMs) >= GPS_TIMEOUT_MS ||
|
||||
(gpsSettings.DataProtocol == GPSSETTINGS_DATAPROTOCOL_UBX && gpspositionsensor.AutoConfigStatus == GPSPOSITIONSENSOR_AUTOCONFIGSTATUS_ERROR)) {
|
||||
// we have not received any valid GPS sentences for a while.
|
||||
// either the GPS is not plugged in or a hardware problem or the GPS has locked up.
|
||||
uint8_t status = GPSPOSITIONSENSOR_STATUS_NOGPS;
|
||||
|
@ -515,6 +515,14 @@ uint32_t parse_ubx_message(struct UBXPacket *ubx, GPSPositionSensorData *GpsPosi
|
||||
GPSPositionSensorSet(GpsPosition);
|
||||
msgtracker.msg_received = NONE_RECEIVED;
|
||||
id = GPSPOSITIONSENSOR_OBJID;
|
||||
} else {
|
||||
uint8_t status;
|
||||
GPSPositionSensorStatusGet(&status);
|
||||
if (status == GPSPOSITIONSENSOR_STATUS_NOGPS) {
|
||||
// Some ubx thing has been received so GPS is there
|
||||
status = GPSPOSITIONSENSOR_STATUS_NOFIX;
|
||||
GPSPositionSensorStatusSet(&status);
|
||||
}
|
||||
}
|
||||
return id;
|
||||
}
|
||||
|
@ -33,13 +33,20 @@
|
||||
|
||||
// defines
|
||||
// TODO: NEO8 max rate is for Rom version, flash is limited to 10Hz, need to handle that.
|
||||
#define UBX_MAX_RATE_VER8 18
|
||||
#define UBX_MAX_RATE_VER7 10
|
||||
#define UBX_MAX_RATE 5
|
||||
|
||||
#define UBX_REPLY_TIMEOUT (500 * 1000)
|
||||
#define UBX_MAX_RETRIES 5
|
||||
#define UBX_MAX_RATE_VER8 18
|
||||
#define UBX_MAX_RATE_VER7 10
|
||||
#define UBX_MAX_RATE 5
|
||||
|
||||
// time to wait before reinitializing the fsm due to disconnection
|
||||
#define UBX_CONNECTION_TIMEOUT (2000 * 1000)
|
||||
// times between retries in case an error does occurs
|
||||
#define UBX_ERROR_RETRY_TIMEOUT (1000 * 1000)
|
||||
// timeout for ack reception
|
||||
#define UBX_REPLY_TIMEOUT (500 * 1000)
|
||||
// max retries in case of timeout
|
||||
#define UBX_MAX_RETRIES 5
|
||||
// pause between each configuration step
|
||||
#define UBX_STEP_WAIT_TIME (10 * 1000)
|
||||
// types
|
||||
typedef enum {
|
||||
UBX_AUTOCONFIG_STATUS_DISABLED = 0,
|
||||
@ -179,7 +186,7 @@ typedef union {
|
||||
} message;
|
||||
} __attribute__((packed)) UBXSentPacket_t;
|
||||
|
||||
void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send);
|
||||
void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send, bool gps_connected);
|
||||
void ubx_autoconfig_set(ubx_autoconfig_settings_t config);
|
||||
int32_t ubx_autoconfig_get_status();
|
||||
#endif /* UBX_AUTOCONFIG_H_ */
|
||||
|
@ -46,6 +46,7 @@ typedef enum {
|
||||
typedef struct {
|
||||
initSteps_t currentStep; // Current configuration "fsm" status
|
||||
uint32_t lastStepTimestampRaw; // timestamp of last operation
|
||||
uint32_t lastConnectedRaw; // timestamp of last time gps was connected
|
||||
UBXSentPacket_t working_packet; // outbound "buffer"
|
||||
ubx_autoconfig_settings_t currentSettings;
|
||||
int8_t lastConfigSent; // index of last configuration string sent
|
||||
@ -227,7 +228,7 @@ void config_save(uint16_t *bytes_to_send)
|
||||
{
|
||||
memset(status->working_packet.buffer, 0, sizeof(UBXSentHeader_t) + sizeof(ubx_cfg_cfg_t));
|
||||
// mask LSB=ioPort|msgConf|infMsg|navConf|rxmConf|||||rinvConf|antConf|....|= MSB
|
||||
status->working_packet.message.payload.cfg_cfg.saveMask = 0x01 | 0x08; // msgConf + navConf
|
||||
status->working_packet.message.payload.cfg_cfg.saveMask = 0x02 | 0x08; // msgConf + navConf
|
||||
status->working_packet.message.payload.cfg_cfg.deviceMask = UBX_CFG_CFG_ALL_DEVICES_MASK;
|
||||
*bytes_to_send = prepare_packet(&status->working_packet, UBX_CLASS_CFG, UBX_ID_CFG_CFG, sizeof(ubx_cfg_cfg_t));
|
||||
status->requiredAck.clsID = UBX_CLASS_CFG;
|
||||
@ -279,21 +280,50 @@ static void enable_sentences(__attribute__((unused)) uint16_t *bytes_to_send)
|
||||
}
|
||||
}
|
||||
|
||||
void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send)
|
||||
void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send, bool gps_connected)
|
||||
{
|
||||
*bytes_to_send = 0;
|
||||
*buffer = (char *)status->working_packet.buffer;
|
||||
if (!status || !enabled) {
|
||||
if (!status || !enabled || status->currentStep == INIT_STEP_DISABLED) {
|
||||
return; // autoconfig not enabled
|
||||
}
|
||||
if (PIOS_DELAY_DiffuS(status->lastStepTimestampRaw) < UBX_STEP_WAIT_TIME) {
|
||||
return;
|
||||
}
|
||||
// when gps is disconnected it will replay the autoconfig sequence.
|
||||
if (!gps_connected) {
|
||||
if (status->currentStep == INIT_STEP_DONE) {
|
||||
// if some operation is in progress and it is not running into issues it maybe that
|
||||
// the disconnection is only due to wrong message rates, so reinit only when done.
|
||||
// errors caused by disconnection are handled by error retry logic
|
||||
if (PIOS_DELAY_DiffuS(status->lastConnectedRaw) > UBX_CONNECTION_TIMEOUT) {
|
||||
status->currentStep = INIT_STEP_START;
|
||||
return;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
// reset connection timer
|
||||
status->lastConnectedRaw = PIOS_DELAY_GetRaw();
|
||||
}
|
||||
|
||||
switch (status->currentStep) {
|
||||
case INIT_STEP_ERROR: // TODO: what to do? retries after a while? maybe gps was disconnected (this can be detected)?
|
||||
case INIT_STEP_ERROR:
|
||||
if (PIOS_DELAY_DiffuS(status->lastStepTimestampRaw) > UBX_ERROR_RETRY_TIMEOUT) {
|
||||
status->currentStep = INIT_STEP_START;
|
||||
status->lastStepTimestampRaw = PIOS_DELAY_GetRaw();
|
||||
}
|
||||
return;
|
||||
|
||||
case INIT_STEP_DISABLED:
|
||||
case INIT_STEP_DONE:
|
||||
return;
|
||||
|
||||
case INIT_STEP_START:
|
||||
case INIT_STEP_ASK_VER:
|
||||
// clear ack
|
||||
ubxLastAck.clsID = 0x00;
|
||||
ubxLastAck.msgID = 0x00;
|
||||
|
||||
status->lastStepTimestampRaw = PIOS_DELAY_GetRaw();
|
||||
build_request(&status->working_packet, UBX_CLASS_MON, UBX_ID_MON_VER, bytes_to_send);
|
||||
status->currentStep = INIT_STEP_WAIT_VER;
|
||||
@ -348,6 +378,7 @@ void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send)
|
||||
status->retryCount++;
|
||||
if (status->retryCount > UBX_MAX_RETRIES) {
|
||||
status->currentStep = INIT_STEP_ERROR;
|
||||
status->lastStepTimestampRaw = PIOS_DELAY_GetRaw();
|
||||
return;
|
||||
}
|
||||
}
|
||||
@ -374,12 +405,16 @@ void ubx_autoconfig_set(ubx_autoconfig_settings_t config)
|
||||
status->currentSettings = config;
|
||||
status->currentStep = INIT_STEP_START;
|
||||
enabled = true;
|
||||
} else {
|
||||
if (!status) {
|
||||
status->currentStep = INIT_STEP_DISABLED;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int32_t ubx_autoconfig_get_status()
|
||||
{
|
||||
if (!status) {
|
||||
if (!status || !enabled) {
|
||||
return UBX_AUTOCONFIG_STATUS_DISABLED;
|
||||
}
|
||||
switch (status->currentStep) {
|
||||
|
33
flight/modules/Notify/inc/notify.h
Normal file
@ -0,0 +1,33 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file notify.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Notify module, show events and status on external led.
|
||||
*
|
||||
* @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 NOTIFY_H_
|
||||
#define NOTIFY_H_
|
||||
|
||||
|
||||
int32_t NotifyInitialize(void);
|
||||
|
||||
|
||||
#endif /* NOTIFY_H_ */
|
222
flight/modules/Notify/inc/sequences.h
Normal file
@ -0,0 +1,222 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file sequences.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Notify module, sequences configuration.
|
||||
*
|
||||
* @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 SEQUENCES_H_
|
||||
#define SEQUENCES_H_
|
||||
#include <optypes.h>
|
||||
#include <pios_notify.h>
|
||||
#include <flightstatus.h>
|
||||
#include <systemalarms.h>
|
||||
#include <pios_helpers.h>
|
||||
|
||||
// This represent the list of basic light sequences, defined later
|
||||
typedef enum {
|
||||
NOTIFY_SEQUENCE_ARMED_FM_MANUAL = 0,
|
||||
NOTIFY_SEQUENCE_ARMED_FM_STABILIZED1 = 1,
|
||||
NOTIFY_SEQUENCE_ARMED_FM_STABILIZED2 = 2,
|
||||
NOTIFY_SEQUENCE_ARMED_FM_STABILIZED3 = 3,
|
||||
NOTIFY_SEQUENCE_ARMED_FM_STABILIZED4 = 4,
|
||||
NOTIFY_SEQUENCE_ARMED_FM_STABILIZED5 = 5,
|
||||
NOTIFY_SEQUENCE_ARMED_FM_STABILIZED6 = 6,
|
||||
NOTIFY_SEQUENCE_ARMED_FM_AUTOTUNE = 7,
|
||||
NOTIFY_SEQUENCE_ARMED_FM_GPS = 8,
|
||||
NOTIFY_SEQUENCE_ARMED_FM_RTH = 9,
|
||||
NOTIFY_SEQUENCE_ARMED_FM_LAND = 10,
|
||||
NOTIFY_SEQUENCE_ARMED_FM_AUTO = 11,
|
||||
NOTIFY_SEQUENCE_ALM_WARN_GPS = 12,
|
||||
NOTIFY_SEQUENCE_ALM_ERROR_GPS = 13,
|
||||
NOTIFY_SEQUENCE_ALM_WARN_BATTERY = 14,
|
||||
NOTIFY_SEQUENCE_ALM_ERROR_BATTERY = 15,
|
||||
NOTIFY_SEQUENCE_ALM_MAG = 16,
|
||||
NOTIFY_SEQUENCE_ALM_CONFIG = 17,
|
||||
NOTIFY_SEQUENCE_ALM_RECEIVER = 18,
|
||||
NOTIFY_SEQUENCE_DISARMED = 19,
|
||||
NOTIFY_SEQUENCE_NULL = 255, // skips any signalling for this condition
|
||||
} NotifySequences;
|
||||
|
||||
// This structure determine sequences attached to an alarm
|
||||
typedef struct {
|
||||
uint32_t timeBetweenNotifications; // time in milliseconds to wait between each notification iteration
|
||||
uint8_t alarmIndex; // Index of the alarm, use one of the SYSTEMALARMS_ALARM_XXXXX defines
|
||||
uint8_t warnNotification; // index of the sequence to be used when alarm is in warning status(pick one from NotifySequences enum)
|
||||
uint8_t errorNotification; // index of the sequence to be used when alarm is in error status(pick one from NotifySequences enum)
|
||||
} AlarmDefinition_t;
|
||||
|
||||
|
||||
// This is the list of defined light sequences
|
||||
/* how each sequence is defined
|
||||
* [NOTIFY_SEQUENCE_DISARMED] = { // Sequence ID
|
||||
.repeats = -1, // Number of repetitions or -1 for infinite
|
||||
.steps = { // List of steps (until NOTIFY_SEQUENCE_MAX_STEPS steps, default to 5)
|
||||
{
|
||||
.time_off = 500, // Off time for the step
|
||||
.time_on = 500, // On time for the step
|
||||
.color = COLOR_TEAL, // color
|
||||
.repeats = 1, // repetitions for this step
|
||||
},
|
||||
},
|
||||
},
|
||||
*
|
||||
* There are two kind of sequences:
|
||||
* - "Background" sequences, executed if no higher priority sequence is played;
|
||||
* - "Alarm" sequences, that are "modal", they temporarily suspends background sequences and plays.
|
||||
* Cannot have "-1" repetitions
|
||||
* At the end background sequence are resumed;
|
||||
*
|
||||
*/
|
||||
const LedSequence_t notifications[] = {
|
||||
[NOTIFY_SEQUENCE_DISARMED] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 500, .time_on = 500, .color = COLOR_TEAL, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ARMED_FM_MANUAL] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 900, .time_on = 100, .color = COLOR_YELLOW, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED1] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 900, .time_on = 100, .color = COLOR_BLUE, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED2] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 100, .time_on = 100, .color = COLOR_BLUE, .repeats = 1, },
|
||||
{ .time_off = 700, .time_on = 100, .color = COLOR_BLUE, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED3] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 100, .time_on = 100, .color = COLOR_BLUE, .repeats = 2, },
|
||||
{ .time_off = 500, .time_on = 100, .color = COLOR_BLUE, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED4] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 900, .time_on = 100, .color = COLOR_PURPLE, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED5] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 100, .time_on = 100, .color = COLOR_PURPLE, .repeats = 1, },
|
||||
{ .time_off = 700, .time_on = 100, .color = COLOR_BLUE, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED6] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 100, .time_on = 100, .color = COLOR_PURPLE, .repeats = 1, },
|
||||
{ .time_off = 100, .time_on = 100, .color = COLOR_PURPLE, .repeats = 1, },
|
||||
{ .time_off = 500, .time_on = 100, .color = COLOR_BLUE, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ARMED_FM_AUTOTUNE] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 800, .time_on = 200, .color = COLOR_BLUE, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ARMED_FM_GPS] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 800, .time_on = 200, .color = COLOR_GREEN, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ARMED_FM_RTH] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 100, .time_on = 100, .color = COLOR_GREEN, .repeats = 1, },
|
||||
{ .time_off = 100, .time_on = 100, .color = COLOR_YELLOW, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ARMED_FM_LAND] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 100, .time_on = 100, .color = COLOR_GREEN, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ARMED_FM_AUTO] = { .repeats = -1, .steps = {
|
||||
{ .time_off = 100, .time_on = 200, .color = COLOR_GREEN, .repeats = 2, },
|
||||
{ .time_off = 500, .time_on = 200, .color = COLOR_GREEN, .repeats = 1, },
|
||||
}, },
|
||||
|
||||
[NOTIFY_SEQUENCE_ALM_WARN_GPS] = { .repeats = 2, .steps = {
|
||||
{ .time_off = 300, .time_on = 300, .color = COLOR_ORANGE, .repeats = 2, },
|
||||
{ .time_off = 300, .time_on = 300, .color = COLOR_GREEN, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ALM_ERROR_GPS] = { .repeats = 2, .steps = {
|
||||
{ .time_off = 300, .time_on = 300, .color = COLOR_RED, .repeats = 2, },
|
||||
{ .time_off = 300, .time_on = 300, .color = COLOR_GREEN, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ALM_WARN_BATTERY] = { .repeats = 1, .steps = {
|
||||
{ .time_off = 100, .time_on = 100, .color = COLOR_ORANGE, .repeats = 10, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ALM_ERROR_BATTERY] = { .repeats = 1, .steps = {
|
||||
{ .time_off = 100, .time_on = 100, .color = COLOR_RED, .repeats = 10, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ALM_MAG] = { .repeats = 1, .steps = {
|
||||
{ .time_off = 300, .time_on = 300, .color = COLOR_RED, .repeats = 2, },
|
||||
{ .time_off = 300, .time_on = 300, .color = COLOR_PURPLE, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ALM_CONFIG] = { .repeats = 1, .steps = {
|
||||
{ .time_off = 50, .time_on = 50, .color = COLOR_RED, .repeats = 9, },
|
||||
{ .time_off = 500, .time_on = 50, .color = COLOR_RED, .repeats = 1, },
|
||||
}, },
|
||||
[NOTIFY_SEQUENCE_ALM_RECEIVER] = { .repeats = 1, .steps = {
|
||||
{ .time_off = 50, .time_on = 50, .color = COLOR_ORANGE, .repeats = 9, },
|
||||
{ .time_off = 500, .time_on = 50, .color = COLOR_ORANGE, .repeats = 1, },
|
||||
}, },
|
||||
};
|
||||
|
||||
// List of background sequences attached to each flight mode
|
||||
const LedSequence_t *flightModeMap[] = {
|
||||
[FLIGHTSTATUS_FLIGHTMODE_MANUAL] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_MANUAL],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_STABILIZED1] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED1],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_STABILIZED2] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED2],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_STABILIZED3] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED3],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_STABILIZED4] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED4],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_STABILIZED5] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED5],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_STABILIZED6] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED6],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_AUTO],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_AUTOTUNE],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIOFPV] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIOLOS] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIONSEW] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_RTH],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_LAND] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_LAND],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_POI] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS],
|
||||
[FLIGHTSTATUS_FLIGHTMODE_AUTOCRUISE] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS],
|
||||
};
|
||||
|
||||
// List of alarms to show with attached sequences for each status
|
||||
const AlarmDefinition_t alarmsMap[] = {
|
||||
{
|
||||
.timeBetweenNotifications = 10000,
|
||||
.alarmIndex = SYSTEMALARMS_ALARM_GPS,
|
||||
.warnNotification = NOTIFY_SEQUENCE_ALM_WARN_GPS,
|
||||
.errorNotification = NOTIFY_SEQUENCE_ALM_ERROR_GPS,
|
||||
},
|
||||
{
|
||||
.timeBetweenNotifications = 15000,
|
||||
.alarmIndex = SYSTEMALARMS_ALARM_MAGNETOMETER,
|
||||
.warnNotification = NOTIFY_SEQUENCE_NULL,
|
||||
.errorNotification = NOTIFY_SEQUENCE_ALM_MAG,
|
||||
},
|
||||
{
|
||||
.timeBetweenNotifications = 15000,
|
||||
.alarmIndex = SYSTEMALARMS_ALARM_BATTERY,
|
||||
.warnNotification = NOTIFY_SEQUENCE_ALM_WARN_BATTERY,
|
||||
.errorNotification = NOTIFY_SEQUENCE_ALM_ERROR_BATTERY,
|
||||
},
|
||||
{
|
||||
.timeBetweenNotifications = 5000,
|
||||
.alarmIndex = SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION,
|
||||
.warnNotification = NOTIFY_SEQUENCE_NULL,
|
||||
.errorNotification = NOTIFY_SEQUENCE_ALM_CONFIG,
|
||||
},
|
||||
{
|
||||
.timeBetweenNotifications = 5000,
|
||||
.alarmIndex = SYSTEMALARMS_ALARM_RECEIVER,
|
||||
.warnNotification = NOTIFY_SEQUENCE_ALM_RECEIVER,
|
||||
.errorNotification = NOTIFY_SEQUENCE_ALM_RECEIVER,
|
||||
},
|
||||
};
|
||||
|
||||
const uint8_t alarmsMapSize = NELEMENTS(alarmsMap);
|
||||
|
||||
#endif /* SEQUENCES_H_ */
|
136
flight/modules/Notify/notify.c
Normal file
@ -0,0 +1,136 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file notify.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Notify module, show events and status on external led.
|
||||
*
|
||||
* @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 "openpilot.h"
|
||||
#include <flightstatus.h>
|
||||
#include <systemalarms.h>
|
||||
#include <flightbatterystate.h>
|
||||
#include <lednotification.h>
|
||||
#include <optypes.h>
|
||||
#include <pios_notify.h>
|
||||
#include <FreeRTOS.h>
|
||||
#include <task.h>
|
||||
#include <eventdispatcher.h>
|
||||
#include "inc/notify.h"
|
||||
#include "inc/sequences.h"
|
||||
#include <pios_mem.h>
|
||||
#include <hwsettings.h>
|
||||
|
||||
#define SAMPLE_PERIOD_MS 250
|
||||
// private types
|
||||
typedef struct {
|
||||
uint32_t lastAlarmTime;
|
||||
uint8_t lastAlarm;
|
||||
} AlarmStatus_t;
|
||||
// function declarations
|
||||
static void updatedCb(UAVObjEvent *ev);
|
||||
static void onTimerCb(UAVObjEvent *ev);
|
||||
static void checkAlarm(uint8_t alarm, uint8_t *last_alarm, uint32_t *last_alm_time,
|
||||
uint8_t warn_sequence, uint8_t error_sequence,
|
||||
uint32_t timeBetweenNotifications);
|
||||
static AlarmStatus_t *alarmStatus;
|
||||
int32_t NotifyInitialize(void)
|
||||
{
|
||||
uint8_t ws281xOutStatus;
|
||||
|
||||
HwSettingsWS2811LED_OutGet(&ws281xOutStatus);
|
||||
// Todo: Until further applications exists for WS2811 notify enabled status is tied to ws281x output configuration
|
||||
bool enabled = ws281xOutStatus != HWSETTINGS_WS2811LED_OUT_DISABLED;
|
||||
|
||||
if (enabled) {
|
||||
alarmStatus = (AlarmStatus_t *)pios_malloc(sizeof(AlarmStatus_t) * alarmsMapSize);
|
||||
for (uint8_t i = 0; i < alarmsMapSize; i++) {
|
||||
alarmStatus[i].lastAlarm = SYSTEMALARMS_ALARM_OK;
|
||||
alarmStatus[i].lastAlarmTime = 0;
|
||||
}
|
||||
|
||||
FlightStatusConnectCallback(&updatedCb);
|
||||
static UAVObjEvent ev;
|
||||
memset(&ev, 0, sizeof(UAVObjEvent));
|
||||
EventPeriodicCallbackCreate(&ev, onTimerCb, SAMPLE_PERIOD_MS / portTICK_RATE_MS);
|
||||
|
||||
updatedCb(0);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(NotifyInitialize, 0);
|
||||
|
||||
|
||||
void updatedCb(UAVObjEvent *ev)
|
||||
{
|
||||
if (!ev || ev->obj == FlightStatusHandle()) {
|
||||
static uint8_t last_armed = 0xff;
|
||||
static uint8_t last_flightmode = 0xff;
|
||||
uint8_t armed;
|
||||
uint8_t flightmode;
|
||||
FlightStatusArmedGet(&armed);
|
||||
FlightStatusFlightModeGet(&flightmode);
|
||||
if (last_armed != armed || (armed && flightmode != last_flightmode)) {
|
||||
if (armed) {
|
||||
PIOS_NOTIFICATION_Default_Ext_Led_Play(flightModeMap[flightmode], NOTIFY_PRIORITY_BACKGROUND);
|
||||
} else {
|
||||
PIOS_NOTIFICATION_Default_Ext_Led_Play(¬ifications[NOTIFY_SEQUENCE_DISARMED], NOTIFY_PRIORITY_BACKGROUND);
|
||||
}
|
||||
}
|
||||
last_armed = armed;
|
||||
last_flightmode = flightmode;
|
||||
}
|
||||
}
|
||||
|
||||
void onTimerCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
static SystemAlarmsAlarmData alarms;
|
||||
|
||||
SystemAlarmsAlarmGet(&alarms);
|
||||
for (uint8_t i = 0; i < alarmsMapSize; i++) {
|
||||
uint8_t alarm = ((uint8_t *)&alarms)[alarmsMap[i].alarmIndex];
|
||||
checkAlarm(alarm,
|
||||
&alarmStatus[i].lastAlarm,
|
||||
&alarmStatus[i].lastAlarmTime,
|
||||
alarmsMap[i].warnNotification,
|
||||
alarmsMap[i].errorNotification,
|
||||
alarmsMap[i].timeBetweenNotifications);
|
||||
}
|
||||
}
|
||||
|
||||
void checkAlarm(uint8_t alarm, uint8_t *last_alarm, uint32_t *last_alm_time, uint8_t warn_sequence, uint8_t error_sequence, uint32_t timeBetweenNotifications)
|
||||
{
|
||||
if (alarm > SYSTEMALARMS_ALARM_OK) {
|
||||
uint32_t current_time = PIOS_DELAY_GetuS();
|
||||
if (*last_alarm < alarm || *last_alm_time + timeBetweenNotifications * 1000 < current_time) {
|
||||
uint8_t sequence = (alarm == SYSTEMALARMS_ALARM_WARNING) ? warn_sequence : error_sequence;
|
||||
if (sequence != NOTIFY_SEQUENCE_NULL) {
|
||||
PIOS_NOTIFICATION_Default_Ext_Led_Play(
|
||||
¬ifications[sequence],
|
||||
alarm == SYSTEMALARMS_ALARM_WARNING ? NOTIFY_PRIORITY_REGULAR : NOTIFY_PRIORITY_CRITICAL);
|
||||
}
|
||||
*last_alarm = alarm;
|
||||
*last_alm_time = current_time;
|
||||
}
|
||||
} else {
|
||||
*last_alarm = SYSTEMALARMS_ALARM_OK;
|
||||
}
|
||||
}
|
@ -41,7 +41,11 @@
|
||||
#include <openpilot.h>
|
||||
// private includes
|
||||
#include "inc/systemmod.h"
|
||||
#include "notification.h"
|
||||
|
||||
#include <notification.h>
|
||||
#ifdef PIOS_INCLUDE_WS2811
|
||||
#include <lednotification.h>
|
||||
#endif
|
||||
|
||||
// UAVOs
|
||||
#include <objectpersistence.h>
|
||||
@ -54,6 +58,7 @@
|
||||
#include <callbackinfo.h>
|
||||
#include <hwsettings.h>
|
||||
#include <pios_flashfs.h>
|
||||
#include <pios_notify.h>
|
||||
|
||||
#ifdef PIOS_INCLUDE_INSTRUMENTATION
|
||||
#include <instrumentation.h>
|
||||
@ -632,6 +637,9 @@ static void updateSystemAlarms()
|
||||
void vApplicationIdleHook(void)
|
||||
{
|
||||
NotificationOnboardLedsRun();
|
||||
#ifdef PIOS_INCLUDE_WS2811
|
||||
LedNotificationExtLedsRun();
|
||||
#endif
|
||||
}
|
||||
/**
|
||||
* Called by the RTOS when a stack overflow is detected.
|
||||
|
@ -28,7 +28,8 @@
|
||||
|
||||
static volatile pios_notify_notification currentNotification = NOTIFY_NONE;
|
||||
static volatile pios_notify_priority currentPriority;
|
||||
|
||||
static volatile ExtLedNotification_t extLedNotification;
|
||||
static volatile bool newNotification;
|
||||
|
||||
void PIOS_NOTIFY_StartNotification(pios_notify_notification notification, pios_notify_priority priority)
|
||||
{
|
||||
@ -47,3 +48,36 @@ pios_notify_notification PIOS_NOTIFY_GetActiveNotification(bool clear)
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Play a sequence on the default external led. Sequences with priority higher than NOTIFY_PRIORITY_LOW
|
||||
* are repeated only once if repeat = -1
|
||||
* @param sequence Sequence to be played
|
||||
* @param priority Priority of the sequence being played
|
||||
*/
|
||||
void PIOS_NOTIFICATION_Default_Ext_Led_Play(const LedSequence_t *sequence, pios_notify_priority priority)
|
||||
{
|
||||
// alert and alarms are repeated if condition persists. bacground notification instead are set once, so try to prevent loosing any update
|
||||
if (newNotification && priority != NOTIFY_PRIORITY_BACKGROUND) {
|
||||
// prevent overwriting higher priority or background notifications
|
||||
if (extLedNotification.priority == NOTIFY_PRIORITY_BACKGROUND || extLedNotification.priority > priority) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
extLedNotification.priority = priority;
|
||||
extLedNotification.sequence = *sequence;
|
||||
newNotification = true;
|
||||
}
|
||||
|
||||
|
||||
ExtLedNotification_t *PIOS_NOTIFY_GetNewExtLedSequence(bool clear)
|
||||
{
|
||||
if (!newNotification) {
|
||||
return 0;
|
||||
}
|
||||
if (clear) {
|
||||
newNotification = false;
|
||||
}
|
||||
return (ExtLedNotification_t *)&extLedNotification;
|
||||
}
|
||||
|
@ -26,7 +26,7 @@
|
||||
#ifndef PIOS_NOTIFY_H_
|
||||
#define PIOS_NOTIFY_H_
|
||||
#include <stdbool.h>
|
||||
|
||||
#include <optypes.h>
|
||||
typedef enum {
|
||||
NOTIFY_NONE = 0,
|
||||
NOTIFY_OK,
|
||||
@ -35,11 +35,35 @@ typedef enum {
|
||||
} pios_notify_notification;
|
||||
|
||||
typedef enum {
|
||||
NOTIFY_PRIORITY_CRITICAL = 2,
|
||||
NOTIFY_PRIORITY_REGULAR = 1,
|
||||
NOTIFY_PRIORITY_CRITICAL = 2,
|
||||
NOTIFY_PRIORITY_REGULAR = 1,
|
||||
NOTIFY_PRIORITY_LOW = 0,
|
||||
NOTIFY_PRIORITY_BACKGROUND = -1,
|
||||
} pios_notify_priority;
|
||||
|
||||
|
||||
// A single led step, Color, time On/Off, repeat count
|
||||
#define NOTIFY_SEQUENCE_MAX_STEPS 5
|
||||
|
||||
typedef struct {
|
||||
uint16_t time_off;
|
||||
uint16_t time_on;
|
||||
Color_t color;
|
||||
uint8_t repeats;
|
||||
} LedStep_t;
|
||||
|
||||
typedef struct {
|
||||
int8_t repeats; // -1 for infinite repetitions
|
||||
LedStep_t steps[NOTIFY_SEQUENCE_MAX_STEPS];
|
||||
} LedSequence_t;
|
||||
|
||||
typedef struct {
|
||||
LedSequence_t sequence;
|
||||
pios_notify_priority priority;
|
||||
} ExtLedNotification_t;
|
||||
|
||||
#define NOTIFY_IS_NULL_STEP(x) (!x || (!x->time_off && !x->time_on && !x->repeats))
|
||||
|
||||
/**
|
||||
* start a new notification. If a notification is active it will be overwritten if its priority is lower than the new one.
|
||||
* The new will be discarded otherwise
|
||||
@ -55,4 +79,24 @@ void PIOS_NOTIFY_StartNotification(pios_notify_notification notification, pios_n
|
||||
*/
|
||||
pios_notify_notification PIOS_NOTIFY_GetActiveNotification(bool clear);
|
||||
|
||||
/*
|
||||
* Play a sequence on the default external led. Sequences with priority higher than NOTIFY_PRIORITY_LOW
|
||||
* are repeated only once if repeat = -1
|
||||
* @param sequence Sequence to be played
|
||||
* @param priority Priority of the sequence being played
|
||||
*/
|
||||
void PIOS_NOTIFICATION_Default_Ext_Led_Play(const LedSequence_t *sequence, pios_notify_priority priority);
|
||||
|
||||
/*
|
||||
* Play a sequence on an external rgb led. Sequences with priority higher than NOTIFY_PRIORITY_LOW
|
||||
* are repeated only once if repeat = -1
|
||||
* @param sequence Sequence to be played
|
||||
* @param ledNumber Led number
|
||||
* @param priority Priority of the sequence being played
|
||||
*
|
||||
*/
|
||||
// void PIOS_NOTIFICATION_Ext_Led_Play(const LedSequence_t sequence, uint8_t ledNumber, pios_notify_priority priority);
|
||||
|
||||
ExtLedNotification_t *PIOS_NOTIFY_GetNewExtLedSequence(bool clear);
|
||||
|
||||
#endif /* PIOS_NOTIFY_H_ */
|
||||
|
@ -29,119 +29,11 @@
|
||||
#define PIOS_WS2811_H_
|
||||
|
||||
#include <stdint.h>
|
||||
#include <pios_gpio.h>
|
||||
#include <pios_stm32.h>
|
||||
#include <pios_gpio_priv.h>
|
||||
#include <stm32f4xx.h>
|
||||
#include <stm32f4xx_tim.h>
|
||||
#include <stm32f4xx_dma.h>
|
||||
#include <optypes.h>
|
||||
|
||||
#define PIOS_WS2811_NUMLEDS 2
|
||||
|
||||
#define sign(x) ((x > 0) - (x < 0))
|
||||
#define PIOS_WS2811_NUMLEDS 2
|
||||
#define PIOS_WS2811_BUFFER_SIZE (((PIOS_WS2811_NUMLEDS) * 24))
|
||||
#define PIOS_WS2811_MEMORYDATASIZE DMA_MemoryDataSize_HalfWord
|
||||
#define PIOS_WS2811_PERIPHERALDATASIZE DMA_PeripheralDataSize_HalfWord
|
||||
#define PIOS_WS2811_TIM_PERIOD 20
|
||||
|
||||
// Following times are keept on the lower side to accounts
|
||||
// for bus contentions and irq response time
|
||||
#define PIOS_WS2811_T0_HIGH_PERIOD 25 // .35us +/- 150nS
|
||||
#define PIOS_WS2811_T1_HIGH_PERIOD 60 // .70us +/- 150nS
|
||||
|
||||
#define PIOS_WS2811_DMA_CH1_CONFIG(channel) \
|
||||
{ \
|
||||
.DMA_BufferSize = PIOS_WS2811_BUFFER_SIZE, \
|
||||
.DMA_Channel = channel, \
|
||||
.DMA_DIR = DMA_DIR_MemoryToPeripheral, \
|
||||
.DMA_FIFOMode = DMA_FIFOMode_Enable, \
|
||||
.DMA_FIFOThreshold = DMA_FIFOThreshold_HalfFull, \
|
||||
.DMA_Memory0BaseAddr = 0, \
|
||||
.DMA_MemoryBurst = DMA_MemoryBurst_INC4, \
|
||||
.DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable, \
|
||||
.DMA_Mode = DMA_Mode_Circular, \
|
||||
.DMA_PeripheralBaseAddr = 0, \
|
||||
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \
|
||||
.DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable, \
|
||||
.DMA_Priority = DMA_Priority_VeryHigh, }
|
||||
|
||||
#define PIOS_WS2811_DMA_CH2_CONFIG(channel) \
|
||||
{ \
|
||||
.DMA_BufferSize = 4, \
|
||||
.DMA_Channel = channel, \
|
||||
.DMA_DIR = DMA_DIR_MemoryToPeripheral, \
|
||||
.DMA_FIFOMode = DMA_FIFOMode_Enable, \
|
||||
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full, \
|
||||
.DMA_Memory0BaseAddr = 0, \
|
||||
.DMA_MemoryBurst = DMA_MemoryBurst_INC4, \
|
||||
.DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable, \
|
||||
.DMA_Mode = DMA_Mode_Circular, \
|
||||
.DMA_PeripheralBaseAddr = 0, \
|
||||
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \
|
||||
.DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable, \
|
||||
.DMA_Priority = DMA_Priority_VeryHigh, }
|
||||
|
||||
#define PIOS_WS2811_DMA_UPDATE_CONFIG(channel) \
|
||||
{ \
|
||||
.DMA_BufferSize = 4, \
|
||||
.DMA_Channel = channel, \
|
||||
.DMA_DIR = DMA_DIR_MemoryToPeripheral, \
|
||||
.DMA_FIFOMode = DMA_FIFOMode_Enable, \
|
||||
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full, \
|
||||
.DMA_Memory0BaseAddr = 0, \
|
||||
.DMA_MemoryBurst = DMA_MemoryBurst_INC4, \
|
||||
.DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable, \
|
||||
.DMA_Mode = DMA_Mode_Circular, \
|
||||
.DMA_PeripheralBaseAddr = 0, \
|
||||
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \
|
||||
.DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable, \
|
||||
.DMA_Priority = DMA_Priority_High }
|
||||
|
||||
|
||||
typedef uint16_t ledbuf_t;
|
||||
|
||||
typedef struct Color Color;
|
||||
struct Color {
|
||||
uint8_t R;
|
||||
uint8_t G;
|
||||
uint8_t B;
|
||||
};
|
||||
struct pios_ws2811_pin_cfg {
|
||||
GPIO_TypeDef *gpio;
|
||||
GPIO_InitTypeDef gpioInit;
|
||||
};
|
||||
struct pios_ws2811_cfg {
|
||||
TIM_TimeBaseInitTypeDef timerInit;
|
||||
TIM_TypeDef *timer;
|
||||
uint8_t timerCh1;
|
||||
uint8_t timerCh2;
|
||||
|
||||
DMA_InitTypeDef dmaInitCh1;
|
||||
DMA_Stream_TypeDef *streamCh1;
|
||||
uint32_t dmaItCh1;
|
||||
|
||||
DMA_InitTypeDef dmaInitCh2;
|
||||
DMA_Stream_TypeDef *streamCh2;
|
||||
uint32_t dmaItCh2;
|
||||
|
||||
DMA_InitTypeDef dmaInitUpdate;
|
||||
DMA_Stream_TypeDef *streamUpdate;
|
||||
uint32_t dmaItUpdate;
|
||||
uint16_t dmaSource;
|
||||
struct stm32_irq irq;
|
||||
};
|
||||
|
||||
void PIOS_WS2811_Init(const struct pios_ws2811_cfg *ws2811_cfg, const struct pios_ws2811_pin_cfg *ws2811_pin_cfg);
|
||||
|
||||
void PIOS_WS2811_setColorRGB(Color c, uint8_t led, bool update);
|
||||
void PIOS_WS2811_setColorRGB(Color_t c, uint8_t led, bool update);
|
||||
void PIOS_WS2811_Update();
|
||||
|
||||
void PIOS_WS2811_DMA_irq_handler();
|
||||
|
||||
#endif /* PIOS_WS2811_H_ */
|
||||
|
136
flight/pios/inc/pios_ws2811_cfg.h
Normal file
@ -0,0 +1,136 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_ws2811_cfg.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @brief A driver for ws2811 rgb led controller.
|
||||
* this is a plain PiOS port of the very clever solution
|
||||
* implemented by Omri Iluz in the chibios driver here:
|
||||
* https://github.com/omriiluz/WS2812B-LED-Driver-ChibiOS
|
||||
* @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_WS2811_CFG_H_
|
||||
#define PIOS_WS2811_CFG_H_
|
||||
|
||||
#include <stdint.h>
|
||||
#include <pios_gpio.h>
|
||||
#include <pios_stm32.h>
|
||||
#include <pios_gpio_priv.h>
|
||||
#include <stm32f4xx.h>
|
||||
#include <stm32f4xx_tim.h>
|
||||
#include <stm32f4xx_dma.h>
|
||||
#include <optypes.h>
|
||||
#include <pios_ws2811.h>
|
||||
|
||||
#define PIOS_WS2811_BUFFER_SIZE (((PIOS_WS2811_NUMLEDS) * 24))
|
||||
#define PIOS_WS2811_MEMORYDATASIZE DMA_MemoryDataSize_HalfWord
|
||||
#define PIOS_WS2811_PERIPHERALDATASIZE DMA_PeripheralDataSize_HalfWord
|
||||
#define PIOS_WS2811_TIM_PERIOD 20
|
||||
|
||||
// Following times are keept on the lower side to accounts
|
||||
// for bus contentions and irq response time
|
||||
#define PIOS_WS2811_T0_HIGH_PERIOD 32 // .35us +/- 150nS
|
||||
#define PIOS_WS2811_T1_HIGH_PERIOD 70 // .70us +/- 150nS
|
||||
|
||||
#define PIOS_WS2811_DMA_CH1_CONFIG(channel) \
|
||||
{ \
|
||||
.DMA_BufferSize = PIOS_WS2811_BUFFER_SIZE, \
|
||||
.DMA_Channel = channel, \
|
||||
.DMA_DIR = DMA_DIR_MemoryToPeripheral, \
|
||||
.DMA_FIFOMode = DMA_FIFOMode_Enable, \
|
||||
.DMA_FIFOThreshold = DMA_FIFOThreshold_HalfFull, \
|
||||
.DMA_Memory0BaseAddr = 0, \
|
||||
.DMA_MemoryBurst = DMA_MemoryBurst_INC4, \
|
||||
.DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable, \
|
||||
.DMA_Mode = DMA_Mode_Circular, \
|
||||
.DMA_PeripheralBaseAddr = 0, \
|
||||
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \
|
||||
.DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable, \
|
||||
.DMA_Priority = DMA_Priority_VeryHigh, }
|
||||
|
||||
#define PIOS_WS2811_DMA_CH2_CONFIG(channel) \
|
||||
{ \
|
||||
.DMA_BufferSize = 4, \
|
||||
.DMA_Channel = channel, \
|
||||
.DMA_DIR = DMA_DIR_MemoryToPeripheral, \
|
||||
.DMA_FIFOMode = DMA_FIFOMode_Enable, \
|
||||
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full, \
|
||||
.DMA_Memory0BaseAddr = 0, \
|
||||
.DMA_MemoryBurst = DMA_MemoryBurst_INC4, \
|
||||
.DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable, \
|
||||
.DMA_Mode = DMA_Mode_Circular, \
|
||||
.DMA_PeripheralBaseAddr = 0, \
|
||||
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \
|
||||
.DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable, \
|
||||
.DMA_Priority = DMA_Priority_VeryHigh, }
|
||||
|
||||
#define PIOS_WS2811_DMA_UPDATE_CONFIG(channel) \
|
||||
{ \
|
||||
.DMA_BufferSize = 4, \
|
||||
.DMA_Channel = channel, \
|
||||
.DMA_DIR = DMA_DIR_MemoryToPeripheral, \
|
||||
.DMA_FIFOMode = DMA_FIFOMode_Enable, \
|
||||
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full, \
|
||||
.DMA_Memory0BaseAddr = 0, \
|
||||
.DMA_MemoryBurst = DMA_MemoryBurst_INC4, \
|
||||
.DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable, \
|
||||
.DMA_Mode = DMA_Mode_Circular, \
|
||||
.DMA_PeripheralBaseAddr = 0, \
|
||||
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \
|
||||
.DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable, \
|
||||
.DMA_Priority = DMA_Priority_High }
|
||||
|
||||
|
||||
typedef uint16_t ledbuf_t;
|
||||
|
||||
struct pios_ws2811_pin_cfg {
|
||||
GPIO_TypeDef *gpio;
|
||||
GPIO_InitTypeDef gpioInit;
|
||||
};
|
||||
struct pios_ws2811_cfg {
|
||||
TIM_TimeBaseInitTypeDef timerInit;
|
||||
TIM_TypeDef *timer;
|
||||
uint8_t timerCh1;
|
||||
uint8_t timerCh2;
|
||||
|
||||
DMA_InitTypeDef dmaInitCh1;
|
||||
DMA_Stream_TypeDef *streamCh1;
|
||||
uint32_t dmaItCh1;
|
||||
|
||||
DMA_InitTypeDef dmaInitCh2;
|
||||
DMA_Stream_TypeDef *streamCh2;
|
||||
uint32_t dmaItCh2;
|
||||
|
||||
DMA_InitTypeDef dmaInitUpdate;
|
||||
DMA_Stream_TypeDef *streamUpdate;
|
||||
uint32_t dmaItUpdate;
|
||||
uint16_t dmaSource;
|
||||
struct stm32_irq irq;
|
||||
};
|
||||
|
||||
void PIOS_WS2811_Init(const struct pios_ws2811_cfg *ws2811_cfg, const struct pios_ws2811_pin_cfg *ws2811_pin_cfg);
|
||||
|
||||
void PIOS_WS2811_DMA_irq_handler();
|
||||
#endif /* PIOS_WS2811_H_ */
|
@ -29,7 +29,7 @@
|
||||
|
||||
#ifdef PIOS_INCLUDE_WS2811
|
||||
|
||||
#include "pios_ws2811.h"
|
||||
#include "pios_ws2811_cfg.h"
|
||||
#include <stm32f4xx_rcc.h>
|
||||
#include <pios_stm32.h>
|
||||
#include "FreeRTOS.h"
|
||||
@ -177,7 +177,7 @@ void PIOS_WS2811_Init(const struct pios_ws2811_cfg *ws2811_cfg, const struct pio
|
||||
|
||||
fb = (ledbuf_t *)pios_malloc(PIOS_WS2811_BUFFER_SIZE * sizeof(ledbuf_t));
|
||||
memset(fb, 0, PIOS_WS2811_BUFFER_SIZE * sizeof(ledbuf_t));
|
||||
Color ledoff = { 0, 0, 0 };
|
||||
const Color_t ledoff = Color_Off;
|
||||
for (uint8_t i = 0; i < PIOS_WS2811_NUMLEDS; i++) {
|
||||
PIOS_WS2811_setColorRGB(ledoff, i, false);
|
||||
}
|
||||
@ -302,7 +302,7 @@ void setColor(uint8_t color, ledbuf_t *buf)
|
||||
* @param led led number
|
||||
* @param update Perform an update after changing led color
|
||||
*/
|
||||
void PIOS_WS2811_setColorRGB(Color c, uint8_t led, bool update)
|
||||
void PIOS_WS2811_setColorRGB(Color_t c, uint8_t led, bool update)
|
||||
{
|
||||
if (led >= PIOS_WS2811_NUMLEDS) {
|
||||
return;
|
||||
@ -310,6 +310,7 @@ void PIOS_WS2811_setColorRGB(Color c, uint8_t led, bool update)
|
||||
setColor(c.G, fb + (led * 24));
|
||||
setColor(c.R, fb + 8 + (led * 24));
|
||||
setColor(c.B, fb + 16 + (led * 24));
|
||||
|
||||
if (update) {
|
||||
PIOS_WS2811_Update();
|
||||
}
|
||||
@ -327,6 +328,10 @@ void PIOS_WS2811_Update()
|
||||
|
||||
// reset counters for synchronization
|
||||
pios_ws2811_cfg->timer->CNT = PIOS_WS2811_TIM_PERIOD - 1;
|
||||
|
||||
DMA_Cmd(pios_ws2811_cfg->streamCh2, ENABLE);
|
||||
DMA_Cmd(pios_ws2811_cfg->streamCh1, ENABLE);
|
||||
DMA_Cmd(pios_ws2811_cfg->streamUpdate, ENABLE);
|
||||
// Start a new cycle
|
||||
TIM_Cmd(pios_ws2811_cfg->timer, ENABLE);
|
||||
}
|
||||
@ -337,8 +342,12 @@ void PIOS_WS2811_Update()
|
||||
|
||||
void PIOS_WS2811_DMA_irq_handler()
|
||||
{
|
||||
pios_ws2811_pin_cfg->gpio->BSRRH = dmaSource[0];
|
||||
pios_ws2811_cfg->timer->CR1 &= (uint16_t) ~TIM_CR1_CEN;
|
||||
DMA_ClearFlag(pios_ws2811_cfg->streamCh1, pios_ws2811_cfg->irq.flags);
|
||||
DMA_Cmd(pios_ws2811_cfg->streamCh2, DISABLE);
|
||||
DMA_Cmd(pios_ws2811_cfg->streamCh1, DISABLE);
|
||||
DMA_Cmd(pios_ws2811_cfg->streamUpdate, DISABLE);
|
||||
}
|
||||
|
||||
#endif // PIOS_INCLUDE_WS2811
|
||||
|
@ -1811,7 +1811,7 @@ const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */
|
||||
#ifdef PIOS_INCLUDE_WS2811
|
||||
#include <pios_ws2811.h>
|
||||
#include <pios_ws2811_cfg.h>
|
||||
#define PIOS_WS2811_TIM_DIVIDER (PIOS_PERIPHERAL_APB2_CLOCK / (800000 * PIOS_WS2811_TIM_PERIOD))
|
||||
|
||||
void DMA2_Stream1_IRQHandler(void) __attribute__((alias("PIOS_WS2811_irq_handler")));
|
||||
|
@ -35,6 +35,7 @@ USE_DSP_LIB ?= NO
|
||||
#MODULES += Airspeed
|
||||
#MODULES += AltitudeHold
|
||||
MODULES += Stabilization
|
||||
MODULES += Notify
|
||||
MODULES += ManualControl
|
||||
MODULES += Receiver
|
||||
MODULES += Actuator
|
||||
@ -88,6 +89,7 @@ ifndef TESTAPP
|
||||
SRC += $(FLIGHTLIB)/WorldMagModel.c
|
||||
SRC += $(FLIGHTLIB)/insgps13state.c
|
||||
SRC += $(FLIGHTLIB)/auxmagsupport.c
|
||||
SRC += $(FLIGHTLIB)/lednotification.c
|
||||
|
||||
## UAVObjects
|
||||
include ./UAVObjects.inc
|
||||
|
@ -1964,7 +1964,7 @@ const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */
|
||||
|
||||
#ifdef PIOS_INCLUDE_WS2811
|
||||
#include <pios_ws2811.h>
|
||||
#include <pios_ws2811_cfg.h>
|
||||
#include <hwsettings.h>
|
||||
#define PIOS_WS2811_TIM_DIVIDER (PIOS_PERIPHERAL_APB2_CLOCK / (800000 * PIOS_WS2811_TIM_PERIOD))
|
||||
|
||||
|
@ -49,6 +49,7 @@ MODULES += PathFollower
|
||||
MODULES += Osd/osdoutout
|
||||
MODULES += Logging
|
||||
MODULES += Telemetry
|
||||
MODULES += Notify
|
||||
|
||||
OPTMODULES += ComUsbBridge
|
||||
|
||||
@ -88,6 +89,7 @@ ifndef TESTAPP
|
||||
SRC += $(FLIGHTLIB)/WorldMagModel.c
|
||||
SRC += $(FLIGHTLIB)/insgps13state.c
|
||||
SRC += $(FLIGHTLIB)/auxmagsupport.c
|
||||
SRC += $(FLIGHTLIB)/lednotification.c
|
||||
|
||||
## UAVObjects
|
||||
include ./UAVObjects.inc
|
||||
|
1
flight/tests/lednotification/FreeRTOS.h
Normal file
@ -0,0 +1 @@
|
||||
#include <stdlib.h>
|
41
flight/tests/lednotification/Makefile
Normal file
@ -0,0 +1,41 @@
|
||||
###############################################################################
|
||||
# @file Makefile
|
||||
# @author PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
|
||||
# Copyright (c) 2013, The OpenPilot Team, http://www.openpilot.org
|
||||
# @addtogroup
|
||||
# @{
|
||||
# @addtogroup
|
||||
# @{
|
||||
# @brief Makefile for unit test
|
||||
###############################################################################
|
||||
#
|
||||
# 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 OPENPILOT_IS_COOL
|
||||
$(error Top level Makefile must be used to build this target)
|
||||
endif
|
||||
|
||||
include $(ROOT_DIR)/make/firmware-defs.mk
|
||||
|
||||
EXTRAINCDIRS += $(TOPDIR)
|
||||
EXTRAINCDIRS += $(PIOS)/inc
|
||||
EXTRAINCDIRS += $(FLIGHTLIB)/inc
|
||||
EXTRAINCDIRS += $(FLIGHTLIB)
|
||||
|
||||
SRC += $(FLIGHTLIB)/optypes.c
|
||||
SRC += $(PIOS)/common/pios_notify.c
|
||||
|
||||
include $(ROOT_DIR)/make/unittest.mk
|
11
flight/tests/lednotification/openpilot.h
Normal file
@ -0,0 +1,11 @@
|
||||
#ifndef OPENPILOT_H
|
||||
#define OPENPILOT_H
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#define PIOS_Assert(x) \
|
||||
if (!(x)) { while (1) {; } \
|
||||
}
|
||||
#define PIOS_DEBUG_Assert(x) PIOS_Assert(x)
|
||||
|
||||
#endif /* OPENPILOT_H */
|
13
flight/tests/lednotification/pios.h
Normal file
@ -0,0 +1,13 @@
|
||||
#ifndef PIOS_H
|
||||
#define PIOS_H
|
||||
|
||||
/* PIOS Feature Selection */
|
||||
#include "pios_config.h"
|
||||
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
/* FreeRTOS Includes */
|
||||
#include "FreeRTOS.h"
|
||||
#endif
|
||||
#include "pios_mem.h"
|
||||
|
||||
#endif /* PIOS_H */
|
6
flight/tests/lednotification/pios_config.h
Normal file
@ -0,0 +1,6 @@
|
||||
#ifndef PIOS_CONFIG_H
|
||||
#define PIOS_CONFIG_H
|
||||
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
34
flight/tests/lednotification/pios_mem.h
Normal file
@ -0,0 +1,34 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_mem.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @addtogroup PiOS
|
||||
* @{
|
||||
* @addtogroup PiOS
|
||||
* @{
|
||||
* @brief PiOS memory allocation API
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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_MEM_H
|
||||
#define PIOS_MEM_H
|
||||
|
||||
#define pios_fastheapmalloc(size) (malloc(size))
|
||||
#define pios_malloc(size) (malloc(size))
|
||||
#define pios_free(p) (free(p))
|
||||
|
||||
#endif /* PIOS_MEM_H */
|
153
flight/tests/lednotification/unittest.cpp
Normal file
@ -0,0 +1,153 @@
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
#include <stdio.h> /* printf */
|
||||
#include <stdlib.h> /* abort */
|
||||
#include <string.h> /* memset */
|
||||
|
||||
extern "C" {
|
||||
#define xTaskGetTickCount() 1
|
||||
#define portTICK_RATE_MS 1
|
||||
|
||||
#include "lednotification.c"
|
||||
|
||||
void PIOS_WS2811_setColorRGB(__attribute__((unused)) Color_t c, __attribute__((unused)) uint8_t led, __attribute__((unused)) bool update) {}
|
||||
void PIOS_WS2811_Update() {}
|
||||
}
|
||||
|
||||
class LedNotificationTest : public testing::Test {};
|
||||
|
||||
int compare_int8(const void *a, const void *b)
|
||||
{
|
||||
const int8_t *da = (const int8_t *)a;
|
||||
const int8_t *db = (const int8_t *)b;
|
||||
|
||||
return (*da > *db) - (*da < *db);
|
||||
}
|
||||
|
||||
|
||||
void sort_priorities(int8_t *queued_priorities)
|
||||
{
|
||||
qsort(queued_priorities, MAX_BACKGROUND_NOTIFICATIONS, sizeof(int8_t), compare_int8);
|
||||
}
|
||||
|
||||
void set_highest_active(NotifierLedStatus_t *status)
|
||||
{
|
||||
int8_t highest = NOTIFY_PRIORITY_BACKGROUND;
|
||||
|
||||
for (int i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) {
|
||||
if (status->queued_priorities[i] > highest) {
|
||||
status->active_sequence_num = i;
|
||||
highest = status->queued_priorities[i];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void insert(NotifierLedStatus_t *status, pios_notify_priority priority)
|
||||
{
|
||||
ExtLedNotification_t notification;
|
||||
|
||||
notification.priority = priority;
|
||||
push_queued_sequence(¬ification, status);
|
||||
}
|
||||
|
||||
void init(NotifierLedStatus_t *status, pios_notify_priority priority)
|
||||
{
|
||||
for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) {
|
||||
status->queued_priorities[i] = priority;
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(LedNotificationTest, TestQueueOrder1) {
|
||||
NotifierLedStatus_t status;
|
||||
|
||||
init(&status, NOTIFY_PRIORITY_BACKGROUND);
|
||||
|
||||
insert(&status, NOTIFY_PRIORITY_LOW);
|
||||
insert(&status, NOTIFY_PRIORITY_CRITICAL);
|
||||
insert(&status, NOTIFY_PRIORITY_LOW);
|
||||
insert(&status, NOTIFY_PRIORITY_CRITICAL);
|
||||
|
||||
set_highest_active(&status);
|
||||
|
||||
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_CRITICAL, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_CRITICAL, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, (status.queued_priorities[status.active_sequence_num]));
|
||||
}
|
||||
|
||||
TEST_F(LedNotificationTest, TestQueueOrder2) {
|
||||
NotifierLedStatus_t status;
|
||||
|
||||
// Fails because insert_point and first_point will both be -1. This will also cause an array-out-of bounds at:
|
||||
// 146 status->queued_priorities[insert_point] = new_notification->priority;
|
||||
// 147 status->queued_sequences[insert_point] = new_notification->sequence;
|
||||
// 148 updated_sequence = insert_point;
|
||||
|
||||
init(&status, NOTIFY_PRIORITY_LOW);
|
||||
status.queued_priorities[0] = NOTIFY_PRIORITY_BACKGROUND;
|
||||
|
||||
insert(&status, NOTIFY_PRIORITY_REGULAR);
|
||||
|
||||
set_highest_active(&status);
|
||||
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, (status.queued_priorities[status.active_sequence_num]));
|
||||
}
|
||||
|
||||
TEST_F(LedNotificationTest, TestQueueOrder3) {
|
||||
NotifierLedStatus_t status;
|
||||
|
||||
// Fails because queued_priorities[0] _LOW and not _REGULAR. I _thibnk_ this is a bug.
|
||||
init(&status, NOTIFY_PRIORITY_REGULAR);
|
||||
status.queued_priorities[0] = NOTIFY_PRIORITY_BACKGROUND;
|
||||
|
||||
insert(&status, NOTIFY_PRIORITY_LOW);
|
||||
|
||||
set_highest_active(&status);
|
||||
|
||||
|
||||
for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS - 1; i++) {
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(LedNotificationTest, TestQueueOrder4) {
|
||||
NotifierLedStatus_t status;
|
||||
|
||||
init(&status, NOTIFY_PRIORITY_BACKGROUND);
|
||||
|
||||
insert(&status, NOTIFY_PRIORITY_REGULAR);
|
||||
insert(&status, NOTIFY_PRIORITY_REGULAR);
|
||||
insert(&status, NOTIFY_PRIORITY_REGULAR);
|
||||
insert(&status, NOTIFY_PRIORITY_LOW);
|
||||
|
||||
set_highest_active(&status);
|
||||
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, (status.queued_priorities[status.active_sequence_num]));
|
||||
pop_queued_sequence(&status);
|
||||
EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, (status.queued_priorities[status.active_sequence_num]));
|
||||
}
|
@ -13,20 +13,329 @@
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_10">
|
||||
<property name="margin">
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="2" column="0">
|
||||
<widget class="QGroupBox" name="airframeBox">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Airframe</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_8" stretch="1">
|
||||
<property name="leftMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QGraphicsView" name="planeShape">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background:transparent</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Plain</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QGroupBox" name="throttleCurveBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Throttle Curve</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_9">
|
||||
<property name="leftMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="MixerCurve" name="fixedWingThrottle" native="true">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="sizeIncrement">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="baseSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>50</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QGroupBox" name="elevonMixBox">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Mixer</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<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>0</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QLabel" name="elevonLabel1">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="elevonSlider1">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Weight of mixing in percent</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="elevonSliderLabel1">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>50</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<widget class="QLabel" name="elevonLabel2">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="elevonSlider2">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>50</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Weight of mixing in percent</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="elevonSliderLabel2">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>50</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0" colspan="3">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_7">
|
||||
<property name="sizeConstraint">
|
||||
<enum>QLayout::SetFixedSize</enum>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<widget class="QLabel" name="aiframeTypelabel">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
@ -34,409 +343,60 @@
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Airplane type:</string>
|
||||
<string>Airframe Type:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="fixedWingType"/>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_4">
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="channelBox">
|
||||
<widget class="QComboBox" name="fixedWingType">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Minimum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>230</width>
|
||||
<height>100</height>
|
||||
<width>25</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Output Channel Assignments</string>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>25</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Select Fixed-wing type</string>
|
||||
</property>
|
||||
<layout class="QFormLayout" name="formLayout_3">
|
||||
<property name="fieldGrowthPolicy">
|
||||
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="fwEngineLabel">
|
||||
<property name="text">
|
||||
<string>Engine</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QComboBox" name="fwEngineChannelBox">
|
||||
<property name="toolTip">
|
||||
<string>Select output channel for the engine</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="fwAileron1Label">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>60</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Aileron 1</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QComboBox" name="fwAileron1ChannelBox">
|
||||
<property name="toolTip">
|
||||
<string>Select output channel for the first aileron (or elevon)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="fwAileron2Label">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>60</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Aileron 2</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QComboBox" name="fwAileron2ChannelBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Select output channel for the second aileron (or elevon)</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="fwElevator1Label">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>67</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Elevator 1</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QComboBox" name="fwElevator1ChannelBox">
|
||||
<property name="toolTip">
|
||||
<string>Select output channel for the first elevator</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="0">
|
||||
<widget class="QLabel" name="fwElevator2Label">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>67</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Elevator 2</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<widget class="QComboBox" name="fwElevator2ChannelBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Select output channel for a secondary elevator</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="0">
|
||||
<widget class="QLabel" name="fwRudder1Label">
|
||||
<property name="text">
|
||||
<string>Rudder 1</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="5" column="1">
|
||||
<widget class="QComboBox" name="fwRudder1ChannelBox">
|
||||
<property name="toolTip">
|
||||
<string>Select output channel for the first rudder</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="0">
|
||||
<widget class="QLabel" name="fwRudder2Label">
|
||||
<property name="text">
|
||||
<string>Rudder 2</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<widget class="QComboBox" name="fwRudder2ChannelBox">
|
||||
<property name="toolTip">
|
||||
<string>Select output channel for a secondary rudder</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="elevonMixBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Elevon Mix</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_13">
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_8">
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_14">
|
||||
<item>
|
||||
<widget class="QLabel" name="elevonLabel1">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>65</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Rudder %</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="elevonSlider1">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="elevonSliderLabel1">
|
||||
<property name="text">
|
||||
<string>50</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_15">
|
||||
<item>
|
||||
<widget class="QLabel" name="elevonLabel2">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>65</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Pitch %</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="elevonSlider2">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="elevonSliderLabel2">
|
||||
<property name="text">
|
||||
<string>50</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="throttleCurveBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>100</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Throttle Curve</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_16">
|
||||
<item>
|
||||
<widget class="MixerCurve" name="fixedWingThrottle" native="true">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>1</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>500</width>
|
||||
<height>500</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="sizeIncrement">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="baseSize">
|
||||
<size>
|
||||
<width>300</width>
|
||||
<height>350</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<spacer name="horizontalSpacer_5">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
<width>10</width>
|
||||
<height>13</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="bottomLayout">
|
||||
<item row="4" column="0" colspan="3">
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_6">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_11">
|
||||
<spacer name="horizontalSpacer_6">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<width>10</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
@ -444,6 +404,12 @@ margin:1px;</string>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="fwStatusLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
@ -453,10 +419,276 @@ margin:1px;</string>
|
||||
<property name="text">
|
||||
<string>Mixer OK</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="3" column="0" colspan="3">
|
||||
<widget class="QGroupBox" name="channelBox">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>140</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Output Channel Assignments</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_7" columnstretch="1,1">
|
||||
<property name="leftMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item row="0" column="1" rowspan="2">
|
||||
<layout class="QFormLayout" name="formLayout_5">
|
||||
<property name="sizeConstraint">
|
||||
<enum>QLayout::SetMaximumSize</enum>
|
||||
</property>
|
||||
<property name="fieldGrowthPolicy">
|
||||
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
|
||||
</property>
|
||||
<property name="verticalSpacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="fwElevator2Label">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>70</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Elevator 2</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QComboBox" name="fwElevator2ChannelBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Assign your output channel</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="fwRudder1Label">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>70</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Rudder 1</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QComboBox" name="fwRudder1ChannelBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Assign your output channel</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="fwRudder2Label">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>70</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Rudder 2</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QComboBox" name="fwRudder2ChannelBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Assign your output channel</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item row="0" column="0" rowspan="2">
|
||||
<layout class="QFormLayout" name="formLayout_3">
|
||||
<property name="sizeConstraint">
|
||||
<enum>QLayout::SetMaximumSize</enum>
|
||||
</property>
|
||||
<property name="fieldGrowthPolicy">
|
||||
<enum>QFormLayout::AllNonFixedFieldsGrow</enum>
|
||||
</property>
|
||||
<property name="verticalSpacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="fwEngineLabel">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>70</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Motor</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QComboBox" name="fwEngineChannelBox">
|
||||
<property name="toolTip">
|
||||
<string>Assign your motor output channel</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="fwAileron1Label">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>70</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Aileron 1</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QComboBox" name="fwAileron1ChannelBox">
|
||||
<property name="toolTip">
|
||||
<string>Assign your output channel</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="fwAileron2Label">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>70</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Aileron 2</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QComboBox" name="fwAileron2ChannelBox">
|
||||
<property name="toolTip">
|
||||
<string>Assign your output channel</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="fwElevator1Label">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>70</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255));
|
||||
color: rgb(255, 255, 255);
|
||||
border-radius: 5;
|
||||
font: bold 12px;
|
||||
margin:1px;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Elevator 1</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="1">
|
||||
<widget class="QComboBox" name="fwElevator1ChannelBox">
|
||||
<property name="toolTip">
|
||||
<string>Assign your output channel</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<customwidgets>
|
||||
|
@ -14,7 +14,16 @@
|
||||
<string>Form</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<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 row="2" column="0">
|
||||
@ -32,10 +41,19 @@
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Frame</string>
|
||||
<string>Airframe</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_8" stretch="1">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -90,7 +108,16 @@
|
||||
<string>Throttle Curve</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_9">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item>
|
||||
@ -136,12 +163,21 @@
|
||||
<string>Mix Level</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<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>0</number>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
@ -189,7 +225,7 @@ margin:1px;</string>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Weight of Roll mixing in percent.
|
||||
Typical values are 100% for + configuration and 50% for X configuration on quads.</string>
|
||||
Typical values are 100% for + configuration and 50% for X configuration on quads</string>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
@ -375,7 +411,7 @@ Typical value is 50% for + or X configuration on quads.</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Frame Type:</string>
|
||||
<string>Airframe Type:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
@ -400,7 +436,7 @@ Typical value is 50% for + or X configuration on quads.</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Select the Multirotor frame type here.</string>
|
||||
<string>Select the Multirotor frame type</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
@ -476,7 +512,16 @@ Typical value is 50% for + or X configuration on quads.</string>
|
||||
<string>Motor output channels</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_7" columnstretch="1,1,0,0,1">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item row="0" column="0" rowspan="5">
|
||||
@ -801,9 +846,7 @@ margin:1px;</string>
|
||||
<container>1</container>
|
||||
</customwidget>
|
||||
</customwidgets>
|
||||
<resources>
|
||||
<include location="../coreplugin/core.qrc"/>
|
||||
</resources>
|
||||
<resources/>
|
||||
<connections>
|
||||
<connection>
|
||||
<sender>mrRollMixLevel</sender>
|
||||
|
@ -2,7 +2,7 @@
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configfixedwingwidget.cpp
|
||||
* @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
@ -84,12 +84,15 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) :
|
||||
populateChannelComboBoxes();
|
||||
|
||||
QStringList fixedWingTypes;
|
||||
fixedWingTypes << "Elevator aileron rudder" << "Elevon" << "Vtail";
|
||||
fixedWingTypes << "Aileron" << "Elevon" << "Vtail";
|
||||
m_aircraft->fixedWingType->addItems(fixedWingTypes);
|
||||
|
||||
// Set default model to "Elevator aileron rudder"
|
||||
m_aircraft->planeShape->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff);
|
||||
m_aircraft->planeShape->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff);
|
||||
|
||||
// Set default model to "Aileron"
|
||||
connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString)));
|
||||
m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder"));
|
||||
m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Aileron"));
|
||||
setupUI(m_aircraft->fixedWingType->currentText());
|
||||
}
|
||||
|
||||
@ -104,9 +107,14 @@ ConfigFixedWingWidget::~ConfigFixedWingWidget()
|
||||
void ConfigFixedWingWidget::setupUI(QString frameType)
|
||||
{
|
||||
Q_ASSERT(m_aircraft);
|
||||
QSvgRenderer *renderer = new QSvgRenderer();
|
||||
renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg"));
|
||||
planeimg = new QGraphicsSvgItem();
|
||||
planeimg->setSharedRenderer(renderer);
|
||||
|
||||
if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") {
|
||||
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevator aileron rudder"));
|
||||
if (frameType == "FixedWing" || frameType == "Aileron") {
|
||||
planeimg->setElementId("aileron");
|
||||
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Aileron"));
|
||||
m_aircraft->fwRudder1ChannelBox->setEnabled(true);
|
||||
m_aircraft->fwRudder2ChannelBox->setEnabled(true);
|
||||
m_aircraft->fwElevator1ChannelBox->setEnabled(true);
|
||||
@ -122,14 +130,16 @@ void ConfigFixedWingWidget::setupUI(QString frameType)
|
||||
m_aircraft->elevonSlider1->setEnabled(false);
|
||||
m_aircraft->elevonSlider2->setEnabled(false);
|
||||
} else if (frameType == "FixedWingElevon" || frameType == "Elevon") {
|
||||
planeimg->setElementId("elevon");
|
||||
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon"));
|
||||
m_aircraft->fwAileron1Label->setText("Elevon 1");
|
||||
m_aircraft->fwAileron2Label->setText("Elevon 2");
|
||||
m_aircraft->fwElevator1ChannelBox->setEnabled(false);
|
||||
m_aircraft->fwElevator2ChannelBox->setEnabled(false);
|
||||
m_aircraft->fwRudder1ChannelBox->setEnabled(true);
|
||||
m_aircraft->fwElevator1ChannelBox->setCurrentText("None");
|
||||
m_aircraft->fwRudder2ChannelBox->setEnabled(true);
|
||||
|
||||
m_aircraft->fwElevator2ChannelBox->setCurrentText("None");
|
||||
m_aircraft->fwElevator1Label->setText("Elevator 1");
|
||||
m_aircraft->fwElevator2Label->setText("Elevator 2");
|
||||
m_aircraft->elevonLabel1->setText("Roll");
|
||||
@ -138,9 +148,12 @@ void ConfigFixedWingWidget::setupUI(QString frameType)
|
||||
m_aircraft->elevonSlider1->setEnabled(true);
|
||||
m_aircraft->elevonSlider2->setEnabled(true);
|
||||
} else if (frameType == "FixedWingVtail" || frameType == "Vtail") {
|
||||
planeimg->setElementId("vtail");
|
||||
setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail"));
|
||||
m_aircraft->fwRudder1ChannelBox->setEnabled(false);
|
||||
m_aircraft->fwRudder1ChannelBox->setCurrentText("None");
|
||||
m_aircraft->fwRudder2ChannelBox->setEnabled(false);
|
||||
m_aircraft->fwRudder2ChannelBox->setCurrentText("None");
|
||||
|
||||
m_aircraft->fwElevator1Label->setText("Vtail 1");
|
||||
m_aircraft->fwElevator1ChannelBox->setEnabled(true);
|
||||
@ -156,6 +169,11 @@ void ConfigFixedWingWidget::setupUI(QString frameType)
|
||||
m_aircraft->elevonSlider1->setEnabled(true);
|
||||
m_aircraft->elevonSlider2->setEnabled(true);
|
||||
}
|
||||
QGraphicsScene *scene = new QGraphicsScene();
|
||||
scene->addItem(planeimg);
|
||||
scene->setSceneRect(planeimg->boundingRect());
|
||||
m_aircraft->planeShape->fitInView(planeimg, Qt::KeepAspectRatio);
|
||||
m_aircraft->planeShape->setScene(scene);
|
||||
}
|
||||
|
||||
void ConfigFixedWingWidget::registerWidgets(ConfigTaskWidget &parent)
|
||||
@ -264,7 +282,7 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets()
|
||||
setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->fixedWingThrottle->getCurve());
|
||||
|
||||
// All airframe types must start with "FixedWing"
|
||||
if (m_aircraft->fixedWingType->currentText() == "Elevator aileron rudder") {
|
||||
if (m_aircraft->fixedWingType->currentText() == "Aileron") {
|
||||
airframeType = "FixedWing";
|
||||
setupFrameFixedWing(airframeType);
|
||||
} else if (m_aircraft->fixedWingType->currentText() == "Elevon") {
|
||||
@ -600,3 +618,18 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType)
|
||||
|
||||
return error;
|
||||
}
|
||||
|
||||
|
||||
void ConfigFixedWingWidget::resizeEvent(QResizeEvent *)
|
||||
{
|
||||
if (planeimg) {
|
||||
m_aircraft->planeShape->fitInView(planeimg, Qt::KeepAspectRatio);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigFixedWingWidget::showEvent(QShowEvent *)
|
||||
{
|
||||
if (planeimg) {
|
||||
m_aircraft->planeShape->fitInView(planeimg, Qt::KeepAspectRatio);
|
||||
}
|
||||
}
|
||||
|
@ -54,6 +54,7 @@ public:
|
||||
|
||||
private:
|
||||
Ui_FixedWingConfigWidget *m_aircraft;
|
||||
QGraphicsSvgItem *planeimg;
|
||||
|
||||
virtual void registerWidgets(ConfigTaskWidget &parent);
|
||||
virtual void resetActuators(GUIConfigDataUnion *configData);
|
||||
@ -64,6 +65,8 @@ private:
|
||||
|
||||
protected:
|
||||
void enableControls(bool enable);
|
||||
void resizeEvent(QResizeEvent *);
|
||||
void showEvent(QShowEvent *);
|
||||
|
||||
private slots:
|
||||
virtual void setupUI(QString airframeType);
|
||||
|
@ -137,15 +137,13 @@ ConfigMultiRotorWidget::ConfigMultiRotorWidget(QWidget *parent) :
|
||||
m_aircraft->quadShape->setScene(scene);
|
||||
|
||||
QStringList multiRotorTypes;
|
||||
multiRotorTypes << "Tricopter Y" << "Quad +" << "Quad X" << "Hexacopter" << "Hexacopter X" << "Hexacopter H" << "Hexacopter Y6"
|
||||
<< "Octocopter" << "Octocopter X" << "Octocopter V" << "Octo Coax +" << "Octo Coax X";
|
||||
multiRotorTypes << "Tricopter Y" << "Quad +" << "Quad X" << "Quad H" << "Hexacopter" << "Hexacopter X" << "Hexacopter H"
|
||||
<< "Hexacopter Y6" << "Octocopter" << "Octocopter X" << "Octocopter V" << "Octo Coax +" << "Octo Coax X";
|
||||
m_aircraft->multirotorFrameType->addItems(multiRotorTypes);
|
||||
|
||||
// Set default model to "Quad X"
|
||||
m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Quad X"));
|
||||
|
||||
// setupUI(m_aircraft->multirotorFrameType->currentText());
|
||||
|
||||
connect(m_aircraft->multirotorFrameType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString)));
|
||||
|
||||
// Connect the multirotor motor reverse checkbox
|
||||
@ -179,6 +177,12 @@ void ConfigMultiRotorWidget::setupUI(QString frameType)
|
||||
m_aircraft->mrRollMixLevel->setValue(50);
|
||||
m_aircraft->mrPitchMixLevel->setValue(50);
|
||||
setYawMixLevel(50);
|
||||
} else if (frameType == "QuadH" || frameType == "Quad H") {
|
||||
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad H"));
|
||||
|
||||
m_aircraft->mrRollMixLevel->setValue(50);
|
||||
m_aircraft->mrPitchMixLevel->setValue(70);
|
||||
setYawMixLevel(50);
|
||||
} else if (frameType == "QuadP" || frameType == "Quad +") {
|
||||
setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +"));
|
||||
|
||||
@ -274,6 +278,8 @@ void ConfigMultiRotorWidget::setupEnabledControls(QString frameType)
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 4, true);
|
||||
} else if (frameType == "QuadP" || frameType == "Quad +") {
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 4, true);
|
||||
} else if (frameType == "QuadH" || frameType == "Quad H") {
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 4, true);
|
||||
} else if (frameType == "Hexa" || frameType == "Hexacopter") {
|
||||
enableComboBoxes(this, CHANNELBOXNAME, 6, true);
|
||||
} else if (frameType == "HexaX" || frameType == "Hexacopter X") {
|
||||
@ -375,6 +381,12 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2, multi.VTOLMotorNE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3, multi.VTOLMotorSE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4, multi.VTOLMotorSW);
|
||||
} else if (frameType == "QuadH") {
|
||||
// Motors 1/2/3/4 are: NW / NE / SE / SW
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNW);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox2, multi.VTOLMotorNE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox3, multi.VTOLMotorSE);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4, multi.VTOLMotorSW);
|
||||
} else if (frameType == "Hexa") {
|
||||
// Motors 1/2/3 4/5/6 are: N / NE / SE / S / SW / NW
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorN);
|
||||
@ -399,6 +411,26 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType)
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox4, multi.VTOLMotorSW);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox5, multi.VTOLMotorW);
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox6, multi.VTOLMotorNW);
|
||||
|
||||
// Now, read the 1st mixer R/P/Y levels and initialize the mix sliders.
|
||||
// This assumes that all vectors are identical - if not, the user should use the
|
||||
// "custom" setting.
|
||||
|
||||
int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1;
|
||||
if (channel > -1) {
|
||||
// get motor 1 value for Pitch
|
||||
double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH);
|
||||
m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27));
|
||||
|
||||
// get motor 2 value for Yaw and Roll
|
||||
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW);
|
||||
setYawMixLevel(qRound(value / 1.27));
|
||||
|
||||
channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1;
|
||||
value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL);
|
||||
m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27));
|
||||
}
|
||||
} else if (frameType == "HexaCoax") {
|
||||
// Motors 1/2/3 4/5/6 are: NW/W NE/E S/SE
|
||||
setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNW);
|
||||
@ -473,6 +505,9 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets()
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Quad X") {
|
||||
airframeType = "QuadX";
|
||||
setupQuad(false);
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Quad H") {
|
||||
airframeType = "QuadH";
|
||||
setupQuad(false);
|
||||
} else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter") {
|
||||
airframeType = "Hexa";
|
||||
setupHexa(true);
|
||||
@ -746,6 +781,8 @@ void ConfigMultiRotorWidget::updateAirframe(QString frameType)
|
||||
elementId = "quad-x";
|
||||
} else if (frameType == "QuadP" || frameType == "Quad +") {
|
||||
elementId = "quad-plus";
|
||||
} else if (frameType == "QuadH" || frameType == "Quad H") {
|
||||
elementId = "quad-h";
|
||||
} else if (frameType == "Hexa" || frameType == "Hexacopter") {
|
||||
elementId = "quad-hexa";
|
||||
} else if (frameType == "HexaX" || frameType == "Hexacopter X") {
|
||||
@ -877,7 +914,7 @@ bool ConfigMultiRotorWidget::setupQuad(bool pLayout)
|
||||
setupMotors(motorList);
|
||||
|
||||
// Now, setup the mixer:
|
||||
// Motor 1 to 4, X Layout:
|
||||
// Motor 1 to 4, X Layout and Hlayout
|
||||
// pitch roll yaw
|
||||
// {0.5 ,0.5 ,-0.5 //Front left motor (CW)
|
||||
// {0.5 ,-0.5 ,0.5 //Front right motor(CCW)
|
||||
|
@ -3,6 +3,8 @@
|
||||
<file>images/help2.png</file>
|
||||
<file>images/ahrs-calib.svg</file>
|
||||
<file>images/multirotor-shapes.svg</file>
|
||||
<!-- these are different from the files in /setupwiz/resources -->
|
||||
<file>images/fixedwing-shapes.svg</file>
|
||||
<file>images/ccpm_setup.svg</file>
|
||||
<file>images/PipXtreme.png</file>
|
||||
<file>images/help.png</file>
|
||||
|
@ -133,6 +133,8 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa
|
||||
ui->thrustPIDScalingCurve->setYAxisLabel(tr("Scaling factor"));
|
||||
ui->thrustPIDScalingCurve->setMin(-0.5);
|
||||
ui->thrustPIDScalingCurve->setMax(0.5);
|
||||
ui->thrustPIDScalingCurve->initLinearCurve(5, -0.25, 0.25);
|
||||
connect(ui->thrustPIDScalingCurve, SIGNAL(curveUpdated()), this, SLOT(throttleCurveUpdated()));
|
||||
|
||||
addWidget(ui->defaultThrottleCurveButton);
|
||||
addWidget(ui->enableThrustPIDScalingCheckBox);
|
||||
@ -169,6 +171,7 @@ void ConfigStabilizationWidget::updateObjectsFromWidgets()
|
||||
|
||||
void ConfigStabilizationWidget::updateThrottleCurveFromObject()
|
||||
{
|
||||
bool dirty = isDirty();
|
||||
UAVObject *stabBank = getObjectManager()->getObject(QString(m_pidTabBars.at(0)->tabData(m_currentPIDBank).toString()));
|
||||
|
||||
Q_ASSERT(stabBank);
|
||||
@ -191,6 +194,7 @@ void ConfigStabilizationWidget::updateThrottleCurveFromObject()
|
||||
bool enabled = field->getValue() == "TRUE";
|
||||
ui->enableThrustPIDScalingCheckBox->setChecked(enabled);
|
||||
ui->thrustPIDScalingCurve->setEnabled(enabled);
|
||||
setDirty(dirty);
|
||||
}
|
||||
|
||||
void ConfigStabilizationWidget::updateObjectFromThrottleCurve()
|
||||
@ -241,6 +245,11 @@ void ConfigStabilizationWidget::resetThrottleCurveToDefault()
|
||||
delete defaultStabBank;
|
||||
}
|
||||
|
||||
void ConfigStabilizationWidget::throttleCurveUpdated()
|
||||
{
|
||||
setDirty(true);
|
||||
}
|
||||
|
||||
void ConfigStabilizationWidget::realtimeUpdatesSlot(bool value)
|
||||
{
|
||||
ui->realTimeUpdates_6->setChecked(value);
|
||||
@ -334,6 +343,8 @@ void ConfigStabilizationWidget::onBoardConnected()
|
||||
|
||||
void ConfigStabilizationWidget::pidBankChanged(int index)
|
||||
{
|
||||
bool dirty = isDirty();
|
||||
|
||||
updateObjectFromThrottleCurve();
|
||||
foreach(QTabBar * tabBar, m_pidTabBars) {
|
||||
disconnect(tabBar, SIGNAL(currentChanged(int)), this, SLOT(pidBankChanged(int)));
|
||||
@ -350,6 +361,7 @@ void ConfigStabilizationWidget::pidBankChanged(int index)
|
||||
m_currentPIDBank = index;
|
||||
qDebug() << "current bank:" << m_currentPIDBank;
|
||||
updateThrottleCurveFromObject();
|
||||
setDirty(dirty);
|
||||
}
|
||||
|
||||
bool ConfigStabilizationWidget::shouldObjectBeSaved(UAVObject *object)
|
||||
|
@ -74,6 +74,6 @@ private slots:
|
||||
void onBoardConnected();
|
||||
void pidBankChanged(int index);
|
||||
void resetThrottleCurveToDefault();
|
||||
void throttleCurveUpdated();
|
||||
};
|
||||
|
||||
#endif // ConfigStabilizationWidget_H
|
||||
|
@ -68,9 +68,12 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions()
|
||||
QStringList channelDesc;
|
||||
switch (systemSettingsData.AirframeType) {
|
||||
case SystemSettings::AIRFRAMETYPE_FIXEDWING:
|
||||
channelDesc = ConfigFixedWingWidget::getChannelDescriptions();
|
||||
break;
|
||||
case SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON:
|
||||
channelDesc = ConfigFixedWingWidget::getChannelDescriptions();
|
||||
break;
|
||||
case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL:
|
||||
// fixed wing
|
||||
channelDesc = ConfigFixedWingWidget::getChannelDescriptions();
|
||||
break;
|
||||
case SystemSettings::AIRFRAMETYPE_HELICP:
|
||||
@ -81,6 +84,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions()
|
||||
case SystemSettings::AIRFRAMETYPE_TRI:
|
||||
case SystemSettings::AIRFRAMETYPE_QUADX:
|
||||
case SystemSettings::AIRFRAMETYPE_QUADP:
|
||||
case SystemSettings::AIRFRAMETYPE_QUADH:
|
||||
case SystemSettings::AIRFRAMETYPE_OCTOV:
|
||||
case SystemSettings::AIRFRAMETYPE_OCTOCOAXX:
|
||||
case SystemSettings::AIRFRAMETYPE_OCTOCOAXP:
|
||||
@ -194,8 +198,7 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *o)
|
||||
UAVObjectField *field = system->getField(QString("AirframeType"));
|
||||
Q_ASSERT(field);
|
||||
|
||||
// At this stage, we will need to have some hardcoded settings in this code, this
|
||||
// is not ideal, but there you go.
|
||||
// At this stage, we will need to have some hardcoded settings in this code
|
||||
QString frameType = field->getValue().toString();
|
||||
|
||||
// Always update custom tab from others airframe settings : debug/learn hardcoded mixers
|
||||
@ -274,11 +277,12 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets()
|
||||
|
||||
int ConfigVehicleTypeWidget::frameCategory(QString frameType)
|
||||
{
|
||||
if (frameType == "FixedWing" || frameType == "Elevator aileron rudder" || frameType == "FixedWingElevon"
|
||||
if (frameType == "FixedWing" || frameType == "Aileron" || frameType == "FixedWingElevon"
|
||||
|| frameType == "Elevon" || frameType == "FixedWingVtail" || frameType == "Vtail") {
|
||||
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 == "QuadP" || frameType == "Quad +" || frameType == "Quad H" || frameType == "QuadH"
|
||||
|| frameType == "Hexa" || frameType == "Hexacopter"
|
||||
|| frameType == "HexaX" || frameType == "Hexacopter X" || frameType == "HexaCoax"
|
||||
|| frameType == "HexaH" || frameType == "Hexacopter H" || frameType == "Hexacopter Y6"
|
||||
|| frameType == "Octo" || frameType == "Octocopter"
|
||||
|
2661
ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg
Normal file
After Width: | Height: | Size: 165 KiB |
3127
ground/openpilotgcs/src/plugins/config/images/ground-shapes.svg
Normal file
After Width: | Height: | Size: 256 KiB |
Before Width: | Height: | Size: 898 KiB After Width: | Height: | Size: 1.1 MiB |
@ -282,8 +282,8 @@
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
<string>Setup "RapidESC" here: usual value is 500 Hz for multirotor airframes.
|
||||
</string>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
@ -320,6 +320,11 @@ Leave at 50Hz for fixed wing.</string>
|
||||
<string>400</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>500</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="3">
|
||||
@ -340,8 +345,8 @@ Leave at 50Hz for fixed wing.</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
<string>Setup "RapidESC" here: usual value is 500 Hz for multirotor airframes.
|
||||
</string>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
@ -378,6 +383,11 @@ Leave at 50Hz for fixed wing.</string>
|
||||
<string>400</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>500</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
@ -420,8 +430,8 @@ Leave at 50Hz for fixed wing.</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
<string>Setup "RapidESC" here: usual value is 500 Hz for multirotor airframes.
|
||||
</string>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
@ -458,6 +468,11 @@ Leave at 50Hz for fixed wing.</string>
|
||||
<string>400</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>500</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="5">
|
||||
@ -478,8 +493,8 @@ Leave at 50Hz for fixed wing.</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
<string>Setup "RapidESC" here: usual value is 500 Hz for multirotor airframes.
|
||||
</string>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
@ -516,6 +531,11 @@ Leave at 50Hz for fixed wing.</string>
|
||||
<string>400</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>500</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="7">
|
||||
@ -546,8 +566,8 @@ Leave at 50Hz for fixed wing.</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
<string>Setup "RapidESC" here: usual value is 500 Hz for multirotor airframes.
|
||||
</string>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
@ -584,6 +604,11 @@ Leave at 50Hz for fixed wing.</string>
|
||||
<string>400</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>500</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="7">
|
||||
@ -604,8 +629,8 @@ Leave at 50Hz for fixed wing.</string>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes.
|
||||
Leave at 50Hz for fixed wing.</string>
|
||||
<string>Setup "RapidESC" here: usual value is 500 Hz for multirotor airframes.
|
||||
</string>
|
||||
</property>
|
||||
<item>
|
||||
<property name="text">
|
||||
@ -642,6 +667,11 @@ Leave at 50Hz for fixed wing.</string>
|
||||
<string>400</string>
|
||||
</property>
|
||||
</item>
|
||||
<item>
|
||||
<property name="text">
|
||||
<string>500</string>
|
||||
</property>
|
||||
</item>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
|
@ -6,7 +6,7 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>882</width>
|
||||
<width>995</width>
|
||||
<height>789</height>
|
||||
</rect>
|
||||
</property>
|
||||
@ -136,8 +136,8 @@
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>844</width>
|
||||
<height>726</height>
|
||||
<width>971</width>
|
||||
<height>712</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
@ -7836,9 +7836,9 @@ border-radius: 5;</string>
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>-295</y>
|
||||
<width>844</width>
|
||||
<height>998</height>
|
||||
<y>0</y>
|
||||
<width>954</width>
|
||||
<height>732</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_29">
|
||||
@ -7864,2864 +7864,4620 @@ border-radius: 5;</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_7">
|
||||
<item>
|
||||
<widget class="QGroupBox" name="advancedResponsivenessGroupBox">
|
||||
<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>Responsiveness</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_18">
|
||||
<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="2" column="0" colspan="3">
|
||||
<widget class="QGroupBox" name="advancedResponsivenessControls">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_4" stretch="4,3">
|
||||
<item>
|
||||
<widget class="QGroupBox" name="advancedResponsivenessGroupBox">
|
||||
<property name="enabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<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="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Responsiveness</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_18">
|
||||
<property name="leftMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
<property name="topMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>140</height>
|
||||
</size>
|
||||
<property name="rightMargin">
|
||||
<number>9</number>
|
||||
</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="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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>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="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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>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="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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>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="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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>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="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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>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="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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>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 name="bottomMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
<property name="horizontalSpacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QGroupBox{border: 0px;}</string>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_6" rowstretch="0,0,0,0" columnstretch="0,0,1,0,1,0,1,0">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="verticalSpacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="1" column="4">
|
||||
<widget class="QDoubleSpinBox" name="ratePitchKp_4">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<item row="1" column="0" alignment="Qt::AlignTop">
|
||||
<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>Use Advanced Configuration</string>
|
||||
</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>
|
||||
<item row="1" column="2" alignment="Qt::AlignTop">
|
||||
<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="2" column="0" colspan="3">
|
||||
<widget class="QGroupBox" name="advancedResponsivenessControls">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>140</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="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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>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="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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>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="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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>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="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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>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="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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>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="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Window">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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>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>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QGroupBox{border: 0px;}</string>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="flat">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_6" rowstretch="0,0,0,0" columnstretch="0,0,0,0,0,0,0">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>180.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:PitchMax</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_22">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>128</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Max rate limit (all modes) (deg/s)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QDoubleSpinBox" name="rateRollILimit_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>1000000.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:MaximumRate</string>
|
||||
<string>element:Roll</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<spacer name="horizontalSpacer_30">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="2" column="6">
|
||||
<widget class="QDoubleSpinBox" name="rateYawKi_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>1000000.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:ManualRate</string>
|
||||
<string>element:Yaw</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="6">
|
||||
<widget class="QDoubleSpinBox" name="rateYawKp_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>180.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:YawMax</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QDoubleSpinBox" name="ratePitchILimit_4">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<property name="verticalSpacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>1000000.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:MaximumRate</string>
|
||||
<string>element:Pitch</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="6">
|
||||
<widget class="QLabel" name="label_38">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</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">
|
||||
<item row="2" column="4">
|
||||
<widget class="QDoubleSpinBox" name="ratePitchKi_4">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>1000000.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:ManualRate</string>
|
||||
<string>element:Pitch</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_33">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</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>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>58</red>
|
||||
<green>58</green>
|
||||
<blue>58</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>48</red>
|
||||
<green>48</green>
|
||||
<blue>48</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</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">
|
||||
</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>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</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>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>58</red>
|
||||
<green>58</green>
|
||||
<blue>58</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>48</red>
|
||||
<green>48</green>
|
||||
<blue>48</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</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));
|
||||
</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>Yaw</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<spacer name="horizontalSpacer_31">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="2" column="5">
|
||||
<spacer name="horizontalSpacer_32">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="label_37">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</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">
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Roll</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QDoubleSpinBox" name="rateRollKi_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>1000000.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:ManualRate</string>
|
||||
<string>element:Roll</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QDoubleSpinBox" name="rateRollKp_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="buttonSymbols">
|
||||
<enum>QAbstractSpinBox::UpDownArrows</enum>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>180.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:RollMax</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_40">
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Rate mode
|
||||
response (deg/s)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="6">
|
||||
<widget class="QDoubleSpinBox" name="rateYawILimit_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>1000000.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:MaximumRate</string>
|
||||
<string>element:Yaw</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="2">
|
||||
<widget class="QDoubleSpinBox" name="rateRollILimit_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>1000000.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:MaximumRate</string>
|
||||
<string>element:Roll</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<spacer name="horizontalSpacer_30">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="2" column="6">
|
||||
<widget class="QDoubleSpinBox" name="rateYawKi_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>1000000.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:ManualRate</string>
|
||||
<string>element:Yaw</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="6">
|
||||
<widget class="QDoubleSpinBox" name="rateYawKp_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>180.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:YawMax</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="3">
|
||||
<spacer name="horizontalSpacer_31">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="4">
|
||||
<widget class="QLabel" name="label_37">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</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>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>58</red>
|
||||
<green>58</green>
|
||||
<blue>58</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>48</red>
|
||||
<green>48</green>
|
||||
<blue>48</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</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">
|
||||
</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>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</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>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>58</red>
|
||||
<green>58</green>
|
||||
<blue>58</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>48</red>
|
||||
<green>48</green>
|
||||
<blue>48</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</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));
|
||||
</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>Pitch</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_39">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>69</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Attitude mode response (deg)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<widget class="QDoubleSpinBox" name="ratePitchKi_4">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>1000000.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:ManualRate</string>
|
||||
<string>element:Pitch</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<spacer name="horizontalSpacer_29">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>140</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_33">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</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">
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Pitch</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="5">
|
||||
<spacer name="horizontalSpacer_32">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Fixed</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>10</width>
|
||||
<height>10</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="3" column="4">
|
||||
<widget class="QDoubleSpinBox" name="ratePitchILimit_4">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>1000000.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:MaximumRate</string>
|
||||
<string>element:Pitch</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="6">
|
||||
<widget class="QLabel" name="label_38">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="palette">
|
||||
<palette>
|
||||
<active>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</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>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>58</red>
|
||||
<green>58</green>
|
||||
<blue>58</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>48</red>
|
||||
<green>48</green>
|
||||
<blue>48</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="BrightText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ButtonText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</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">
|
||||
</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>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="AlternateBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipBase">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>220</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="ToolTipText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
</active>
|
||||
<inactive>
|
||||
<colorrole role="WindowText">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</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>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>58</red>
|
||||
<green>58</green>
|
||||
<blue>58</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Midlight">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>48</red>
|
||||
<green>48</green>
|
||||
<blue>48</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Dark">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>19</red>
|
||||
<green>19</green>
|
||||
<blue>19</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">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Mid">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>74</red>
|
||||
<green>74</green>
|
||||
<blue>74</blue>
|
||||
<red>26</red>
|
||||
<green>26</green>
|
||||
<blue>26</blue>
|
||||
</color>
|
||||
</gradientstop>
|
||||
<gradientstop position="0.786070000000000">
|
||||
</brush>
|
||||
</colorrole>
|
||||
<colorrole role="Text">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>36</red>
|
||||
<green>36</green>
|
||||
<blue>36</blue>
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</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));
|
||||
</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="2" column="2">
|
||||
<widget class="QDoubleSpinBox" name="rateRollKi_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Yaw</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_39">
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Attitude mode
|
||||
response (deg)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<widget class="QDoubleSpinBox" name="ratePitchKp_4">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>180.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:PitchMax</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<widget class="QLabel" name="label_22">
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Max rate limit
|
||||
(all modes) (deg/s)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0">
|
||||
<spacer name="verticalSpacer_8">
|
||||
<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>
|
||||
<widget class="QGroupBox" name="thrustPIDScalingGroup">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>16777215</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="title">
|
||||
<string>Thrust PID Scaling</string>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_27" rowstretch="0,0,0" columnminimumwidth="0,0">
|
||||
<property name="leftMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item row="1" column="0" rowspan="2">
|
||||
<widget class="QFrame" name="frame_3">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>140</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_17">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>1000000.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:ManualRate</string>
|
||||
<string>element:Roll</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QDoubleSpinBox" name="rateRollKp_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="buttonSymbols">
|
||||
<enum>QAbstractSpinBox::UpDownArrows</enum>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>180.000000000000000</double>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:RollMax</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="6">
|
||||
<widget class="QDoubleSpinBox" name="rateYawILimit_3">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>16777215</width>
|
||||
<height>22</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="focusPolicy">
|
||||
<enum>Qt::StrongFocus</enum>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string><html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html></string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
<property name="decimals">
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<double>1000000.000000000000000</double>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<double>1.000000000000000</double>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:MaximumRate</string>
|
||||
<string>element:Yaw</string>
|
||||
<string>haslimits:no</string>
|
||||
<string>scale:1</string>
|
||||
<string>buttongroup:6,20</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_40">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>16</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true"/>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Rate mode response (deg/s)</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="7">
|
||||
<spacer name="horizontalSpacer_33">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<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>Use Advanced Configuration</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<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="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>
|
||||
<widget class="QCheckBox" name="enableThrustPIDScalingCheckBox">
|
||||
<property name="text">
|
||||
<string>Enable TPS</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:EnableThrustPIDScaling</string>
|
||||
<string>buttongroup:99</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_36">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</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>Source</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="ThrustPIDSource">
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:ThrustPIDScaleSource</string>
|
||||
<string>buttongroup:99</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_35">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</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>Targets</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="ThrustPIDTarget">
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:ThrustPIDScaleTarget</string>
|
||||
<string>buttongroup:99</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="ThrustPIDAxisLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</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>Axis</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="ThrustPIDAxis">
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:ThrustPIDScaleAxes</string>
|
||||
<string>buttongroup:99</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="defaultThrottleCurveButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="layoutDirection">
|
||||
<enum>Qt::LeftToRight</enum>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Default</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettings</string>
|
||||
<string>button:default</string>
|
||||
<string>buttongroup:99</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1" rowspan="2">
|
||||
<widget class="MixerCurveWidget" name="thrustPIDScalingCurve" native="true">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>180</width>
|
||||
<height>180</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>7</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="RateStabilizationGroup_8">
|
||||
@ -16182,1815 +17938,6 @@ border-radius: 5;</string>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGroupBox" name="thrustPIDScalingGroup">
|
||||
<property name="title">
|
||||
<string>Thrust PID Scaling</string>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout_27">
|
||||
<item row="0" column="1">
|
||||
<widget class="MixerCurveWidget" name="thrustPIDScalingCurve" native="true">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>200</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>7</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="3" rowspan="3" alignment="Qt::AlignTop">
|
||||
<widget class="QFrame" name="frame_2">
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_20">
|
||||
<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 alignment="Qt::AlignTop">
|
||||
<widget class="QPushButton" name="defaultThrottleCurveButton">
|
||||
<property name="text">
|
||||
<string>Default</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettings</string>
|
||||
<string>button:default</string>
|
||||
<string>buttongroup:99</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<spacer name="horizontalSpacer_61">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeType">
|
||||
<enum>QSizePolicy::Expanding</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QFrame" name="frame_3">
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Raised</enum>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_17">
|
||||
<item>
|
||||
<widget class="QCheckBox" name="enableThrustPIDScalingCheckBox">
|
||||
<property name="text">
|
||||
<string>Enable Thrust PID Scaling</string>
|
||||
</property>
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:EnableThrustPIDScaling</string>
|
||||
<string>buttongroup:99</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_36">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</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>Source</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="ThrustPIDSource">
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:ThrustPIDScaleSource</string>
|
||||
<string>buttongroup:99</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_35">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</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>Targets</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="ThrustPIDTarget">
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:ThrustPIDScaleTarget</string>
|
||||
<string>buttongroup:99</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="ThrustPIDAxisLabel">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>20</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>Axis</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="ThrustPIDAxis">
|
||||
<property name="objrelation" stdset="0">
|
||||
<stringlist>
|
||||
<string>objname:StabilizationSettingsBankX</string>
|
||||
<string>fieldname:ThrustPIDScaleAxes</string>
|
||||
<string>buttongroup:99</string>
|
||||
</stringlist>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_8">
|
||||
<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>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
@ -18108,8 +18055,8 @@ border-radius: 5;</string>
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>860</width>
|
||||
<height>703</height>
|
||||
<width>971</width>
|
||||
<height>712</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_8" stretch="0,0,0,0,0,0">
|
||||
@ -24051,8 +23998,8 @@ font:bold;</string>
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>860</width>
|
||||
<height>703</height>
|
||||
<width>971</width>
|
||||
<height>712</height>
|
||||
</rect>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_18">
|
||||
|
@ -63,5 +63,6 @@
|
||||
<file>qml/images/tab.png</file>
|
||||
<file>qml/AboutDialog.qml</file>
|
||||
<file alias="qml/AuthorsModel.qml">../../../../../build/openpilotgcs-synthetics/AuthorsModel.qml</file>
|
||||
<file>images/opie_90x120.gif</file>
|
||||
</qresource>
|
||||
</RCC>
|
||||
|
After Width: | Height: | Size: 350 KiB |
@ -57,6 +57,17 @@ Rectangle {
|
||||
}
|
||||
}
|
||||
}
|
||||
AnimatedImage {
|
||||
id: opie
|
||||
anchors.left: parent.left
|
||||
anchors.leftMargin: 10
|
||||
anchors.top: logo.bottom
|
||||
anchors.topMargin: 10
|
||||
source: "../images/opie_90x120.gif"
|
||||
z: 100
|
||||
fillMode: Image.PreserveAspectFit
|
||||
visible: false
|
||||
}
|
||||
|
||||
Rectangle {
|
||||
anchors.left: logo.right
|
||||
@ -76,7 +87,15 @@ Rectangle {
|
||||
Layout.fillWidth: true
|
||||
font.pixelSize: 14
|
||||
font.bold: true
|
||||
|
||||
MouseArea {
|
||||
id: easter_egg
|
||||
anchors.fill: parent
|
||||
hoverEnabled: true
|
||||
cursorShape: Qt.PointingHandCursor
|
||||
onClicked: {
|
||||
opie.visible = !opie.visible
|
||||
}
|
||||
}
|
||||
}
|
||||
Text {
|
||||
id: versionLabel
|
||||
|
@ -31,8 +31,11 @@
|
||||
#include "connectiondiagram.h"
|
||||
#include "ui_connectiondiagram.h"
|
||||
|
||||
const char *ConnectionDiagram::FILE_NAME = ":/setupwizard/resources/connection-diagrams.svg";
|
||||
const int ConnectionDiagram::IMAGE_PADDING = 10;
|
||||
|
||||
ConnectionDiagram::ConnectionDiagram(QWidget *parent, VehicleConfigurationSource *configSource) :
|
||||
QDialog(parent), ui(new Ui::ConnectionDiagram), m_configSource(configSource), m_background(0)
|
||||
QDialog(parent), ui(new Ui::ConnectionDiagram), m_configSource(configSource)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
setWindowTitle(tr("Connection Diagram"));
|
||||
@ -48,33 +51,32 @@ void ConnectionDiagram::resizeEvent(QResizeEvent *event)
|
||||
{
|
||||
QWidget::resizeEvent(event);
|
||||
|
||||
ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio);
|
||||
fitInView();
|
||||
}
|
||||
|
||||
void ConnectionDiagram::showEvent(QShowEvent *event)
|
||||
{
|
||||
QWidget::showEvent(event);
|
||||
|
||||
ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio);
|
||||
fitInView();
|
||||
}
|
||||
|
||||
void ConnectionDiagram::fitInView()
|
||||
{
|
||||
ui->connectionDiagram->setSceneRect(m_scene->itemsBoundingRect());
|
||||
ui->connectionDiagram->fitInView(
|
||||
m_scene->itemsBoundingRect().adjusted(-IMAGE_PADDING, -IMAGE_PADDING, IMAGE_PADDING, IMAGE_PADDING),
|
||||
Qt::KeepAspectRatio);
|
||||
}
|
||||
|
||||
void ConnectionDiagram::setupGraphicsScene()
|
||||
{
|
||||
m_renderer = new QSvgRenderer();
|
||||
if (QFile::exists(QString(":/setupwizard/resources/connection-diagrams.svg")) &&
|
||||
m_renderer->load(QString(":/setupwizard/resources/connection-diagrams.svg")) &&
|
||||
if (QFile::exists(QString(FILE_NAME)) &&
|
||||
m_renderer->load(QString(FILE_NAME)) &&
|
||||
m_renderer->isValid()) {
|
||||
m_scene = new QGraphicsScene(this);
|
||||
ui->connectionDiagram->setScene(m_scene);
|
||||
// ui->connectionDiagram->setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
|
||||
|
||||
m_background = new QGraphicsSvgItem();
|
||||
m_background->setSharedRenderer(m_renderer);
|
||||
m_background->setElementId("background");
|
||||
m_background->setOpacity(0);
|
||||
// m_background->setFlags(QGraphicsItem::ItemClipsToShape);
|
||||
m_background->setZValue(-1);
|
||||
m_scene->addItem(m_background);
|
||||
|
||||
QList<QString> elementsToShow;
|
||||
|
||||
@ -86,6 +88,9 @@ void ConnectionDiagram::setupGraphicsScene()
|
||||
case VehicleConfigurationSource::CONTROLLER_REVO:
|
||||
elementsToShow << "controller-revo";
|
||||
break;
|
||||
case VehicleConfigurationSource::CONTROLLER_NANO:
|
||||
elementsToShow << "controller-nano";
|
||||
break;
|
||||
case VehicleConfigurationSource::CONTROLLER_OPLINK:
|
||||
default:
|
||||
elementsToShow << "controller-cc";
|
||||
@ -104,6 +109,9 @@ void ConnectionDiagram::setupGraphicsScene()
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_QUAD_PLUS:
|
||||
elementsToShow << "quad-p";
|
||||
break;
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_QUAD_H:
|
||||
elementsToShow << "quad-h";
|
||||
break;
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA:
|
||||
elementsToShow << "hexa";
|
||||
break;
|
||||
@ -121,6 +129,19 @@ void ConnectionDiagram::setupGraphicsScene()
|
||||
}
|
||||
break;
|
||||
case VehicleConfigurationSource::VEHICLE_FIXEDWING:
|
||||
switch (m_configSource->getVehicleSubType()) {
|
||||
case VehicleConfigurationSource::FIXED_WING_DUAL_AILERON:
|
||||
elementsToShow << "aileron";
|
||||
break;
|
||||
case VehicleConfigurationSource::FIXED_WING_AILERON:
|
||||
elementsToShow << "aileron-single";
|
||||
break;
|
||||
case VehicleConfigurationSource::FIXED_WING_ELEVON:
|
||||
elementsToShow << "elevon";
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
case VehicleConfigurationSource::VEHICLE_HELI:
|
||||
case VehicleConfigurationSource::VEHICLE_SURFACE:
|
||||
default:
|
||||
@ -129,28 +150,91 @@ void ConnectionDiagram::setupGraphicsScene()
|
||||
|
||||
switch (m_configSource->getInputType()) {
|
||||
case VehicleConfigurationSource::INPUT_PWM:
|
||||
elementsToShow << "pwm";
|
||||
if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) {
|
||||
elementsToShow << "pwm-nano";
|
||||
} else {
|
||||
elementsToShow << "pwm";
|
||||
}
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_PPM:
|
||||
elementsToShow << "ppm";
|
||||
if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) {
|
||||
elementsToShow << "ppm-nano";
|
||||
} else {
|
||||
elementsToShow << "ppm";
|
||||
}
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_SBUS:
|
||||
elementsToShow << "sbus";
|
||||
if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) {
|
||||
elementsToShow << "sbus-nano";
|
||||
} else {
|
||||
elementsToShow << "sbus";
|
||||
}
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_DSMX10:
|
||||
case VehicleConfigurationSource::INPUT_DSMX11:
|
||||
case VehicleConfigurationSource::INPUT_DSM2:
|
||||
elementsToShow << "satellite";
|
||||
if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) {
|
||||
elementsToShow << "satellite-nano";
|
||||
} else {
|
||||
elementsToShow << "satellite";
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
switch (m_configSource->getGpsType()) {
|
||||
case VehicleConfigurationSource::GPS_DISABLED:
|
||||
break;
|
||||
case VehicleConfigurationSource::GPS_NMEA:
|
||||
if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) {
|
||||
elementsToShow << "nano-generic-nmea";
|
||||
} else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) {
|
||||
elementsToShow << "generic-nmea";
|
||||
}
|
||||
break;
|
||||
case VehicleConfigurationSource::GPS_PLATINUM:
|
||||
if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) {
|
||||
elementsToShow << "nano-OPGPS-v9";
|
||||
} else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) {
|
||||
elementsToShow << "OPGPS-v9";
|
||||
}
|
||||
break;
|
||||
case VehicleConfigurationSource::GPS_UBX:
|
||||
if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) {
|
||||
elementsToShow << "nano-OPGPS-v8-ublox";
|
||||
} else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) {
|
||||
elementsToShow << "OPGPS-v8-ublox";
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
if (m_configSource->getVehicleType() == VehicleConfigurationSource::VEHICLE_FIXEDWING &&
|
||||
m_configSource->getAirspeedType() != VehicleConfigurationSource::AIRSPEED_ESTIMATE) {
|
||||
switch (m_configSource->getAirspeedType()) {
|
||||
case VehicleConfigurationSource::AIRSPEED_EAGLETREE:
|
||||
if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) {
|
||||
elementsToShow << "nano-eagletree-speed-sensor";
|
||||
} else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) {
|
||||
elementsToShow << "eagletree-speed-sensor";
|
||||
}
|
||||
break;
|
||||
case VehicleConfigurationSource::AIRSPEED_MS4525:
|
||||
if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) {
|
||||
elementsToShow << "nano-ms4525-speed-sensor";
|
||||
} else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) {
|
||||
elementsToShow << "ms4525-speed-sensor";
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
setupGraphicsSceneItems(elementsToShow);
|
||||
|
||||
ui->connectionDiagram->setSceneRect(m_background->boundingRect());
|
||||
ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio);
|
||||
|
||||
fitInView();
|
||||
qDebug() << "Scene complete";
|
||||
}
|
||||
}
|
||||
@ -159,8 +243,6 @@ void ConnectionDiagram::setupGraphicsSceneItems(QList<QString> elementsToShow)
|
||||
{
|
||||
qreal z = 0;
|
||||
|
||||
// QRectF backgBounds = m_renderer->boundsOnElement("background");
|
||||
|
||||
foreach(QString elementId, elementsToShow) {
|
||||
if (m_renderer->elementExists(elementId)) {
|
||||
QGraphicsSvgItem *element = new QGraphicsSvgItem();
|
||||
@ -172,10 +254,6 @@ void ConnectionDiagram::setupGraphicsSceneItems(QList<QString> elementsToShow)
|
||||
QMatrix matrix = m_renderer->matrixForElement(elementId);
|
||||
QRectF orig = matrix.mapRect(m_renderer->boundsOnElement(elementId));
|
||||
element->setPos(orig.x(), orig.y());
|
||||
|
||||
// QRectF orig = m_renderer->boundsOnElement(elementId);
|
||||
// element->setPos(orig.x() - backgBounds.x(), orig.y() - backgBounds.y());
|
||||
|
||||
m_scene->addItem(element);
|
||||
qDebug() << "Adding " << elementId << " to scene at " << element->pos();
|
||||
} else {
|
||||
@ -188,7 +266,7 @@ void ConnectionDiagram::on_saveButton_clicked()
|
||||
{
|
||||
QImage image(2200, 1100, QImage::Format_ARGB32);
|
||||
|
||||
image.fill(0);
|
||||
image.fill(Qt::white);
|
||||
QPainter painter(&image);
|
||||
m_scene->render(&painter);
|
||||
QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "", tr("Images (*.png *.xpm *.jpg)"));
|
||||
|
@ -47,12 +47,14 @@ public:
|
||||
explicit ConnectionDiagram(QWidget *parent, VehicleConfigurationSource *configSource);
|
||||
~ConnectionDiagram();
|
||||
|
||||
void fitInView();
|
||||
private:
|
||||
static const char *FILE_NAME;
|
||||
static const int IMAGE_PADDING;
|
||||
Ui::ConnectionDiagram *ui;
|
||||
VehicleConfigurationSource *m_configSource;
|
||||
|
||||
QSvgRenderer *m_renderer;
|
||||
QGraphicsSvgItem *m_background;
|
||||
QGraphicsScene *m_scene;
|
||||
|
||||
void setupGraphicsScene();
|
||||
|
@ -40,6 +40,9 @@
|
||||
</color>
|
||||
</brush>
|
||||
</property>
|
||||
<property name="renderHints">
|
||||
<set>QPainter::HighQualityAntialiasing|QPainter::TextAntialiasing</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
|
@ -52,7 +52,7 @@ void OutputCalibrationUtil::startChannelOutput(quint16 channel, quint16 safeValu
|
||||
m_outputChannel = channel;
|
||||
m_safeValue = safeValue;
|
||||
|
||||
qDebug() << "Starting output for channel " << m_outputChannel << "...";
|
||||
qDebug() << "Starting output for channel " << m_outputChannel + 1 << "...";
|
||||
|
||||
ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager);
|
||||
Q_ASSERT(actuatorCommand);
|
||||
@ -74,17 +74,17 @@ void OutputCalibrationUtil::startChannelOutput(quint16 channel, quint16 safeValu
|
||||
actuatorCommand->setMetadata(metaData);
|
||||
actuatorCommand->updated();
|
||||
|
||||
qDebug() << "Output for channel " << m_outputChannel << " started.";
|
||||
qDebug() << "Output for channel " << m_outputChannel + 1 << " started.";
|
||||
}
|
||||
}
|
||||
|
||||
void OutputCalibrationUtil::stopChannelOutput()
|
||||
{
|
||||
if (m_outputChannel >= 0) {
|
||||
qDebug() << "Stopping output for channel " << m_outputChannel << "...";
|
||||
qDebug() << "Stopping output for channel " << m_outputChannel + 1 << "...";
|
||||
// Stop output...
|
||||
setChannelOutputValue(m_safeValue);
|
||||
qDebug() << "Settings output for channel " << m_outputChannel << " to " << m_safeValue;
|
||||
qDebug() << "Settings output for channel " << m_outputChannel + 1 << " to " << m_safeValue;
|
||||
|
||||
// Restore metadata to what it was before
|
||||
ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager);
|
||||
@ -93,7 +93,7 @@ void OutputCalibrationUtil::stopChannelOutput()
|
||||
actuatorCommand->setMetadata(m_savedActuatorCommandMetadata);
|
||||
actuatorCommand->updated();
|
||||
|
||||
qDebug() << "Output for channel " << m_outputChannel << " stopped.";
|
||||
qDebug() << "Output for channel " << m_outputChannel + 1 << " stopped.";
|
||||
|
||||
m_outputChannel = -1;
|
||||
}
|
||||
|
@ -0,0 +1,211 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file airframestabfixedwingpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup AirframeStabFixedwingPage
|
||||
* @{
|
||||
* @brief
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "airframeinitialtuningpage.h"
|
||||
#include "ui_airframeinitialtuningpage.h"
|
||||
#include <QJsonDocument>
|
||||
#include <QJsonArray>
|
||||
#include <QDir>
|
||||
#include "vehicletemplateexportdialog.h"
|
||||
|
||||
AirframeInitialTuningPage::AirframeInitialTuningPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::AirframeInitialTuningPage), m_dir(NULL), m_photoItem(NULL)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
ui->templateImage->setScene(new QGraphicsScene());
|
||||
connect(ui->templateList, SIGNAL(itemSelectionChanged()), this, SLOT(templateSelectionChanged()));
|
||||
}
|
||||
|
||||
AirframeInitialTuningPage::~AirframeInitialTuningPage()
|
||||
{
|
||||
ui->templateList->clear();
|
||||
foreach(QJsonObject * templ, m_templates.values()) {
|
||||
delete templ;
|
||||
}
|
||||
m_templates.clear();
|
||||
|
||||
delete ui;
|
||||
}
|
||||
|
||||
void AirframeInitialTuningPage::initializePage()
|
||||
{
|
||||
switch (getWizard()->getVehicleType()) {
|
||||
case VehicleConfigurationSource::VEHICLE_FIXEDWING:
|
||||
m_dir = VehicleTemplateExportDialog::EXPORT_FIXEDWING_NAME;
|
||||
break;
|
||||
case VehicleConfigurationSource::VEHICLE_MULTI:
|
||||
m_dir = VehicleTemplateExportDialog::EXPORT_MULTI_NAME;
|
||||
break;
|
||||
case VehicleConfigurationSource::VEHICLE_HELI:
|
||||
m_dir = VehicleTemplateExportDialog::EXPORT_HELI_NAME;
|
||||
break;
|
||||
case VehicleConfigurationSource::VEHICLE_SURFACE:
|
||||
m_dir = VehicleTemplateExportDialog::EXPORT_SURFACE_NAME;
|
||||
break;
|
||||
default:
|
||||
m_dir = NULL;
|
||||
break;
|
||||
}
|
||||
loadValidFiles();
|
||||
setupTemplateList();
|
||||
}
|
||||
|
||||
bool AirframeInitialTuningPage::validatePage()
|
||||
{
|
||||
QJsonObject *templ = NULL;
|
||||
|
||||
if (ui->templateList->currentRow() >= 0) {
|
||||
templ = ui->templateList->item(ui->templateList->currentRow())->data(Qt::UserRole + 1).value<QJsonObject *>();
|
||||
}
|
||||
if (getWizard()->getVehicleTemplate() != NULL) {
|
||||
delete getWizard()->getVehicleTemplate();
|
||||
}
|
||||
getWizard()->setVehicleTemplate(new QJsonObject(*templ));
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AirframeInitialTuningPage::isComplete() const
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
void AirframeInitialTuningPage::updatePhoto(QJsonObject *templ)
|
||||
{
|
||||
QPixmap photo;
|
||||
|
||||
if (m_photoItem != NULL) {
|
||||
ui->templateImage->scene()->removeItem(m_photoItem);
|
||||
}
|
||||
if (templ != NULL) {
|
||||
QByteArray imageData = QByteArray::fromBase64(templ->value("photo").toString().toLatin1());
|
||||
photo.loadFromData(imageData, "PNG");
|
||||
} else {
|
||||
photo.load(":/core/images/opie_90x120.gif");
|
||||
}
|
||||
m_photoItem = ui->templateImage->scene()->addPixmap(photo);
|
||||
ui->templateImage->setSceneRect(ui->templateImage->scene()->itemsBoundingRect());
|
||||
ui->templateImage->fitInView(ui->templateImage->scene()->itemsBoundingRect(), Qt::KeepAspectRatio);
|
||||
}
|
||||
|
||||
void AirframeInitialTuningPage::updateDescription(QJsonObject *templ)
|
||||
{
|
||||
if (templ != NULL) {
|
||||
QString description;
|
||||
description.append("<b>").append(tr("Name of Vehicle: ")).append("</b>").append(templ->value("name").toString()).append("<br>");
|
||||
description.append("<b>").append(tr("Name of Owner: ")).append("</b>").append(templ->value("owner").toString());
|
||||
if (templ->value("nick") != "") {
|
||||
description.append(" (").append(templ->value("nick").toString()).append(")");
|
||||
}
|
||||
description.append("<br>");
|
||||
description.append("<b>").append(tr("Size: ")).append("</b>").append(templ->value("size").toString()).append("<br>");
|
||||
description.append("<b>").append(tr("Weight: ")).append("</b>").append(templ->value("weight").toString()).append("<br>");
|
||||
description.append("<b>").append(tr("Motor(s): ")).append("</b>").append(templ->value("motor").toString()).append("<br>");
|
||||
description.append("<b>").append(tr("ESC(s): ")).append("</b>").append(templ->value("esc").toString()).append("<br>");
|
||||
description.append("<b>").append(tr("Servo(s): ")).append("</b>").append(templ->value("servo").toString()).append("<br>");
|
||||
description.append("<b>").append(tr("Battery: ")).append("</b>").append(templ->value("battery").toString()).append("<br>");
|
||||
description.append("<b>").append(tr("Propellers(s): ")).append("</b>").append(templ->value("propeller").toString()).append("<br>");
|
||||
description.append("<b>").append(tr("Controller: ")).append("</b>").append(templ->value("controller").toString()).append("<br>");
|
||||
description.append("<b>").append(tr("Comments: ")).append("</b>").append(templ->value("comment").toString());
|
||||
ui->templateDescription->setText(description);
|
||||
} else {
|
||||
ui->templateDescription->setText(tr("No vehicle selected!"));
|
||||
}
|
||||
}
|
||||
|
||||
void AirframeInitialTuningPage::templateSelectionChanged()
|
||||
{
|
||||
if (ui->templateList->currentRow() >= 0) {
|
||||
QJsonObject *templ = ui->templateList->item(ui->templateList->currentRow())->data(Qt::UserRole + 1).value<QJsonObject *>();
|
||||
updatePhoto(templ);
|
||||
updateDescription(templ);
|
||||
}
|
||||
}
|
||||
|
||||
void AirframeInitialTuningPage::loadValidFiles()
|
||||
{
|
||||
ui->templateList->clear();
|
||||
foreach(QJsonObject * templ, m_templates.values()) {
|
||||
delete templ;
|
||||
}
|
||||
m_templates.clear();
|
||||
|
||||
QDir templateDir(QString("%1/%2/").arg(VehicleTemplateExportDialog::EXPORT_BASE_NAME).arg(m_dir));
|
||||
QStringList names;
|
||||
names << "*.optmpl";
|
||||
templateDir.setNameFilters(names);
|
||||
templateDir.setSorting(QDir::Name);
|
||||
QStringList files = templateDir.entryList();
|
||||
foreach(QString fileName, files) {
|
||||
QFile file(QString("%1/%2").arg(templateDir.absolutePath()).arg(fileName));
|
||||
|
||||
if (file.open(QFile::ReadOnly)) {
|
||||
QByteArray jsonData = file.readAll();
|
||||
QJsonDocument templateDoc = QJsonDocument::fromJson(jsonData);
|
||||
QJsonObject json = templateDoc.object();
|
||||
if (json["type"].toInt() == getWizard()->getVehicleType() &&
|
||||
json["subtype"].toInt() == getWizard()->getVehicleSubType()) {
|
||||
QString uuid = json["uuid"].toString();
|
||||
if (!m_templates.contains(uuid)) {
|
||||
m_templates[json["uuid"].toString()] = new QJsonObject(json);
|
||||
}
|
||||
}
|
||||
}
|
||||
file.close();
|
||||
}
|
||||
}
|
||||
|
||||
void AirframeInitialTuningPage::setupTemplateList()
|
||||
{
|
||||
QListWidgetItem *item = new QListWidgetItem(tr("None"), ui->templateList);
|
||||
|
||||
item->setData(Qt::UserRole + 1, QVariant::fromValue((QJsonObject *)NULL));
|
||||
foreach(QString templ, m_templates.keys()) {
|
||||
QJsonObject *json = m_templates[templ];
|
||||
|
||||
item = new QListWidgetItem(json->value("name").toString(), ui->templateList);
|
||||
item->setData(Qt::UserRole + 1, QVariant::fromValue(json));
|
||||
}
|
||||
ui->templateList->setCurrentRow(0);
|
||||
}
|
||||
|
||||
QString AirframeInitialTuningPage::getTemplateKey(QJsonObject *templ)
|
||||
{
|
||||
return QString(templ->value("name").toString());
|
||||
}
|
||||
|
||||
void AirframeInitialTuningPage::resizeEvent(QResizeEvent *)
|
||||
{
|
||||
ui->templateImage->setSceneRect(ui->templateImage->scene()->itemsBoundingRect());
|
||||
ui->templateImage->fitInView(ui->templateImage->scene()->itemsBoundingRect(), Qt::KeepAspectRatio);
|
||||
}
|
||||
|
||||
void AirframeInitialTuningPage::showEvent(QShowEvent *)
|
||||
{
|
||||
ui->templateImage->setSceneRect(ui->templateImage->scene()->itemsBoundingRect());
|
||||
ui->templateImage->fitInView(ui->templateImage->scene()->itemsBoundingRect(), Qt::KeepAspectRatio);
|
||||
}
|
@ -0,0 +1,70 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file airframestabfixedwingpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup AirframeStabFixedwingPage
|
||||
* @{
|
||||
* @brief
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 AIRFRAMEINITIALTUNINGPAGE_H
|
||||
#define AIRFRAMEINITIALTUNINGPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
#include <QJsonObject>
|
||||
|
||||
namespace Ui {
|
||||
class AirframeInitialTuningPage;
|
||||
}
|
||||
|
||||
class AirframeInitialTuningPage : public AbstractWizardPage {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit AirframeInitialTuningPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~AirframeInitialTuningPage();
|
||||
void initializePage();
|
||||
bool validatePage();
|
||||
bool isComplete() const;
|
||||
|
||||
public slots:
|
||||
void templateSelectionChanged();
|
||||
|
||||
protected:
|
||||
void resizeEvent(QResizeEvent *);
|
||||
void showEvent(QShowEvent *);
|
||||
|
||||
private:
|
||||
Ui::AirframeInitialTuningPage *ui;
|
||||
const char *m_dir;
|
||||
QMap<QString, QJsonObject *> m_templates;
|
||||
QGraphicsPixmapItem *m_photoItem;
|
||||
|
||||
void loadValidFiles();
|
||||
void setupTemplateList();
|
||||
QString getTemplateKey(QJsonObject *templ);
|
||||
void updatePhoto(QJsonObject *templ);
|
||||
void updateDescription(QJsonObject *templ);
|
||||
};
|
||||
|
||||
Q_DECLARE_METATYPE(QJsonObject *)
|
||||
|
||||
#endif // AIRFRAMEINITIALTUNINGPAGE_H
|
@ -0,0 +1,105 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>AirframeInitialTuningPage</class>
|
||||
<widget class="QWizardPage" name="AirframeInitialTuningPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>598</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_main">
|
||||
<property name="text">
|
||||
<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:8pt; font-weight:400; font-style:normal;">
|
||||
<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-size:12pt; font-weight:600;">Initial Tuning</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-size:12pt; font-weight:600;"><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:'MS Shell Dlg 2,sans-serif';">This section of the OpenPilot Wizard allows you to select a set of initial tunning parameters for your airframe. Presented below is a list of common airframe types, select the one that matches your airframe the closest, if unsure select the generic variant.</span> </p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3" stretch="2,0">
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2" stretch="0,4">
|
||||
<item>
|
||||
<widget class="QListWidget" name="templateList">
|
||||
<property name="verticalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOn</enum>
|
||||
</property>
|
||||
<property name="editTriggers">
|
||||
<set>QAbstractItemView::NoEditTriggers</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QGraphicsView" name="templateImage">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>250</width>
|
||||
<height>250</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: rgba(254, 254, 254, 0);</string>
|
||||
</property>
|
||||
<property name="interactive">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="renderHints">
|
||||
<set>QPainter::Antialiasing|QPainter::HighQualityAntialiasing|QPainter::TextAntialiasing</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QTextEdit" name="templateDescription">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="undoRedoEnabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="readOnly">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="placeholderText">
|
||||
<string>Information about the Vehicle in short.</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,92 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file fixedwingpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup FixedWingPage
|
||||
* @{
|
||||
* @brief
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "airspeedpage.h"
|
||||
#include "setupwizard.h"
|
||||
|
||||
AirSpeedPage::AirSpeedPage(SetupWizard *wizard, QWidget *parent) :
|
||||
SelectionPage(wizard, QString(":/setupwizard/resources/sensor-shapes.svg"), parent)
|
||||
{}
|
||||
|
||||
AirSpeedPage::~AirSpeedPage()
|
||||
{}
|
||||
|
||||
void AirSpeedPage::initializePage(VehicleConfigurationSource *settings)
|
||||
{
|
||||
// Enable all
|
||||
setItemDisabled(-1, false);
|
||||
if (settings->getInputType() == VehicleConfigurationSource::INPUT_SBUS ||
|
||||
settings->getInputType() == VehicleConfigurationSource::INPUT_DSM2 ||
|
||||
settings->getInputType() == VehicleConfigurationSource::INPUT_DSMX10 ||
|
||||
settings->getInputType() == VehicleConfigurationSource::INPUT_DSMX11) {
|
||||
// Disable non estimated sensors if ports are taken by receivers
|
||||
setItemDisabled(VehicleConfigurationSource::AIRSPEED_EAGLETREE, true);
|
||||
setItemDisabled(VehicleConfigurationSource::AIRSPEED_MS4525, true);
|
||||
if (getSelectedItem()->id() == VehicleConfigurationSource::AIRSPEED_EAGLETREE ||
|
||||
getSelectedItem()->id() == VehicleConfigurationSource::AIRSPEED_MS4525) {
|
||||
// If previously selected invalid sensor, reset to estimated
|
||||
setSelectedItem(VehicleConfigurationSource::AIRSPEED_ESTIMATE);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool AirSpeedPage::validatePage(SelectionItem *selectedItem)
|
||||
{
|
||||
getWizard()->setAirspeedType((SetupWizard::AIRSPEED_TYPE)selectedItem->id());
|
||||
return true;
|
||||
}
|
||||
|
||||
void AirSpeedPage::setupSelection(Selection *selection)
|
||||
{
|
||||
selection->setTitle(tr("OpenPilot Airspeed Sensor Selection"));
|
||||
selection->setText(tr("This part of the wizard will help you select and configure a way to obtain "
|
||||
"airspeed data. OpenPilot support three methods to achieve this, one is a "
|
||||
"software estimation technique and the other two utilize hardware sensors.\n\n"
|
||||
"Note: if previously selected input combinations use the Flexi-port for input, "
|
||||
"only estimated airspeed will be available.\n\n"));
|
||||
selection->addItem(tr("Estimated"),
|
||||
tr("This option uses an intelligent estimation algorithm which utilizes the OpenPilot INS/GPS "
|
||||
"to estimate wind speed and subtract it from ground speed obtained from the GPS.\n\n"
|
||||
"This solution is highly accurate in normal level flight with the drawback of being less "
|
||||
"accurate in rapid altitude changes.\n\n"),
|
||||
"estimated-airspeed-sensor",
|
||||
SetupWizard::AIRSPEED_ESTIMATE);
|
||||
|
||||
selection->addItem(tr("EagleTree"),
|
||||
tr("Select this option to use the Airspeed MicroSensor V3 from EagleTree, this is an accurate "
|
||||
"airspeed sensor that includes on-board Temperature Compensation.\n\n"
|
||||
"Selecting this option will set your board's Flexi-Port in to I2C mode."),
|
||||
"eagletree-speed-sensor",
|
||||
SetupWizard::AIRSPEED_EAGLETREE);
|
||||
|
||||
selection->addItem(tr("MS4525 Based"),
|
||||
tr("Select this option to use an airspeed sensor based on the MS4525DO pressure transducer "
|
||||
"from Measurement Specialties. This includes the PixHawk sensor and their clones.\n\n"
|
||||
"Selecting this option will set your board's Flexi-Port in to I2C mode."),
|
||||
"ms4525-speed-sensor",
|
||||
SetupWizard::AIRSPEED_MS4525);
|
||||
}
|
@ -0,0 +1,46 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file airspeedpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup AirSpeedPage
|
||||
* @{
|
||||
* @brief
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 AIRSPEEDPAGE_H
|
||||
#define AIRSPEEDPAGE_H
|
||||
|
||||
#include "selectionpage.h"
|
||||
|
||||
class AirSpeedPage : public SelectionPage {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit AirSpeedPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~AirSpeedPage();
|
||||
|
||||
protected:
|
||||
void initializePage(VehicleConfigurationSource *settings);
|
||||
bool validatePage(SelectionItem *selectedItem);
|
||||
void setupSelection(Selection *selection);
|
||||
};
|
||||
|
||||
#endif // AIRSPEEDPAGE_H
|
@ -21,7 +21,7 @@
|
||||
<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:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Firmware Update Wizard</span></p>
|
||||
<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-size:12pt; font-weight:600;">Firmware Update</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-size:12pt; font-weight:600;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">It is necessary that your firmware and ground control software are the same version.</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;"><br /></p>
|
||||
|
@ -21,11 +21,11 @@
|
||||
<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:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot sensor calibration procedure</span></p>
|
||||
<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-size:12pt; font-weight:600;">OpenPilot Sensor Calibration Procedure</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-size:12pt; font-weight:600;"><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-size:10pt;">The wizard needs to get information from the controller to determine in which position the vehicle is normally considered to be level. To be able to successfully perform these measurements, you need to place the vehicle on a surface that is as flat and level as possible. Examples of such surfaces could be a table top or the floor. Be careful to ensure that the vehicle really is level, since this step will affect the accelerometer and gyro bias in the controller software.</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-size:10pt;"><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-size:10pt;">To perform the calibration, please push the Calculate button and wait for the process to finish. </span></p></body></html></string>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">To perform the calibration, please push the Calculate button and wait for the process to finish.</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
|
@ -33,7 +33,7 @@
|
||||
<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:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot board identification</span></p>
|
||||
<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-size:12pt; font-weight:600;">OpenPilot Board Identification</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;"><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-size:10pt;">To continue, the wizard needs to determine the configuration required for the type of OpenPilot controller you have. When connected, the wizard will attempt to automatically detect the type of board.</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-size:10pt;"><br /></p>
|
||||
|
@ -1,11 +1,11 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file outputpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @file escpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup OutputPage
|
||||
* @addtogroup EscPage
|
||||
* @{
|
||||
* @brief
|
||||
*****************************************************************************/
|
||||
@ -25,29 +25,29 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "outputpage.h"
|
||||
#include "ui_outputpage.h"
|
||||
#include "escpage.h"
|
||||
#include "ui_escpage.h"
|
||||
#include "setupwizard.h"
|
||||
|
||||
OutputPage::OutputPage(SetupWizard *wizard, QWidget *parent) :
|
||||
EscPage::EscPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
|
||||
ui(new Ui::OutputPage)
|
||||
ui(new Ui::EscPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
}
|
||||
|
||||
OutputPage::~OutputPage()
|
||||
EscPage::~EscPage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
||||
|
||||
bool OutputPage::validatePage()
|
||||
bool EscPage::validatePage()
|
||||
{
|
||||
if (ui->rapidESCButton->isChecked()) {
|
||||
getWizard()->setESCType(SetupWizard::ESC_RAPID);
|
||||
getWizard()->setEscType(SetupWizard::ESC_RAPID);
|
||||
} else {
|
||||
getWizard()->setESCType(SetupWizard::ESC_LEGACY);
|
||||
getWizard()->setEscType(SetupWizard::ESC_STANDARD);
|
||||
}
|
||||
|
||||
return true;
|
49
ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.h
Normal file
@ -0,0 +1,49 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file escpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup EscPage
|
||||
* @{
|
||||
* @brief
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 ESCPAGE_H
|
||||
#define ESCPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class EscPage;
|
||||
}
|
||||
|
||||
class EscPage : public AbstractWizardPage {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit EscPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~EscPage();
|
||||
bool validatePage();
|
||||
|
||||
private:
|
||||
Ui::EscPage *ui;
|
||||
};
|
||||
|
||||
#endif // ESCPAGE_H
|
@ -1,7 +1,7 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>OutputPage</class>
|
||||
<widget class="QWizardPage" name="OutputPage">
|
||||
<class>EscPage</class>
|
||||
<widget class="QWizardPage" name="EscPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
@ -20,14 +20,13 @@
|
||||
<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:'Lucida Grande'; font-size:13pt; 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:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;">OpenPilot basic output signal configuration</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:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;"></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:'MS Shell Dlg 2'; font-size:10pt;">To set an optimal configuration of the output signals powering your motors, the wizard needs to know what type of Electronic Speed Controllers (ESCs) you will use and what their capabilities are.</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:'MS Shell Dlg 2'; font-size:10pt;"></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:'MS Shell Dlg 2'; font-size:10pt;">Please select one of the options below. If you are unsure about the capabilities of your ESCs, just leave the default option selected and continue the wizard.</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:'MS Shell Dlg 2'; font-size:10pt;"></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:'MS Shell Dlg 2'; font-size:10pt;">To read more regarding ESC refresh rates, please see </span><a href="http://wiki.openpilot.org/x/HIEu"><span style=" text-decoration: underline; color:#0000ff;">this article</span></a><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;"> in the OpenPilot Wiki</span></p></body></html></string>
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<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-size:12pt; font-weight:600;">OpenPilot Output Signal Configuration</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-size:12pt; font-weight:600;"><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-size:10pt;">To set an optimal configuration of the output signals powering your motors, the wizard needs to know what type of Electronic Speed Controllers (ESCs) you will use and what their capabilities are.</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-size:10pt;"><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-size:10pt;">Please select one of the options below. If you are unsure about the capabilities of your ESCs, just leave the default option selected and continue the wizard.</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-size:10pt;"><br /></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
@ -113,12 +112,12 @@ p, li { white-space: pre-wrap; }
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Turbo PWM</string>
|
||||
<string>Rapid ESC</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-turbo-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-turbo-down.png</normalon>:/setupwizard/resources/bttn-turbo-up.png</iconset>
|
||||
<normaloff>:/setupwizard/resources/bttn-rapid-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-rapid-dwn.png</normalon>:/setupwizard/resources/bttn-rapid-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
@ -26,17 +26,49 @@
|
||||
*/
|
||||
|
||||
#include "fixedwingpage.h"
|
||||
#include "ui_fixedwingpage.h"
|
||||
#include "setupwizard.h"
|
||||
|
||||
FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::FixedWingPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
setFinalPage(true);
|
||||
}
|
||||
SelectionPage(wizard, QString(":/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg"), parent)
|
||||
{}
|
||||
|
||||
FixedWingPage::~FixedWingPage()
|
||||
{}
|
||||
|
||||
void FixedWingPage::initializePage(VehicleConfigurationSource *settings)
|
||||
{
|
||||
delete ui;
|
||||
Q_UNUSED(settings);
|
||||
}
|
||||
|
||||
bool FixedWingPage::validatePage(SelectionItem *selectedItem)
|
||||
{
|
||||
getWizard()->setVehicleSubType((SetupWizard::VEHICLE_SUB_TYPE)selectedItem->id());
|
||||
return true;
|
||||
}
|
||||
|
||||
void FixedWingPage::setupSelection(Selection *selection)
|
||||
{
|
||||
selection->setTitle(tr("OpenPilot Fixed-wing Configuration"));
|
||||
selection->setText(tr("This part of the wizard will set up the OpenPilot controller for use with a fixed-wing "
|
||||
"flying aircraft utilizing servos. The wizard supports the most common types of fixed-wing "
|
||||
"aircraft, other variants of fixed-wing aircraft can be configured by using custom "
|
||||
"configuration options in the Configuration plugin in the GCS.\n\n"
|
||||
"Please select the type of fixed-wing you want to create a configuration for below:"));
|
||||
selection->addItem(tr("Aileron Dual Servos"),
|
||||
tr("This setup expects a traditional airframe using two independent aileron servos "
|
||||
"on their own channel (not connected by Y adapter) plus an elevator and a rudder."),
|
||||
"aileron",
|
||||
SetupWizard::FIXED_WING_DUAL_AILERON);
|
||||
|
||||
selection->addItem(tr("Aileron Single Servo"),
|
||||
tr("This setup expects a traditional airframe using a single alieron servo or two servos "
|
||||
"connected by a Y adapter plus an elevator and a rudder."),
|
||||
"aileron-single",
|
||||
SetupWizard::FIXED_WING_AILERON);
|
||||
|
||||
selection->addItem(tr("Elevon"),
|
||||
tr("This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet "
|
||||
"supported. Setup should include only two elevons, and should explicitly not include a rudder."),
|
||||
"elevon",
|
||||
SetupWizard::FIXED_WING_ELEVON);
|
||||
}
|
||||
|
@ -28,21 +28,19 @@
|
||||
#ifndef FIXEDWINGPAGE_H
|
||||
#define FIXEDWINGPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
#include "selectionpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class FixedWingPage;
|
||||
}
|
||||
|
||||
class FixedWingPage : public AbstractWizardPage {
|
||||
class FixedWingPage : public SelectionPage {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit FixedWingPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~FixedWingPage();
|
||||
|
||||
private:
|
||||
Ui::FixedWingPage *ui;
|
||||
protected:
|
||||
void initializePage(VehicleConfigurationSource *settings);
|
||||
bool validatePage(SelectionItem *selectedItem);
|
||||
void setupSelection(Selection *selection);
|
||||
};
|
||||
|
||||
#endif // FIXEDWINGPAGE_H
|
||||
|
@ -1,39 +0,0 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>FixedWingPage</class>
|
||||
<widget class="QWizardPage" name="FixedWingPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="text">
|
||||
<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;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">The Fixed Wing section of the OpenPilot Setup Wizard is not yet implemented</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-size:8pt;"></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,84 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file fixedwingpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup FixedWingPage
|
||||
* @{
|
||||
* @brief
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "gpspage.h"
|
||||
#include "setupwizard.h"
|
||||
|
||||
GpsPage::GpsPage(SetupWizard *wizard, QWidget *parent) :
|
||||
SelectionPage(wizard, QString(":/setupwizard/resources/sensor-shapes.svg"), parent)
|
||||
{}
|
||||
|
||||
GpsPage::~GpsPage()
|
||||
{}
|
||||
|
||||
void GpsPage::initializePage(VehicleConfigurationSource *settings)
|
||||
{
|
||||
Q_UNUSED(settings);
|
||||
}
|
||||
|
||||
bool GpsPage::validatePage(SelectionItem *selectedItem)
|
||||
{
|
||||
getWizard()->setGpsType((SetupWizard::GPS_TYPE)selectedItem->id());
|
||||
if (getWizard()->getGpsType() == SetupWizard::GPS_DISABLED) {
|
||||
getWizard()->setAirspeedType(VehicleConfigurationSource::AIRSPEED_DISABLED);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void GpsPage::setupSelection(Selection *selection)
|
||||
{
|
||||
selection->setTitle(tr("OpenPilot GPS Selection"));
|
||||
selection->setText(tr("Please select the type of GPS you wish to use. As well as OpenPilot hardware, "
|
||||
"3rd party GPSs are supported also, although please note that performance could "
|
||||
"be less than optimal as not all GPSs are created equal.\n\n"
|
||||
"Note: NMEA only GPSs perform poorly on VTOL aircraft and are not recommended for Helis and MultiRotors.\n\n"
|
||||
"Please select your GPS type data below:"));
|
||||
|
||||
selection->addItem(tr("Disabled"),
|
||||
tr("GPS Features are not to be enabled"),
|
||||
"no-gps",
|
||||
SetupWizard::GPS_DISABLED);
|
||||
|
||||
selection->addItem(tr("OpenPilot Platinum"),
|
||||
tr("Select this option to use the OpenPilot Platinum GPS with integrated Magnetometer "
|
||||
"and Microcontroller connected to the Main Port of your controller.\n\n"
|
||||
"Note: for the OpenPilot v8 GPS please select the U-Blox option."),
|
||||
"OPGPS-v9",
|
||||
SetupWizard::GPS_PLATINUM);
|
||||
|
||||
selection->addItem(tr("U-Blox Based"),
|
||||
tr("Select this option for the OpenPilot V8 GPS or generic U-Blox chipset GPSs connected"
|
||||
"to the Main Port of your controller."),
|
||||
"OPGPS-v8-ublox",
|
||||
SetupWizard::GPS_UBX);
|
||||
|
||||
selection->addItem(tr("NMEA Based"),
|
||||
tr("Select this option for a generic NMEA based GPS connected to the Main Port of your"
|
||||
"controller."),
|
||||
"generic-nmea",
|
||||
SetupWizard::GPS_NMEA);
|
||||
}
|
46
ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h
Normal file
@ -0,0 +1,46 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file gpspage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup GpsPage
|
||||
* @{
|
||||
* @brief
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 GPSPAGE_H
|
||||
#define GPSPAGE_H
|
||||
|
||||
#include "selectionpage.h"
|
||||
|
||||
class GpsPage : public SelectionPage {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit GpsPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~GpsPage();
|
||||
|
||||
public:
|
||||
void initializePage(VehicleConfigurationSource *settings);
|
||||
bool validatePage(SelectionItem *selectedItem);
|
||||
void setupSelection(Selection *selection);
|
||||
};
|
||||
|
||||
#endif // GPSPAGE_H
|
@ -24,7 +24,7 @@
|
||||
<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:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot basic input signal configuration</span></p>
|
||||
<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-size:12pt; font-weight:600;">OpenPilot Input Signal Configuration</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-size:12pt; font-weight:600;"><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-size:10pt;">The OpenPilot controller supports many different types of input signals. Please select the type of input that matches your receiver configuration. If you are unsure, just leave the default option selected and continue the wizard.</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-size:10pt;"><br /></p>
|
||||
|
@ -26,165 +26,78 @@
|
||||
*/
|
||||
|
||||
#include "multipage.h"
|
||||
#include "ui_multipage.h"
|
||||
#include "setupwizard.h"
|
||||
|
||||
MultiPage::MultiPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::MultiPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
|
||||
QSvgRenderer *renderer = new QSvgRenderer();
|
||||
renderer->load(QString(":/configgadget/images/multirotor-shapes.svg"));
|
||||
m_multiPic = new QGraphicsSvgItem();
|
||||
m_multiPic->setSharedRenderer(renderer);
|
||||
QGraphicsScene *scene = new QGraphicsScene(this);
|
||||
scene->addItem(m_multiPic);
|
||||
ui->typeGraphicsView->setScene(scene);
|
||||
|
||||
setupMultiTypesCombo();
|
||||
|
||||
// Default to Quad X since it is the most common setup
|
||||
ui->typeCombo->setCurrentIndex(1);
|
||||
connect(ui->typeCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateImageAndDescription()));
|
||||
ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect());
|
||||
ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio);
|
||||
}
|
||||
SelectionPage(wizard, QString(":/configgadget/images/multirotor-shapes.svg"), parent)
|
||||
{}
|
||||
|
||||
MultiPage::~MultiPage()
|
||||
{}
|
||||
|
||||
void MultiPage::initializePage(VehicleConfigurationSource *settings)
|
||||
{
|
||||
delete ui;
|
||||
Q_UNUSED(settings);
|
||||
}
|
||||
|
||||
void MultiPage::initializePage()
|
||||
bool MultiPage::validatePage(SelectionItem *selectedItem)
|
||||
{
|
||||
updateAvailableTypes();
|
||||
updateImageAndDescription();
|
||||
}
|
||||
|
||||
bool MultiPage::validatePage()
|
||||
{
|
||||
SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE)ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt();
|
||||
|
||||
getWizard()->setVehicleSubType(type);
|
||||
getWizard()->setVehicleSubType((SetupWizard::VEHICLE_SUB_TYPE)selectedItem->id());
|
||||
return true;
|
||||
}
|
||||
|
||||
void MultiPage::resizeEvent(QResizeEvent *event)
|
||||
void MultiPage::setupSelection(Selection *selection)
|
||||
{
|
||||
Q_UNUSED(event);
|
||||
if (m_multiPic) {
|
||||
ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect());
|
||||
ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio);
|
||||
}
|
||||
}
|
||||
|
||||
void MultiPage::setupMultiTypesCombo()
|
||||
{
|
||||
ui->typeCombo->addItem(tr("Tricopter"), SetupWizard::MULTI_ROTOR_TRI_Y);
|
||||
m_descriptions << tr("The Tricopter uses three motors and one servo. The servo is used to give yaw authority to the rear motor. "
|
||||
"The front motors are rotating in opposite directions. The Tricopter is known for its sweeping yaw movement and "
|
||||
"it is very well suited for FPV since the front rotors are spread wide apart.");
|
||||
|
||||
ui->typeCombo->addItem(tr("Quadcopter X"), SetupWizard::MULTI_ROTOR_QUAD_X);
|
||||
m_descriptions << tr("The X Quadcopter uses four motors and is the most common multi rotor configuration. Two of the motors rotate clockwise "
|
||||
"and two counter clockwise. The motors positioned diagonal to each other rotate in the same direction. "
|
||||
"This setup is perfect for sport flying and is also commonly used for FPV platforms.");
|
||||
|
||||
ui->typeCombo->addItem(tr("Quadcopter +"), SetupWizard::MULTI_ROTOR_QUAD_PLUS);
|
||||
m_descriptions << tr("The Plus(+) Quadcopter uses four motors and is similar to the X Quadcopter but the forward direction is offset by 45 degrees. "
|
||||
"The motors front and rear rotate in clockwise and the motors right and left rotate counter-clockwise. "
|
||||
"This setup was one of the first to be used and is still used for sport flying. This configuration is not that well suited "
|
||||
"for FPV since the fore rotor tend to be in the way of the camera.");
|
||||
|
||||
ui->typeCombo->addItem(tr("Hexacopter"), SetupWizard::MULTI_ROTOR_HEXA);
|
||||
m_descriptions << tr("Hexacopter");
|
||||
|
||||
ui->typeCombo->addItem(tr("Hexacopter X"), SetupWizard::MULTI_ROTOR_HEXA_X);
|
||||
m_descriptions << tr("Hexacopter X");
|
||||
|
||||
ui->typeCombo->addItem(tr("Hexacopter H"), SetupWizard::MULTI_ROTOR_HEXA_H);
|
||||
m_descriptions << tr("Hexacopter H");
|
||||
|
||||
ui->typeCombo->addItem(tr("Hexacopter Coax (Y6)"), SetupWizard::MULTI_ROTOR_HEXA_COAX_Y);
|
||||
m_descriptions << tr("Hexacopter Coax (Y6)");
|
||||
|
||||
|
||||
// Fredrik Arvidsson(m_thread) 2012-08-26 Disable Octos until further notice
|
||||
/*
|
||||
ui->typeCombo->addItem(tr("Octocopter"), SetupWizard::MULTI_ROTOR_OCTO);
|
||||
m_descriptions << tr("Octocopter");
|
||||
|
||||
ui->typeCombo->addItem(tr("Octocopter Coax X"), SetupWizard::MULTI_ROTOR_OCTO_COAX_X);
|
||||
m_descriptions << tr("Octocopter Coax X");
|
||||
|
||||
ui->typeCombo->addItem(tr("Octocopter Coax +"), SetupWizard::MULTI_ROTOR_OCTO_COAX_PLUS);
|
||||
m_descriptions << tr("Octocopter Coax +");
|
||||
|
||||
ui->typeCombo->addItem(tr("Octocopter V"), SetupWizard::MULTI_ROTOR_OCTO_V);
|
||||
m_descriptions << tr("Octocopter V");
|
||||
*/
|
||||
}
|
||||
|
||||
void MultiPage::updateAvailableTypes()
|
||||
{
|
||||
/*
|
||||
QVariant enable = (getWizard()->getInputType() == SetupWizard::INPUT_PWM) ? QVariant(0) : QVariant(1 | 32);
|
||||
ui->typeCombo->model()->setData(ui->typeCombo->model()->index(6, 0), enable, Qt::UserRole - 1);
|
||||
ui->typeCombo->model()->setData(ui->typeCombo->model()->index(7, 0), enable, Qt::UserRole - 1);
|
||||
ui->typeCombo->model()->setData(ui->typeCombo->model()->index(8, 0), enable, Qt::UserRole - 1);
|
||||
ui->typeCombo->model()->setData(ui->typeCombo->model()->index(9, 0), enable, Qt::UserRole - 1);
|
||||
*/
|
||||
}
|
||||
|
||||
void MultiPage::updateImageAndDescription()
|
||||
{
|
||||
SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE)ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt();
|
||||
QString elementId = "";
|
||||
QString description = m_descriptions.at(ui->typeCombo->currentIndex());
|
||||
|
||||
switch (type) {
|
||||
case SetupWizard::MULTI_ROTOR_TRI_Y:
|
||||
elementId = "tri";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_QUAD_X:
|
||||
elementId = "quad-x";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_QUAD_PLUS:
|
||||
elementId = "quad-plus";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA:
|
||||
elementId = "quad-hexa";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_COAX_Y:
|
||||
elementId = "hexa-coax";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_H:
|
||||
elementId = "quad-hexa-H";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_X:
|
||||
elementId = "quad-hexa-X";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_OCTO:
|
||||
elementId = "quad-octo";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_OCTO_COAX_X:
|
||||
elementId = "octo-coax-X";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_OCTO_COAX_PLUS:
|
||||
elementId = "octo-coax-P";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_OCTO_V:
|
||||
elementId = "quad-octo-v";
|
||||
break;
|
||||
default:
|
||||
elementId = "";
|
||||
break;
|
||||
}
|
||||
m_multiPic->setElementId(elementId);
|
||||
ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect());
|
||||
ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio);
|
||||
|
||||
ui->typeDescription->setText(description);
|
||||
selection->setTitle(tr("OpenPilot Multirotor Configuration"));
|
||||
selection->setText(tr("This part of the wizard will set up the OpenPilot controller for use with a flying platform utilizing multiple rotors. "
|
||||
"The wizard supports the most common types of multirotors. Other variants of multirotors can be configured by using custom "
|
||||
"configuration options in the Configuration plugin in the GCS.\n\n"
|
||||
"Please select the type of multirotor you want to create a configuration for below:"));
|
||||
|
||||
selection->addItem(tr("Tricopter"),
|
||||
tr("The Tricopter uses three motors and one servo. The servo is used to give yaw authority to the rear motor. "
|
||||
"The front motors are rotating in opposite directions. The Tricopter is known for its sweeping yaw movement and "
|
||||
"it is very well suited for FPV since the front rotors are spread wide apart."),
|
||||
"tri",
|
||||
SetupWizard::MULTI_ROTOR_TRI_Y);
|
||||
|
||||
selection->addItem(tr("Quadcopter X"),
|
||||
tr("The X Quadcopter uses four motors and is the most common multi rotor configuration. Two of the motors rotate clockwise "
|
||||
"and two counter clockwise. The motors positioned diagonal to each other rotate in the same direction. "
|
||||
"This setup is perfect for sport flying and is also commonly used for FPV platforms."),
|
||||
"quad-x",
|
||||
SetupWizard::MULTI_ROTOR_QUAD_X);
|
||||
|
||||
selection->addItem(tr("Quadcopter +"),
|
||||
tr("The Plus(+) Quadcopter uses four motors and is similar to the X Quadcopter but the forward direction is offset by 45 degrees. "
|
||||
"The motors front and rear rotate in clockwise and the motors right and left rotate counter-clockwise. "
|
||||
"This setup was one of the first to be used and is still used for sport flying. This configuration is not that well suited "
|
||||
"for FPV since the fore rotor tend to be in the way of the camera."),
|
||||
"quad-plus",
|
||||
SetupWizard::MULTI_ROTOR_QUAD_PLUS);
|
||||
|
||||
selection->addItem(tr("Quadcopter H"),
|
||||
tr("Quadcopter H, Blackout miniH"),
|
||||
"quad-h",
|
||||
SetupWizard::MULTI_ROTOR_QUAD_H);
|
||||
|
||||
selection->addItem(tr("Hexacopter"),
|
||||
tr("A multirotor with six motors, one motor in front."),
|
||||
"quad-hexa",
|
||||
SetupWizard::MULTI_ROTOR_HEXA);
|
||||
|
||||
selection->addItem(tr("Hexacopter X"),
|
||||
tr("A multirotor with six motors, two motors in front."),
|
||||
"quad-hexa-X",
|
||||
SetupWizard::MULTI_ROTOR_HEXA_X);
|
||||
|
||||
selection->addItem(tr("Hexacopter H"),
|
||||
tr("A multirotor with six motors in two rows."),
|
||||
"quad-hexa-H",
|
||||
SetupWizard::MULTI_ROTOR_HEXA_H);
|
||||
|
||||
selection->addItem(tr("Hexacopter Coax (Y6)"),
|
||||
tr("A multirotor with six motors mounted in a coaxial fashion."),
|
||||
"hexa-coax",
|
||||
SetupWizard::MULTI_ROTOR_HEXA_COAX_Y);
|
||||
}
|
||||
|
@ -28,38 +28,19 @@
|
||||
#ifndef MULTIPAGE_H
|
||||
#define MULTIPAGE_H
|
||||
|
||||
#include <QtSvg/QGraphicsSvgItem>
|
||||
#include <QtSvg/QSvgRenderer>
|
||||
#include <QList>
|
||||
#include "selectionpage.h"
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class MultiPage;
|
||||
}
|
||||
|
||||
class MultiPage : public AbstractWizardPage {
|
||||
class MultiPage : public SelectionPage {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit MultiPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~MultiPage();
|
||||
|
||||
void initializePage();
|
||||
bool validatePage();
|
||||
virtual ~MultiPage();
|
||||
|
||||
protected:
|
||||
void resizeEvent(QResizeEvent *event);
|
||||
|
||||
private:
|
||||
Ui::MultiPage *ui;
|
||||
void setupMultiTypesCombo();
|
||||
QGraphicsSvgItem *m_multiPic;
|
||||
void updateAvailableTypes();
|
||||
QList<QString> m_descriptions;
|
||||
|
||||
private slots:
|
||||
void updateImageAndDescription();
|
||||
void initializePage(VehicleConfigurationSource *settings);
|
||||
bool validatePage(SelectionItem *selectedItem);
|
||||
void setupSelection(Selection *selection);
|
||||
};
|
||||
|
||||
#endif // MULTIPAGE_H
|
||||
|
@ -39,16 +39,18 @@
|
||||
<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:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Welcome to the OpenPilot Setup Wizard</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;"><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-size:10pt;">This wizard will guide you through the basic steps required to setup your OpenPilot controller for the first time. You will be asked questions about your platform (multirotor/heli/fixed-wing) which this wizard will use to configure your controller for its first flight. </span></p>
|
||||
<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-size:12pt; font-weight:600;">Welcome to the OpenPilot Setup Wizard</span><img src=":/setupwizard/resources/wizard.png" style="float: right;" /></p>
|
||||
<p align="center" 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-size:12pt; font-weight:600;"><br /></p>
|
||||
<p align="right" style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><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-size:10pt;">This wizard will guide you through the basic steps required to setup your OpenPilot controller for the first time. You will be asked questions about your platform (multirotor/heli/fixed-wing) which this wizard will use to configure your controller for its first flight.</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-size:10pt;"><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-size:10pt;">This wizard does not configure all of the advanced settings available in the GCS Configuration. All basic and advanced configuration parameters can be modified later by using the GCS Configuration plugin.</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-size:10pt;"><br /></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-size:10pt;"><br /></p>
|
||||
<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-size:12pt; font-weight:600; color:#ff0000;">WARNING: YOU MUST REMOVE ALL PROPELLERS </span></p>
|
||||
<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-size:12pt; font-weight:600; color:#ff0000;">FROM THE VEHICLE BEFORE PROCEEDING!</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:'Lucida Grande'; font-size:13pt;"><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-size:10pt;">Disregarding this warning puts you at</span><span style=" font-size:10pt; font-weight:600; color:#000000;"> risk of very serious injury</span><span style=" font-size:10pt;">!</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-size:10pt;">Disregarding this warning puts you at</span><span style=" font-size:10pt; font-weight:600; color:#000000;"> risk of injury</span><span style=" font-size:10pt;">!</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-size:10pt;"><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-size:10pt;">Now that your props are removed we can get started. Ready?</span></p></body></html></string>
|
||||
</property>
|
||||
|
@ -30,19 +30,21 @@
|
||||
#include "systemalarms.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
const QString OutputCalibrationPage::MULTI_SVG_FILE = QString(":/setupwizard/resources/multirotor-shapes.svg");
|
||||
const QString OutputCalibrationPage::FIXEDWING_SVG_FILE = QString(":/setupwizard/resources/fixedwing-shapes-wizard.svg");
|
||||
|
||||
OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent), ui(new Ui::OutputCalibrationPage), m_vehicleBoundsItem(0),
|
||||
m_currentWizardIndex(-1), m_calibrationUtil(0)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
|
||||
qDebug() << "calling output calibration page";
|
||||
m_vehicleRenderer = new QSvgRenderer();
|
||||
if (QFile::exists(QString(":/setupwizard/resources/multirotor-shapes.svg")) &&
|
||||
m_vehicleRenderer->load(QString(":/setupwizard/resources/multirotor-shapes.svg")) &&
|
||||
m_vehicleRenderer->isValid()) {
|
||||
m_vehicleScene = new QGraphicsScene(this);
|
||||
ui->vehicleView->setScene(m_vehicleScene);
|
||||
}
|
||||
|
||||
// move the code that was here to setupVehicle() so we can determine which image to use.
|
||||
m_vehicleScene = new QGraphicsScene(this);
|
||||
ui->vehicleView->setScene(m_vehicleScene);
|
||||
}
|
||||
|
||||
OutputCalibrationPage::~OutputCalibrationPage()
|
||||
@ -54,6 +56,40 @@ OutputCalibrationPage::~OutputCalibrationPage()
|
||||
delete ui;
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::loadSVGFile(QString file)
|
||||
{
|
||||
if (QFile::exists(file) && m_vehicleRenderer->load(file) && m_vehicleRenderer->isValid()) {
|
||||
ui->vehicleView->setScene(m_vehicleScene);
|
||||
}
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::setupActuatorMinMaxAndNeutral(int motorChannelStart, int motorChannelEnd, int totalUsedChannels)
|
||||
{
|
||||
// Default values for the actuator settings, extra important for
|
||||
// servos since a value out of range can actually destroy the
|
||||
// vehicle if unlucky.
|
||||
// Motors are not that important. REMOVE propellers always!!
|
||||
|
||||
for (int servoid = 0; servoid < 12; servoid++) {
|
||||
if (servoid >= motorChannelStart && servoid <= motorChannelEnd) {
|
||||
// Set to motor safe values
|
||||
m_actuatorSettings[servoid].channelMin = 1000;
|
||||
m_actuatorSettings[servoid].channelNeutral = 1000;
|
||||
m_actuatorSettings[servoid].channelMax = 2000;
|
||||
} else if (servoid < totalUsedChannels) {
|
||||
// Set to servo safe values
|
||||
m_actuatorSettings[servoid].channelMin = 1500;
|
||||
m_actuatorSettings[servoid].channelNeutral = 1500;
|
||||
m_actuatorSettings[servoid].channelMax = 1500;
|
||||
} else {
|
||||
// "Disable" these channels
|
||||
m_actuatorSettings[servoid].channelMin = 1000;
|
||||
m_actuatorSettings[servoid].channelNeutral = 1000;
|
||||
m_actuatorSettings[servoid].channelMax = 1000;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::setupVehicle()
|
||||
{
|
||||
m_actuatorSettings = getWizard()->getActuatorSettings();
|
||||
@ -63,52 +99,119 @@ void OutputCalibrationPage::setupVehicle()
|
||||
m_channelIndex.clear();
|
||||
m_currentWizardIndex = 0;
|
||||
m_vehicleScene->clear();
|
||||
|
||||
switch (getWizard()->getVehicleSubType()) {
|
||||
case SetupWizard::MULTI_ROTOR_TRI_Y:
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 2 << 3 << 4;
|
||||
// Loads the SVG file resourse and sets the scene
|
||||
loadSVGFile(MULTI_SVG_FILE);
|
||||
|
||||
// The m_wizardIndexes array contains the index of the QStackedWidget
|
||||
// in the page to use for each step.
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 2;
|
||||
|
||||
// All element ids to load from the svg file and manage.
|
||||
m_vehicleElementIds << "tri" << "tri-frame" << "tri-m1" << "tri-m2" << "tri-m3" << "tri-s1";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 4 << 4;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3 << 3 << 3;
|
||||
m_actuatorSettings[3].channelMin = 1500;
|
||||
m_actuatorSettings[3].channelNeutral = 1500;
|
||||
m_actuatorSettings[3].channelMax = 1500;
|
||||
|
||||
// The index of the elementId to highlight ( not dim ) for each step
|
||||
// this is the index in the m_vehicleElementIds - 1.
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4;
|
||||
|
||||
// The channel number to configure for each step.
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3;
|
||||
|
||||
setupActuatorMinMaxAndNeutral(0, 2, 3);
|
||||
|
||||
getWizard()->setActuatorSettings(m_actuatorSettings);
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_QUAD_X:
|
||||
loadSVGFile(MULTI_SVG_FILE);
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1;
|
||||
m_vehicleElementIds << "quad-x" << "quad-x-frame" << "quad-x-m1" << "quad-x-m2" << "quad-x-m3" << "quad-x-m4";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3;
|
||||
setupActuatorMinMaxAndNeutral(0, 3, 4);
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_QUAD_H:
|
||||
loadSVGFile(MULTI_SVG_FILE);
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1;
|
||||
m_vehicleElementIds << "quad-h" << "quad-h-frame" << "quad-h-m1" << "quad-h-m2" << "quad-h-m3" << "quad-h-m4";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3;
|
||||
setupActuatorMinMaxAndNeutral(0, 3, 4);
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_QUAD_PLUS:
|
||||
loadSVGFile(MULTI_SVG_FILE);
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1;
|
||||
m_vehicleElementIds << "quad-p" << "quad-p-frame" << "quad-p-m1" << "quad-p-m2" << "quad-p-m3" << "quad-p-m4";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3;
|
||||
setupActuatorMinMaxAndNeutral(0, 3, 4);
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA:
|
||||
loadSVGFile(MULTI_SVG_FILE);
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1;
|
||||
m_vehicleElementIds << "hexa" << "hexa-frame" << "hexa-m1" << "hexa-m2" << "hexa-m3" << "hexa-m4" << "hexa-m5" << "hexa-m6";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5;
|
||||
setupActuatorMinMaxAndNeutral(0, 5, 6);
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_COAX_Y:
|
||||
loadSVGFile(MULTI_SVG_FILE);
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1;
|
||||
m_vehicleElementIds << "hexa-y6" << "hexa-y6-frame" << "hexa-y6-m2" << "hexa-y6-m1" << "hexa-y6-m4" << "hexa-y6-m3" << "hexa-y6-m6" << "hexa-y6-m5";
|
||||
m_vehicleHighlightElementIndexes << 0 << 2 << 1 << 4 << 3 << 6 << 5;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5;
|
||||
setupActuatorMinMaxAndNeutral(0, 5, 6);
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_H:
|
||||
loadSVGFile(MULTI_SVG_FILE);
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1;
|
||||
m_vehicleElementIds << "hexa-h" << "hexa-h-frame" << "hexa-h-m1" << "hexa-h-m2" << "hexa-h-m3" << "hexa-h-m4" << "hexa-h-m5" << "hexa-h-m6";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5;
|
||||
setupActuatorMinMaxAndNeutral(0, 5, 6);
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_X:
|
||||
loadSVGFile(MULTI_SVG_FILE);
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1;
|
||||
m_vehicleElementIds << "hexa-x" << "hexa-x-frame" << "hexa-x-m1" << "hexa-x-m2" << "hexa-x-m3" << "hexa-x-m4" << "hexa-x-m5" << "hexa-x-m6";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5;
|
||||
setupActuatorMinMaxAndNeutral(0, 5, 6);
|
||||
break;
|
||||
// Fixed Wing
|
||||
case SetupWizard::FIXED_WING_DUAL_AILERON:
|
||||
loadSVGFile(FIXEDWING_SVG_FILE);
|
||||
m_wizardIndexes << 0 << 1 << 2 << 2 << 2 << 2;
|
||||
m_vehicleElementIds << "aileron" << "aileron-frame" << "aileron-motor" << "aileron-ail-left" << "aileron-ail-right" << "aileron-elevator" << "aileron-rudder";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5;
|
||||
m_channelIndex << 0 << 2 << 0 << 5 << 1 << 3;
|
||||
|
||||
setupActuatorMinMaxAndNeutral(2, 2, 5);
|
||||
|
||||
getWizard()->setActuatorSettings(m_actuatorSettings);
|
||||
break;
|
||||
case SetupWizard::FIXED_WING_AILERON:
|
||||
loadSVGFile(FIXEDWING_SVG_FILE);
|
||||
m_wizardIndexes << 0 << 1 << 2 << 2 << 2;
|
||||
m_vehicleElementIds << "aileron-single" << "ail2-frame" << "ail2-motor" << "ail2-aileron" << "ail2-elevator" << "ail2-rudder";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4;
|
||||
m_channelIndex << 0 << 2 << 0 << 1 << 3;
|
||||
|
||||
setupActuatorMinMaxAndNeutral(2, 2, 4);
|
||||
|
||||
getWizard()->setActuatorSettings(m_actuatorSettings);
|
||||
break;
|
||||
case SetupWizard::FIXED_WING_ELEVON:
|
||||
loadSVGFile(FIXEDWING_SVG_FILE);
|
||||
m_wizardIndexes << 0 << 1 << 2 << 2;
|
||||
m_vehicleElementIds << "elevon" << "elevon-frame" << "elevon-motor" << "elevon-left" << "elevon-right";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3;
|
||||
m_channelIndex << 0 << 2 << 0 << 1;
|
||||
|
||||
setupActuatorMinMaxAndNeutral(2, 2, 3);
|
||||
|
||||
getWizard()->setActuatorSettings(m_actuatorSettings);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
@ -183,18 +286,27 @@ void OutputCalibrationPage::setWizardPage()
|
||||
ui->calibrationStack->setCurrentIndex(currentPageIndex);
|
||||
|
||||
int currentChannel = getCurrentChannel();
|
||||
qDebug() << "Current channel: " << currentChannel;
|
||||
qDebug() << "Current channel: " << currentChannel + 1;
|
||||
if (currentChannel >= 0) {
|
||||
if (currentPageIndex == 1) {
|
||||
ui->motorNeutralSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral);
|
||||
} else if (currentPageIndex == 2) {
|
||||
ui->servoCenterSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral);
|
||||
} else if (currentPageIndex == 3) {
|
||||
ui->servoMinAngleSlider->setMaximum(m_actuatorSettings[currentChannel].channelNeutral);
|
||||
ui->servoMinAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMin);
|
||||
} else if (currentPageIndex == 4) {
|
||||
ui->servoMaxAngleSlider->setMinimum(m_actuatorSettings[currentChannel].channelNeutral);
|
||||
ui->servoMaxAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMax);
|
||||
if (m_actuatorSettings[currentChannel].channelMax < m_actuatorSettings[currentChannel].channelMin &&
|
||||
!ui->reverseCheckbox->isChecked()) {
|
||||
ui->reverseCheckbox->setChecked(true);
|
||||
} else {
|
||||
ui->reverseCheckbox->setChecked(false);
|
||||
}
|
||||
enableServoSliders(false);
|
||||
if (ui->reverseCheckbox->isChecked()) {
|
||||
ui->servoMaxAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMax);
|
||||
ui->servoCenterAngleSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral);
|
||||
ui->servoMinAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMin);
|
||||
} else {
|
||||
ui->servoMinAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMin);
|
||||
ui->servoCenterAngleSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral);
|
||||
ui->servoMaxAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMax);
|
||||
}
|
||||
}
|
||||
}
|
||||
setupVehicleHighlightedPart();
|
||||
@ -265,8 +377,10 @@ void OutputCalibrationPage::enableButtons(bool enable)
|
||||
void OutputCalibrationPage::on_motorNeutralButton_toggled(bool checked)
|
||||
{
|
||||
ui->motorNeutralButton->setText(checked ? tr("Stop") : tr("Start"));
|
||||
quint16 channel = getCurrentChannel();
|
||||
onStartButtonToggle(ui->motorNeutralButton, channel, m_actuatorSettings[channel].channelNeutral, 1000, ui->motorNeutralSlider);
|
||||
ui->motorNeutralSlider->setEnabled(checked);
|
||||
quint16 channel = getCurrentChannel();
|
||||
quint16 safeValue = m_actuatorSettings[channel].channelNeutral;
|
||||
onStartButtonToggle(ui->motorNeutralButton, channel, m_actuatorSettings[channel].channelNeutral, safeValue, ui->motorNeutralSlider);
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::onStartButtonToggle(QAbstractButton *button, quint16 channel, quint16 value, quint16 safeValue, QSlider *slider)
|
||||
@ -274,6 +388,7 @@ void OutputCalibrationPage::onStartButtonToggle(QAbstractButton *button, quint16
|
||||
if (button->isChecked()) {
|
||||
if (checkAlarms()) {
|
||||
enableButtons(false);
|
||||
enableServoSliders(true);
|
||||
m_calibrationUtil->startChannelOutput(channel, safeValue);
|
||||
slider->setValue(value);
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
@ -282,11 +397,20 @@ void OutputCalibrationPage::onStartButtonToggle(QAbstractButton *button, quint16
|
||||
}
|
||||
} else {
|
||||
m_calibrationUtil->stopChannelOutput();
|
||||
enableServoSliders(false);
|
||||
enableButtons(true);
|
||||
}
|
||||
debugLogChannelValues();
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::enableServoSliders(bool enabled)
|
||||
{
|
||||
ui->servoCenterAngleSlider->setEnabled(enabled);
|
||||
ui->servoMinAngleSlider->setEnabled(enabled);
|
||||
ui->servoMaxAngleSlider->setEnabled(enabled);
|
||||
ui->reverseCheckbox->setEnabled(!enabled);
|
||||
}
|
||||
|
||||
bool OutputCalibrationPage::checkAlarms()
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
@ -338,68 +462,118 @@ void OutputCalibrationPage::on_motorNeutralSlider_valueChanged(int value)
|
||||
}
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_servoCenterButton_toggled(bool checked)
|
||||
void OutputCalibrationPage::on_servoButton_toggled(bool checked)
|
||||
{
|
||||
ui->servoCenterButton->setText(checked ? tr("Stop") : tr("Start"));
|
||||
ui->servoButton->setText(checked ? tr("Stop") : tr("Start"));
|
||||
quint16 channel = getCurrentChannel();
|
||||
quint16 safeValue = m_actuatorSettings[channel].channelNeutral;
|
||||
onStartButtonToggle(ui->servoCenterButton, channel, safeValue, safeValue, ui->servoCenterSlider);
|
||||
onStartButtonToggle(ui->servoButton, channel, safeValue, safeValue, ui->servoCenterAngleSlider);
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_servoCenterSlider_valueChanged(int position)
|
||||
void OutputCalibrationPage::on_servoCenterAngleSlider_valueChanged(int position)
|
||||
{
|
||||
Q_UNUSED(position);
|
||||
if (ui->servoCenterButton->isChecked()) {
|
||||
quint16 value = ui->servoCenterSlider->value();
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
quint16 channel = getCurrentChannel();
|
||||
m_actuatorSettings[channel].channelNeutral = value;
|
||||
quint16 value = ui->servoCenterAngleSlider->value();
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
quint16 channel = getCurrentChannel();
|
||||
m_actuatorSettings[channel].channelNeutral = value;
|
||||
|
||||
// Adjust min and max
|
||||
if (value < m_actuatorSettings[channel].channelMin) {
|
||||
m_actuatorSettings[channel].channelMin = value;
|
||||
// Adjust min and max
|
||||
if (ui->reverseCheckbox->isChecked()) {
|
||||
if (value >= m_actuatorSettings[channel].channelMin) {
|
||||
ui->servoMinAngleSlider->setValue(value);
|
||||
}
|
||||
if (value > m_actuatorSettings[channel].channelMax) {
|
||||
m_actuatorSettings[channel].channelMax = value;
|
||||
if (value <= m_actuatorSettings[channel].channelMax) {
|
||||
ui->servoMaxAngleSlider->setValue(value);
|
||||
}
|
||||
} else {
|
||||
if (value <= m_actuatorSettings[channel].channelMin) {
|
||||
ui->servoMinAngleSlider->setValue(value);
|
||||
}
|
||||
if (value >= m_actuatorSettings[channel].channelMax) {
|
||||
ui->servoMaxAngleSlider->setValue(value);
|
||||
}
|
||||
debugLogChannelValues();
|
||||
}
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_servoMinAngleButton_toggled(bool checked)
|
||||
{
|
||||
ui->servoMinAngleButton->setText(checked ? tr("Stop") : tr("Start"));
|
||||
quint16 channel = getCurrentChannel();
|
||||
quint16 safeValue = m_actuatorSettings[channel].channelNeutral;
|
||||
onStartButtonToggle(ui->servoMinAngleButton, channel, m_actuatorSettings[channel].channelMin, safeValue, ui->servoMinAngleSlider);
|
||||
debugLogChannelValues();
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_servoMinAngleSlider_valueChanged(int position)
|
||||
{
|
||||
Q_UNUSED(position);
|
||||
if (ui->servoMinAngleButton->isChecked()) {
|
||||
quint16 value = ui->servoMinAngleSlider->value();
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
m_actuatorSettings[getCurrentChannel()].channelMin = value;
|
||||
debugLogChannelValues();
|
||||
}
|
||||
}
|
||||
quint16 value = ui->servoMinAngleSlider->value();
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
m_actuatorSettings[getCurrentChannel()].channelMin = value;
|
||||
|
||||
void OutputCalibrationPage::on_servoMaxAngleButton_toggled(bool checked)
|
||||
{
|
||||
ui->servoMaxAngleButton->setText(checked ? tr("Stop") : tr("Start"));
|
||||
quint16 channel = getCurrentChannel();
|
||||
quint16 safeValue = m_actuatorSettings[channel].channelNeutral;
|
||||
onStartButtonToggle(ui->servoMaxAngleButton, channel, m_actuatorSettings[channel].channelMax, safeValue, ui->servoMaxAngleSlider);
|
||||
// Adjust neutral and max
|
||||
if (ui->reverseCheckbox->isChecked()) {
|
||||
if (value <= m_actuatorSettings[getCurrentChannel()].channelNeutral) {
|
||||
ui->servoCenterAngleSlider->setValue(value);
|
||||
}
|
||||
if (value <= m_actuatorSettings[getCurrentChannel()].channelMax) {
|
||||
ui->servoMaxAngleSlider->setValue(value);
|
||||
}
|
||||
} else {
|
||||
if (value >= m_actuatorSettings[getCurrentChannel()].channelNeutral) {
|
||||
ui->servoCenterAngleSlider->setValue(value);
|
||||
}
|
||||
if (value >= m_actuatorSettings[getCurrentChannel()].channelMax) {
|
||||
ui->servoMaxAngleSlider->setValue(value);
|
||||
}
|
||||
}
|
||||
debugLogChannelValues();
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_servoMaxAngleSlider_valueChanged(int position)
|
||||
{
|
||||
Q_UNUSED(position);
|
||||
if (ui->servoMaxAngleButton->isChecked()) {
|
||||
quint16 value = ui->servoMaxAngleSlider->value();
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
m_actuatorSettings[getCurrentChannel()].channelMax = value;
|
||||
debugLogChannelValues();
|
||||
quint16 value = ui->servoMaxAngleSlider->value();
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
m_actuatorSettings[getCurrentChannel()].channelMax = value;
|
||||
|
||||
// Adjust neutral and min
|
||||
if (ui->reverseCheckbox->isChecked()) {
|
||||
if (value >= m_actuatorSettings[getCurrentChannel()].channelNeutral) {
|
||||
ui->servoCenterAngleSlider->setValue(value);
|
||||
}
|
||||
if (value >= m_actuatorSettings[getCurrentChannel()].channelMin) {
|
||||
ui->servoMinAngleSlider->setValue(value);
|
||||
}
|
||||
} else {
|
||||
if (value <= m_actuatorSettings[getCurrentChannel()].channelNeutral) {
|
||||
ui->servoCenterAngleSlider->setValue(value);
|
||||
}
|
||||
if (value <= m_actuatorSettings[getCurrentChannel()].channelMin) {
|
||||
ui->servoMinAngleSlider->setValue(value);
|
||||
}
|
||||
}
|
||||
debugLogChannelValues();
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_reverseCheckbox_toggled(bool checked)
|
||||
{
|
||||
if (checked && m_actuatorSettings[getCurrentChannel()].channelMax > m_actuatorSettings[getCurrentChannel()].channelMin) {
|
||||
quint16 oldMax = m_actuatorSettings[getCurrentChannel()].channelMax;
|
||||
m_actuatorSettings[getCurrentChannel()].channelMax = m_actuatorSettings[getCurrentChannel()].channelMin;
|
||||
m_actuatorSettings[getCurrentChannel()].channelMin = oldMax;
|
||||
} else if (!checked && m_actuatorSettings[getCurrentChannel()].channelMax < m_actuatorSettings[getCurrentChannel()].channelMin) {
|
||||
quint16 oldMax = m_actuatorSettings[getCurrentChannel()].channelMax;
|
||||
m_actuatorSettings[getCurrentChannel()].channelMax = m_actuatorSettings[getCurrentChannel()].channelMin;
|
||||
m_actuatorSettings[getCurrentChannel()].channelMin = oldMax;
|
||||
}
|
||||
ui->servoCenterAngleSlider->setInvertedAppearance(checked);
|
||||
ui->servoCenterAngleSlider->setInvertedControls(checked);
|
||||
ui->servoMinAngleSlider->setInvertedAppearance(checked);
|
||||
ui->servoMinAngleSlider->setInvertedControls(checked);
|
||||
ui->servoMaxAngleSlider->setInvertedAppearance(checked);
|
||||
ui->servoMaxAngleSlider->setInvertedControls(checked);
|
||||
|
||||
if (ui->reverseCheckbox->isChecked()) {
|
||||
ui->servoMaxAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelMax);
|
||||
ui->servoCenterAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelNeutral);
|
||||
ui->servoMinAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelMin);
|
||||
} else {
|
||||
ui->servoMinAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelMin);
|
||||
ui->servoCenterAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelNeutral);
|
||||
ui->servoMaxAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelMax);
|
||||
}
|
||||
}
|
||||
|
@ -52,6 +52,8 @@ public:
|
||||
return m_currentWizardIndex >= m_wizardIndexes.size() - 1;
|
||||
}
|
||||
|
||||
void loadSVGFile(QString file);
|
||||
void setupActuatorMinMaxAndNeutral(int motorChannelStart, int motorChannelEnd, int totalUsedChannels);
|
||||
protected:
|
||||
void showEvent(QShowEvent *event);
|
||||
void resizeEvent(QResizeEvent *event);
|
||||
@ -63,14 +65,11 @@ private slots:
|
||||
void on_motorNeutralButton_toggled(bool checked);
|
||||
void on_motorNeutralSlider_valueChanged(int value);
|
||||
|
||||
void on_servoCenterButton_toggled(bool checked);
|
||||
void on_servoCenterSlider_valueChanged(int position);
|
||||
|
||||
void on_servoMinAngleButton_toggled(bool checked);
|
||||
void on_servoButton_toggled(bool checked);
|
||||
void on_servoCenterAngleSlider_valueChanged(int position);
|
||||
void on_servoMinAngleSlider_valueChanged(int position);
|
||||
|
||||
void on_servoMaxAngleButton_toggled(bool checked);
|
||||
void on_servoMaxAngleSlider_valueChanged(int position);
|
||||
void on_reverseCheckbox_toggled(bool checked);
|
||||
|
||||
private:
|
||||
void setupVehicle();
|
||||
@ -79,6 +78,7 @@ private:
|
||||
void setupVehicleHighlightedPart();
|
||||
void setWizardPage();
|
||||
void enableButtons(bool enable);
|
||||
void enableServoSliders(bool enabled);
|
||||
void onStartButtonToggle(QAbstractButton *button, quint16 channel, quint16 value, quint16 safeValue, QSlider *slider);
|
||||
bool checkAlarms();
|
||||
void debugLogChannelValues();
|
||||
@ -100,6 +100,9 @@ private:
|
||||
QList<actuatorChannelSettings> m_actuatorSettings;
|
||||
|
||||
OutputCalibrationUtil *m_calibrationUtil;
|
||||
|
||||
static const QString MULTI_SVG_FILE;
|
||||
static const QString FIXEDWING_SVG_FILE;
|
||||
};
|
||||
|
||||
#endif // OUTPUTCALIBRATIONPAGE_H
|
||||
|
@ -27,14 +27,33 @@
|
||||
<string>Output calibration</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QGraphicsView" name="vehicleView">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>200</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QStackedWidget" name="calibrationStack">
|
||||
<property name="currentIndex">
|
||||
<number>1</number>
|
||||
<number>2</number>
|
||||
</property>
|
||||
<widget class="QWidget" name="intro">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_3">
|
||||
@ -65,8 +84,14 @@ p, li { white-space: pre-wrap; }
|
||||
<layout class="QVBoxLayout" name="verticalLayout_4">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>300</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><html><head/><body><p>In this step we will set the neutral rate for the motor highlighted in the illustration to the right. <br/>Please pay attention to the details and in particular the motors position and its rotation direction. Ensure the motors are spinning in the correct direction as shown in the diagram. Swap any 2 motor wires to change the direction of a motor. </p><p>To find the neutral rate for this engine, press the Start button below and slide the slider to the right until the engine just starts to spin stable. <br/><br/>When done press button again to stop.</p></body></html></string>
|
||||
<string><html><head/><body><p>In this step we will set the neutral rate for the motor highlighted in the illustration to the right. <br/>Please pay attention to the details and in particular the motors position and its rotation direction. Ensure the motors are spinning in the correct direction as shown in the diagram. Swap any 2 motor wires to change the direction of a motor. </p><p>To find <span style=" font-weight:600;">the neutral rate for this motor</span>, press the Start button below and slide the slider to the right until the motor just starts to spin stable. <br/><br/>When done press button again to stop.</p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
@ -85,7 +110,7 @@ p, li { white-space: pre-wrap; }
|
||||
<number>1000</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>1300</number>
|
||||
<number>1500</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>1</number>
|
||||
@ -127,7 +152,7 @@ p, li { white-space: pre-wrap; }
|
||||
<item>
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="text">
|
||||
<string><html><head/><body><p>This step calibrates the center position of the servo. To set the center position for this servo, press the Start button below and slide the slider to center the servo. </p><p>When done press button again to stop.</p></body></html></string>
|
||||
<string><html><head/><body><p>This step calibrates<span style=" font-weight:600;"> the minimum, center and maximum angle of the servo</span>. To set the angles for this servo, press the Start button below and slide the slider for the angle to set. The servo will follow the sliders position. <br/>When done press button again to stop.</p><p>Check Reverse to reverse servo action.</p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
@ -138,47 +163,435 @@ p, li { white-space: pre-wrap; }
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="servoCenterSlider">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>1000</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>2000</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>10</number>
|
||||
</property>
|
||||
<property name="pageStep">
|
||||
<number>20</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>1500</number>
|
||||
</property>
|
||||
<property name="tracking">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="invertedAppearance">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="invertedControls">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>40</number>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QWidget" name="widget" native="true">
|
||||
<layout class="QFormLayout" name="formLayout">
|
||||
<property name="horizontalSpacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="verticalSpacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<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 row="0" column="1">
|
||||
<widget class="QSlider" name="servoMinAngleSlider">
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QSlider::groove:horizontal {
|
||||
border: 1px solid rgb(196, 196, 196);
|
||||
background: white;
|
||||
height: 6px;
|
||||
border-radius: 2px;
|
||||
margin 10px 10px;
|
||||
}
|
||||
|
||||
QSlider::add-page:horizontal {
|
||||
background: #fff;
|
||||
border: 1px solid #777;
|
||||
height: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::add-page:horizontal:disabled {
|
||||
background: #eee;
|
||||
border: 1px solid #999;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::sub-page:horizontal {
|
||||
background: rgb(78, 147, 246);
|
||||
border: 1px solid #777;
|
||||
height: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::sub-page:horizontal:disabled {
|
||||
background: #ccc;
|
||||
border: 1px solid #999;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::handle:horizontal {
|
||||
background: rgb(196, 196, 196);
|
||||
width: 18px;
|
||||
height: 28px;
|
||||
margin: -2px 0;
|
||||
border-radius: 3px;
|
||||
border: 1px solid #777;
|
||||
}
|
||||
|
||||
QSlider::groove:vertical {
|
||||
border: 1px solid rgb(196, 196, 196);
|
||||
background: white;
|
||||
width: 6px;
|
||||
border-radius: 2px;
|
||||
margin 0px -10px;
|
||||
margin-top: 5px;
|
||||
margin-bottom: 5px;
|
||||
}
|
||||
|
||||
QSlider::sub-page:vertical {
|
||||
background: #fff;
|
||||
border: 1px solid #777;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::sub-page:vertical:disabled {
|
||||
background: #eee;
|
||||
border: 1px solid #999;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::add-page:vertical {
|
||||
background: rgb(78, 147, 246);
|
||||
border: 1px solid #777;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::add-page:vertical:disabled {
|
||||
background: #ccc;
|
||||
border: 1px solid #999;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::handle:vertical {
|
||||
background: rgb(196, 196, 196);
|
||||
width: 18px;
|
||||
margin: -6 -6;
|
||||
border-radius: 3px;
|
||||
border: 1px solid #777;
|
||||
}
|
||||
|
||||
QSlider::handle:vertical:hover {
|
||||
background: qlineargradient(x1:0, y1:0, x2:1, y2:1, stop:0 #fff, stop:1 #ddd);
|
||||
border: 1px solid #444;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::handle:horizontal:hover {
|
||||
background: qlineargradient(x1:0, y1:0, x2:1, y2:1, stop:0 #fff, stop:1 #ddd);
|
||||
border: 1px solid #444;
|
||||
border-radius: 4px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>600</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>2400</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>1500</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QSlider" name="servoCenterAngleSlider">
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QSlider::groove:horizontal {
|
||||
border: 1px solid rgb(196, 196, 196);
|
||||
background: white;
|
||||
height: 6px;
|
||||
border-radius: 2px;
|
||||
margin 10px 10px;
|
||||
}
|
||||
|
||||
QSlider::add-page:horizontal {
|
||||
background: rgb(78, 147, 246);
|
||||
border: 1px solid #777;
|
||||
height: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::add-page:horizontal:disabled {
|
||||
background: #eee;
|
||||
border: 1px solid #999;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::sub-page:horizontal {
|
||||
background: rgb(78, 147, 246);
|
||||
border: 1px solid #777;
|
||||
height: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::sub-page:horizontal:disabled {
|
||||
background: #eee;
|
||||
border: 1px solid #999;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::handle:horizontal {
|
||||
background: rgb(196, 196, 196);
|
||||
width: 18px;
|
||||
height: 28px;
|
||||
margin: -2px 0;
|
||||
border-radius: 3px;
|
||||
border: 1px solid #777;
|
||||
}
|
||||
|
||||
QSlider::groove:vertical {
|
||||
border: 1px solid rgb(196, 196, 196);
|
||||
background: white;
|
||||
width: 6px;
|
||||
border-radius: 2px;
|
||||
margin 0px -10px;
|
||||
margin-top: 5px;
|
||||
margin-bottom: 5px;
|
||||
}
|
||||
|
||||
QSlider::sub-page:vertical {
|
||||
background: #fff;
|
||||
border: 1px solid #777;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::sub-page:vertical:disabled {
|
||||
background: #eee;
|
||||
border: 1px solid #999;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::add-page:vertical {
|
||||
background: rgb(78, 147, 246);
|
||||
border: 1px solid #777;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::add-page:vertical:disabled {
|
||||
background: #ccc;
|
||||
border: 1px solid #999;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::handle:vertical {
|
||||
background: rgb(196, 196, 196);
|
||||
width: 18px;
|
||||
margin: -6 -6;
|
||||
border-radius: 3px;
|
||||
border: 1px solid #777;
|
||||
}
|
||||
|
||||
QSlider::handle:vertical:hover {
|
||||
background: qlineargradient(x1:0, y1:0, x2:1, y2:1, stop:0 #fff, stop:1 #ddd);
|
||||
border: 1px solid #444;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::handle:horizontal:hover {
|
||||
background: qlineargradient(x1:0, y1:0, x2:1, y2:1, stop:0 #fff, stop:1 #ddd);
|
||||
border: 1px solid #444;
|
||||
border-radius: 4px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>600</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>2400</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>1500</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QSlider" name="servoMaxAngleSlider">
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QSlider::groove:horizontal {
|
||||
border: 1px solid rgb(196, 196, 196);
|
||||
background: white;
|
||||
height: 6px;
|
||||
border-radius: 2px;
|
||||
margin 10px 10px;
|
||||
}
|
||||
|
||||
QSlider::sub-page:horizontal {
|
||||
background: #fff;
|
||||
border: 1px solid #777;
|
||||
height: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::sub-page:horizontal:disabled {
|
||||
background: #eee;
|
||||
border: 1px solid #999;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::add-page:horizontal {
|
||||
background: rgb(78, 147, 246);
|
||||
border: 1px solid #777;
|
||||
height: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::add-page:horizontal:disabled {
|
||||
background: #ccc;
|
||||
border: 1px solid #999;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::handle:horizontal {
|
||||
background: rgb(196, 196, 196);
|
||||
width: 18px;
|
||||
height: 28px;
|
||||
margin: -2px 0;
|
||||
border-radius: 3px;
|
||||
border: 1px solid #777;
|
||||
}
|
||||
|
||||
QSlider::groove:vertical {
|
||||
border: 1px solid rgb(196, 196, 196);
|
||||
background: white;
|
||||
width: 6px;
|
||||
border-radius: 2px;
|
||||
margin 0px -10px;
|
||||
margin-top: 5px;
|
||||
margin-bottom: 5px;
|
||||
}
|
||||
|
||||
QSlider::sub-page:vertical {
|
||||
background: #fff;
|
||||
border: 1px solid #777;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::sub-page:vertical:disabled {
|
||||
background: #eee;
|
||||
border: 1px solid #999;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::add-page:vertical {
|
||||
background: rgb(78, 147, 246);
|
||||
border: 1px solid #777;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::add-page:vertical:disabled {
|
||||
background: #ccc;
|
||||
border: 1px solid #999;
|
||||
width: 1px;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::handle:vertical {
|
||||
background: rgb(196, 196, 196);
|
||||
width: 18px;
|
||||
margin: -6 -6;
|
||||
border-radius: 3px;
|
||||
border: 1px solid #777;
|
||||
}
|
||||
|
||||
QSlider::handle:vertical:hover {
|
||||
background: qlineargradient(x1:0, y1:0, x2:1, y2:1, stop:0 #fff, stop:1 #ddd);
|
||||
border: 1px solid #444;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
QSlider::handle:horizontal:hover {
|
||||
background: qlineargradient(x1:0, y1:0, x2:1, y2:1, stop:0 #fff, stop:1 #ddd);
|
||||
border: 1px solid #444;
|
||||
border-radius: 4px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>600</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>2400</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>1500</number>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="invertedAppearance">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="3" column="0" colspan="2">
|
||||
<widget class="QCheckBox" name="reverseCheckbox">
|
||||
<property name="text">
|
||||
<string>Reverse</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<string>Min</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="text">
|
||||
<string>Center</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="0">
|
||||
<widget class="QLabel" name="label_7">
|
||||
<property name="text">
|
||||
<string>Max</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="servoCenterButton">
|
||||
<widget class="QPushButton" name="servoButton">
|
||||
<property name="text">
|
||||
<string>Start</string>
|
||||
</property>
|
||||
@ -192,234 +605,10 @@ p, li { white-space: pre-wrap; }
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<widget class="QWidget" name="servoMinMax">
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_7">
|
||||
<property name="text">
|
||||
<string><html><head/><body><p>To save the servo and other hardware from damage we have to set the max and min angles for the servo. </p><p>To set the minimum angle for the servo, press the Start button below and select the top slider and slide it to the left until min angle is reached.</p><p>When done press button again to stop.</p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="servoMinAngleSlider">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>1000</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>1500</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>10</number>
|
||||
</property>
|
||||
<property name="pageStep">
|
||||
<number>20</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>1500</number>
|
||||
</property>
|
||||
<property name="tracking">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="invertedAppearance">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="invertedControls">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>40</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="servoMinAngleButton">
|
||||
<property name="text">
|
||||
<string>Start</string>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<widget class="QWidget" name="page">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_8">
|
||||
<property name="text">
|
||||
<string><html><head/><body><p>To set the maximum angle for the servo, press the Start button below and select the top slider and slide it to the right until max angle is reached.</p><p>When done press button again to stop.</p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSlider" name="servoMaxAngleSlider">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>1500</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>2000</number>
|
||||
</property>
|
||||
<property name="singleStep">
|
||||
<number>10</number>
|
||||
</property>
|
||||
<property name="pageStep">
|
||||
<number>20</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>1500</number>
|
||||
</property>
|
||||
<property name="tracking">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="invertedAppearance">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="invertedControls">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="tickPosition">
|
||||
<enum>QSlider::TicksBelow</enum>
|
||||
</property>
|
||||
<property name="tickInterval">
|
||||
<number>40</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="servoMaxAngleButton">
|
||||
<property name="text">
|
||||
<string>Start</string>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QGraphicsView" name="vehicleView">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Minimum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>200</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections>
|
||||
<connection>
|
||||
<sender>motorNeutralButton</sender>
|
||||
<signal>toggled(bool)</signal>
|
||||
<receiver>motorNeutralSlider</receiver>
|
||||
<slot>setEnabled(bool)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>147</x>
|
||||
<y>291</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>150</x>
|
||||
<y>249</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>servoMinAngleButton</sender>
|
||||
<signal>toggled(bool)</signal>
|
||||
<receiver>servoMinAngleSlider</receiver>
|
||||
<slot>setEnabled(bool)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>147</x>
|
||||
<y>291</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>150</x>
|
||||
<y>249</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>servoMaxAngleButton</sender>
|
||||
<signal>toggled(bool)</signal>
|
||||
<receiver>servoMaxAngleSlider</receiver>
|
||||
<slot>setEnabled(bool)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>147</x>
|
||||
<y>291</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>150</x>
|
||||
<y>249</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
<connection>
|
||||
<sender>servoCenterButton</sender>
|
||||
<signal>toggled(bool)</signal>
|
||||
<receiver>servoCenterSlider</receiver>
|
||||
<slot>setEnabled(bool)</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>147</x>
|
||||
<y>291</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>150</x>
|
||||
<y>249</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
</connections>
|
||||
<connections/>
|
||||
</ui>
|
||||
|
@ -27,7 +27,7 @@
|
||||
<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:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot Revolution controller sensor calibration procedure</span></p>
|
||||
<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-size:12pt; font-weight:600;">OpenPilot Revolution Calibration Procedure</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-size:12pt; font-weight:600;"><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-size:10pt;">The calibration procedure for the OpenPilot Revolution controller is not yet implemented in this setup wizard. To calibrate your OpenPilot Revolution controller please use the calibration utility found in the configuration plugin after you have finished this wizard.</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-size:10pt;"><br /></p>
|
||||
|
@ -0,0 +1,149 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file multipage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup MultiPage
|
||||
* @{
|
||||
* @brief
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "selectionpage.h"
|
||||
#include "ui_selectionpage.h"
|
||||
#include "setupwizard.h"
|
||||
|
||||
SelectionPage::SelectionPage(SetupWizard *wizard, QString shapeFile, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent), Selection(),
|
||||
ui(new Ui::SelectionPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
|
||||
QSvgRenderer *renderer = new QSvgRenderer();
|
||||
renderer->load(shapeFile);
|
||||
m_shape = new QGraphicsSvgItem();
|
||||
m_shape->setSharedRenderer(renderer);
|
||||
QGraphicsScene *scene = new QGraphicsScene(this);
|
||||
scene->addItem(m_shape);
|
||||
ui->typeGraphicsView->setScene(scene);
|
||||
|
||||
connect(ui->typeCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(selectionChanged(int)));
|
||||
}
|
||||
|
||||
SelectionPage::~SelectionPage()
|
||||
{
|
||||
while (!m_selectionItems.empty()) {
|
||||
delete m_selectionItems.takeFirst();
|
||||
}
|
||||
delete ui;
|
||||
}
|
||||
|
||||
void SelectionPage::initializePage()
|
||||
{
|
||||
// lazy init
|
||||
if (m_selectionItems.isEmpty()) {
|
||||
setupSelection(this);
|
||||
foreach(SelectionItem * item, m_selectionItems) {
|
||||
ui->typeCombo->addItem(item->name());
|
||||
}
|
||||
|
||||
// Default to first item if any
|
||||
if (ui->typeCombo->count() > 0) {
|
||||
ui->typeCombo->setCurrentIndex(0);
|
||||
}
|
||||
}
|
||||
initializePage(getWizard());
|
||||
}
|
||||
|
||||
bool SelectionPage::validatePage()
|
||||
{
|
||||
return validatePage(m_selectionItems.at(ui->typeCombo->currentIndex()));
|
||||
}
|
||||
|
||||
void SelectionPage::fitImage()
|
||||
{
|
||||
if (m_shape) {
|
||||
ui->typeGraphicsView->setSceneRect(m_shape->boundingRect());
|
||||
ui->typeGraphicsView->fitInView(m_shape, Qt::KeepAspectRatio);
|
||||
}
|
||||
}
|
||||
|
||||
void SelectionPage::resizeEvent(QResizeEvent *event)
|
||||
{
|
||||
Q_UNUSED(event);
|
||||
fitImage();
|
||||
}
|
||||
|
||||
void SelectionPage::showEvent(QShowEvent *event)
|
||||
{
|
||||
Q_UNUSED(event);
|
||||
fitImage();
|
||||
}
|
||||
|
||||
void SelectionPage::selectionChanged(int index)
|
||||
{
|
||||
SelectionItem *item = m_selectionItems.at(index);
|
||||
|
||||
m_shape->setElementId(item->shapeId());
|
||||
ui->typeDescription->setText(item->description());
|
||||
fitImage();
|
||||
}
|
||||
|
||||
void SelectionPage::addItem(QString name, QString description, QString shapeId, int id, bool disabled)
|
||||
{
|
||||
m_selectionItems << new SelectionItem(name, description, shapeId, id, disabled);
|
||||
}
|
||||
|
||||
void SelectionPage::setTitle(QString title)
|
||||
{
|
||||
ui->label->setText(title);
|
||||
}
|
||||
|
||||
void SelectionPage::setText(QString text)
|
||||
{
|
||||
ui->text->setText(text);
|
||||
}
|
||||
|
||||
void SelectionPage::setItemDisabled(int id, bool disabled)
|
||||
{
|
||||
for (int i = 0; i < m_selectionItems.count(); i++) {
|
||||
if (id < 0 || m_selectionItems.at(i)->id() == id) {
|
||||
m_selectionItems.at(i)->setDisabled(disabled);
|
||||
ui->typeCombo->setItemData(i, disabled ? 0 : 33, Qt::UserRole - 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void SelectionPage::setSelectedItem(int id)
|
||||
{
|
||||
for (int i = 0; i < m_selectionItems.count(); i++) {
|
||||
if (m_selectionItems.at(i)->id() == id) {
|
||||
ui->typeCombo->setCurrentIndex(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
SelectionItem *SelectionPage::getSelectedItem()
|
||||
{
|
||||
return m_selectionItems.at(ui->typeCombo->currentIndex());
|
||||
}
|
||||
|
||||
SelectionItem::SelectionItem(QString name, QString description, QString shapeId, int id, bool disabled) :
|
||||
m_name(name), m_description(description), m_shapeId(shapeId), m_id(id), m_disabled(disabled)
|
||||
{}
|
@ -0,0 +1,120 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file subvehiclepage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup SubVehiclePage
|
||||
* @{
|
||||
* @brief
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 SUBVEHICLEPAGEPAGE_H
|
||||
#define SUBVEHICLEPAGEPAGE_H
|
||||
|
||||
#include <QtSvg/QGraphicsSvgItem>
|
||||
#include <QtSvg/QSvgRenderer>
|
||||
#include <QList>
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class SelectionPage;
|
||||
}
|
||||
|
||||
class SelectionItem {
|
||||
public:
|
||||
SelectionItem(QString name, QString description, QString shapeId, int id, bool disabled = false);
|
||||
|
||||
QString name()
|
||||
{
|
||||
return m_name;
|
||||
}
|
||||
QString description()
|
||||
{
|
||||
return m_description;
|
||||
}
|
||||
QString shapeId()
|
||||
{
|
||||
return m_shapeId;
|
||||
}
|
||||
int id()
|
||||
{
|
||||
return m_id;
|
||||
}
|
||||
void setDisabled(bool disabled)
|
||||
{
|
||||
m_disabled = disabled;
|
||||
}
|
||||
bool disabled()
|
||||
{
|
||||
return m_disabled;
|
||||
}
|
||||
|
||||
private:
|
||||
QString m_name;
|
||||
QString m_description;
|
||||
QString m_shapeId;
|
||||
int m_id;
|
||||
bool m_disabled;
|
||||
};
|
||||
|
||||
class Selection {
|
||||
public:
|
||||
Selection() {}
|
||||
virtual void addItem(QString name, QString description, QString shapeId, int id, bool disabled = false) = 0;
|
||||
virtual void setTitle(QString title) = 0;
|
||||
virtual void setText(QString text) = 0;
|
||||
virtual void setItemDisabled(int id, bool disabled) = 0;
|
||||
};
|
||||
|
||||
class SelectionPage : public AbstractWizardPage, public Selection {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit SelectionPage(SetupWizard *wizard, QString shapeFile, QWidget *parent = 0);
|
||||
~SelectionPage();
|
||||
|
||||
void initializePage();
|
||||
bool validatePage();
|
||||
void addItem(QString name, QString description, QString shapeId, int id, bool disabled = false);
|
||||
void setTitle(QString title);
|
||||
void setText(QString text);
|
||||
void setItemDisabled(int id, bool disabled);
|
||||
void setSelectedItem(int id);
|
||||
SelectionItem *getSelectedItem();
|
||||
|
||||
protected:
|
||||
virtual void setupSelection(Selection *selection) = 0;
|
||||
virtual void initializePage(VehicleConfigurationSource *settings) = 0;
|
||||
virtual bool validatePage(SelectionItem *selectedItem) = 0;
|
||||
void resizeEvent(QResizeEvent *event);
|
||||
void showEvent(QShowEvent *event);
|
||||
|
||||
private:
|
||||
Ui::SelectionPage *ui;
|
||||
QGraphicsSvgItem *m_shape;
|
||||
QList<SelectionItem *> m_selectionItems;
|
||||
|
||||
private slots:
|
||||
void selectionChanged(int index);
|
||||
void fitImage();
|
||||
};
|
||||
|
||||
#endif // SUBVEHICLEPAGEPAGE_H
|
@ -1,7 +1,7 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>MultiPage</class>
|
||||
<widget class="QWizardPage" name="MultiPage">
|
||||
<class>SelectionPage</class>
|
||||
<widget class="QWizardPage" name="SelectionPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
@ -16,19 +16,31 @@
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>13</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<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:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot Multirotor Configuration</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-size:12pt; font-weight:600;"><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-size:10pt;">This part of the wizard will set up the OpenPilot controller for use with a flying platform utilizing multiple rotors. The wizard supports the most common types of multirotors. Other variants of multirotors can be configured by using custom configuration options in the Configuration plugin in the GCS.</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-size:10pt;"><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-size:10pt;">Please select the type of multirotor you want to create a configuration for below:</span></p></body></html></string>
|
||||
<string>placeholder_text</string>
|
||||
</property>
|
||||
<property name="textFormat">
|
||||
<enum>Qt::PlainText</enum>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="text">
|
||||
<property name="text">
|
||||
<string>TextLabel</string>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
@ -37,43 +49,45 @@ p, li { white-space: pre-wrap; }
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<property name="spacing">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>4</number>
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_2">
|
||||
<property name="spacing">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<property name="spacing">
|
||||
<number>9</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>4</number>
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>125</width>
|
||||
<height>36</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Multirotor type:</string>
|
||||
<string>Select:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QComboBox" name="typeCombo">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>125</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
@ -82,13 +96,13 @@ p, li { white-space: pre-wrap; }
|
||||
<item>
|
||||
<widget class="QTextEdit" name="typeDescription">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Maximum" vsizetype="Expanding">
|
||||
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="verticalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOn</enum>
|
||||
<enum>Qt::ScrollBarAsNeeded</enum>
|
||||
</property>
|
||||
<property name="horizontalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
@ -120,6 +134,9 @@ p, li { white-space: pre-wrap; }
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="frameShadow">
|
||||
<enum>QFrame::Plain</enum>
|
||||
</property>
|
||||
<property name="lineWidth">
|
||||
<number>0</number>
|
||||
</property>
|
||||
@ -153,6 +170,9 @@ p, li { white-space: pre-wrap; }
|
||||
<property name="interactive">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="renderHints">
|
||||
<set>QPainter::Antialiasing|QPainter::HighQualityAntialiasing</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
@ -0,0 +1,53 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file outputfixedwingpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup OutputPage
|
||||
* @{
|
||||
* @brief
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "servopage.h"
|
||||
#include "ui_servopage.h"
|
||||
#include "setupwizard.h"
|
||||
|
||||
ServoPage::ServoPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::ServoPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
}
|
||||
|
||||
ServoPage::~ServoPage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
||||
|
||||
bool ServoPage::validatePage()
|
||||
{
|
||||
if (ui->ServoTypeButton->isChecked()) {
|
||||
getWizard()->setServoType(SetupWizard::SERVO_DIGITAL);
|
||||
} else {
|
||||
getWizard()->setServoType(SetupWizard::SERVO_ANALOG);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
@ -1,7 +1,7 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file outputpage.h
|
||||
* @file outputfixedwingpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
@ -25,25 +25,25 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#ifndef OUTPUTPAGE_H
|
||||
#define OUTPUTPAGE_H
|
||||
#ifndef OUTPUTFIXEDWINGPAGE_H
|
||||
#define OUTPUTFIXEDWINGPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class OutputPage;
|
||||
class ServoPage;
|
||||
}
|
||||
|
||||
class OutputPage : public AbstractWizardPage {
|
||||
class ServoPage : public AbstractWizardPage {
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit OutputPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~OutputPage();
|
||||
explicit ServoPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~ServoPage();
|
||||
bool validatePage();
|
||||
|
||||
private:
|
||||
Ui::OutputPage *ui;
|
||||
Ui::ServoPage *ui;
|
||||
};
|
||||
|
||||
#endif // OUTPUTPAGE_H
|
||||
#endif // OUTPUTFIXEDWINGPAGE_H
|
153
ground/openpilotgcs/src/plugins/setupwizard/pages/servopage.ui
Normal file
@ -0,0 +1,153 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>ServoPage</class>
|
||||
<widget class="QWizardPage" name="ServoPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="text">
|
||||
<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:8pt; font-weight:400; font-style:normal;">
|
||||
<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-size:12pt; font-weight:600;">OpenPilot Output Signal Configuration</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-size:12pt; font-weight:600;"><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-size:10pt;">To set an optimal configuration of the output signals powering your servos, the wizard needs to know what type of servos you will use and what their capabilities are.</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-size:10pt;"><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-size:10pt;">Please select one of the options below. If you are unsure about the capabilities of your servos, just leave the default option selected and continue the wizard.</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-size:10pt;"><br /></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="openExternalLinks">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<widget class="QToolButton" name="defaultESCButton">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Analog Servo 50Hz</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Analog Servos</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-servo-standard-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-servo-standard-dwn.png</normalon>:/setupwizard/resources/bttn-servo-standard-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QToolButton" name="ServoTypeButton">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Digital Servo 333Hz</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Digital Servos</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-servo-digital-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-servo-digital-dwn.png</normalon>:/setupwizard/resources/bttn-servo-digital-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="../wizardResources.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
@ -20,15 +20,14 @@
|
||||
<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:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot configuration summary</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-size:12pt; font-weight:600;"><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-size:10pt;">The first part of this wizard is now complete. All information required to create a basic OpenPilot controller configuration for a specific vehicle has been collected.</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-size:10pt;">Below is a summary of the configuration and a button that links to a diagram illustrating how to connect required hardware and the OpenPilot Controller with the current configuration.</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-size:10pt;"><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-size:10pt;">To continue the wizard and go through some basic configuration steps, please continue to the next step of this wizard.</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-size:10pt;"><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-size:10pt;">The following steps require that your OpenPilot controller is set up according to the diagram, it is </span><span style=" font-size:10pt; font-weight:600;">connected to the computer</span><span style=" font-size:10pt;"> by USB, and that the vehicle is</span><span style=" font-size:10pt; font-weight:600;"> powered by a battery</span><span style=" font-size:10pt;">.</span></p></body></html></string>
|
||||
</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;">
|
||||
<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:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;">OpenPilot Configuration Summary</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:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;"><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:'MS Shell Dlg 2'; font-size:10pt;">The first part of this wizard is now complete. All information required to create a basic OpenPilot controller configuration for a specific vehicle has been collected.</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:'MS Shell Dlg 2'; font-size:10pt;">Below is a summary of the configuration and a button that links to a diagram illustrating how to connect required hardware and the OpenPilot Controller with the current configuration.</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:'MS Shell Dlg 2'; font-size:10pt;"><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:'MS Shell Dlg 2'; font-size:10pt;">To continue the wizard and go through some basic configuration steps, please continue to the next step of this wizard.</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:'MS Shell Dlg 2'; font-size:10pt;">The following steps require that your OpenPilot controller is set up according to the diagram, it is </span><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt; font-weight:600;">connected to the computer</span><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;"> by USB, and that the vehicle is</span><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt; font-weight:600;"> powered by a battery</span><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">.</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
@ -74,13 +73,12 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-illustration-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-illustration-down.png</normalon>:/setupwizard/resources/bttn-illustration-up.png</iconset>
|
||||
<normaloff>:/setupwizard/resources/bttn-illustration-color-up.png</normaloff>:/setupwizard/resources/bttn-illustration-color-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
<width>120</width>
|
||||
<height>120</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
|
@ -46,6 +46,7 @@ bool VehiclePage::validatePage()
|
||||
getWizard()->setVehicleType(SetupWizard::VEHICLE_MULTI);
|
||||
} else if (ui->fixedwingButton->isChecked()) {
|
||||
getWizard()->setVehicleType(SetupWizard::VEHICLE_FIXEDWING);
|
||||
getWizard()->setEscType(SetupWizard::ESC_STANDARD);
|
||||
} else if (ui->heliButton->isChecked()) {
|
||||
getWizard()->setVehicleType(SetupWizard::VEHICLE_HELI);
|
||||
} else if (ui->surfaceButton->isChecked()) {
|
||||
@ -55,3 +56,9 @@ bool VehiclePage::validatePage()
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void VehiclePage::initializePage()
|
||||
{
|
||||
// ui->fixedwingButton->setEnabled(getWizard()->getControllerType() == SetupWizard::CONTROLLER_REVO ||
|
||||
// getWizard()->getControllerType() == SetupWizard::CONTROLLER_NANO);
|
||||
}
|
||||
|
@ -41,6 +41,7 @@ public:
|
||||
explicit VehiclePage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~VehiclePage();
|
||||
bool validatePage();
|
||||
void initializePage();
|
||||
|
||||
private:
|
||||
Ui::VehiclePage *ui;
|
||||
|
@ -21,13 +21,13 @@
|
||||
<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:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Vehicle type selection</span></p>
|
||||
<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-size:12pt; font-weight:600;">Vehicle Type Selection</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-size:12pt; font-weight:600;"><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-size:10pt;">To continue, the wizard needs to know what type of vehicle the OpenPilot controller board is going to be used with. This step is crucial since much of the following configuration is unique per vehicle type.</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;"><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-size:10pt;">Go ahead and select the type of vehicle for which you want to create a configuration.</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-size:10pt;"><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-size:10pt;">(The current version only provides functionality for multirotors.)</span></p></body></html></string>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">The current version only provides functionality for Multirotors and Fixed-wing aircraft.</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
@ -99,54 +99,10 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QToolButton" name="heliButton">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>CCPM Helicopters</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Helicopter</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-heli-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-heli-down.png</normalon>:/setupwizard/resources/bttn-heli-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QToolButton" name="fixedwingButton">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
@ -190,6 +146,50 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QToolButton" name="heliButton">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>CCPM Helicopters</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Helicopter</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-heli-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-heli-down.png</normalon>:/setupwizard/resources/bttn-heli-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QToolButton" name="surfaceButton">
|
||||
<property name="enabled">
|
||||
|
After Width: | Height: | Size: 19 KiB |
After Width: | Height: | Size: 19 KiB |
Before Width: | Height: | Size: 6.5 KiB |
Before Width: | Height: | Size: 8.2 KiB |
After Width: | Height: | Size: 5.6 KiB |
After Width: | Height: | Size: 6.4 KiB |
After Width: | Height: | Size: 4.1 KiB |
After Width: | Height: | Size: 4.8 KiB |
After Width: | Height: | Size: 4.2 KiB |
After Width: | Height: | Size: 4.8 KiB |
Before Width: | Height: | Size: 524 KiB After Width: | Height: | Size: 2.3 MiB |
After Width: | Height: | Size: 288 KiB |
After Width: | Height: | Size: 421 KiB |